From 34deddef9cfee3adfeb63c0a8269a56831ae4612 Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 01:05:43 -0800 Subject: [PATCH 1/8] Make generating plots and metrics automatic upon exit of a run by auto_plot --- GEMstack/onboard/execution/entrypoint.py | 2 + GEMstack/onboard/execution/execution.py | 3 + GEMstack/onboard/execution/logging.py | 8 +- GEMstack/utils/log_plot.py | 125 +++++++++++++++++++++++ 4 files changed, 137 insertions(+), 1 deletion(-) create mode 100644 GEMstack/utils/log_plot.py diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index b1e7a8d10..d9351a3cf 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -129,10 +129,12 @@ def caution_callback(k,variant): suffix = log_settings.get('suffix',default_suffix) logfolder = os.path.join(topfolder,prefix+suffix) print(EXECUTION_PREFIX,"Logging to",logfolder) + auto_plot = log_settings.get("auto_plot", False) os.makedirs(logfolder,exist_ok=True) #configure logging for components mission_executor.set_log_folder(logfolder) + mission_executor.set_auto_plot(auto_plot) #configure ROS logging log_topics = log_settings.get('ros_topics',[]) rosbag_options = log_settings.get('rosbag_options','') diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index a65c2acc5..9af6ee5f3 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -424,6 +424,9 @@ def add_pipeline(self,name : str, perception : Dict[str,ComponentExecutor], plan def set_log_folder(self,folder : str): self.logging_manager.set_log_folder(folder) + + def set_auto_plot(self,enabled : bool): + self.logging_manager.set_auto_plot(enabled) def log_vehicle_interface(self,enabled=True): """Indicates that the vehicle interface should be logged""" diff --git a/GEMstack/onboard/execution/logging.py b/GEMstack/onboard/execution/logging.py index 31ebd962b..21f401994 100644 --- a/GEMstack/onboard/execution/logging.py +++ b/GEMstack/onboard/execution/logging.py @@ -1,6 +1,6 @@ from __future__ import annotations from ..component import Component -from ...utils import serialization,logging,config,settings +from ...utils import serialization,logging,config,settings,log_plot from typing import List,Optional,Dict,Set,Any import time import datetime @@ -27,6 +27,10 @@ def __init__(self): self.vehicle_time = None self.start_vehicle_time = None self.debug_messages = {} + self.auto_plot = False + + def set_auto_plot(self, auto_plot : bool) -> None: + self.auto_plot = auto_plot def logging(self) -> bool: return self.log_folder is not None @@ -264,6 +268,8 @@ def log_component_stderr(self, component : str, msg : List[str]) -> None: def close(self): self.dump_debug() + if self.auto_plot: + log_plot.main(self.log_folder) self.debug_messages = {} if self.rosbag_process is not None: out,err = self.rosbag_process.communicate() # Will block diff --git a/GEMstack/utils/log_plot.py b/GEMstack/utils/log_plot.py new file mode 100644 index 000000000..1cfeadf75 --- /dev/null +++ b/GEMstack/utils/log_plot.py @@ -0,0 +1,125 @@ +import matplotlib.pyplot as plt +import pandas as pd +import os +import numpy as np + +def create_plot(t, actual, desired, xlabel, ylabel, title, legend, save_path=None): + plt.figure() + plt.plot(t, actual) + plt.plot(t, desired) + overshoot = np.max(np.array(actual) - np.array(desired)) + rmse = np.sqrt(np.mean((np.array(actual) - np.array(desired))**2)) + print(f'{title} - Maximum Overshoot: {overshoot}, RMSE: {rmse}') + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(f'{title} (Max Overshoot: {overshoot:.2f}, RMSE: {rmse:.2f})') + plt.legend(legend) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + plt.close() + +def create_error_plot(t, error, xlabel, ylabel, title, save_path=None): + plt.figure() + plt.plot(t, error) + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(title) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + plt.close() + +def main(log_folder): + if log_folder is None: + return + df = pd.read_csv(log_folder + '/PurePursuitTrajectoryTracker_debug.csv') + save_figures =True + + plots_folder = os.path.join(log_folder, 'plots') + os.makedirs(plots_folder, exist_ok=True) + + t = df['curr pt[0] vehicle time'].tolist() + x = df['curr pt[0]'].tolist() + y = df['curr pt[1]'].tolist() + v = df['current speed (m/s)'].tolist() + yaw = df['current yaw (rad)'].tolist() + + xd = df['desired pt[0]'].tolist() + yd = df['desired pt[1]'].tolist() + vd = df['desired speed (m/s)'].tolist() + yawd = df['desired yaw (rad)'].tolist() + + cte = df['crosstrack error'].tolist() + front_wheel_angle = df['front wheel angle (rad)'].tolist() + accel = df['output accel (m/s^2)'].tolist() + + + + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + + max_accel_error = np.max((np.array(accel) - 1.0)**2) + print(f'Maximum (acceleration - 1.0)^2: {max_accel_error}') + + rms_forward_acceleration = np.sqrt(np.mean(np.array(accel)**2)) + print(f'RMS of Acceleration: {rms_forward_acceleration}') + + dt = np.mean(np.diff(t)) + jerk = np.gradient(np.array(accel), dt) + rms_jerk = np.sqrt(np.mean(jerk**2)) + print(f'RMS of Jerk: {rms_jerk}') + + w1, w2 = 0.7, 0.3 + comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + print(f'Comfort Index: {comfort_index}') + + + create_plot(t, y, yd, '$t$ (s)', '$y(t)$, $y_{d}(t)$ (m)', 'Actual and Desired y', ['Actual $y(t)$', 'Desired $y_{d}(t)$'], os.path.join(plots_folder, 'y_vs_yd.png') if save_figures else None) + create_error_plot(t, np.array(y) - np.array(yd), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error between Actual and Desired $y(t)$', os.path.join(plots_folder, 'error_y.png') if save_figures else None) + + create_plot(t, x, xd, '$t$ (s)', '$x(t)$, $x_{d}(t)$ (m)', 'Actual and Desired x', ['Actual $x(t)$', 'Desired $x_{d}(t)$'], os.path.join(plots_folder, 'x_vs_xd.png') if save_figures else None) + create_error_plot(t, np.array(x) - np.array(xd), '$t$ (s)', 'Error in $x(t)$ (m)', 'Error between Actual and Desired $x(t)$', os.path.join(plots_folder, 'error_x.png') if save_figures else None) + + create_plot(t, v, vd, '$t$ (s)', '$v(t)$, $v_{d}(t)$ (m/s)', 'Actual and Desired v', ['Actual $v(t)$', 'Desired $v_{d}(t)$'], os.path.join(plots_folder, 'v_vs_vd.png') if save_figures else None) + create_error_plot(t, np.array(v) - np.array(vd), '$t$ (s)', 'Error in $v(t)$ (m/s)', 'Error between Actual and Desired $v(t)$', os.path.join(plots_folder, 'error_v.png') if save_figures else None) + + plt.figure() + plt.plot(t, cte) + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + plt.xlabel('$t$ (s)') + plt.ylabel('Crosstrack Error (m)') + plt.title(f'Crosstrack Error over Time (RMSE: {rmse_cte:.2f})') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'cte.png'), dpi=600) + plt.close() + + plt.figure() + plt.plot(t, front_wheel_angle) + plt.xlabel('$t$ (s)') + plt.ylabel('Front Wheel Angle (rad)') + plt.title('Front Wheel Angle over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'front_wheel_angle.png'), dpi=600) + plt.close() + + plt.figure() + plt.plot(t, accel) + plt.xlabel('$t$ (s)') + plt.ylabel('Acceleration (m/s^2)') + plt.title('Acceleration over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'accel.png'), dpi=600) + plt.close() + + + + +if __name__ == '__main__': + # Change this to the log folder you want to plot if running this script manually + log_folder = '2025-02-13_21-10-39' + main(log_folder) From 90acf7cdddbd28bbb5165f67c25f415fe7c69a3b Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 01:20:12 -0800 Subject: [PATCH 2/8] add speed error as a factor of comfort index --- GEMstack/utils/log_plot.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/GEMstack/utils/log_plot.py b/GEMstack/utils/log_plot.py index 1cfeadf75..9a8f33e65 100644 --- a/GEMstack/utils/log_plot.py +++ b/GEMstack/utils/log_plot.py @@ -3,6 +3,8 @@ import os import numpy as np +# Most of the code in this file is copied from ./tuning_logs/log_plot.py by Mikayel Aramyan (mikayel2) + def create_plot(t, actual, desired, xlabel, ylabel, title, legend, save_path=None): plt.figure() plt.plot(t, actual) @@ -70,8 +72,12 @@ def main(log_folder): rms_jerk = np.sqrt(np.mean(jerk**2)) print(f'RMS of Jerk: {rms_jerk}') - w1, w2 = 0.7, 0.3 - comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + speed_error = np.array(v) - np.array(vd) + rms_speed_error = np.sqrt(np.mean(speed_error**2)) + print(f'RMS of Speed Error: {rms_speed_error}') + + w1, w2, w3 = 0.5, 0.3, 0.2 + comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + w3 * rms_speed_error print(f'Comfort Index: {comfort_index}') From 92e4ba80d9d571e3c26f8b4e82a61bf3a66f6421 Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 01:59:45 -0800 Subject: [PATCH 3/8] fix a typo for log folder --- GEMstack/onboard/execution/entrypoint.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index d9351a3cf..f20621bbd 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -122,7 +122,7 @@ def caution_callback(k,variant): #configure logging if log_settings: - topfolder = log_settings.get('log','logs') + topfolder = log_settings.get('folder','logs') prefix = log_settings.get('prefix','') from datetime import datetime default_suffix = datetime.now().strftime('%Y-%m-%d_%H-%M-%S') From bb666ba8618d89aba11f7662d2aa8c2b78955b47 Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 02:52:20 -0800 Subject: [PATCH 4/8] add safety index --- GEMstack/utils/log_plot.py | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/GEMstack/utils/log_plot.py b/GEMstack/utils/log_plot.py index 9a8f33e65..09abdc00e 100644 --- a/GEMstack/utils/log_plot.py +++ b/GEMstack/utils/log_plot.py @@ -76,10 +76,27 @@ def main(log_folder): rms_speed_error = np.sqrt(np.mean(speed_error**2)) print(f'RMS of Speed Error: {rms_speed_error}') + angular_velocity = np.gradient(front_wheel_angle, dt) + angular_acceleration = np.gradient(angular_velocity, dt) + angular_jerk = np.gradient(angular_acceleration, dt) + rms_angular_acceleration = np.sqrt(np.mean(angular_acceleration**2)) + rms_angular_jerk = np.sqrt(np.mean(angular_jerk**2)) + print(f'RMS of Angular Acceleration: {rms_angular_acceleration}') + print(f'RMS of Angular Jerk: {rms_angular_jerk}') + + yaw_error = np.array(yaw) - np.array(yawd) + rms_yaw_error = np.sqrt(np.mean(yaw_error**2)) + print(f'RMS of Yaw Error: {rms_yaw_error}') + w1, w2, w3 = 0.5, 0.3, 0.2 comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + w3 * rms_speed_error - print(f'Comfort Index: {comfort_index}') + print(f'=====Comfort Index: {comfort_index}=====') + w1, w2, w3, w4, w5, w6, w7 = 0.2, 0.1, 0.15, 0.2, 0.15, 0.2, 0.1 + safety_index = (w1 * rmse_cte + w2 * rms_angular_jerk + w3 * rms_angular_acceleration + + w4 * rms_forward_acceleration + w5 * rms_jerk + w6 * rms_speed_error + + w7 * rms_yaw_error) + print(f'=====Safety Index: {safety_index}=====') create_plot(t, y, yd, '$t$ (s)', '$y(t)$, $y_{d}(t)$ (m)', 'Actual and Desired y', ['Actual $y(t)$', 'Desired $y_{d}(t)$'], os.path.join(plots_folder, 'y_vs_yd.png') if save_figures else None) create_error_plot(t, np.array(y) - np.array(yd), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error between Actual and Desired $y(t)$', os.path.join(plots_folder, 'error_y.png') if save_figures else None) From 24347d51aee402343ae51c0128d7d9ec4e1d5b9e Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 03:00:53 -0800 Subject: [PATCH 5/8] format metrics to 2 decimal places --- GEMstack/utils/log_plot.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/GEMstack/utils/log_plot.py b/GEMstack/utils/log_plot.py index 09abdc00e..e2b11753f 100644 --- a/GEMstack/utils/log_plot.py +++ b/GEMstack/utils/log_plot.py @@ -90,13 +90,13 @@ def main(log_folder): w1, w2, w3 = 0.5, 0.3, 0.2 comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + w3 * rms_speed_error - print(f'=====Comfort Index: {comfort_index}=====') + print(f'===== Comfort Index: {comfort_index:.2f} =====') w1, w2, w3, w4, w5, w6, w7 = 0.2, 0.1, 0.15, 0.2, 0.15, 0.2, 0.1 safety_index = (w1 * rmse_cte + w2 * rms_angular_jerk + w3 * rms_angular_acceleration + w4 * rms_forward_acceleration + w5 * rms_jerk + w6 * rms_speed_error + w7 * rms_yaw_error) - print(f'=====Safety Index: {safety_index}=====') + print(f'===== Safety Index: {safety_index:.2f} =====') create_plot(t, y, yd, '$t$ (s)', '$y(t)$, $y_{d}(t)$ (m)', 'Actual and Desired y', ['Actual $y(t)$', 'Desired $y_{d}(t)$'], os.path.join(plots_folder, 'y_vs_yd.png') if save_figures else None) create_error_plot(t, np.array(y) - np.array(yd), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error between Actual and Desired $y(t)$', os.path.join(plots_folder, 'error_y.png') if save_figures else None) From e14d743eff66a55e530ca838fddac87b5392533e Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 03:22:44 -0800 Subject: [PATCH 6/8] add auto_plot attribute in log as comment --- launch/blink_launch.yaml | 2 ++ launch/fixed_route.yaml | 2 ++ launch/gather_data.yaml | 2 ++ launch/pedestrian_detection.yaml | 2 ++ 4 files changed, 8 insertions(+) diff --git a/launch/blink_launch.yaml b/launch/blink_launch.yaml index f8b60eb2d..ab28ae31a 100644 --- a/launch/blink_launch.yaml +++ b/launch/blink_launch.yaml @@ -38,6 +38,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index c05de8ff7..924ae1a9b 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -43,6 +43,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/launch/gather_data.yaml b/launch/gather_data.yaml index 4f3d03d4c..e04e8337d 100644 --- a/launch/gather_data.yaml +++ b/launch/gather_data.yaml @@ -37,6 +37,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/launch/pedestrian_detection.yaml b/launch/pedestrian_detection.yaml index 62dd8f202..edb0dde47 100644 --- a/launch/pedestrian_detection.yaml +++ b/launch/pedestrian_detection.yaml @@ -52,6 +52,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: From 90c25fdbf9b2aff5ff83dcd5c45e046314f482db Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 03:26:06 -0800 Subject: [PATCH 7/8] add result for fake_sim with pedestrian_detection.yaml --- .../PurePursuitTrajectoryTracker_debug.csv | 1241 ++++++++ tuning logs/2025-02-25_02-59-27/behavior.json | 2834 +++++++++++++++++ tuning logs/2025-02-25_02-59-27/meta.yaml | 19 + .../2025-02-25_02-59-27/plots/accel.png | Bin 0 -> 229317 bytes tuning logs/2025-02-25_02-59-27/plots/cte.png | Bin 0 -> 153700 bytes .../2025-02-25_02-59-27/plots/error_v.png | Bin 0 -> 207875 bytes .../2025-02-25_02-59-27/plots/error_x.png | Bin 0 -> 221104 bytes .../2025-02-25_02-59-27/plots/error_y.png | Bin 0 -> 135775 bytes .../plots/front_wheel_angle.png | Bin 0 -> 144089 bytes .../2025-02-25_02-59-27/plots/v_vs_vd.png | Bin 0 -> 326630 bytes .../2025-02-25_02-59-27/plots/x_vs_xd.png | Bin 0 -> 279814 bytes .../2025-02-25_02-59-27/plots/y_vs_yd.png | Bin 0 -> 192169 bytes tuning logs/2025-02-25_02-59-27/settings.yaml | 335 ++ 13 files changed, 4429 insertions(+) create mode 100644 tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv create mode 100644 tuning logs/2025-02-25_02-59-27/behavior.json create mode 100644 tuning logs/2025-02-25_02-59-27/meta.yaml create mode 100644 tuning logs/2025-02-25_02-59-27/plots/accel.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/cte.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_v.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_x.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_y.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/v_vs_vd.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/x_vs_xd.png create mode 100644 tuning logs/2025-02-25_02-59-27/plots/y_vs_yd.png create mode 100644 tuning logs/2025-02-25_02-59-27/settings.yaml diff --git a/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv new file mode 100644 index 000000000..5ba243644 --- /dev/null +++ b/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv @@ -0,0 +1,1241 @@ +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),Past the end of trajectory time,Past the end of trajectory vehicle time +1740481168.1550307,0.019999980926513672,0.0,1740481168.1550329,0.019999980926513672,0.0,1740481168.1550357,0.019999980926513672,0.0,1740481168.1550379,0.019999980926513672,2.0,1740481168.155039,0.019999980926513672,0.0,1740481168.1550407,0.019999980926513672,0.0,1740481168.1550417,0.019999980926513672,0.0,1740481168.1550431,0.019999980926513672,0.0,1740481168.155044,0.019999980926513672,0.061237243569579464,1740481168.1550453,0.019999980926513672,0.0,1740481168.1550467,0.019999980926513672,0.061237243569579464,1740481168.1550477,0.019999980926513672,0.0,1740481168.1550488,0.019999980926513672,0.0,1740481175.818341,7.639992713928223 +1740481168.1736927,0.039999961853027344,0.0,1740481168.1736946,0.039999961853027344,0.0,1740481168.173697,0.039999961853027344,0.0,1740481168.1736991,0.039999961853027344,2.0,1740481168.1737,0.039999961853027344,0.0,1740481168.1737013,0.039999961853027344,0.0,1740481168.1737027,0.039999961853027344,0.0,1740481168.1737037,0.039999961853027344,0.0,1740481168.1737046,0.039999961853027344,0.061237243569579464,1740481168.1737056,0.039999961853027344,0.0,1740481168.1737065,0.039999961853027344,0.061237243569579464,1740481168.1737075,0.039999961853027344,0.0,1740481168.1737082,0.039999961853027344,0.0,1740481175.838934,7.659992694854736 +1740481168.1907423,0.059999942779541016,0.0,1740481168.1907442,0.059999942779541016,0.0,1740481168.1907463,0.059999942779541016,0.0,1740481168.1907485,0.059999942779541016,2.0,1740481168.1907494,0.059999942779541016,0.0,1740481168.1907508,0.059999942779541016,0.0,1740481168.190752,0.059999942779541016,0.0,1740481168.1907527,0.059999942779541016,0.0,1740481168.1907537,0.059999942779541016,0.061237243569579464,1740481168.190755,0.059999942779541016,0.0,1740481168.1907556,0.059999942779541016,0.061237243569579464,1740481168.1907566,0.059999942779541016,0.0,1740481168.1907573,0.059999942779541016,0.0,1740481175.85758,7.67999267578125 +1740481168.210773,0.08999991416931152,9.179463234421092e-05,1740481168.2107751,0.08999991416931152,0.0,1740481168.210777,0.08999991416931152,9.179463234421094e-07,1740481168.2107792,0.08999991416931152,2.0073402035928103,1740481168.2107801,0.08999991416931152,0.0,1740481168.210781,0.08999991416931152,0.0,1740481168.2107825,0.08999991416931152,0.0,1740481168.2107832,0.08999991416931152,0.0,1740481168.2107842,0.08999991416931152,0.061237243569579464,1740481168.2107854,0.08999991416931152,1.0,1740481168.2107863,0.08999991416931152,1.0558995796904764,1740481168.210787,0.08999991416931152,0.0,1740481168.210788,0.08999991416931152,0.003669642823243459,1740481175.8787684,7.699992656707764 +1740481168.23064,0.09999990463256836,9.179463234421092e-05,1740481168.2306416,0.09999990463256836,0.0,1740481168.2306437,0.09999990463256836,9.179463234421094e-07,1740481168.2306461,0.09999990463256836,2.0073402035928103,1740481168.230647,0.09999990463256836,0.0,1740481168.2306483,0.09999990463256836,0.0,1740481168.2306497,0.09999990463256836,0.0,1740481168.2306507,0.09999990463256836,0.0,1740481168.2306516,0.09999990463256836,0.061237243569579464,1740481168.2306528,0.09999990463256836,1.0,1740481168.230654,0.09999990463256836,1.057567600746336,1740481168.230655,0.09999990463256836,0.0,1740481168.230656,0.09999990463256836,0.003669642823243459,1740481175.897922,7.719992637634277 +1740481168.2537935,0.11999988555908203,9.179463234421092e-05,1740481168.2537951,0.11999988555908203,0.0,1740481168.2537973,0.11999988555908203,0.0,1740481168.2537997,0.11999988555908203,2.007431080278831,1740481168.2538004,0.11999988555908203,0.0,1740481168.2538018,0.11999988555908203,0.0,1740481168.253803,0.11999988555908203,0.0,1740481168.253804,0.11999988555908203,0.0,1740481168.2538047,0.11999988555908203,0.06490688639282292,1740481168.2538059,0.11999988555908203,0.0,1740481168.2538068,0.11999988555908203,0.061237243569579464,1740481168.2538075,0.11999988555908203,0.0,1740481168.2538085,0.11999988555908203,0.003669642823243459,1740481175.9188528,7.739992618560791 +1740481168.2718706,0.14999985694885254,9.179463234421092e-05,1740481168.2718735,0.14999985694885254,0.0,1740481168.2718768,0.14999985694885254,0.0,1740481168.271879,0.14999985694885254,2.007431080278831,1740481168.27188,0.14999985694885254,0.0,1740481168.271881,0.14999985694885254,0.0,1740481168.2718823,0.14999985694885254,0.0,1740481168.2718832,0.14999985694885254,0.0,1740481168.2718842,0.14999985694885254,0.06490688639282292,1740481168.2718854,0.14999985694885254,0.0,1740481168.2718863,0.14999985694885254,0.061237243569579464,1740481168.271887,0.14999985694885254,0.0,1740481168.2718885,0.14999985694885254,0.003669642823243459,1740481175.9376323,7.759992599487305 +1740481168.2922604,0.1699998378753662,9.179463234421092e-05,1740481168.292262,0.1699998378753662,0.0,1740481168.2922645,0.1699998378753662,0.0,1740481168.2922666,0.1699998378753662,2.007431080278831,1740481168.2922676,0.1699998378753662,0.0,1740481168.292269,0.1699998378753662,0.0,1740481168.2922702,0.1699998378753662,0.0,1740481168.2922711,0.1699998378753662,0.0,1740481168.292272,0.1699998378753662,0.06490688639282292,1740481168.2922728,0.1699998378753662,0.0,1740481168.292274,0.1699998378753662,0.061237243569579464,1740481168.292275,0.1699998378753662,0.0,1740481168.292276,0.1699998378753662,0.003669642823243459,1740481175.9577725,7.779992580413818 +1740481168.3110068,0.18999981880187988,9.179463234421092e-05,1740481168.311009,0.18999981880187988,0.0,1740481168.3110113,0.18999981880187988,0.0,1740481168.311014,0.18999981880187988,2.007431080278831,1740481168.311015,0.18999981880187988,0.0,1740481168.311016,0.18999981880187988,0.0,1740481168.3110175,0.18999981880187988,0.0,1740481168.3110187,0.18999981880187988,0.0,1740481168.3110197,0.18999981880187988,0.06490688639282292,1740481168.3110209,0.18999981880187988,0.0,1740481168.3110218,0.18999981880187988,0.061237243569579464,1740481168.3110228,0.18999981880187988,0.0,1740481168.311024,0.18999981880187988,0.003669642823243459,1740481175.9780724,7.799992561340332 +1740481168.3316643,0.20999979972839355,0.004016390192037811,1740481168.3316665,0.20999979972839355,0.0,1740481168.3316684,0.20999979972839355,4.159777012846354e-05,1740481168.3316705,0.20999979972839355,2.0956501663273044,1740481168.3316715,0.20999979972839355,0.0,1740481168.331673,0.20999979972839355,0.0,1740481168.3316739,0.20999979972839355,0.0,1740481168.331675,0.20999979972839355,0.0,1740481168.331676,0.20999979972839355,0.06490688639282292,1740481168.331677,0.20999979972839355,1.0,1740481168.3316777,0.20999979972839355,0.9971081420733545,1740481168.3316786,0.20999979972839355,0.0,1740481168.3316796,0.20999979972839355,0.04775838696241595,1740481175.9982026,7.819992542266846 +1740481168.3549738,0.22999978065490723,0.004016390192037811,1740481168.3549755,0.22999978065490723,0.0,1740481168.3549778,0.22999978065490723,0.0,1740481168.3549798,0.22999978065490723,2.0995331641168695,1740481168.354981,0.22999978065490723,0.0,1740481168.3549821,0.22999978065490723,0.0,1740481168.3549833,0.22999978065490723,0.0,1740481168.3549845,0.22999978065490723,0.0,1740481168.3549855,0.22999978065490723,0.10899563053199542,1740481168.3549864,0.22999978065490723,0.0,1740481168.3549876,0.22999978065490723,0.061237243569579464,1740481168.3549883,0.22999978065490723,0.0,1740481168.3549893,0.22999978065490723,0.04775838696241595,1740481176.0186145,7.839992523193359 +1740481168.3719118,0.2499997615814209,0.004016390192037811,1740481168.3719134,0.2499997615814209,0.0,1740481168.3719158,0.2499997615814209,0.0,1740481168.3719177,0.2499997615814209,2.0995331641168695,1740481168.3719192,0.2499997615814209,0.0,1740481168.3719203,0.2499997615814209,0.0,1740481168.3719213,0.2499997615814209,0.0,1740481168.3719227,0.2499997615814209,0.0,1740481168.3719234,0.2499997615814209,0.10899563053199542,1740481168.3719244,0.2499997615814209,0.0,1740481168.3719256,0.2499997615814209,0.061237243569579464,1740481168.3719265,0.2499997615814209,0.0,1740481168.3719273,0.2499997615814209,0.04775838696241595,1740481176.0383296,7.859992504119873 +1740481168.3913038,0.26999974250793457,0.004016390192037811,1740481168.3913054,0.26999974250793457,0.0,1740481168.3913076,0.26999974250793457,0.0,1740481168.3913097,0.26999974250793457,2.0995331641168695,1740481168.391311,0.26999974250793457,0.0,1740481168.3913121,0.26999974250793457,0.0,1740481168.391313,0.26999974250793457,0.0,1740481168.3913143,0.26999974250793457,0.0,1740481168.3913152,0.26999974250793457,0.10899563053199542,1740481168.3913164,0.26999974250793457,0.0,1740481168.3913176,0.26999974250793457,0.061237243569579464,1740481168.3913186,0.26999974250793457,0.0,1740481168.3913195,0.26999974250793457,0.04775838696241595,1740481176.0575826,7.879992485046387 +1740481168.411221,0.28999972343444824,0.004016390192037811,1740481168.411223,0.28999972343444824,0.0,1740481168.4112253,0.28999972343444824,0.0,1740481168.4112275,0.28999972343444824,2.0995331641168695,1740481168.4112284,0.28999972343444824,0.0,1740481168.4112294,0.28999972343444824,0.0,1740481168.4112308,0.28999972343444824,0.0,1740481168.4112318,0.28999972343444824,0.0,1740481168.4112327,0.28999972343444824,0.10899563053199542,1740481168.4112334,0.28999972343444824,0.0,1740481168.4112346,0.28999972343444824,0.061237243569579464,1740481168.4112356,0.28999972343444824,0.0,1740481168.4112363,0.28999972343444824,0.04775838696241595,1740481176.0782351,7.8999924659729 +1740481168.431356,0.3099997043609619,0.011180782430692204,1740481168.4313579,0.3099997043609619,0.0,1740481168.4313602,0.3099997043609619,0.00012751838650990288,1740481168.4313624,0.3099997043609619,2.149841769486342,1740481168.4313784,0.3099997043609619,0.0,1740481168.43138,0.3099997043609619,0.0,1740481168.431381,0.3099997043609619,0.0,1740481168.4313822,0.3099997043609619,0.0,1740481168.4313831,0.3099997043609619,0.10899563053199542,1740481168.431384,0.3099997043609619,1.0,1740481168.431385,0.3099997043609619,1.0247418967055022,1740481168.4313858,0.3099997043609619,0.0,1740481168.431387,0.3099997043609619,0.07284893045389727,1740481176.1017585,7.919992446899414 +1740481168.4542625,0.31999969482421875,0.011180782430692204,1740481168.4542668,0.31999969482421875,0.0,1740481168.4542692,0.31999969482421875,0.0,1740481168.4542713,0.31999969482421875,2.156878643338487,1740481168.4542723,0.31999969482421875,0.0,1740481168.4542732,0.31999969482421875,0.0,1740481168.4542747,0.31999969482421875,0.0,1740481168.4542756,0.31999969482421875,0.0,1740481168.4542763,0.31999969482421875,0.13408617402347675,1740481168.4542773,0.31999969482421875,0.0,1740481168.4542782,0.31999969482421875,0.06123724356957948,1740481168.4542792,0.31999969482421875,0.0,1740481168.45428,0.31999969482421875,0.07284893045389727,1740481176.1185913,7.939992427825928 +1740481168.4715338,0.34999966621398926,0.011180782430692204,1740481168.4715357,0.34999966621398926,0.0,1740481168.4715378,0.34999966621398926,0.0,1740481168.4715607,0.34999966621398926,2.156878643338487,1740481168.471562,0.34999966621398926,0.0,1740481168.4715633,0.34999966621398926,0.0,1740481168.4715645,0.34999966621398926,0.0,1740481168.4715655,0.34999966621398926,0.0,1740481168.4715664,0.34999966621398926,0.13408617402347675,1740481168.4715674,0.34999966621398926,0.0,1740481168.4715683,0.34999966621398926,0.06123724356957948,1740481168.471583,0.34999966621398926,0.0,1740481168.471584,0.34999966621398926,0.07284893045389727,1740481176.138666,7.959992408752441 +1740481168.491414,0.3599996566772461,0.011180782430692204,1740481168.4914157,0.3599996566772461,0.0,1740481168.4914181,0.3599996566772461,0.0,1740481168.4914203,0.3599996566772461,2.156878643338487,1740481168.4914212,0.3599996566772461,0.0,1740481168.4914227,0.3599996566772461,0.0,1740481168.491424,0.3599996566772461,0.0,1740481168.4914248,0.3599996566772461,0.0,1740481168.491426,0.3599996566772461,0.13408617402347675,1740481168.4914272,0.3599996566772461,0.0,1740481168.4914281,0.3599996566772461,0.06123724356957948,1740481168.4914289,0.3599996566772461,0.0,1740481168.4914298,0.3599996566772461,0.07284893045389727,1740481176.1583812,7.979992389678955 +1740481168.5106363,0.37999963760375977,0.011180782430692204,1740481168.510638,0.37999963760375977,0.0,1740481168.5106404,0.37999963760375977,0.0,1740481168.5106428,0.37999963760375977,2.156878643338487,1740481168.5106435,0.37999963760375977,0.0,1740481168.510645,0.37999963760375977,0.0,1740481168.510646,0.37999963760375977,0.0,1740481168.510647,0.37999963760375977,0.0,1740481168.510648,0.37999963760375977,0.13408617402347675,1740481168.5106492,0.37999963760375977,0.0,1740481168.5106502,0.37999963760375977,0.06123724356957948,1740481168.510651,0.37999963760375977,0.0,1740481168.5106518,0.37999963760375977,0.07284893045389727,1740481176.1776118,7.999992370605469 +1740481168.5316155,0.4099996089935303,0.011180782430692204,1740481168.5316172,0.4099996089935303,0.0,1740481168.5316195,0.4099996089935303,0.0,1740481168.5316217,0.4099996089935303,2.156878643338487,1740481168.5316226,0.4099996089935303,0.0,1740481168.531624,0.4099996089935303,0.0,1740481168.5316255,0.4099996089935303,0.0,1740481168.5316265,0.4099996089935303,0.0,1740481168.5316272,0.4099996089935303,0.13408617402347675,1740481168.5316284,0.4099996089935303,0.0,1740481168.5316293,0.4099996089935303,0.06123724356957948,1740481168.5316303,0.4099996089935303,0.0,1740481168.5316315,0.4099996089935303,0.07284893045389727,1740481176.1982167,8.019992351531982 +1740481168.5550847,0.42999958992004395,0.02128988060126069,1740481168.5550866,0.42999958992004395,0.0,1740481168.555089,0.42999958992004395,0.0,1740481168.555091,0.42999958992004395,2.216980844298003,1740481168.5550919,0.42999958992004395,0.0,1740481168.5550933,0.42999958992004395,0.0,1740481168.5550942,0.42999958992004395,0.0,1740481168.5550952,0.42999958992004395,0.0,1740481168.5550961,0.42999958992004395,0.15908272541795052,1740481168.555097,0.42999958992004395,1.0,1740481168.555098,0.42999958992004395,1.0612372435695794,1740481168.5550988,0.42999958992004395,0.0,1740481168.5551002,0.42999958992004395,0.09784548184837108,1740481176.2188554,8.039992332458496 +1740481168.5717857,0.4399995803833008,0.02128988060126069,1740481168.5717878,0.4399995803833008,0.0,1740481168.5717897,0.4399995803833008,0.0,1740481168.571792,0.4399995803833008,2.216980844298003,1740481168.571793,0.4399995803833008,0.0,1740481168.5717945,0.4399995803833008,0.0,1740481168.5717955,0.4399995803833008,0.0,1740481168.5717964,0.4399995803833008,0.0,1740481168.5717976,0.4399995803833008,0.15908272541795052,1740481168.5717986,0.4399995803833008,1.0,1740481168.5717995,0.4399995803833008,1.0612372435695794,1740481168.5718005,0.4399995803833008,0.0,1740481168.5718017,0.4399995803833008,0.09784548184837108,1740481176.2375052,8.05999231338501 +1740481168.591285,0.4699995517730713,0.02128988060126069,1740481168.591287,0.4699995517730713,0.0,1740481168.591289,0.4699995517730713,0.0,1740481168.5912912,0.4699995517730713,2.216980844298003,1740481168.5912921,0.4699995517730713,0.0,1740481168.5912933,0.4699995517730713,0.0,1740481168.5912948,0.4699995517730713,0.0,1740481168.5912957,0.4699995517730713,0.0,1740481168.5912967,0.4699995517730713,0.15908272541795052,1740481168.5912979,0.4699995517730713,1.0,1740481168.5912988,0.4699995517730713,1.0612372435695794,1740481168.5912995,0.4699995517730713,0.0,1740481168.5913007,0.4699995517730713,0.09784548184837108,1740481176.2581203,8.079992294311523 +1740481168.6114552,0.48999953269958496,0.02128988060126069,1740481168.6114573,0.48999953269958496,0.0,1740481168.6114593,0.48999953269958496,0.0,1740481168.6114614,0.48999953269958496,2.216980844298003,1740481168.6114624,0.48999953269958496,0.0,1740481168.611464,0.48999953269958496,0.0,1740481168.611465,0.48999953269958496,0.0,1740481168.6114662,0.48999953269958496,0.0,1740481168.6114674,0.48999953269958496,0.15908272541795052,1740481168.6114683,0.48999953269958496,1.0,1740481168.6114693,0.48999953269958496,1.0612372435695794,1740481168.61147,0.48999953269958496,0.0,1740481168.6114712,0.48999953269958496,0.09784548184837108,1740481176.2775009,8.099992275238037 +1740481168.6330137,0.5099995136260986,0.02128988060126069,1740481168.633016,0.5099995136260986,0.0,1740481168.6330187,0.5099995136260986,0.0,1740481168.6330419,0.5099995136260986,2.216980844298003,1740481168.633043,0.5099995136260986,0.0,1740481168.6330445,0.5099995136260986,0.0,1740481168.6330454,0.5099995136260986,0.0,1740481168.6330469,0.5099995136260986,0.0,1740481168.6330478,0.5099995136260986,0.15908272541795052,1740481168.633049,0.5099995136260986,1.0,1740481168.6330502,0.5099995136260986,1.0612372435695794,1740481168.633051,0.5099995136260986,0.0,1740481168.6330519,0.5099995136260986,0.09784548184837108,1740481176.2985492,8.11999225616455 +1740481168.6543286,0.5199995040893555,0.02128988060126069,1740481168.654331,0.5199995040893555,0.0,1740481168.6543334,0.5199995040893555,0.0,1740481168.6543357,0.5199995040893555,2.216980844298003,1740481168.6543367,0.5199995040893555,0.0,1740481168.6543381,0.5199995040893555,0.0,1740481168.6543393,0.5199995040893555,0.0,1740481168.6543403,0.5199995040893555,0.0,1740481168.6543415,0.5199995040893555,0.15908272541795052,1740481168.6543427,0.5199995040893555,1.0,1740481168.6543436,0.5199995040893555,1.0612372435695794,1740481168.654345,0.5199995040893555,0.0,1740481168.6543462,0.5199995040893555,0.09784548184837108,1740481176.3194714,8.139992237091064 +1740481168.6774688,0.549999475479126,0.03658030270426593,1740481168.6774707,0.549999475479126,0.0,1740481168.6774728,0.549999475479126,0.0003972161186799886,1740481168.6774745,0.549999475479126,2.4170292552071655,1740481168.6774757,0.549999475479126,0.0,1740481168.677477,0.549999475479126,0.0,1740481168.677478,0.549999475479126,0.0,1740481168.6774793,0.549999475479126,0.0,1740481168.6774802,0.549999475479126,0.2815572125571095,1740481168.6774812,0.549999475479126,0.0,1740481168.6774821,0.549999475479126,0.09418109301513448,1740481168.6774833,0.549999475479126,0.0,1740481168.6774843,0.549999475479126,0.19767107924361257,1740481176.3397815,8.159992218017578 +1740481168.7391875,0.5899994373321533,0.03658030270426593,1740481168.7391894,0.5899994373321533,0.0,1740481168.7391918,0.5899994373321533,0.0003972161186799886,1740481168.7391942,0.5899994373321533,2.4170292552071655,1740481168.7391949,0.5899994373321533,0.0,1740481168.739196,0.5899994373321533,0.0,1740481168.7391975,0.5899994373321533,0.0,1740481168.7391984,0.5899994373321533,0.0,1740481168.7391994,0.5899994373321533,0.2815572125571095,1740481168.7392006,0.5899994373321533,0.0,1740481168.7392013,0.5899994373321533,0.08388613331349695,1740481168.7392023,0.5899994373321533,0.0,1740481168.7392032,0.5899994373321533,0.19767107924361257,1740481176.3589513,8.179992198944092 +1740481168.7969403,0.6299993991851807,0.03658030270426593,1740481168.7969422,0.6299993991851807,0.0,1740481168.7969449,0.6299993991851807,0.0,1740481168.7969472,0.6299993991851807,2.431922461191491,1740481168.7969482,0.6299993991851807,0.0,1740481168.7969494,0.6299993991851807,0.0,1740481168.7969506,0.6299993991851807,0.0,1740481168.7969515,0.6299993991851807,0.0,1740481168.7969525,0.6299993991851807,0.25890832281319204,1740481168.7969537,0.6299993991851807,0.0,1740481168.7969546,0.6299993991851807,0.061237243569579464,1740481168.7969556,0.6299993991851807,0.0,1740481168.7969568,0.6299993991851807,0.19767107924361257,1740481176.3779638,8.199992179870605 +1740481169.0216656,0.8399991989135742,0.08542104944423468,1740481169.0216675,0.8399991989135742,0.0,1740481169.0216696,0.8399991989135742,0.0,1740481169.0216718,0.8399991989135742,2.5446043705295285,1740481169.0216727,0.8399991989135742,0.0,1740481169.021674,0.8399991989135742,0.0,1740481169.0216753,0.8399991989135742,0.0,1740481169.0216763,0.8399991989135742,0.0,1740481169.0216773,0.8399991989135742,0.4133033912513854,1740481169.0216784,0.8399991989135742,0.0,1740481169.0216792,0.8399991989135742,0.21154686796783906,1740481169.02168,0.8399991989135742,0.0,1740481169.021681,0.8399991989135742,0.229591660542647,1740481176.3975103,8.21999216079712 +1740481169.0410554,0.8599991798400879,0.11094645689171756,1740481169.0410576,0.8599991798400879,0.0,1740481169.0410604,0.8599991798400879,0.0012122567643879484,1740481169.0410626,0.8599991798400879,2.5596240043301326,1740481169.0410638,0.8599991798400879,0.0,1740481169.0410652,0.8599991798400879,0.0,1740481169.0410664,0.8599991798400879,0.0,1740481169.0410678,0.8599991798400879,0.0,1740481169.0410688,0.8599991798400879,0.5357778783905444,1740481169.0410695,0.8599991798400879,0.0,1740481169.0410707,0.8599991798400879,0.3518147606198158,1740481169.0410717,0.8599991798400879,0.0,1740481169.0410724,0.8599991798400879,0.2364953490607551,1740481176.419309,8.239992141723633 +1740481169.056597,0.8799991607666016,0.11094645689171756,1740481169.0565994,0.8799991607666016,0.0,1740481169.0566015,0.8799991607666016,0.0012122567643879484,1740481169.056604,0.8799991607666016,2.5596240043301326,1740481169.0566049,0.8799991607666016,0.0,1740481169.0566063,0.8799991607666016,0.0,1740481169.0566075,0.8799991607666016,0.0,1740481169.0566084,0.8799991607666016,0.0,1740481169.05661,0.8799991607666016,0.5357778783905444,1740481169.056611,0.8799991607666016,0.0,1740481169.0566123,0.8799991607666016,0.29928252932978927,1740481169.056614,0.8799991607666016,0.0,1740481169.056615,0.8799991607666016,0.2364953490607551,1740481176.4394772,8.259992122650146 +1740481169.0771894,0.8999991416931152,0.11094645689171756,1740481169.0771914,0.8999991416931152,0.0,1740481169.0771935,0.8999991416931152,0.0012122567643879484,1740481169.077196,0.8999991416931152,2.5596240043301326,1740481169.0771968,0.8999991416931152,0.0,1740481169.077198,0.8999991416931152,0.0,1740481169.0771995,0.8999991416931152,0.0,1740481169.0772002,0.8999991416931152,0.0,1740481169.0772011,0.8999991416931152,0.5357778783905444,1740481169.077202,0.8999991416931152,0.0,1740481169.0772033,0.8999991416931152,0.29928252932978927,1740481169.077204,0.8999991416931152,0.0,1740481169.077205,0.8999991416931152,0.2364953490607551,1740481176.4592218,8.27999210357666 +1740481169.0964708,0.9199991226196289,0.11094645689171756,1740481169.0964725,0.9199991226196289,0.0,1740481169.0964751,0.9199991226196289,0.0012122567643879484,1740481169.0964773,0.9199991226196289,2.5596240043301326,1740481169.0964782,0.9199991226196289,0.0,1740481169.0964794,0.9199991226196289,0.0,1740481169.0964808,0.9199991226196289,0.0,1740481169.0964816,0.9199991226196289,0.0,1740481169.0964825,0.9199991226196289,0.5357778783905444,1740481169.0964835,0.9199991226196289,0.0,1740481169.0964844,0.9199991226196289,0.29928252932978927,1740481169.0964854,0.9199991226196289,0.0,1740481169.0964866,0.9199991226196289,0.2364953490607551,1740481176.4786985,8.299992084503174 +1740481169.1263273,0.9399991035461426,0.11094645689171756,1740481169.1263297,0.9399991035461426,0.0,1740481169.126332,0.9399991035461426,0.0,1740481169.1263342,0.9399991035461426,2.5839371550132277,1740481169.1263354,0.9399991035461426,0.0,1740481169.1263368,0.9399991035461426,0.0,1740481169.126338,0.9399991035461426,0.0,1740481169.1263394,0.9399991035461426,0.0,1740481169.1263404,0.9399991035461426,0.2977325926303346,1740481169.1263413,0.9399991035461426,0.0,1740481169.1263423,0.9399991035461426,0.06123724356957949,1740481169.1263435,0.9399991035461426,0.0,1740481169.1263444,0.9399991035461426,0.2364953490607551,1740481176.4974556,8.319992065429688 +1740481169.1386058,0.9599990844726562,0.11094645689171756,1740481169.1386082,0.9599990844726562,0.0,1740481169.1386106,0.9599990844726562,0.0,1740481169.138613,0.9599990844726562,2.5839371550132277,1740481169.138614,0.9599990844726562,0.0,1740481169.1386156,0.9599990844726562,0.0,1740481169.1386168,0.9599990844726562,0.0,1740481169.1386178,0.9599990844726562,0.0,1740481169.138619,0.9599990844726562,0.2977325926303346,1740481169.13862,0.9599990844726562,0.0,1740481169.138621,0.9599990844726562,0.06123724356957949,1740481169.1386223,0.9599990844726562,0.0,1740481169.1386232,0.9599990844726562,0.2364953490607551,1740481176.5210686,8.339992046356201 +1740481169.1595428,0.9799990653991699,0.1386120652195162,1740481169.1595445,0.9799990653991699,0.0,1740481169.1595469,0.9799990653991699,0.0013450888403838438,1740481169.159549,0.9799990653991699,2.6407979801627057,1740481169.15955,0.9799990653991699,0.0,1740481169.1595511,0.9799990653991699,0.0,1740481169.1595523,0.9799990653991699,0.0,1740481169.1595533,0.9799990653991699,0.0,1740481169.1595542,0.9799990653991699,0.2977325926303346,1740481169.1595554,0.9799990653991699,1.0,1740481169.1595562,0.9799990653991699,1.0208621505847875,1740481169.159557,0.9799990653991699,0.0,1740481169.159558,0.9799990653991699,0.26425321721530226,1740481176.5377154,8.359992027282715 +1740481169.1782062,0.9999990463256836,0.1386120652195162,1740481169.1782084,0.9999990463256836,0.0,1740481169.1782105,0.9999990463256836,0.0013450888403838438,1740481169.1782126,0.9999990463256836,2.6407979801627057,1740481169.1782136,0.9999990463256836,0.0,1740481169.178215,0.9999990463256836,0.0,1740481169.1782162,0.9999990463256836,0.0,1740481169.1782172,0.9999990463256836,0.0,1740481169.1782181,0.9999990463256836,0.2977325926303346,1740481169.1782193,0.9999990463256836,1.0,1740481169.1782203,0.9999990463256836,1.0334793754150322,1740481169.1782212,0.9999990463256836,0.0,1740481169.1782224,0.9999990463256836,0.26425321721530226,1740481176.5585482,8.379992008209229 +1740481169.1991549,1.0199990272521973,0.1386120652195162,1740481169.1991572,1.0199990272521973,0.0,1740481169.1991594,1.0199990272521973,0.0013450888403838438,1740481169.1991615,1.0199990272521973,2.6407979801627057,1740481169.1991627,1.0199990272521973,0.0,1740481169.199164,1.0199990272521973,0.0,1740481169.1991649,1.0199990272521973,0.0,1740481169.199166,1.0199990272521973,0.0,1740481169.199167,1.0199990272521973,0.2977325926303346,1740481169.199168,1.0199990272521973,1.0,1740481169.199169,1.0199990272521973,1.0334793754150322,1740481169.19917,1.0199990272521973,0.0,1740481169.199171,1.0199990272521973,0.26425321721530226,1740481176.5802834,8.399991989135742 +1740481169.2240694,1.039999008178711,0.1386120652195162,1740481169.224073,1.039999008178711,0.0,1740481169.224077,1.039999008178711,0.0,1740481169.2240794,1.039999008178711,2.6671184996501207,1740481169.2240803,1.039999008178711,0.0,1740481169.2240822,1.039999008178711,0.0,1740481169.2240834,1.039999008178711,0.0,1740481169.2240849,1.039999008178711,0.0,1740481169.2240863,1.039999008178711,0.3254904607848818,1740481169.2240875,1.039999008178711,0.0,1740481169.2240891,1.039999008178711,0.06123724356957955,1740481169.2240915,1.039999008178711,0.0,1740481169.2240932,1.039999008178711,0.26425321721530226,1740481176.598306,8.419991970062256 +1740481169.2386713,1.0599989891052246,0.1386120652195162,1740481169.2386734,1.0599989891052246,0.0,1740481169.2386756,1.0599989891052246,0.0,1740481169.238678,1.0599989891052246,2.6671184996501207,1740481169.238679,1.0599989891052246,0.0,1740481169.2386804,1.0599989891052246,0.0,1740481169.2386813,1.0599989891052246,0.0,1740481169.2386825,1.0599989891052246,0.0,1740481169.2386837,1.0599989891052246,0.3254904607848818,1740481169.2386847,1.0599989891052246,0.0,1740481169.2386856,1.0599989891052246,0.06123724356957955,1740481169.2386868,1.0599989891052246,0.0,1740481169.2386878,1.0599989891052246,0.26425321721530226,1740481176.6188796,8.43999195098877 +1740481169.258961,1.0799989700317383,0.17187636392815353,1740481169.2589626,1.0799989700317383,0.0,1740481169.2589648,1.0799989700317383,0.0017680763018110275,1740481169.258967,1.0799989700317383,2.8102564131064374,1740481169.258968,1.0799989700317383,0.0,1740481169.2589693,1.0799989700317383,0.0,1740481169.2589703,1.0799989700317383,0.0,1740481169.2589715,1.0799989700317383,0.0,1740481169.2589724,1.0799989700317383,0.3254904607848818,1740481169.2589734,1.0799989700317383,1.0,1740481169.2589746,1.0799989700317383,0.9584227859070047,1740481169.2589755,1.0799989700317383,0.0,1740481169.2589765,1.0799989700317383,0.3349381357925551,1740481176.6380754,8.459991931915283 +1740481169.2778692,1.099998950958252,0.17187636392815353,1740481169.2778711,1.099998950958252,0.0,1740481169.2778735,1.099998950958252,0.0017680763018110275,1740481169.2778754,1.099998950958252,2.8102564131064374,1740481169.2778764,1.099998950958252,0.0,1740481169.2778778,1.099998950958252,0.0,1740481169.2778788,1.099998950958252,0.0,1740481169.2778797,1.099998950958252,0.0,1740481169.277881,1.099998950958252,0.3254904607848818,1740481169.2778816,1.099998950958252,1.0,1740481169.2778955,1.099998950958252,0.9905523249923267,1740481169.2778983,1.099998950958252,0.0,1740481169.2778993,1.099998950958252,0.3349381357925551,1740481176.6598272,8.479991912841797 +1740481169.2983742,1.1199989318847656,0.17187636392815353,1740481169.2983758,1.1199989318847656,0.0,1740481169.2983782,1.1199989318847656,0.0017680763018110275,1740481169.2983806,1.1199989318847656,2.8102564131064374,1740481169.2983816,1.1199989318847656,0.0,1740481169.2983828,1.1199989318847656,0.0,1740481169.298384,1.1199989318847656,0.0,1740481169.298385,1.1199989318847656,0.0,1740481169.2983859,1.1199989318847656,0.3254904607848818,1740481169.298387,1.1199989318847656,1.0,1740481169.2983878,1.1199989318847656,0.9905523249923267,1740481169.298389,1.1199989318847656,0.0,1740481169.29839,1.1199989318847656,0.3349381357925551,1740481176.678172,8.49999189376831 +1740481169.3222163,1.1399989128112793,0.17187636392815353,1740481169.322222,1.1399989128112793,0.0,1740481169.322225,1.1399989128112793,0.0,1740481169.3222275,1.1399989128112793,2.841752635513264,1740481169.3222284,1.1399989128112793,0.0,1740481169.3222306,1.1399989128112793,0.0,1740481169.3222318,1.1399989128112793,0.0,1740481169.3222337,1.1399989128112793,0.0,1740481169.322235,1.1399989128112793,0.39617537936213454,1740481169.3222368,1.1399989128112793,0.0,1740481169.3222387,1.1399989128112793,0.061237243569579436,1740481169.3222404,1.1399989128112793,0.0,1740481169.3222415,1.1399989128112793,0.3349381357925551,1740481176.6995654,8.519991874694824 +1740481169.3391926,1.159998893737793,0.17187636392815353,1740481169.3391945,1.159998893737793,0.0,1740481169.339197,1.159998893737793,0.0,1740481169.339199,1.159998893737793,2.841752635513264,1740481169.3392,1.159998893737793,0.0,1740481169.3392012,1.159998893737793,0.0,1740481169.3392024,1.159998893737793,0.0,1740481169.3392034,1.159998893737793,0.0,1740481169.3392043,1.159998893737793,0.39617537936213454,1740481169.3392053,1.159998893737793,0.0,1740481169.3392065,1.159998893737793,0.061237243569579436,1740481169.3392074,1.159998893737793,0.0,1740481169.3392084,1.159998893737793,0.3349381357925551,1740481176.7200031,8.539991855621338 +1740481169.3585055,1.1799988746643066,0.17187636392815353,1740481169.358508,1.1799988746643066,0.0,1740481169.3585105,1.1799988746643066,0.0,1740481169.35853,1.1799988746643066,2.841752635513264,1740481169.3585312,1.1799988746643066,0.0,1740481169.3585327,1.1799988746643066,0.0,1740481169.3585336,1.1799988746643066,0.0,1740481169.3585348,1.1799988746643066,0.0,1740481169.358536,1.1799988746643066,0.39617537936213454,1740481169.3585374,1.1799988746643066,0.0,1740481169.3585384,1.1799988746643066,0.061237243569579436,1740481169.3585396,1.1799988746643066,0.0,1740481169.3585405,1.1799988746643066,0.3349381357925551,1740481176.737952,8.559991836547852 +1740481169.3798795,1.1999988555908203,0.21344188182821888,1740481169.3798814,1.1999988555908203,0.0,1740481169.3798835,1.1999988555908203,0.002689088185971574,1740481169.3798857,1.1999988555908203,2.982260865605955,1740481169.3798866,1.1999988555908203,0.0,1740481169.3798878,1.1999988555908203,0.0,1740481169.379889,1.1999988555908203,0.0,1740481169.37989,1.1999988555908203,0.0,1740481169.379891,1.1999988555908203,0.39617537936213454,1740481169.3798919,1.1999988555908203,1.0,1740481169.3798928,1.1999988555908203,0.9610051104931695,1740481169.3798938,1.1999988555908203,0.0,1740481169.3798947,1.1999988555908203,0.40384770674591486,1740481176.7598326,8.579991817474365 +1740481169.3981311,1.219998836517334,0.21344188182821888,1740481169.3981342,1.219998836517334,0.0,1740481169.3981378,1.219998836517334,0.002689088185971574,1740481169.3981407,1.219998836517334,2.982260865605955,1740481169.3981428,1.219998836517334,0.0,1740481169.3981445,1.219998836517334,0.0,1740481169.3981466,1.219998836517334,0.0,1740481169.3981483,1.219998836517334,0.0,1740481169.3981502,1.219998836517334,0.39617537936213454,1740481169.398152,1.219998836517334,1.0,1740481169.3981538,1.219998836517334,0.9923276726162197,1740481169.3981555,1.219998836517334,0.0,1740481169.3981574,1.219998836517334,0.40384770674591486,1740481176.778266,8.599991798400879 +1740481169.4276063,1.2399988174438477,0.21344188182821888,1740481169.4276085,1.2399988174438477,0.0,1740481169.4276109,1.2399988174438477,0.0,1740481169.427613,1.2399988174438477,3.021137295320049,1740481169.427614,1.2399988174438477,0.0,1740481169.4276152,1.2399988174438477,0.0,1740481169.4276164,1.2399988174438477,0.0,1740481169.4276173,1.2399988174438477,0.0,1740481169.4276183,1.2399988174438477,0.4650849503154945,1740481169.427619,1.2399988174438477,0.0,1740481169.4276202,1.2399988174438477,0.06123724356957966,1740481169.4276211,1.2399988174438477,0.0,1740481169.4276218,1.2399988174438477,0.40384770674591486,1740481176.7982213,8.619991779327393 +1740481169.4390292,1.2599987983703613,0.21344188182821888,1740481169.4390316,1.2599987983703613,0.0,1740481169.4390357,1.2599987983703613,0.0,1740481169.439038,1.2599987983703613,3.021137295320049,1740481169.439039,1.2599987983703613,0.0,1740481169.4390404,1.2599987983703613,0.0,1740481169.4390416,1.2599987983703613,0.0,1740481169.4390428,1.2599987983703613,0.0,1740481169.4390442,1.2599987983703613,0.4650849503154945,1740481169.4390461,1.2599987983703613,0.0,1740481169.439047,1.2599987983703613,0.06123724356957966,1740481169.4390485,1.2599987983703613,0.0,1740481169.439063,1.2599987983703613,0.40384770674591486,1740481176.8189104,8.639991760253906 +1740481169.4578896,1.279998779296875,0.21344188182821888,1740481169.4578912,1.279998779296875,0.0,1740481169.4578936,1.279998779296875,0.0,1740481169.457896,1.279998779296875,3.021137295320049,1740481169.457897,1.279998779296875,0.0,1740481169.4578981,1.279998779296875,0.0,1740481169.457985,1.279998779296875,0.0,1740481169.4579866,1.279998779296875,0.0,1740481169.4579875,1.279998779296875,0.4650849503154945,1740481169.4579885,1.279998779296875,0.0,1740481169.4579897,1.279998779296875,0.06123724356957966,1740481169.4579906,1.279998779296875,0.0,1740481169.4579916,1.279998779296875,0.40384770674591486,1740481176.8391314,8.65999174118042 +1740481169.478042,1.2999987602233887,0.2612812321811804,1740481169.4780438,1.2999987602233887,0.0,1740481169.4780462,1.2999987602233887,0.0036333055809006642,1740481169.4780486,1.2999987602233887,3.124898057195178,1740481169.4780495,1.2999987602233887,0.0,1740481169.4780507,1.2999987602233887,0.0,1740481169.478052,1.2999987602233887,0.0,1740481169.4780529,1.2999987602233887,0.0,1740481169.4780538,1.2999987602233887,0.4650849503154945,1740481169.478055,1.2999987602233887,1.0,1740481169.478056,1.2999987602233887,0.988417253653533,1740481169.478057,1.2999987602233887,0.0,1740481169.478058,1.2999987602233887,0.45391143489302915,1740481176.8589654,8.679991722106934 +1740481169.4983923,1.3199987411499023,0.2612812321811804,1740481169.4983943,1.3199987411499023,0.0,1740481169.4983966,1.3199987411499023,0.0036333055809006642,1740481169.498399,1.3199987411499023,3.124898057195178,1740481169.4984002,1.3199987411499023,0.0,1740481169.4984016,1.3199987411499023,0.0,1740481169.4984028,1.3199987411499023,0.0,1740481169.4984038,1.3199987411499023,0.0,1740481169.498405,1.3199987411499023,0.4650849503154945,1740481169.4984062,1.3199987411499023,1.0,1740481169.4984071,1.3199987411499023,1.0111735154224655,1740481169.498408,1.3199987411499023,0.0,1740481169.4984093,1.3199987411499023,0.45391143489302915,1740481176.8794858,8.699991703033447 +1740481169.528807,1.339998722076416,0.2612812321811804,1740481169.528809,1.339998722076416,0.0,1740481169.5288112,1.339998722076416,0.0,1740481169.5288134,1.339998722076416,3.1691041019672386,1740481169.5288143,1.339998722076416,0.0,1740481169.5288155,1.339998722076416,0.0,1740481169.5288167,1.339998722076416,0.0,1740481169.5288177,1.339998722076416,0.0,1740481169.5288186,1.339998722076416,0.5151486784626086,1740481169.5288198,1.339998722076416,0.0,1740481169.5288205,1.339998722076416,0.061237243569579436,1740481169.5288215,1.339998722076416,0.0,1740481169.5288224,1.339998722076416,0.45391143489302915,1740481176.8975391,8.719991683959961 +1740481169.5385935,1.3599987030029297,0.2612812321811804,1740481169.5385957,1.3599987030029297,0.0,1740481169.5385978,1.3599987030029297,0.0,1740481169.5386002,1.3599987030029297,3.1691041019672386,1740481169.5386012,1.3599987030029297,0.0,1740481169.5386026,1.3599987030029297,0.0,1740481169.5386038,1.3599987030029297,0.0,1740481169.538605,1.3599987030029297,0.0,1740481169.5386062,1.3599987030029297,0.5151486784626086,1740481169.5386071,1.3599987030029297,0.0,1740481169.5386083,1.3599987030029297,0.061237243569579436,1740481169.5386095,1.3599987030029297,0.0,1740481169.5386105,1.3599987030029297,0.45391143489302915,1740481176.9193647,8.739991664886475 +1740481169.5599134,1.3799986839294434,0.2612812321811804,1740481169.5599155,1.3799986839294434,0.0,1740481169.5599182,1.3799986839294434,0.0,1740481169.5599203,1.3799986839294434,3.1691041019672386,1740481169.5599215,1.3799986839294434,0.0,1740481169.5599227,1.3799986839294434,0.0,1740481169.559924,1.3799986839294434,0.0,1740481169.559925,1.3799986839294434,0.0,1740481169.5599263,1.3799986839294434,0.5151486784626086,1740481169.5599272,1.3799986839294434,0.0,1740481169.5599284,1.3799986839294434,0.061237243569579436,1740481169.5599294,1.3799986839294434,0.0,1740481169.5599303,1.3799986839294434,0.45391143489302915,1740481176.938086,8.759991645812988 +1740481169.5782979,1.399998664855957,0.2612812321811804,1740481169.5782998,1.399998664855957,0.0,1740481169.5783017,1.399998664855957,0.0,1740481169.578304,1.399998664855957,3.1691041019672386,1740481169.578305,1.399998664855957,0.0,1740481169.5783062,1.399998664855957,0.0,1740481169.5783074,1.399998664855957,0.0,1740481169.5783083,1.399998664855957,0.0,1740481169.5783093,1.399998664855957,0.5151486784626086,1740481169.5783105,1.399998664855957,0.0,1740481169.5783114,1.399998664855957,0.061237243569579436,1740481169.5783124,1.399998664855957,0.0,1740481169.578313,1.399998664855957,0.45391143489302915,1740481176.9599748,8.779991626739502 +1740481169.5985923,1.4199986457824707,0.31513679521697924,1740481169.598595,1.4199986457824707,0.0,1740481169.598597,1.4199986457824707,0.004530514521645381,1740481169.5985994,1.4199986457824707,3.2746061918453018,1740481169.5986006,1.4199986457824707,0.0,1740481169.598603,1.4199986457824707,0.0,1740481169.598605,1.4199986457824707,0.0,1740481169.598606,1.4199986457824707,0.0,1740481169.5986073,1.4199986457824707,0.5151486784626086,1740481169.5986087,1.4199986457824707,1.0,1740481169.5986097,1.4199986457824707,0.9878033486980732,1740481169.5986109,1.4199986457824707,0.0,1740481169.5986125,1.4199986457824707,0.5043972225712381,1740481176.9777746,8.799991607666016 +1740481169.632012,1.4399986267089844,0.31513679521697924,1740481169.632014,1.4399986267089844,0.0,1740481169.6320164,1.4399986267089844,0.0,1740481169.6320183,1.4399986267089844,3.3239312403594554,1740481169.6320195,1.4399986267089844,0.0,1740481169.6320207,1.4399986267089844,0.0,1740481169.632022,1.4399986267089844,0.0,1740481169.632023,1.4399986267089844,0.0,1740481169.632024,1.4399986267089844,0.5656344661408178,1740481169.632025,1.4399986267089844,0.0,1740481169.6320262,1.4399986267089844,0.061237243569579713,1740481169.6320271,1.4399986267089844,0.0,1740481169.632028,1.4399986267089844,0.5043972225712381,1740481176.9978573,8.81999158859253 +1740481169.638486,1.459998607635498,0.31513679521697924,1740481169.6384883,1.459998607635498,0.0,1740481169.6384907,1.459998607635498,0.0,1740481169.6384928,1.459998607635498,3.3239312403594554,1740481169.6384943,1.459998607635498,0.0,1740481169.6384954,1.459998607635498,0.0,1740481169.638512,1.459998607635498,0.0,1740481169.638513,1.459998607635498,0.0,1740481169.6385143,1.459998607635498,0.5656344661408178,1740481169.6385155,1.459998607635498,0.0,1740481169.6385164,1.459998607635498,0.061237243569579713,1740481169.6385176,1.459998607635498,0.0,1740481169.6385188,1.459998607635498,0.5043972225712381,1740481177.0183895,8.839991569519043 +1740481169.6578226,1.4799985885620117,0.31513679521697924,1740481169.6578248,1.4799985885620117,0.0,1740481169.6578271,1.4799985885620117,0.0,1740481169.657829,1.4799985885620117,3.3239312403594554,1740481169.6578302,1.4799985885620117,0.0,1740481169.657832,1.4799985885620117,0.0,1740481169.657833,1.4799985885620117,0.0,1740481169.6578343,1.4799985885620117,0.0,1740481169.6578352,1.4799985885620117,0.5656344661408178,1740481169.6578362,1.4799985885620117,0.0,1740481169.6578374,1.4799985885620117,0.061237243569579713,1740481169.657838,1.4799985885620117,0.0,1740481169.657839,1.4799985885620117,0.5043972225712381,1740481177.038142,8.859991550445557 +1740481169.6778302,1.4999985694885254,0.31513679521697924,1740481169.677832,1.4999985694885254,0.0,1740481169.6778343,1.4999985694885254,0.0,1740481169.6778367,1.4999985694885254,3.3239312403594554,1740481169.6778376,1.4999985694885254,0.0,1740481169.6778388,1.4999985694885254,0.0,1740481169.6778398,1.4999985694885254,0.0,1740481169.677841,1.4999985694885254,0.0,1740481169.677842,1.4999985694885254,0.5656344661408178,1740481169.6778429,1.4999985694885254,0.0,1740481169.677844,1.4999985694885254,0.061237243569579713,1740481169.677845,1.4999985694885254,0.0,1740481169.6778462,1.4999985694885254,0.5043972225712381,1740481177.0587397,8.87999153137207 +1740481169.6985795,1.519998550415039,0.37357836674119493,1740481169.6985815,1.519998550415039,0.0,1740481169.6985836,1.519998550415039,0.005398114804427861,1740481169.6985857,1.519998550415039,3.4104611495706667,1740481169.698587,1.519998550415039,0.0,1740481169.6985884,1.519998550415039,0.0,1740481169.6985893,1.519998550415039,0.0,1740481169.6985905,1.519998550415039,0.0,1740481169.6985915,1.519998550415039,0.5656344661408178,1740481169.6985924,1.519998550415039,1.0,1740481169.6985936,1.519998550415039,1.0022322845979683,1740481169.6985943,1.519998550415039,0.0,1740481169.6985953,1.519998550415039,0.5449631197746299,1740481177.0777144,8.899991512298584 +1740481169.7229435,1.5399985313415527,0.37357836674119493,1740481169.7229457,1.5399985313415527,0.0,1740481169.7229483,1.5399985313415527,0.0,1740481169.7229507,1.5399985313415527,3.4635046062904546,1740481169.7229517,1.5399985313415527,0.0,1740481169.7229528,1.5399985313415527,0.0,1740481169.7229543,1.5399985313415527,0.0,1740481169.7229552,1.5399985313415527,0.0,1740481169.7229562,1.5399985313415527,0.6062003633442093,1740481169.7229576,1.5399985313415527,0.0,1740481169.7229583,1.5399985313415527,0.06123724356957949,1740481169.7229593,1.5399985313415527,0.0,1740481169.7229605,1.5399985313415527,0.5449631197746299,1740481177.0974593,8.919991493225098 +1740481169.7393231,1.5599985122680664,0.37357836674119493,1740481169.7393253,1.5599985122680664,0.0,1740481169.7393274,1.5599985122680664,0.0,1740481169.7393296,1.5599985122680664,3.4635046062904546,1740481169.7393308,1.5599985122680664,0.0,1740481169.7393322,1.5599985122680664,0.0,1740481169.7393334,1.5599985122680664,0.0,1740481169.7393343,1.5599985122680664,0.0,1740481169.7393355,1.5599985122680664,0.6062003633442093,1740481169.7393367,1.5599985122680664,0.0,1740481169.7393377,1.5599985122680664,0.06123724356957949,1740481169.7393386,1.5599985122680664,0.0,1740481169.7393396,1.5599985122680664,0.5449631197746299,1740481177.1187258,8.939991474151611 +1740481169.7583575,1.57999849319458,0.37357836674119493,1740481169.7583597,1.57999849319458,0.0,1740481169.7583618,1.57999849319458,0.0,1740481169.758364,1.57999849319458,3.4635046062904546,1740481169.758365,1.57999849319458,0.0,1740481169.7583663,1.57999849319458,0.0,1740481169.7583678,1.57999849319458,0.0,1740481169.758369,1.57999849319458,0.0,1740481169.7583702,1.57999849319458,0.6062003633442093,1740481169.758371,1.57999849319458,0.0,1740481169.7583723,1.57999849319458,0.06123724356957949,1740481169.7583733,1.57999849319458,0.0,1740481169.7583745,1.57999849319458,0.5449631197746299,1740481177.1378493,8.959991455078125 +1740481169.7781882,1.5999984741210938,0.37357836674119493,1740481169.7781904,1.5999984741210938,0.0,1740481169.778193,1.5999984741210938,0.0,1740481169.7781951,1.5999984741210938,3.4635046062904546,1740481169.7781963,1.5999984741210938,0.0,1740481169.7781975,1.5999984741210938,0.0,1740481169.7781985,1.5999984741210938,0.0,1740481169.7782001,1.5999984741210938,0.0,1740481169.7782013,1.5999984741210938,0.6062003633442093,1740481169.7782028,1.5999984741210938,0.0,1740481169.778204,1.5999984741210938,0.06123724356957949,1740481169.778205,1.5999984741210938,0.0,1740481169.7782059,1.5999984741210938,0.5449631197746299,1740481177.1576073,8.979991436004639 +1740481169.7984197,1.6199984550476074,0.37357836674119493,1740481169.7984219,1.6199984550476074,0.0,1740481169.7984269,1.6199984550476074,0.0,1740481169.7984297,1.6199984550476074,3.4635046062904546,1740481169.7984307,1.6199984550476074,0.0,1740481169.798432,1.6199984550476074,0.0,1740481169.798433,1.6199984550476074,0.0,1740481169.7984343,1.6199984550476074,0.0,1740481169.798435,1.6199984550476074,0.6062003633442093,1740481169.7984362,1.6199984550476074,0.0,1740481169.798437,1.6199984550476074,0.06123724356957949,1740481169.7984378,1.6199984550476074,0.0,1740481169.798439,1.6199984550476074,0.5449631197746299,1740481177.1781566,8.999991416931152 +1740481169.8232284,1.639998435974121,0.4362230129252156,1740481169.8232307,1.639998435974121,0.0,1740481169.8232334,1.639998435974121,0.0,1740481169.8232355,1.639998435974121,3.588969008392792,1740481169.8232367,1.639998435974121,0.0,1740481169.8232381,1.639998435974121,0.0,1740481169.823239,1.639998435974121,0.0,1740481169.8232405,1.639998435974121,0.0,1740481169.8232415,1.639998435974121,0.6376102413033673,1740481169.823243,1.639998435974121,1.0,1740481169.823244,1.639998435974121,1.061237243569579,1740481169.823245,1.639998435974121,0.0,1740481169.823246,1.639998435974121,0.5763729977337881,1740481177.19819,9.019991397857666 +1740481169.839048,1.6599984169006348,0.4362230129252156,1740481169.83905,1.6599984169006348,0.0,1740481169.839053,1.6599984169006348,0.0,1740481169.8390553,1.6599984169006348,3.588969008392792,1740481169.8390565,1.6599984169006348,0.0,1740481169.839058,1.6599984169006348,0.0,1740481169.839059,1.6599984169006348,0.0,1740481169.8390605,1.6599984169006348,0.0,1740481169.8390615,1.6599984169006348,0.6376102413033673,1740481169.8390627,1.6599984169006348,1.0,1740481169.839064,1.6599984169006348,1.0612372435695792,1740481169.8390648,1.6599984169006348,0.0,1740481169.8390658,1.6599984169006348,0.5763729977337881,1740481177.2236977,9.03999137878418 +1740481169.8585994,1.6799983978271484,0.4362230129252156,1740481169.8586016,1.6799983978271484,0.0,1740481169.858604,1.6799983978271484,0.0,1740481169.8586063,1.6799983978271484,3.588969008392792,1740481169.8586073,1.6799983978271484,0.0,1740481169.858609,1.6799983978271484,0.0,1740481169.8586102,1.6799983978271484,0.0,1740481169.858611,1.6799983978271484,0.0,1740481169.8586125,1.6799983978271484,0.6376102413033673,1740481169.8586135,1.6799983978271484,1.0,1740481169.8586144,1.6799983978271484,1.0612372435695792,1740481169.8586159,1.6799983978271484,0.0,1740481169.858617,1.6799983978271484,0.5763729977337881,1740481177.2378645,9.059991359710693 +1740481169.8804579,1.699998378753662,0.4362230129252156,1740481169.8804624,1.699998378753662,0.0,1740481169.8804655,1.699998378753662,0.0,1740481169.8804862,1.699998378753662,3.588969008392792,1740481169.8804898,1.699998378753662,0.0,1740481169.8804924,1.699998378753662,0.0,1740481169.8804946,1.699998378753662,0.0,1740481169.8804967,1.699998378753662,0.0,1740481169.8804986,1.699998378753662,0.6376102413033673,1740481169.8805008,1.699998378753662,1.0,1740481169.8805025,1.699998378753662,1.0612372435695792,1740481169.880504,1.699998378753662,0.0,1740481169.8805053,1.699998378753662,0.5763729977337881,1740481177.2599726,9.079991340637207 +1740481169.8983943,1.7199983596801758,0.4362230129252156,1740481169.8983965,1.7199983596801758,0.0,1740481169.8983989,1.7199983596801758,0.0,1740481169.8984013,1.7199983596801758,3.588969008392792,1740481169.898402,1.7199983596801758,0.0,1740481169.898404,1.7199983596801758,0.0,1740481169.8984048,1.7199983596801758,0.0,1740481169.898406,1.7199983596801758,0.0,1740481169.8984072,1.7199983596801758,0.6376102413033673,1740481169.8984082,1.7199983596801758,1.0,1740481169.8984091,1.7199983596801758,1.0612372435695792,1740481169.8984103,1.7199983596801758,0.0,1740481169.898411,1.7199983596801758,0.5763729977337881,1740481177.2781425,9.09999132156372 +1740481169.9235692,1.7399983406066895,0.503158444844102,1740481169.9235713,1.7399983406066895,0.0,1740481169.9235742,1.7399983406066895,0.0,1740481169.9235764,1.7399983406066895,3.8308441580711294,1740481169.9235773,1.7399983406066895,0.0,1740481169.923579,1.7399983406066895,0.0,1740481169.92358,1.7399983406066895,0.0,1740481169.923581,1.7399983406066895,0.0,1740481169.9235818,1.7399983406066895,0.7250801001830938,1740481169.923583,1.7399983406066895,1.0,1740481169.923584,1.7399983406066895,1.0612372435695803,1740481169.9235852,1.7399983406066895,0.0,1740481169.9235864,1.7399983406066895,0.6638428566135138,1740481177.300216,9.119991302490234 +1740481169.9388692,1.7599983215332031,0.503158444844102,1740481169.9388714,1.7599983215332031,0.0,1740481169.9388735,1.7599983215332031,0.0,1740481169.938876,1.7599983215332031,3.8308441580711294,1740481169.9388769,1.7599983215332031,0.0,1740481169.9388785,1.7599983215332031,0.0,1740481169.9388795,1.7599983215332031,0.0,1740481169.9388807,1.7599983215332031,0.0,1740481169.9388819,1.7599983215332031,0.7250801001830938,1740481169.938883,1.7599983215332031,1.0,1740481169.9388838,1.7599983215332031,1.0612372435695798,1740481169.938885,1.7599983215332031,0.0,1740481169.938886,1.7599983215332031,0.6638428566135138,1740481177.3187077,9.139991283416748 +1740481169.9582236,1.7799983024597168,0.503158444844102,1740481169.9582255,1.7799983024597168,0.0,1740481169.9582279,1.7799983024597168,0.0,1740481169.9582305,1.7799983024597168,3.8308441580711294,1740481169.9582312,1.7799983024597168,0.0,1740481169.9582329,1.7799983024597168,0.0,1740481169.9582338,1.7799983024597168,0.0,1740481169.958235,1.7799983024597168,0.0,1740481169.958236,1.7799983024597168,0.7250801001830938,1740481169.9582372,1.7799983024597168,1.0,1740481169.9582381,1.7799983024597168,1.0612372435695798,1740481169.9582393,1.7799983024597168,0.0,1740481169.9582403,1.7799983024597168,0.6638428566135138,1740481177.3380313,9.159991264343262 +1740481169.9780123,1.7999982833862305,0.503158444844102,1740481169.978027,1.7999982833862305,0.0,1740481169.9780307,1.7999982833862305,0.0,1740481169.978033,1.7999982833862305,3.8308441580711294,1740481169.978034,1.7999982833862305,0.0,1740481169.9780354,1.7999982833862305,0.0,1740481169.9780364,1.7999982833862305,0.0,1740481169.9780376,1.7999982833862305,0.0,1740481169.9780385,1.7999982833862305,0.7250801001830938,1740481169.9780395,1.7999982833862305,1.0,1740481169.9780407,1.7999982833862305,1.0612372435695798,1740481169.9780416,1.7999982833862305,0.0,1740481169.9780426,1.7999982833862305,0.6638428566135138,1740481177.3575745,9.179991245269775 +1740481169.9979775,1.8199982643127441,0.503158444844102,1740481169.9979792,1.8199982643127441,0.0,1740481169.9979818,1.8199982643127441,0.0,1740481169.997984,1.8199982643127441,3.8308441580711294,1740481169.997985,1.8199982643127441,0.0,1740481169.9979863,1.8199982643127441,0.0,1740481169.9979873,1.8199982643127441,0.0,1740481169.9979885,1.8199982643127441,0.0,1740481169.9979892,1.8199982643127441,0.7250801001830938,1740481169.9979904,1.8199982643127441,1.0,1740481169.997991,1.8199982643127441,1.0612372435695798,1740481169.9979923,1.8199982643127441,0.0,1740481169.997993,1.8199982643127441,0.6638428566135138,1740481177.3792105,9.199991226196289 +1740481170.0222797,1.8399982452392578,0.503158444844102,1740481170.0222814,1.8399982452392578,0.0,1740481170.0222843,1.8399982452392578,0.0,1740481170.0222864,1.8399982452392578,3.8308441580711294,1740481170.0222874,1.8399982452392578,0.0,1740481170.0222886,1.8399982452392578,0.0,1740481170.0222898,1.8399982452392578,0.0,1740481170.0222907,1.8399982452392578,0.0,1740481170.0222917,1.8399982452392578,0.7250801001830938,1740481170.0223053,1.8399982452392578,1.0,1740481170.022307,1.8399982452392578,1.0612372435695798,1740481170.0223079,1.8399982452392578,0.0,1740481170.0223086,1.8399982452392578,0.6638428566135138,1740481177.3978274,9.219991207122803 +1740481170.0382164,1.8599982261657715,0.5814642529667085,1740481170.038218,1.8599982261657715,0.0,1740481170.03822,1.8599982261657715,0.009271805830702503,1740481170.038222,1.8599982261657715,4.051168484433473,1740481170.038223,1.8599982261657715,0.0,1740481170.0382245,1.8599982261657715,0.0,1740481170.0382252,1.8599982261657715,0.0,1740481170.0382261,1.8599982261657715,0.0,1740481170.038227,1.8599982261657715,0.8475545873222521,1740481170.0382283,1.8599982261657715,0.0,1740481170.038229,1.8599982261657715,0.0858892172776643,1740481170.03823,1.8599982261657715,0.0,1740481170.0382311,1.8599982261657715,0.7693691168793342,1740481177.4189968,9.239991188049316 +1740481170.0585172,1.8799982070922852,0.5814642529667085,1740481170.0585194,1.8799982070922852,0.0,1740481170.0585213,1.8799982070922852,0.009271805830702503,1740481170.0585234,1.8799982070922852,4.051168484433473,1740481170.0585244,1.8799982070922852,0.0,1740481170.0585258,1.8799982070922852,0.0,1740481170.058527,1.8799982070922852,0.0,1740481170.058528,1.8799982070922852,0.0,1740481170.0585291,1.8799982070922852,0.8475545873222521,1740481170.0585303,1.8799982070922852,0.0,1740481170.058531,1.8799982070922852,0.0781854704429179,1740481170.058532,1.8799982070922852,0.0,1740481170.0585332,1.8799982070922852,0.7693691168793342,1740481177.4387093,9.25999116897583 +1740481170.0788612,1.8999981880187988,0.5814642529667085,1740481170.0788667,1.8999981880187988,0.0,1740481170.078871,1.8999981880187988,0.009271805830702503,1740481170.0788739,1.8999981880187988,4.051168484433473,1740481170.0788767,1.8999981880187988,0.0,1740481170.0788786,1.8999981880187988,0.0,1740481170.07888,1.8999981880187988,0.0,1740481170.078882,1.8999981880187988,0.0,1740481170.078884,1.8999981880187988,0.8475545873222521,1740481170.0788865,1.8999981880187988,0.0,1740481170.0788887,1.8999981880187988,0.0781854704429179,1740481170.07889,1.8999981880187988,0.0,1740481170.0788915,1.8999981880187988,0.7693691168793342,1740481177.4577487,9.279991149902344 +1740481170.0982373,1.9199981689453125,0.5814642529667085,1740481170.0982392,1.9199981689453125,0.0,1740481170.0982413,1.9199981689453125,0.009271805830702503,1740481170.0982432,1.9199981689453125,4.051168484433473,1740481170.0982444,1.9199981689453125,0.0,1740481170.0982456,1.9199981689453125,0.0,1740481170.0982466,1.9199981689453125,0.0,1740481170.0982478,1.9199981689453125,0.0,1740481170.0982485,1.9199981689453125,0.8475545873222521,1740481170.0982494,1.9199981689453125,0.0,1740481170.0982504,1.9199981689453125,0.0781854704429179,1740481170.0982516,1.9199981689453125,0.0,1740481170.0982523,1.9199981689453125,0.7693691168793342,1740481177.477954,9.299991130828857 +1740481170.1221538,1.9399981498718262,0.5814642529667085,1740481170.1221561,1.9399981498718262,0.0,1740481170.122159,1.9399981498718262,0.0,1740481170.1221611,1.9399981498718262,4.120202486725377,1740481170.122162,1.9399981498718262,0.0,1740481170.1221638,1.9399981498718262,0.0,1740481170.1221647,1.9399981498718262,0.0,1740481170.1221657,1.9399981498718262,0.0,1740481170.1221676,1.9399981498718262,0.8306063604489139,1740481170.1221688,1.9399981498718262,0.0,1740481170.12217,1.9399981498718262,0.061237243569579713,1740481170.1221712,1.9399981498718262,0.0,1740481170.122172,1.9399981498718262,0.7693691168793342,1740481177.4974577,9.319991111755371 +1740481170.1384015,1.9599981307983398,0.6672108503575007,1740481170.1384077,1.9599981307983398,0.0,1740481170.1384118,1.9599981307983398,0.011630449874629035,1740481170.1384153,1.9599981307983398,4.157188752906128,1740481170.138417,1.9599981307983398,0.0,1740481170.138419,1.9599981307983398,0.0,1740481170.1384206,1.9599981307983398,0.0,1740481170.138423,1.9599981307983398,0.0,1740481170.1384246,1.9599981307983398,0.8306063604489139,1740481170.138426,1.9599981307983398,1.0,1740481170.138427,1.9599981307983398,1.042796644396669,1740481170.1384287,1.9599981307983398,0.0,1740481170.13843,1.9599981307983398,0.7820470250323956,1740481177.526004,9.339991092681885 +1740481170.1597226,1.9799981117248535,0.6672108503575007,1740481170.1597245,1.9799981117248535,0.0,1740481170.159744,1.9799981117248535,0.011630449874629035,1740481170.159746,1.9799981117248535,4.157188752906128,1740481170.159747,1.9799981117248535,0.0,1740481170.159748,1.9799981117248535,0.0,1740481170.159749,1.9799981117248535,0.0,1740481170.1597502,1.9799981117248535,0.0,1740481170.1597514,1.9799981117248535,0.8306063604489139,1740481170.1597524,1.9799981117248535,1.0,1740481170.1597536,1.9799981117248535,1.0485593354165181,1740481170.1597543,1.9799981117248535,0.0,1740481170.1597552,1.9799981117248535,0.7820470250323956,1740481177.5383248,9.359991073608398 +1740481170.1780453,1.9999980926513672,0.6672108503575007,1740481170.178047,1.9999980926513672,0.0,1740481170.178049,1.9999980926513672,0.011630449874629035,1740481170.178051,1.9999980926513672,4.157188752906128,1740481170.178052,1.9999980926513672,0.0,1740481170.1780744,1.9999980926513672,0.0,1740481170.178075,1.9999980926513672,0.0,1740481170.1780767,1.9999980926513672,0.0,1740481170.1780775,1.9999980926513672,0.8306063604489139,1740481170.1780784,1.9999980926513672,1.0,1740481170.1780796,1.9999980926513672,1.0485593354165181,1740481170.1780806,1.9999980926513672,0.0,1740481170.1780813,1.9999980926513672,0.7820470250323956,1740481177.5580506,9.379991054534912 +1740481170.1981606,2.019998073577881,0.6672108503575007,1740481170.1981628,2.019998073577881,0.0,1740481170.1981654,2.019998073577881,0.011630449874629035,1740481170.1981678,2.019998073577881,4.157188752906128,1740481170.1981688,2.019998073577881,0.0,1740481170.1981704,2.019998073577881,0.0,1740481170.1981714,2.019998073577881,0.0,1740481170.1981726,2.019998073577881,0.0,1740481170.1981738,2.019998073577881,0.8306063604489139,1740481170.198175,2.019998073577881,1.0,1740481170.198176,2.019998073577881,1.0485593354165181,1740481170.198177,2.019998073577881,0.0,1740481170.198178,2.019998073577881,0.7820470250323956,1740481177.577938,9.399991035461426 +1740481170.225539,2.0399980545043945,0.6672108503575007,1740481170.225544,2.0399980545043945,0.0,1740481170.225547,2.0399980545043945,0.0,1740481170.2255614,2.0399980545043945,4.231304900422292,1740481170.2255623,2.0399980545043945,0.0,1740481170.225564,2.0399980545043945,0.0,1740481170.225565,2.0399980545043945,0.0,1740481170.2255661,2.0399980545043945,0.0,1740481170.2255673,2.0399980545043945,0.843284268601975,1740481170.225568,2.0399980545043945,0.0,1740481170.225569,2.0399980545043945,0.06123724356957938,1740481170.22557,2.0399980545043945,0.0,1740481170.2255712,2.0399980545043945,0.7820470250323956,1740481177.5995765,9.41999101638794 +1740481170.2389002,2.059998035430908,0.6672108503575007,1740481170.238902,2.059998035430908,0.0,1740481170.2389042,2.059998035430908,0.0,1740481170.2389064,2.059998035430908,4.231304900422292,1740481170.2389073,2.059998035430908,0.0,1740481170.2389088,2.059998035430908,0.0,1740481170.23891,2.059998035430908,0.0,1740481170.238911,2.059998035430908,0.0,1740481170.2389123,2.059998035430908,0.843284268601975,1740481170.2389133,2.059998035430908,0.0,1740481170.238914,2.059998035430908,0.06123724356957938,1740481170.238915,2.059998035430908,0.0,1740481170.2389162,2.059998035430908,0.7820470250323956,1740481177.6184964,9.439990997314453 +1740481170.2596145,2.079998016357422,0.7583830437081547,1740481170.2596164,2.079998016357422,0.0,1740481170.2596185,2.079998016357422,0.012555117099479872,1740481170.2596204,2.079998016357422,4.415679117039821,1740481170.2596214,2.079998016357422,0.0,1740481170.2596226,2.079998016357422,0.0,1740481170.2596238,2.079998016357422,0.0,1740481170.2596247,2.079998016357422,0.0,1740481170.2596257,2.079998016357422,0.843284268601975,1740481170.2596273,2.079998016357422,1.0,1740481170.2596283,2.079998016357422,0.9362778612247208,1740481170.259629,2.079998016357422,0.0,1740481170.25963,2.079998016357422,0.8679565747914205,1740481177.6378593,9.459990978240967 +1740481170.2779005,2.0999979972839355,0.7583830437081547,1740481170.2779024,2.0999979972839355,0.0,1740481170.2779047,2.0999979972839355,0.012555117099479872,1740481170.2779067,2.0999979972839355,4.415679117039821,1740481170.2779076,2.0999979972839355,0.0,1740481170.277909,2.0999979972839355,0.0,1740481170.27791,2.0999979972839355,0.0,1740481170.277911,2.0999979972839355,0.0,1740481170.277912,2.0999979972839355,0.843284268601975,1740481170.2779133,2.0999979972839355,1.0,1740481170.277914,2.0999979972839355,0.9753276938105545,1740481170.2779155,2.0999979972839355,0.0,1740481170.2779162,2.0999979972839355,0.8679565747914205,1740481177.657836,9.47999095916748 +1740481170.2982712,2.119997978210449,0.7583830437081547,1740481170.298273,2.119997978210449,0.0,1740481170.298275,2.119997978210449,0.012555117099479872,1740481170.2982771,2.119997978210449,4.415679117039821,1740481170.298278,2.119997978210449,0.0,1740481170.2982795,2.119997978210449,0.0,1740481170.2982805,2.119997978210449,0.0,1740481170.2982814,2.119997978210449,0.0,1740481170.2982824,2.119997978210449,0.843284268601975,1740481170.2982967,2.119997978210449,1.0,1740481170.2982988,2.119997978210449,0.9753276938105545,1740481170.2982998,2.119997978210449,0.0,1740481170.298301,2.119997978210449,0.8679565747914205,1740481177.6784286,9.499990940093994 +1740481170.3218071,2.139997959136963,0.7583830437081547,1740481170.321809,2.139997959136963,0.0,1740481170.3218114,2.139997959136963,0.0,1740481170.3218136,2.139997959136963,4.494296193290996,1740481170.3218145,2.139997959136963,0.0,1740481170.3218157,2.139997959136963,0.0,1740481170.3218167,2.139997959136963,0.0,1740481170.3218176,2.139997959136963,0.0,1740481170.3218184,2.139997959136963,0.929193818361,1740481170.3218193,2.139997959136963,0.0,1740481170.3218203,2.139997959136963,0.06123724356957949,1740481170.321821,2.139997959136963,0.0,1740481170.321822,2.139997959136963,0.8679565747914205,1740481177.6980588,9.519990921020508 +1740481170.3382738,2.1599979400634766,0.7583830437081547,1740481170.338276,2.1599979400634766,0.0,1740481170.3382783,2.1599979400634766,0.0,1740481170.3382807,2.1599979400634766,4.494296193290996,1740481170.3382816,2.1599979400634766,0.0,1740481170.338283,2.1599979400634766,0.0,1740481170.338284,2.1599979400634766,0.0,1740481170.338285,2.1599979400634766,0.0,1740481170.3382864,2.1599979400634766,0.929193818361,1740481170.3382874,2.1599979400634766,0.0,1740481170.3382883,2.1599979400634766,0.06123724356957949,1740481170.3382895,2.1599979400634766,0.0,1740481170.3382902,2.1599979400634766,0.8679565747914205,1740481177.7183769,9.539990901947021 +1740481170.3602421,2.1799979209899902,0.8576804367323154,1740481170.360262,2.1799979209899902,0.0,1740481170.360267,2.1799979209899902,0.015067060239668865,1740481170.3602698,2.1799979209899902,4.637522356330925,1740481170.3602715,2.1799979209899902,0.0,1740481170.3602731,2.1799979209899902,0.0,1740481170.3602743,2.1799979209899902,0.0,1740481170.360276,2.1799979209899902,0.0,1740481170.3602982,2.1799979209899902,0.929193818361,1740481170.3602998,2.1799979209899902,0.7043237082372222,1740481170.3603008,2.1799979209899902,0.6723543038106665,1740481170.3603032,2.1799979209899902,0.0,1740481170.3603044,2.1799979209899902,0.9320361261915507,1740481177.7382362,9.559990882873535 +1740481170.3820112,2.199997901916504,0.8576804367323154,1740481170.3820126,2.199997901916504,0.0,1740481170.3820148,2.199997901916504,0.015067060239668865,1740481170.3820164,2.199997901916504,4.637522356330925,1740481170.3820174,2.199997901916504,0.0,1740481170.3820186,2.199997901916504,0.0,1740481170.3820195,2.199997901916504,0.0,1740481170.3820202,2.199997901916504,0.0,1740481170.3820214,2.199997901916504,0.929193818361,1740481170.3820221,2.199997901916504,0.7043237082372222,1740481170.3820229,2.199997901916504,0.7014814004066715,1740481170.382024,2.199997901916504,0.0,1740481170.3820248,2.199997901916504,0.9320361261915507,1740481177.7607284,9.579990863800049 +1740481170.3995028,2.2199978828430176,0.8576804367323154,1740481170.399505,2.2199978828430176,0.0,1740481170.3995078,2.2199978828430176,0.015067060239668865,1740481170.3995097,2.2199978828430176,4.637522356330925,1740481170.3995273,2.2199978828430176,0.0,1740481170.3995287,2.2199978828430176,0.0,1740481170.3995297,2.2199978828430176,0.0,1740481170.3995304,2.2199978828430176,0.0,1740481170.3995316,2.2199978828430176,0.929193818361,1740481170.3995323,2.2199978828430176,0.7043237082372222,1740481170.3995333,2.2199978828430176,0.7014814004066715,1740481170.399534,2.2199978828430176,0.0,1740481170.399535,2.2199978828430176,0.9320361261915507,1740481177.7787843,9.599990844726562 +1740481170.421014,2.2399978637695312,0.8576804367323154,1740481170.4210155,2.2399978637695312,0.0,1740481170.4210176,2.2399978637695312,0.0,1740481170.4210196,2.2399978637695312,4.721752689115417,1740481170.4210207,2.2399978637695312,0.0,1740481170.4210217,2.2399978637695312,0.0,1740481170.4210227,2.2399978637695312,0.0,1740481170.4210234,2.2399978637695312,0.0,1740481170.4210246,2.2399978637695312,0.9811426516209764,1740481170.4210255,2.2399978637695312,0.0,1740481170.4210262,2.2399978637695312,0.04910652542942562,1740481170.4210274,2.2399978637695312,0.0,1740481170.4210281,2.2399978637695312,0.9320361261915507,1740481177.7981882,9.619990825653076 +1740481170.4390104,2.259997844696045,0.8576804367323154,1740481170.4390118,2.259997844696045,0.0,1740481170.4390147,2.259997844696045,0.0,1740481170.4390168,2.259997844696045,4.721752689115417,1740481170.4390175,2.259997844696045,0.0,1740481170.4390187,2.259997844696045,0.0,1740481170.4390197,2.259997844696045,0.0,1740481170.4390209,2.259997844696045,0.0,1740481170.4390216,2.259997844696045,0.9811426516209764,1740481170.4390225,2.259997844696045,0.0,1740481170.4390233,2.259997844696045,0.04910652542942562,1740481170.4390244,2.259997844696045,0.0,1740481170.4390254,2.259997844696045,0.9320361261915507,1740481177.8191772,9.63999080657959 +1740481170.4600017,2.2799978256225586,0.8576804367323154,1740481170.460004,2.2799978256225586,0.0,1740481170.4600067,2.2799978256225586,0.0,1740481170.4600086,2.2799978256225586,4.721752689115417,1740481170.4600098,2.2799978256225586,0.0,1740481170.460011,2.2799978256225586,0.0,1740481170.460012,2.2799978256225586,0.0,1740481170.4600132,2.2799978256225586,0.0,1740481170.460014,2.2799978256225586,0.9811426516209764,1740481170.4600148,2.2799978256225586,0.0,1740481170.4600158,2.2799978256225586,0.04910652542942562,1740481170.460017,2.2799978256225586,0.0,1740481170.460018,2.2799978256225586,0.9320361261915507,1740481177.8375084,9.659990787506104 +1740481170.4780867,2.2999978065490723,0.9630207821372734,1740481170.4780889,2.2999978065490723,0.0,1740481170.478091,2.2999978065490723,0.0168776221444155,1740481170.4780931,2.2999978065490723,4.813419105955493,1740481170.478094,2.2999978065490723,0.0,1740481170.4780953,2.2999978065490723,0.0,1740481170.4780965,2.2999978065490723,0.0,1740481170.4780974,2.2999978065490723,0.0,1740481170.4780982,2.2999978065490723,0.9811426516209764,1740481170.478099,2.2999978065490723,0.18857348379024086,1740481170.4781,2.2999978065490723,0.18328814232186325,1740481170.478101,2.2999978065490723,0.0,1740481170.4781163,2.2999978065490723,0.969430523539381,1740481177.857514,9.679990768432617 +1740481170.4981601,2.319997787475586,0.9630207821372734,1740481170.4981623,2.319997787475586,0.0,1740481170.498164,2.319997787475586,0.0168776221444155,1740481170.498166,2.319997787475586,4.813419105955493,1740481170.4981673,2.319997787475586,0.0,1740481170.4981682,2.319997787475586,0.0,1740481170.4981694,2.319997787475586,0.0,1740481170.4981704,2.319997787475586,0.0,1740481170.4981713,2.319997787475586,0.9811426516209764,1740481170.4981725,2.319997787475586,0.18857348379024086,1740481170.4981735,2.319997787475586,0.20028561187183624,1740481170.4981744,2.319997787475586,0.0,1740481170.4981751,2.319997787475586,0.969430523539381,1740481177.8778837,9.69999074935913 +1740481170.523372,2.3399977684020996,0.9630207821372734,1740481170.5233746,2.3399977684020996,0.0,1740481170.523377,2.3399977684020996,0.0,1740481170.5233788,2.3399977684020996,4.901881829216036,1740481170.5233798,2.3399977684020996,0.0,1740481170.523381,2.3399977684020996,0.0,1740481170.5233817,2.3399977684020996,0.0,1740481170.523383,2.3399977684020996,0.0,1740481170.523384,2.3399977684020996,0.9961849487476745,1740481170.5233848,2.3399977684020996,0.0,1740481170.5233858,2.3399977684020996,0.02675442520829352,1740481170.523387,2.3399977684020996,0.0,1740481170.5233884,2.3399977684020996,0.969430523539381,1740481177.8974993,9.719990730285645 +1740481170.5389762,2.3599977493286133,0.9630207821372734,1740481170.5389793,2.3599977493286133,0.0,1740481170.5389836,2.3599977493286133,0.0,1740481170.5389872,2.3599977493286133,4.901881829216036,1740481170.5389888,2.3599977493286133,0.0,1740481170.5389903,2.3599977493286133,0.0,1740481170.5389926,2.3599977493286133,0.0,1740481170.5389938,2.3599977493286133,0.0,1740481170.5389953,2.3599977493286133,0.9961849487476745,1740481170.5389967,2.3599977493286133,0.0,1740481170.5389984,2.3599977493286133,0.02675442520829352,1740481170.5390003,2.3599977493286133,0.0,1740481170.5390024,2.3599977493286133,0.969430523539381,1740481177.9186459,9.739990711212158 +1740481170.5588038,2.379997730255127,0.9630207821372734,1740481170.5588074,2.379997730255127,0.0,1740481170.5588105,2.379997730255127,0.0,1740481170.558813,2.379997730255127,4.901881829216036,1740481170.5588143,2.379997730255127,0.0,1740481170.5588162,2.379997730255127,0.0,1740481170.558818,2.379997730255127,0.0,1740481170.5588195,2.379997730255127,0.0,1740481170.558821,2.379997730255127,0.9961849487476745,1740481170.5588224,2.379997730255127,0.0,1740481170.5588236,2.379997730255127,0.02675442520829352,1740481170.558825,2.379997730255127,0.0,1740481170.5588262,2.379997730255127,0.969430523539381,1740481177.937858,9.759990692138672 +1740481170.578557,2.3999977111816406,1.0700868604287033,1740481170.5785592,2.3999977111816406,0.0,1740481170.5785613,2.3999977111816406,0.01741711571229937,1740481170.5785632,2.3999977111816406,4.929514350966845,1740481170.5785642,2.3999977111816406,0.0,1740481170.5785656,2.3999977111816406,0.0,1740481170.5785663,2.3999977111816406,0.0,1740481170.5785677,2.3999977111816406,0.0,1740481170.5785685,2.3999977111816406,0.9961849487476745,1740481170.5785694,2.3999977111816406,0.03815051252325952,1740481170.5785706,2.3999977111816406,0.05747554930759551,1740481170.578761,2.3999977111816406,0.0,1740481170.5787635,2.3999977111816406,0.9745382265586362,1740481177.9587195,9.779990673065186 +1740481170.6006403,2.4199976921081543,1.0700868604287033,1740481170.600642,2.4199976921081543,0.0,1740481170.600644,2.4199976921081543,0.01741711571229937,1740481170.6006458,2.4199976921081543,4.929514350966845,1740481170.600647,2.4199976921081543,0.0,1740481170.6006482,2.4199976921081543,0.0,1740481170.600649,2.4199976921081543,0.0,1740481170.6006503,2.4199976921081543,0.0,1740481170.600651,2.4199976921081543,0.9961849487476745,1740481170.6006517,2.4199976921081543,0.03815051252325952,1740481170.6006525,2.4199976921081543,0.05979723471229781,1740481170.6006536,2.4199976921081543,0.0,1740481170.6006548,2.4199976921081543,0.9745382265586362,1740481177.9776332,9.7999906539917 +1740481170.6218095,2.439997673034668,1.0700868604287033,1740481170.6218114,2.439997673034668,0.0,1740481170.6218135,2.439997673034668,0.0,1740481170.6218154,2.439997673034668,5.019163313545976,1740481170.6218164,2.439997673034668,0.0,1740481170.6218176,2.439997673034668,0.0,1740481170.6218183,2.439997673034668,0.0,1740481170.6218195,2.439997673034668,0.0,1740481170.6218204,2.439997673034668,0.9973533185485289,1740481170.6218212,2.439997673034668,0.0,1740481170.621822,2.439997673034668,0.022815091989892733,1740481170.621823,2.439997673034668,0.0,1740481170.6218238,2.439997673034668,0.9745382265586362,1740481177.9981143,9.819990634918213 +1740481170.6378872,2.4599976539611816,1.0700868604287033,1740481170.637889,2.4599976539611816,0.0,1740481170.6378908,2.4599976539611816,0.0,1740481170.6378932,2.4599976539611816,5.019163313545976,1740481170.6378942,2.4599976539611816,0.0,1740481170.6378953,2.4599976539611816,0.0,1740481170.6378965,2.4599976539611816,0.0,1740481170.6378975,2.4599976539611816,0.0,1740481170.6378982,2.4599976539611816,0.9973533185485289,1740481170.6378992,2.4599976539611816,0.0,1740481170.6379,2.4599976539611816,0.022815091989892733,1740481170.637901,2.4599976539611816,0.0,1740481170.637902,2.4599976539611816,0.9745382265586362,1740481178.0201204,9.839990615844727 +1740481170.659494,2.4799976348876953,1.0700868604287033,1740481170.6594956,2.4799976348876953,0.0,1740481170.659498,2.4799976348876953,0.0,1740481170.6595001,2.4799976348876953,5.019163313545976,1740481170.659501,2.4799976348876953,0.0,1740481170.6595023,2.4799976348876953,0.0,1740481170.6595035,2.4799976348876953,0.0,1740481170.6595044,2.4799976348876953,0.0,1740481170.6595054,2.4799976348876953,0.9973533185485289,1740481170.6595063,2.4799976348876953,0.0,1740481170.6595075,2.4799976348876953,0.022815091989892733,1740481170.6595085,2.4799976348876953,0.0,1740481170.6595094,2.4799976348876953,0.9745382265586362,1740481178.0401168,9.85999059677124 +1740481170.679327,2.499997615814209,1.0700868604287033,1740481170.6793294,2.499997615814209,0.0,1740481170.6793315,2.499997615814209,0.0,1740481170.679334,2.499997615814209,5.019163313545976,1740481170.6793346,2.499997615814209,0.0,1740481170.6793358,2.499997615814209,0.0,1740481170.679337,2.499997615814209,0.0,1740481170.679338,2.499997615814209,0.0,1740481170.679339,2.499997615814209,0.9973533185485289,1740481170.6793401,2.499997615814209,0.0,1740481170.6793408,2.499997615814209,0.022815091989892733,1740481170.6793418,2.499997615814209,0.0,1740481170.6793425,2.499997615814209,0.9745382265586362,1740481178.0577493,9.879990577697754 +1740481170.6984458,2.5199975967407227,1.1772348792501717,1740481170.6984477,2.5199975967407227,0.0,1740481170.6984499,2.5199975967407227,0.017450888694242,1740481170.698452,2.5199975967407227,5.032436666993938,1740481170.6984527,2.5199975967407227,0.0,1740481170.698454,2.5199975967407227,0.0,1740481170.698455,2.5199975967407227,0.0,1740481170.698456,2.5199975967407227,0.0,1740481170.6984568,2.5199975967407227,0.9973533185485289,1740481170.6984582,2.5199975967407227,0.02646681451471511,1740481170.698459,2.5199975967407227,0.05232011486190497,1740481170.6984603,2.5199975967407227,0.0,1740481170.6984613,2.5199975967407227,0.9724494589354963,1740481178.0790164,9.899990558624268 +1740481170.7238507,2.5399975776672363,1.1772348792501717,1740481170.7238529,2.5399975776672363,0.0,1740481170.723855,2.5399975776672363,0.0,1740481170.7238572,2.5399975776672363,5.1221337971211645,1740481170.7238579,2.5399975776672363,0.0,1740481170.7238593,2.5399975776672363,0.0,1740481170.7238603,2.5399975776672363,0.0,1740481170.723861,2.5399975776672363,0.0,1740481170.723862,2.5399975776672363,0.996901263558326,1740481170.7238631,2.5399975776672363,0.0,1740481170.7238638,2.5399975776672363,0.024451804622829698,1740481170.7238646,2.5399975776672363,0.0,1740481170.7238655,2.5399975776672363,0.9724494589354963,1740481178.0979357,9.919990539550781 +1740481170.7383997,2.55999755859375,1.1772348792501717,1740481170.7384017,2.55999755859375,0.0,1740481170.738404,2.55999755859375,0.0,1740481170.738406,2.55999755859375,5.1221337971211645,1740481170.738407,2.55999755859375,0.0,1740481170.738408,2.55999755859375,0.0,1740481170.7384093,2.55999755859375,0.0,1740481170.7384102,2.55999755859375,0.0,1740481170.738411,2.55999755859375,0.996901263558326,1740481170.7384124,2.55999755859375,0.0,1740481170.738413,2.55999755859375,0.024451804622829698,1740481170.7384138,2.55999755859375,0.0,1740481170.7384148,2.55999755859375,0.9724494589354963,1740481178.11859,9.939990520477295 +1740481170.7588127,2.5799975395202637,1.1772348792501717,1740481170.7588158,2.5799975395202637,0.0,1740481170.758819,2.5799975395202637,0.0,1740481170.758821,2.5799975395202637,5.1221337971211645,1740481170.7588222,2.5799975395202637,0.0,1740481170.7588234,2.5799975395202637,0.0,1740481170.7588243,2.5799975395202637,0.0,1740481170.7588253,2.5799975395202637,0.0,1740481170.758826,2.5799975395202637,0.996901263558326,1740481170.758827,2.5799975395202637,0.0,1740481170.7588277,2.5799975395202637,0.024451804622829698,1740481170.7588286,2.5799975395202637,0.0,1740481170.7588296,2.5799975395202637,0.9724494589354963,1740481178.1394782,9.959990501403809 +1740481170.778319,2.5999975204467773,1.1772348792501717,1740481170.7783206,2.5999975204467773,0.0,1740481170.778323,2.5999975204467773,0.0,1740481170.7783253,2.5999975204467773,5.1221337971211645,1740481170.7783263,2.5999975204467773,0.0,1740481170.7783275,2.5999975204467773,0.0,1740481170.7783287,2.5999975204467773,0.0,1740481170.7783298,2.5999975204467773,0.0,1740481170.7783306,2.5999975204467773,0.996901263558326,1740481170.7783318,2.5999975204467773,0.0,1740481170.778333,2.5999975204467773,0.024451804622829698,1740481170.778334,2.5999975204467773,0.0,1740481170.7783346,2.5999975204467773,0.9724494589354963,1740481178.1589706,9.979990482330322 +1740481170.7985098,2.619997501373291,1.2840848427002083,1740481170.7985115,2.619997501373291,0.0,1740481170.7985141,2.619997501373291,0.01739445758257763,1740481170.798516,2.619997501373291,5.133786215648208,1740481170.798517,2.619997501373291,0.0,1740481170.798518,2.619997501373291,0.0,1740481170.7985191,2.619997501373291,0.0,1740481170.7985198,2.619997501373291,0.0,1740481170.7985208,2.619997501373291,0.996901263558326,1740481170.7985215,2.619997501373291,0.030987364416723562,1740481170.7985225,2.619997501373291,0.05961519868813234,1740481170.7985232,2.619997501373291,0.0,1740481170.7985241,2.619997501373291,0.9695784394077295,1740481178.1786032,9.999990463256836 +1740481170.8253512,2.6399974822998047,1.2840848427002083,1740481170.8253527,2.6399974822998047,0.0,1740481170.8253553,2.6399974822998047,0.0,1740481170.8253567,2.6399974822998047,5.2232417215156675,1740481170.825358,2.6399974822998047,0.0,1740481170.825359,2.6399974822998047,0.0,1740481170.8253598,2.6399974822998047,0.0,1740481170.8253605,2.6399974822998047,0.0,1740481170.8253617,2.6399974822998047,0.9962217790395091,1740481170.8253624,2.6399974822998047,0.0,1740481170.8253632,2.6399974822998047,0.026643339631779672,1740481170.8253639,2.6399974822998047,0.0,1740481170.825365,2.6399974822998047,0.9695784394077295,1740481178.2022965,10.029990434646606 +1740481170.8378723,2.6599974632263184,1.2840848427002083,1740481170.8378742,2.6599974632263184,0.0,1740481170.8378766,2.6599974632263184,0.0,1740481170.8378785,2.6599974632263184,5.2232417215156675,1740481170.8378797,2.6599974632263184,0.0,1740481170.8378808,2.6599974632263184,0.0,1740481170.8378816,2.6599974632263184,0.0,1740481170.8378825,2.6599974632263184,0.0,1740481170.8378837,2.6599974632263184,0.9962217790395091,1740481170.8378844,2.6599974632263184,0.0,1740481170.8378851,2.6599974632263184,0.026643339631779672,1740481170.837886,2.6599974632263184,0.0,1740481170.837887,2.6599974632263184,0.9695784394077295,1740481178.2189507,10.039990425109863 +1740481170.859544,2.679997444152832,1.2840848427002083,1740481170.8595462,2.679997444152832,0.0,1740481170.859548,2.679997444152832,0.0,1740481170.8595502,2.679997444152832,5.2232417215156675,1740481170.859551,2.679997444152832,0.0,1740481170.8595521,2.679997444152832,0.0,1740481170.8595533,2.679997444152832,0.0,1740481170.859554,2.679997444152832,0.0,1740481170.859555,2.679997444152832,0.9962217790395091,1740481170.8595557,2.679997444152832,0.0,1740481170.859557,2.679997444152832,0.026643339631779672,1740481170.8595579,2.679997444152832,0.0,1740481170.859559,2.679997444152832,0.9695784394077295,1740481178.238027,10.059990406036377 +1740481170.878756,2.6999974250793457,1.2840848427002083,1740481170.8787582,2.6999974250793457,0.0,1740481170.87876,2.6999974250793457,0.0,1740481170.8787622,2.6999974250793457,5.2232417215156675,1740481170.8787632,2.6999974250793457,0.0,1740481170.8787646,2.6999974250793457,0.0,1740481170.8787658,2.6999974250793457,0.0,1740481170.8787668,2.6999974250793457,0.0,1740481170.878768,2.6999974250793457,0.9962217790395091,1740481170.878769,2.6999974250793457,0.0,1740481170.87877,2.6999974250793457,0.026643339631779672,1740481170.8787708,2.6999974250793457,0.0,1740481170.878772,2.6999974250793457,0.9695784394077295,1740481178.2579613,10.07999038696289 +1740481170.9000983,2.7199974060058594,1.2840848427002083,1740481170.9001,2.7199974060058594,0.0,1740481170.9001026,2.7199974060058594,0.0,1740481170.900105,2.7199974060058594,5.2232417215156675,1740481170.9001057,2.7199974060058594,0.0,1740481170.900107,2.7199974060058594,0.0,1740481170.900108,2.7199974060058594,0.0,1740481170.900109,2.7199974060058594,0.0,1740481170.9001098,2.7199974060058594,0.9962217790395091,1740481170.900111,2.7199974060058594,0.0,1740481170.900112,2.7199974060058594,0.026643339631779672,1740481170.9001126,2.7199974060058594,0.0,1740481170.9001133,2.7199974060058594,0.9695784394077295,1740481178.278773,10.099990367889404 +1740481170.9273968,2.739997386932373,1.3906558029775251,1740481170.9273994,2.739997386932373,0.0,1740481170.927402,2.739997386932373,0.0,1740481170.927404,2.739997386932373,5.324930454437143,1740481170.927405,2.739997386932373,0.0,1740481170.927406,2.739997386932373,0.0,1740481170.927407,2.739997386932373,0.0,1740481170.9274082,2.739997386932373,0.0,1740481170.9274092,2.739997386932373,0.995591100704257,1740481170.9274101,2.739997386932373,0.04408899295743396,1740481170.9274108,2.739997386932373,0.07336569387244364,1740481170.927412,2.739997386932373,0.0,1740481170.9274127,2.739997386932373,0.967137325729809,1740481178.2978606,10.119990348815918 +1740481170.9384215,2.7599973678588867,1.3906558029775251,1740481170.938425,2.7599973678588867,0.0,1740481170.9384284,2.7599973678588867,0.0,1740481170.9384305,2.7599973678588867,5.324930454437143,1740481170.9384315,2.7599973678588867,0.0,1740481170.9384327,2.7599973678588867,0.0,1740481170.938434,2.7599973678588867,0.0,1740481170.9384348,2.7599973678588867,0.0,1740481170.938436,2.7599973678588867,0.995591100704257,1740481170.9384372,2.7599973678588867,0.04408899295743396,1740481170.9384382,2.7599973678588867,0.07254276793188197,1740481170.938439,2.7599973678588867,0.0,1740481170.9384398,2.7599973678588867,0.967137325729809,1740481178.3187675,10.139990329742432 +1740481170.9681683,2.7899973392486572,1.3906558029775251,1740481170.9681723,2.7899973392486572,0.0,1740481170.9681756,2.7899973392486572,0.0,1740481170.9681783,2.7899973392486572,5.324930454437143,1740481170.9681797,2.7899973392486572,0.0,1740481170.968182,2.7899973392486572,0.0,1740481170.9681835,2.7899973392486572,0.0,1740481170.9681857,2.7899973392486572,0.0,1740481170.9681869,2.7899973392486572,0.995591100704257,1740481170.968188,2.7899973392486572,0.04408899295743396,1740481170.9681897,2.7899973392486572,0.07254276793188197,1740481170.968191,2.7899973392486572,0.0,1740481170.9681926,2.7899973392486572,0.967137325729809,1740481178.3384495,10.159990310668945 +1740481170.9791732,2.799997329711914,1.3906558029775251,1740481170.979175,2.799997329711914,0.0,1740481170.9791775,2.799997329711914,0.0,1740481170.9791796,2.799997329711914,5.324930454437143,1740481170.9791806,2.799997329711914,0.0,1740481170.9791818,2.799997329711914,0.0,1740481170.979183,2.799997329711914,0.0,1740481170.9791842,2.799997329711914,0.0,1740481170.9791853,2.799997329711914,0.995591100704257,1740481170.9791865,2.799997329711914,0.04408899295743396,1740481170.9791875,2.799997329711914,0.07254276793188197,1740481170.9791882,2.799997329711914,0.0,1740481170.9791892,2.799997329711914,0.967137325729809,1740481178.360623,10.179990291595459 +1740481170.9984617,2.8199973106384277,1.3906558029775251,1740481170.9984634,2.8199973106384277,0.0,1740481170.9984658,2.8199973106384277,0.0,1740481170.9984677,2.8199973106384277,5.324930454437143,1740481170.9984686,2.8199973106384277,0.0,1740481170.9984698,2.8199973106384277,0.0,1740481170.998471,2.8199973106384277,0.0,1740481170.9984717,2.8199973106384277,0.0,1740481170.9984727,2.8199973106384277,0.995591100704257,1740481170.9984736,2.8199973106384277,0.04408899295743396,1740481170.9984746,2.8199973106384277,0.07254276793188197,1740481170.9984756,2.8199973106384277,0.0,1740481170.9984763,2.8199973106384277,0.967137325729809,1740481178.3775876,10.199990272521973 +1740481171.0205398,2.8399972915649414,1.4970360224747195,1740481171.0205414,2.8399972915649414,0.0,1740481171.0205436,2.8399972915649414,0.0,1740481171.0205455,2.8399972915649414,5.432754950925436,1740481171.0205462,2.8399972915649414,0.0,1740481171.0205476,2.8399972915649414,0.0,1740481171.0205486,2.8399972915649414,0.0,1740481171.0205495,2.8399972915649414,0.0,1740481171.0205505,2.8399972915649414,0.9957827378419335,1740481171.0205514,2.8399972915649414,0.04217262158066948,1740481171.0205522,2.8399972915649414,0.06985475798642689,1740481171.0205529,2.8399972915649414,0.0,1740481171.0205538,2.8399972915649414,0.9678594642253584,1740481178.3978026,10.219990253448486 +1740481171.0399754,2.859997272491455,1.4970360224747195,1740481171.0399778,2.859997272491455,0.0,1740481171.0399797,2.859997272491455,0.0,1740481171.0399818,2.859997272491455,5.432754950925436,1740481171.0399828,2.859997272491455,0.0,1740481171.0399842,2.859997272491455,0.0,1740481171.0399852,2.859997272491455,0.0,1740481171.0399861,2.859997272491455,0.0,1740481171.039987,2.859997272491455,0.9957827378419335,1740481171.0399883,2.859997272491455,0.04217262158066948,1740481171.0399892,2.859997272491455,0.07009589519724457,1740481171.0399902,2.859997272491455,0.0,1740481171.0399914,2.859997272491455,0.9678594642253584,1740481178.4183755,10.239990234375 +1740481171.0584614,2.8799972534179688,1.4970360224747195,1740481171.0584633,2.8799972534179688,0.0,1740481171.0584655,2.8799972534179688,0.0,1740481171.0584676,2.8799972534179688,5.432754950925436,1740481171.0584683,2.8799972534179688,0.0,1740481171.0584695,2.8799972534179688,0.0,1740481171.0584707,2.8799972534179688,0.0,1740481171.0584714,2.8799972534179688,0.0,1740481171.0584724,2.8799972534179688,0.9957827378419335,1740481171.058473,2.8799972534179688,0.04217262158066948,1740481171.058474,2.8799972534179688,0.07009589519724457,1740481171.058475,2.8799972534179688,0.0,1740481171.0584757,2.8799972534179688,0.9678594642253584,1740481178.437754,10.259990215301514 +1740481171.0799267,2.8999972343444824,1.4970360224747195,1740481171.0799322,2.8999972343444824,0.0,1740481171.0799365,2.8999972343444824,0.0,1740481171.07994,2.8999972343444824,5.432754950925436,1740481171.0799413,2.8999972343444824,0.0,1740481171.0799437,2.8999972343444824,0.0,1740481171.0799453,2.8999972343444824,0.0,1740481171.0799472,2.8999972343444824,0.0,1740481171.0799499,2.8999972343444824,0.9957827378419335,1740481171.0799527,2.8999972343444824,0.04217262158066948,1740481171.0799537,2.8999972343444824,0.07009589519724457,1740481171.0799553,2.8999972343444824,0.0,1740481171.079957,2.8999972343444824,0.9678594642253584,1740481178.4596097,10.279990196228027 +1740481171.0979698,2.919997215270996,1.4970360224747195,1740481171.0979714,2.919997215270996,0.0,1740481171.0979738,2.919997215270996,0.0,1740481171.0979757,2.919997215270996,5.432754950925436,1740481171.0979767,2.919997215270996,0.0,1740481171.0979776,2.919997215270996,0.0,1740481171.0979786,2.919997215270996,0.0,1740481171.09798,2.919997215270996,0.0,1740481171.097981,2.919997215270996,0.9957827378419335,1740481171.0979822,2.919997215270996,0.04217262158066948,1740481171.097983,2.919997215270996,0.07009589519724457,1740481171.097984,2.919997215270996,0.0,1740481171.0979848,2.919997215270996,0.9678594642253584,1740481178.4778354,10.299990177154541 +1740481171.1222508,2.9399971961975098,1.4970360224747195,1740481171.1222525,2.9399971961975098,0.0,1740481171.1222672,2.9399971961975098,0.0,1740481171.1222713,2.9399971961975098,5.432754950925436,1740481171.122272,2.9399971961975098,0.0,1740481171.1222734,2.9399971961975098,0.0,1740481171.1222746,2.9399971961975098,0.0,1740481171.1222756,2.9399971961975098,0.0,1740481171.1222763,2.9399971961975098,0.9957827378419335,1740481171.1222773,2.9399971961975098,0.04217262158066948,1740481171.1222782,2.9399971961975098,0.07009589519724457,1740481171.122279,2.9399971961975098,0.0,1740481171.12228,2.9399971961975098,0.9678594642253584,1740481178.4978065,10.319990158081055 +1740481171.1385708,2.9599971771240234,1.6035678104629802,1740481171.1385725,2.9599971771240234,0.0,1740481171.1385746,2.9599971771240234,0.017323202242049456,1740481171.1385767,2.9599971771240234,5.452772966974046,1740481171.1385775,2.9599971771240234,0.0,1740481171.1385787,2.9599971771240234,0.0,1740481171.1385796,2.9599971771240234,0.0,1740481171.1385806,2.9599971771240234,0.0,1740481171.1385815,2.9599971771240234,1.0000000000000004,1740481171.1385825,2.9599971771240234,6.661338147750939e-15,1740481171.1385832,2.9599971771240234,0.03209760977668519,1740481171.1385841,2.9599971771240234,0.0,1740481171.138585,2.9599971771240234,0.9692068711286386,1740481178.5190325,10.339990139007568 +1740481171.1584668,2.979997158050537,1.6035678104629802,1740481171.1584687,2.979997158050537,0.0,1740481171.1584704,2.979997158050537,0.017323202242049456,1740481171.1584725,2.979997158050537,5.452772966974046,1740481171.1584735,2.979997158050537,0.0,1740481171.1584744,2.979997158050537,0.0,1740481171.1584756,2.979997158050537,0.0,1740481171.1584766,2.979997158050537,0.0,1740481171.1584775,2.979997158050537,1.0000000000000004,1740481171.1584787,2.979997158050537,6.661338147750939e-15,1740481171.1584797,2.979997158050537,0.030793128871368536,1740481171.1584804,2.979997158050537,0.0,1740481171.1584811,2.979997158050537,0.9692068711286386,1740481178.5377736,10.359990119934082 +1740481171.1779776,2.999997138977051,1.6035678104629802,1740481171.1779797,2.999997138977051,0.0,1740481171.1779819,2.999997138977051,0.017323202242049456,1740481171.1779842,2.999997138977051,5.452772966974046,1740481171.1779854,2.999997138977051,0.0,1740481171.1779869,2.999997138977051,0.0,1740481171.1779878,2.999997138977051,0.0,1740481171.1779888,2.999997138977051,0.0,1740481171.1779902,2.999997138977051,1.0000000000000004,1740481171.1779914,2.999997138977051,6.661338147750939e-15,1740481171.1779928,2.999997138977051,0.030793128871368536,1740481171.1779938,2.999997138977051,0.0,1740481171.1779947,2.999997138977051,0.9692068711286386,1740481178.5590549,10.379990100860596 +1740481171.1986396,3.0199971199035645,1.6035678104629802,1740481171.198641,3.0199971199035645,0.0,1740481171.1986432,3.0199971199035645,0.017323202242049456,1740481171.1986449,3.0199971199035645,5.452772966974046,1740481171.198646,3.0199971199035645,0.0,1740481171.198647,3.0199971199035645,0.0,1740481171.198648,3.0199971199035645,0.0,1740481171.1986492,3.0199971199035645,0.0,1740481171.1986501,3.0199971199035645,1.0000000000000004,1740481171.198651,3.0199971199035645,6.661338147750939e-15,1740481171.1986518,3.0199971199035645,0.030793128871368536,1740481171.1986527,3.0199971199035645,0.0,1740481171.1986537,3.0199971199035645,0.9692068711286386,1740481178.578208,10.39999008178711 +1740481171.2212737,3.039997100830078,1.6035678104629802,1740481171.2212756,3.039997100830078,0.0,1740481171.221278,3.039997100830078,0.0,1740481171.22128,3.039997100830078,5.541981552720257,1740481171.221281,3.039997100830078,0.0,1740481171.2212822,3.039997100830078,0.0,1740481171.2212834,3.039997100830078,0.0,1740481171.2212842,3.039997100830078,0.0,1740481171.221285,3.039997100830078,0.996128921182537,1740481171.221286,3.039997100830078,0.0,1740481171.221287,3.039997100830078,0.026922050053898472,1740481171.2212877,3.039997100830078,0.0,1740481171.2212887,3.039997100830078,0.9692068711286386,1740481178.5984461,10.419990062713623 +1740481171.2381299,3.059997081756592,1.7100734331534495,1740481171.238132,3.059997081756592,0.0,1740481171.238134,3.059997081756592,0.017324968409132474,1740481171.2381358,3.059997081756592,5.554128813774792,1740481171.2381368,3.059997081756592,0.0,1740481171.238138,3.059997081756592,0.0,1740481171.238139,3.059997081756592,0.0,1740481171.2381396,3.059997081756592,0.0,1740481171.2381406,3.059997081756592,0.996128921182537,1740481171.2381418,3.059997081756592,0.03871078817461293,1740481171.2381425,3.059997081756592,0.06939844469954838,1740481171.2381432,3.059997081756592,0.0,1740481171.238144,3.059997081756592,0.9666180174513399,1740481178.6193225,10.439990043640137 +1740481171.2595892,3.0799970626831055,1.7100734331534495,1740481171.2595909,3.0799970626831055,0.0,1740481171.2595932,3.0799970626831055,0.017324968409132474,1740481171.2595952,3.0799970626831055,5.554128813774792,1740481171.2595963,3.0799970626831055,0.0,1740481171.2595978,3.0799970626831055,0.0,1740481171.2595987,3.0799970626831055,0.0,1740481171.2596,3.0799970626831055,0.0,1740481171.2596009,3.0799970626831055,0.996128921182537,1740481171.2596018,3.0799970626831055,0.03871078817461293,1740481171.2596028,3.0799970626831055,0.06822169190581007,1740481171.2596037,3.0799970626831055,0.0,1740481171.2596045,3.0799970626831055,0.9666180174513399,1740481178.6382673,10.45999002456665 +1740481171.2787387,3.099997043609619,1.7100734331534495,1740481171.2787404,3.099997043609619,0.0,1740481171.2787426,3.099997043609619,0.017324968409132474,1740481171.2787445,3.099997043609619,5.554128813774792,1740481171.2787457,3.099997043609619,0.0,1740481171.278747,3.099997043609619,0.0,1740481171.2787478,3.099997043609619,0.0,1740481171.278749,3.099997043609619,0.0,1740481171.27875,3.099997043609619,0.996128921182537,1740481171.278751,3.099997043609619,0.03871078817461293,1740481171.2787519,3.099997043609619,0.06822169190581007,1740481171.2787528,3.099997043609619,0.0,1740481171.2787535,3.099997043609619,0.9666180174513399,1740481178.658065,10.479990005493164 +1740481171.2980945,3.119997024536133,1.7100734331534495,1740481171.2980995,3.119997024536133,0.0,1740481171.2981033,3.119997024536133,0.017324968409132474,1740481171.2981052,3.119997024536133,5.554128813774792,1740481171.2981064,3.119997024536133,0.0,1740481171.2981076,3.119997024536133,0.0,1740481171.2981086,3.119997024536133,0.0,1740481171.2981098,3.119997024536133,0.0,1740481171.2981105,3.119997024536133,0.996128921182537,1740481171.2981114,3.119997024536133,0.03871078817461293,1740481171.2981122,3.119997024536133,0.06822169190581007,1740481171.298113,3.119997024536133,0.0,1740481171.298114,3.119997024536133,0.9666180174513399,1740481178.6781268,10.499989986419678 +1740481171.3204985,3.1399970054626465,1.7100734331534495,1740481171.3205001,3.1399970054626465,0.0,1740481171.3205023,3.1399970054626465,0.0,1740481171.3205044,3.1399970054626465,5.643309468056129,1740481171.3205051,3.1399970054626465,0.0,1740481171.3205063,3.1399970054626465,0.0,1740481171.320507,3.1399970054626465,0.0,1740481171.3205082,3.1399970054626465,0.0,1740481171.320509,3.1399970054626465,0.995450657582208,1740481171.32051,3.1399970054626465,0.0,1740481171.3205106,3.1399970054626465,0.02883264013086806,1740481171.3205116,3.1399970054626465,0.0,1740481171.3205125,3.1399970054626465,0.9666180174513399,1740481178.6980622,10.519989967346191 +1740481171.3382735,3.15999698638916,1.7100734331534495,1740481171.3382754,3.15999698638916,0.0,1740481171.338288,3.15999698638916,0.0,1740481171.338313,3.15999698638916,5.643309468056129,1740481171.3383143,3.15999698638916,0.0,1740481171.3383157,3.15999698638916,0.0,1740481171.338317,3.15999698638916,0.0,1740481171.3383179,3.15999698638916,0.0,1740481171.3383186,3.15999698638916,0.995450657582208,1740481171.3383195,3.15999698638916,0.0,1740481171.3383386,3.15999698638916,0.02883264013086806,1740481171.3383396,3.15999698638916,0.0,1740481171.3383403,3.15999698638916,0.9666180174513399,1740481178.7189372,10.539989948272705 +1740481171.3591807,3.179996967315674,1.8164497198994622,1740481171.3591993,3.179996967315674,0.0,1740481171.3592026,3.179996967315674,0.017292147461234777,1740481171.3592048,3.179996967315674,5.66059904694203,1740481171.3592057,3.179996967315674,0.0,1740481171.3592072,3.179996967315674,0.0,1740481171.3592083,3.179996967315674,0.0,1740481171.3592093,3.179996967315674,0.0,1740481171.3592103,3.179996967315674,0.995450657582208,1740481171.3592112,3.179996967315674,0.04549342417792479,1740481171.359212,3.179996967315674,0.07432793236413793,1740481171.3592129,3.179996967315674,0.0,1740481171.3592138,3.179996967315674,0.9666167331636729,1740481178.738027,10.559989929199219 +1740481171.378906,3.1999969482421875,1.8164497198994622,1740481171.3789084,3.1999969482421875,0.0,1740481171.3789117,3.1999969482421875,0.017292147461234777,1740481171.378914,3.1999969482421875,5.66059904694203,1740481171.378915,3.1999969482421875,0.0,1740481171.3789165,3.1999969482421875,0.0,1740481171.378918,3.1999969482421875,0.0,1740481171.3789191,3.1999969482421875,0.0,1740481171.37892,3.1999969482421875,0.995450657582208,1740481171.3789215,3.1999969482421875,0.04549342417792479,1740481171.3789222,3.1999969482421875,0.07432734859645984,1740481171.3789232,3.1999969482421875,0.0,1740481171.3789241,3.1999969482421875,0.9666167331636729,1740481178.7583654,10.579989910125732 +1740481171.3980122,3.219996929168701,1.8164497198994622,1740481171.398015,3.219996929168701,0.0,1740481171.3980176,3.219996929168701,0.017292147461234777,1740481171.3980198,3.219996929168701,5.66059904694203,1740481171.3980212,3.219996929168701,0.0,1740481171.398023,3.219996929168701,0.0,1740481171.3980238,3.219996929168701,0.0,1740481171.3980253,3.219996929168701,0.0,1740481171.3980267,3.219996929168701,0.995450657582208,1740481171.3980284,3.219996929168701,0.04549342417792479,1740481171.3980293,3.219996929168701,0.07432734859645984,1740481171.3980308,3.219996929168701,0.0,1740481171.398032,3.219996929168701,0.9666167331636729,1740481178.778938,10.599989891052246 +1740481171.4210105,3.239996910095215,1.8164497198994622,1740481171.421015,3.239996910095215,0.0,1740481171.4210184,3.239996910095215,0.0,1740481171.4210205,3.239996910095215,5.749683186226808,1740481171.4210212,3.239996910095215,0.0,1740481171.4210224,3.239996910095215,0.0,1740481171.4210234,3.239996910095215,0.0,1740481171.4210246,3.239996910095215,0.0,1740481171.4210253,3.239996910095215,0.9954503075265005,1740481171.421026,3.239996910095215,0.0,1740481171.4210272,3.239996910095215,0.02883357436282763,1740481171.421028,3.239996910095215,0.0,1740481171.4210289,3.239996910095215,0.9666167331636729,1740481178.7975457,10.61998987197876 +1740481171.438643,3.2599968910217285,1.8164497198994622,1740481171.438645,3.2599968910217285,0.0,1740481171.4386485,3.2599968910217285,0.0,1740481171.4386506,3.2599968910217285,5.749683186226808,1740481171.4386513,3.2599968910217285,0.0,1740481171.4386528,3.2599968910217285,0.0,1740481171.4386537,3.2599968910217285,0.0,1740481171.4386547,3.2599968910217285,0.0,1740481171.4386559,3.2599968910217285,0.9954503075265005,1740481171.4386566,3.2599968910217285,0.0,1740481171.4386575,3.2599968910217285,0.02883357436282763,1740481171.4386582,3.2599968910217285,0.0,1740481171.4386594,3.2599968910217285,0.9666167331636729,1740481178.8189993,10.639989852905273 +1740481171.4583857,3.279996871948242,1.922796326289891,1740481171.4583871,3.279996871948242,0.0,1740481171.4583893,3.279996871948242,0.01728731664995141,1740481171.458391,3.279996871948242,5.766082194939513,1740481171.4583921,3.279996871948242,0.0,1740481171.458393,3.279996871948242,0.0,1740481171.458394,3.279996871948242,0.0,1740481171.4583952,3.279996871948242,0.0,1740481171.458396,3.279996871948242,0.9954503075265005,1740481171.4583972,3.279996871948242,0.045496924734999,1740481171.458398,3.279996871948242,0.0749765414265414,1740481171.458399,3.279996871948242,0.0,1740481171.4583998,3.279996871948242,0.9661725791950498,1740481178.8387132,10.659989833831787 +1740481171.4801931,3.299996852874756,1.922796326289891,1740481171.4801955,3.299996852874756,0.0,1740481171.480198,3.299996852874756,0.01728731664995141,1740481171.4802175,3.299996852874756,5.766082194939513,1740481171.4802184,3.299996852874756,0.0,1740481171.4802198,3.299996852874756,0.0,1740481171.4802213,3.299996852874756,0.0,1740481171.480222,3.299996852874756,0.0,1740481171.480223,3.299996852874756,0.9954503075265005,1740481171.480224,3.299996852874756,0.045496924734999,1740481171.480236,3.299996852874756,0.0747746530664497,1740481171.4802372,3.299996852874756,0.0,1740481171.4802384,3.299996852874756,0.9661725791950498,1740481178.8578787,10.6799898147583 +1740481171.4982772,3.3199968338012695,1.922796326289891,1740481171.498279,3.3199968338012695,0.0,1740481171.498281,3.3199968338012695,0.01728731664995141,1740481171.498283,3.3199968338012695,5.766082194939513,1740481171.498284,3.3199968338012695,0.0,1740481171.4982858,3.3199968338012695,0.0,1740481171.498287,3.3199968338012695,0.0,1740481171.498288,3.3199968338012695,0.0,1740481171.4982889,3.3199968338012695,0.9954503075265005,1740481171.4982896,3.3199968338012695,0.045496924734999,1740481171.4982908,3.3199968338012695,0.0747746530664497,1740481171.4982915,3.3199968338012695,0.0,1740481171.4982922,3.3199968338012695,0.9661725791950498,1740481178.8786528,10.699989795684814 +1740481171.5230403,3.339996814727783,1.922796326289891,1740481171.5230422,3.339996814727783,0.0,1740481171.5230443,3.339996814727783,0.0,1740481171.5230467,3.339996814727783,5.855141484679991,1740481171.5230474,3.339996814727783,0.0,1740481171.5230486,3.339996814727783,0.0,1740481171.5230498,3.339996814727783,0.0,1740481171.5230505,3.339996814727783,0.0,1740481171.5230513,3.339996814727783,0.9953284376810047,1740481171.523052,3.339996814727783,0.0,1740481171.5230532,3.339996814727783,0.02915585848595481,1740481171.523054,3.339996814727783,0.0,1740481171.5230548,3.339996814727783,0.9661725791950498,1740481178.8975158,10.719989776611328 +1740481171.5410192,3.359996795654297,1.922796326289891,1740481171.5410223,3.359996795654297,0.0,1740481171.5410256,3.359996795654297,0.0,1740481171.5410275,3.359996795654297,5.855141484679991,1740481171.5410285,3.359996795654297,0.0,1740481171.5410297,3.359996795654297,0.0,1740481171.5410306,3.359996795654297,0.0,1740481171.5410314,3.359996795654297,0.0,1740481171.5410326,3.359996795654297,0.9953284376810047,1740481171.5410335,3.359996795654297,0.0,1740481171.5410342,3.359996795654297,0.02915585848595481,1740481171.541035,3.359996795654297,0.0,1740481171.5410361,3.359996795654297,0.9661725791950498,1740481178.918048,10.739989757537842 +1740481171.5586524,3.3799967765808105,1.922796326289891,1740481171.5586543,3.3799967765808105,0.0,1740481171.5586565,3.3799967765808105,0.0,1740481171.5586586,3.3799967765808105,5.855141484679991,1740481171.5586593,3.3799967765808105,0.0,1740481171.5586605,3.3799967765808105,0.0,1740481171.5586617,3.3799967765808105,0.0,1740481171.5586627,3.3799967765808105,0.0,1740481171.5586636,3.3799967765808105,0.9953284376810047,1740481171.558665,3.3799967765808105,0.0,1740481171.558666,3.3799967765808105,0.02915585848595481,1740481171.558667,3.3799967765808105,0.0,1740481171.5586681,3.3799967765808105,0.9661725791950498,1740481178.9390776,10.759989738464355 +1740481171.5781112,3.399996757507324,2.029142359340086,1740481171.5781136,3.399996757507324,0.0,1740481171.578117,3.399996757507324,0.017285107029540624,1740481171.5781193,3.399996757507324,5.872544714904555,1740481171.5781202,3.399996757507324,0.0,1740481171.5781217,3.399996757507324,0.0,1740481171.578123,3.399996757507324,0.0,1740481171.578124,3.399996757507324,0.0,1740481171.578125,3.399996757507324,0.9953284376810047,1740481171.5781262,3.399996757507324,0.04671562318995792,1740481171.5781271,3.399996757507324,0.07578557387211123,1740481171.578128,3.399996757507324,0.0,1740481171.5781293,3.399996757507324,0.9662316407925616,1740481178.957561,10.77998971939087 +1740481171.5982947,3.419996738433838,2.029142359340086,1740481171.5982966,3.419996738433838,0.0,1740481171.5982988,3.419996738433838,0.017285107029540624,1740481171.598301,3.419996738433838,5.872544714904555,1740481171.598302,3.419996738433838,0.0,1740481171.5983033,3.419996738433838,0.0,1740481171.5983045,3.419996738433838,0.0,1740481171.5983055,3.419996738433838,0.0,1740481171.5983067,3.419996738433838,0.9953284376810047,1740481171.5983074,3.419996738433838,0.04671562318995792,1740481171.5983083,3.419996738433838,0.07581242007840094,1740481171.598309,3.419996738433838,0.0,1740481171.5983102,3.419996738433838,0.9662316407925616,1740481178.9781556,10.799989700317383 +1740481171.6220782,3.4399967193603516,2.029142359340086,1740481171.6220806,3.4399967193603516,0.0,1740481171.6220827,3.4399967193603516,0.0,1740481171.6220846,3.4399967193603516,5.961605640925209,1740481171.6220856,3.4399967193603516,0.0,1740481171.622087,3.4399967193603516,0.0,1740481171.622088,3.4399967193603516,0.0,1740481171.622089,3.4399967193603516,0.0,1740481171.6220896,3.4399967193603516,0.9953447362377328,1740481171.6220908,3.4399967193603516,0.0,1740481171.6220915,3.4399967193603516,0.029113095445171155,1740481171.6220922,3.4399967193603516,0.0,1740481171.622093,3.4399967193603516,0.9662316407925616,1740481178.9974802,10.819989681243896 +1740481171.638625,3.4599967002868652,2.029142359340086,1740481171.6386268,3.4599967002868652,0.0,1740481171.6386294,3.4599967002868652,0.0,1740481171.6386316,3.4599967002868652,5.961605640925209,1740481171.6386325,3.4599967002868652,0.0,1740481171.6386337,3.4599967002868652,0.0,1740481171.6386347,3.4599967002868652,0.0,1740481171.6386359,3.4599967002868652,0.0,1740481171.6386368,3.4599967002868652,0.9953447362377328,1740481171.6386378,3.4599967002868652,0.0,1740481171.6386387,3.4599967002868652,0.029113095445171155,1740481171.6386397,3.4599967002868652,0.0,1740481171.6386406,3.4599967002868652,0.9662316407925616,1740481179.0181212,10.83998966217041 +1740481171.6596162,3.479996681213379,2.029142359340086,1740481171.6596189,3.479996681213379,0.0,1740481171.6596222,3.479996681213379,0.0,1740481171.659624,3.479996681213379,5.961605640925209,1740481171.6596253,3.479996681213379,0.0,1740481171.6596265,3.479996681213379,0.0,1740481171.6596274,3.479996681213379,0.0,1740481171.6596284,3.479996681213379,0.0,1740481171.6596293,3.479996681213379,0.9953447362377328,1740481171.6596303,3.479996681213379,0.0,1740481171.659631,3.479996681213379,0.029113095445171155,1740481171.6596322,3.479996681213379,0.0,1740481171.659633,3.479996681213379,0.9662316407925616,1740481179.038017,10.859989643096924 +1740481171.6792479,3.4999966621398926,2.1354343149822705,1740481171.6792498,3.4999966621398926,0.0,1740481171.6792705,3.4999966621398926,0.01727660038006992,1740481171.6792724,3.4999966621398926,5.977273462233186,1740481171.6792731,3.4999966621398926,0.0,1740481171.6792748,3.4999966621398926,0.0,1740481171.6792758,3.4999966621398926,0.0,1740481171.6792767,3.4999966621398926,0.0,1740481171.679278,3.4999966621398926,0.9953447362377328,1740481171.6793005,3.4999966621398926,0.046552637622633286,1740481171.6793017,3.4999966621398926,0.0768357545598387,1740481171.6793027,3.4999966621398926,0.0,1740481171.6793034,3.4999966621398926,0.9654272512565151,1740481179.057792,10.879989624023438 +1740481171.6983995,3.5199966430664062,2.1354343149822705,1740481171.698401,3.5199966430664062,0.0,1740481171.6984031,3.5199966430664062,0.01727660038006992,1740481171.698405,3.5199966430664062,5.977273462233186,1740481171.6984062,3.5199966430664062,0.0,1740481171.6984074,3.5199966430664062,0.0,1740481171.6984084,3.5199966430664062,0.0,1740481171.6984096,3.5199966430664062,0.0,1740481171.6984103,3.5199966430664062,0.9953447362377328,1740481171.6984112,3.5199966430664062,0.046552637622633286,1740481171.6984122,3.5199966430664062,0.076470122603851,1740481171.6984131,3.5199966430664062,0.0,1740481171.698414,3.5199966430664062,0.9654272512565151,1740481179.0775814,10.899989604949951 +1740481171.7210515,3.53999662399292,2.1354343149822705,1740481171.7210534,3.53999662399292,0.0,1740481171.7210567,3.53999662399292,0.0,1740481171.7210588,3.53999662399292,6.066288817495301,1740481171.7210596,3.53999662399292,0.0,1740481171.7210608,3.53999662399292,0.0,1740481171.7210617,3.53999662399292,0.0,1740481171.7210627,3.53999662399292,0.0,1740481171.7210634,3.53999662399292,0.9951203104270931,1740481171.721064,3.53999662399292,0.0,1740481171.721065,3.53999662399292,0.029693059170578073,1740481171.721066,3.53999662399292,0.0,1740481171.7210667,3.53999662399292,0.9654272512565151,1740481179.0989714,10.919989585876465 +1740481171.7385013,3.5599966049194336,2.1354343149822705,1740481171.7385032,3.5599966049194336,0.0,1740481171.7385051,3.5599966049194336,0.0,1740481171.7385073,3.5599966049194336,6.066288817495301,1740481171.7385082,3.5599966049194336,0.0,1740481171.7385094,3.5599966049194336,0.0,1740481171.7385104,3.5599966049194336,0.0,1740481171.738511,3.5599966049194336,0.0,1740481171.738512,3.5599966049194336,0.9951203104270931,1740481171.738513,3.5599966049194336,0.0,1740481171.738514,3.5599966049194336,0.029693059170578073,1740481171.7385147,3.5599966049194336,0.0,1740481171.7385154,3.5599966049194336,0.9654272512565151,1740481179.1181512,10.939989566802979 +1740481171.758492,3.5799965858459473,2.1354343149822705,1740481171.758494,3.5799965858459473,0.0,1740481171.7585132,3.5799965858459473,0.0,1740481171.7585154,3.5799965858459473,6.066288817495301,1740481171.7585166,3.5799965858459473,0.0,1740481171.7585177,3.5799965858459473,0.0,1740481171.7585187,3.5799965858459473,0.0,1740481171.75852,3.5799965858459473,0.0,1740481171.7585206,3.5799965858459473,0.9951203104270931,1740481171.7585218,3.5799965858459473,0.0,1740481171.7585225,3.5799965858459473,0.029693059170578073,1740481171.7585237,3.5799965858459473,0.0,1740481171.7585244,3.5799965858459473,0.9654272512565151,1740481179.1390676,10.959989547729492 +1740481171.7776988,3.599996566772461,2.1354343149822705,1740481171.7777007,3.599996566772461,0.0,1740481171.7777026,3.599996566772461,0.0,1740481171.7777047,3.599996566772461,6.066288817495301,1740481171.7777057,3.599996566772461,0.0,1740481171.7777069,3.599996566772461,0.0,1740481171.7777078,3.599996566772461,0.0,1740481171.7777088,3.599996566772461,0.0,1740481171.7777097,3.599996566772461,0.9951203104270931,1740481171.777711,3.599996566772461,0.0,1740481171.7777116,3.599996566772461,0.029693059170578073,1740481171.7777126,3.599996566772461,0.0,1740481171.7777138,3.599996566772461,0.9654272512565151,1740481179.158064,10.979989528656006 +1740481171.798155,3.6199965476989746,2.24163750167411,1740481171.7981575,3.6199965476989746,0.0,1740481171.7981606,3.6199965476989746,0.01725827975732575,1740481171.7981627,3.6199965476989746,6.081165292893379,1740481171.7981637,3.6199965476989746,0.0,1740481171.798165,3.6199965476989746,0.0,1740481171.798166,3.6199965476989746,0.0,1740481171.798167,3.6199965476989746,0.0,1740481171.7981682,3.6199965476989746,0.9951203104270931,1740481171.7981691,3.6199965476989746,0.048796895729072975,1740481171.79817,3.6199965476989746,0.0802221767680735,1740481171.798171,3.6199965476989746,0.0,1740481171.798172,3.6199965476989746,0.9642363490768915,1740481179.1777751,10.99998950958252 +1740481171.8213463,3.6399965286254883,2.24163750167411,1740481171.8213482,3.6399965286254883,0.0,1740481171.8213503,3.6399965286254883,0.0,1740481171.8213527,3.6399965286254883,6.170110199827893,1740481171.8213534,3.6399965286254883,0.0,1740481171.8213844,3.6399965286254883,0.0,1740481171.8213885,3.6399965286254883,0.0,1740481171.8213897,3.6399965286254883,0.0,1740481171.8213906,3.6399965286254883,0.9947783462612243,1740481171.8213913,3.6399965286254883,0.0,1740481171.8213923,3.6399965286254883,0.030541997184332814,1740481171.8213933,3.6399965286254883,0.0,1740481171.8213942,3.6399965286254883,0.9642363490768915,1740481179.1990256,11.019989490509033 +1740481171.8381422,3.659996509552002,2.24163750167411,1740481171.838144,3.659996509552002,0.0,1740481171.838146,3.659996509552002,0.0,1740481171.838148,3.659996509552002,6.170110199827893,1740481171.838149,3.659996509552002,0.0,1740481171.8381505,3.659996509552002,0.0,1740481171.8381512,3.659996509552002,0.0,1740481171.8381522,3.659996509552002,0.0,1740481171.8381531,3.659996509552002,0.9947783462612243,1740481171.8381543,3.659996509552002,0.0,1740481171.8381553,3.659996509552002,0.030541997184332814,1740481171.838156,3.659996509552002,0.0,1740481171.838157,3.659996509552002,0.9642363490768915,1740481179.2229452,11.039989471435547 +1740481171.8593853,3.6799964904785156,2.24163750167411,1740481171.8593872,3.6799964904785156,0.0,1740481171.8593895,3.6799964904785156,0.0,1740481171.8593915,3.6799964904785156,6.170110199827893,1740481171.8593924,3.6799964904785156,0.0,1740481171.8593938,3.6799964904785156,0.0,1740481171.8593948,3.6799964904785156,0.0,1740481171.8593955,3.6799964904785156,0.0,1740481171.859397,3.6799964904785156,0.9947783462612243,1740481171.8593976,3.6799964904785156,0.0,1740481171.8593986,3.6799964904785156,0.030541997184332814,1740481171.8593993,3.6799964904785156,0.0,1740481171.8594003,3.6799964904785156,0.9642363490768915,1740481179.238567,11.05998945236206 +1740481171.8780854,3.6999964714050293,2.24163750167411,1740481171.8780897,3.6999964714050293,0.0,1740481171.878093,3.6999964714050293,0.0,1740481171.8780951,3.6999964714050293,6.170110199827893,1740481171.8780959,3.6999964714050293,0.0,1740481171.8780973,3.6999964714050293,0.0,1740481171.8780985,3.6999964714050293,0.0,1740481171.8780992,3.6999964714050293,0.0,1740481171.8781,3.6999964714050293,0.9947783462612243,1740481171.878101,3.6999964714050293,0.0,1740481171.8781018,3.6999964714050293,0.030541997184332814,1740481171.8781028,3.6999964714050293,0.0,1740481171.8781037,3.6999964714050293,0.9642363490768915,1740481179.2578835,11.079989433288574 +1740481171.8982008,3.719996452331543,2.347638877618153,1740481171.8982038,3.719996452331543,0.0,1740481171.8982067,3.719996452331543,0.017219565629732606,1740481171.8982096,3.719996452331543,6.183376132733186,1740481171.898211,3.719996452331543,0.0,1740481171.8982127,3.719996452331543,0.0,1740481171.8982139,3.719996452331543,0.0,1740481171.898215,3.719996452331543,0.0,1740481171.8982162,3.719996452331543,0.9947783462612243,1740481171.8982177,3.719996452331543,0.05221653738776144,1740481171.8982189,3.719996452331543,0.08563390468315962,1740481171.89822,3.719996452331543,0.0,1740481171.8982213,3.719996452331543,0.9622595327146718,1740481179.2780669,11.099989414215088 +1740481171.9220347,3.7399964332580566,2.347638877618153,1740481171.922038,3.7399964332580566,0.0,1740481171.922041,3.7399964332580566,0.0,1740481171.9220433,3.7399964332580566,6.272157943047497,1740481171.9220443,3.7399964332580566,0.0,1740481171.922046,3.7399964332580566,0.0,1740481171.9220471,3.7399964332580566,0.0,1740481171.9220486,3.7399964332580566,0.0,1740481171.92205,3.7399964332580566,0.9941851445791459,1740481171.9220521,3.7399964332580566,0.0,1740481171.9220536,3.7399964332580566,0.03192561186447407,1740481171.9220548,3.7399964332580566,0.0,1740481171.9220557,3.7399964332580566,0.9622595327146718,1740481179.2977898,11.119989395141602 +1740481171.937985,3.7599964141845703,2.347638877618153,1740481171.9379866,3.7599964141845703,0.0,1740481171.9379885,3.7599964141845703,0.0,1740481171.9379907,3.7599964141845703,6.272157943047497,1740481171.9379914,3.7599964141845703,0.0,1740481171.9379928,3.7599964141845703,0.0,1740481171.9379935,3.7599964141845703,0.0,1740481171.9379945,3.7599964141845703,0.0,1740481171.9379954,3.7599964141845703,0.9941851445791459,1740481171.9379964,3.7599964141845703,0.0,1740481171.9379973,3.7599964141845703,0.03192561186447407,1740481171.937998,3.7599964141845703,0.0,1740481171.9379988,3.7599964141845703,0.9622595327146718,1740481179.3191392,11.139989376068115 +1740481171.9582222,3.779996395111084,2.347638877618153,1740481171.9582238,3.779996395111084,0.0,1740481171.958226,3.779996395111084,0.0,1740481171.9582279,3.779996395111084,6.272157943047497,1740481171.9582288,3.779996395111084,0.0,1740481171.95823,3.779996395111084,0.0,1740481171.958231,3.779996395111084,0.0,1740481171.9582324,3.779996395111084,0.0,1740481171.958233,3.779996395111084,0.9941851445791459,1740481171.9582345,3.779996395111084,0.0,1740481171.9582355,3.779996395111084,0.03192561186447407,1740481171.9582365,3.779996395111084,0.0,1740481171.9582372,3.779996395111084,0.9622595327146718,1740481179.3379867,11.159989356994629 +1740481171.9782128,3.7999963760375977,2.347638877618153,1740481171.978215,3.7999963760375977,0.0,1740481171.9782171,3.7999963760375977,0.0,1740481171.9782193,3.7999963760375977,6.272157943047497,1740481171.9782202,3.7999963760375977,0.0,1740481171.978222,3.7999963760375977,0.0,1740481171.9782228,3.7999963760375977,0.0,1740481171.9782238,3.7999963760375977,0.0,1740481171.9782248,3.7999963760375977,0.9941851445791459,1740481171.9782257,3.7999963760375977,0.0,1740481171.9782267,3.7999963760375977,0.03192561186447407,1740481171.9782274,3.7999963760375977,0.0,1740481171.9782286,3.7999963760375977,0.9622595327146718,1740481179.3578846,11.179989337921143 +1740481171.9978406,3.8199963569641113,2.347638877618153,1740481171.9978426,3.8199963569641113,0.0,1740481171.9978445,3.8199963569641113,0.0,1740481171.9978466,3.8199963569641113,6.272157943047497,1740481171.9978473,3.8199963569641113,0.0,1740481171.9978485,3.8199963569641113,0.0,1740481171.9978497,3.8199963569641113,0.0,1740481171.9978507,3.8199963569641113,0.0,1740481171.9978514,3.8199963569641113,0.9941851445791459,1740481171.9978523,3.8199963569641113,0.0,1740481171.9978533,3.8199963569641113,0.03192561186447407,1740481171.997854,3.8199963569641113,0.0,1740481171.997855,3.8199963569641113,0.9622595327146718,1740481179.3779762,11.199989318847656 +1740481172.0218134,3.839996337890625,2.4534495041910924,1740481172.0218155,3.839996337890625,0.0,1740481172.021818,3.839996337890625,0.0,1740481172.0218198,3.839996337890625,6.374523856260415,1740481172.0218208,3.839996337890625,0.0,1740481172.021822,3.839996337890625,0.0,1740481172.021823,3.839996337890625,0.0,1740481172.021824,3.839996337890625,0.0,1740481172.0218248,3.839996337890625,0.993642290277364,1740481172.0218258,3.839996337890625,0.06357709722632165,1740481172.0218265,3.839996337890625,0.09721834942497422,1740481172.0218277,3.839996337890625,0.0,1740481172.0218284,3.839996337890625,0.9605371760346616,1740481179.398089,11.21998929977417 +1740481172.0381656,3.8599963188171387,2.4534495041910924,1740481172.0381677,3.8599963188171387,0.0,1740481172.03817,3.8599963188171387,0.0,1740481172.038172,3.8599963188171387,6.374523856260415,1740481172.038173,3.8599963188171387,0.0,1740481172.0381742,3.8599963188171387,0.0,1740481172.0381753,3.8599963188171387,0.0,1740481172.0381765,3.8599963188171387,0.0,1740481172.0381775,3.8599963188171387,0.993642290277364,1740481172.0381784,3.8599963188171387,0.06357709722632165,1740481172.0381794,3.8599963188171387,0.096682211469024,1740481172.0381804,3.8599963188171387,0.0,1740481172.038181,3.8599963188171387,0.9605371760346616,1740481179.4198177,11.239989280700684 +1740481172.0607624,3.8799962997436523,2.4534495041910924,1740481172.060764,3.8799962997436523,0.0,1740481172.0607662,3.8799962997436523,0.0,1740481172.0607684,3.8799962997436523,6.374523856260415,1740481172.0607693,3.8799962997436523,0.0,1740481172.0607705,3.8799962997436523,0.0,1740481172.0607715,3.8799962997436523,0.0,1740481172.0607839,3.8799962997436523,0.0,1740481172.0607848,3.8799962997436523,0.993642290277364,1740481172.0607862,3.8799962997436523,0.06357709722632165,1740481172.060787,3.8799962997436523,0.096682211469024,1740481172.060788,3.8799962997436523,0.0,1740481172.060789,3.8799962997436523,0.9605371760346616,1740481179.4378529,11.259989261627197 +1740481172.0782177,3.899996280670166,2.4534495041910924,1740481172.0782201,3.899996280670166,0.0,1740481172.0782223,3.899996280670166,0.0,1740481172.0782242,3.899996280670166,6.374523856260415,1740481172.0782251,3.899996280670166,0.0,1740481172.0782263,3.899996280670166,0.0,1740481172.0782275,3.899996280670166,0.0,1740481172.0782285,3.899996280670166,0.0,1740481172.0782294,3.899996280670166,0.993642290277364,1740481172.0782304,3.899996280670166,0.06357709722632165,1740481172.0782313,3.899996280670166,0.096682211469024,1740481172.0782323,3.899996280670166,0.0,1740481172.0782332,3.899996280670166,0.9605371760346616,1740481179.459351,11.279989242553711 +1740481172.0982552,3.9199962615966797,2.4534495041910924,1740481172.0982566,3.9199962615966797,0.0,1740481172.098259,3.9199962615966797,0.0,1740481172.0982609,3.9199962615966797,6.374523856260415,1740481172.098262,3.9199962615966797,0.0,1740481172.098263,3.9199962615966797,0.0,1740481172.098264,3.9199962615966797,0.0,1740481172.0982652,3.9199962615966797,0.0,1740481172.0982661,3.9199962615966797,0.993642290277364,1740481172.098267,3.9199962615966797,0.06357709722632165,1740481172.0982678,3.9199962615966797,0.096682211469024,1740481172.0982687,3.9199962615966797,0.0,1740481172.0982695,3.9199962615966797,0.9605371760346616,1740481179.4778016,11.299989223480225 +1740481172.1219013,3.9399962425231934,2.5592027563078537,1740481172.1219032,3.9399962425231934,0.0,1740481172.121905,3.9399962425231934,0.0,1740481172.121907,3.9399962425231934,6.486358916970404,1740481172.121908,3.9399962425231934,0.0,1740481172.1219091,3.9399962425231934,0.0,1740481172.1219103,3.9399962425231934,0.0,1740481172.121911,3.9399962425231934,0.0,1740481172.121912,3.9399962425231934,0.9945843568593686,1740481172.1219132,3.9399962425231934,0.054156431406318095,1740481172.121914,3.9399962425231934,0.08420868988158524,1740481172.1219146,3.9399962425231934,0.0,1740481172.1219153,3.9399962425231934,0.963578080331275,1740481179.4985328,11.319989204406738 +1740481172.1380281,3.959996223449707,2.5592027563078537,1740481172.1380298,3.959996223449707,0.0,1740481172.1380322,3.959996223449707,0.0,1740481172.138034,3.959996223449707,6.486358916970404,1740481172.1380353,3.959996223449707,0.0,1740481172.1380365,3.959996223449707,0.0,1740481172.1380377,3.959996223449707,0.0,1740481172.1380389,3.959996223449707,0.0,1740481172.1380396,3.959996223449707,0.9945843568593686,1740481172.1380405,3.959996223449707,0.054156431406318095,1740481172.1380415,3.959996223449707,0.08516270793441172,1740481172.1380424,3.959996223449707,0.0,1740481172.1380432,3.959996223449707,0.963578080331275,1740481179.519249,11.339989185333252 +1740481172.1606562,3.9799962043762207,2.5592027563078537,1740481172.1606576,3.9799962043762207,0.0,1740481172.16066,3.9799962043762207,0.0,1740481172.1606617,3.9799962043762207,6.486358916970404,1740481172.160663,3.9799962043762207,0.0,1740481172.160664,3.9799962043762207,0.0,1740481172.160665,3.9799962043762207,0.0,1740481172.1606662,3.9799962043762207,0.0,1740481172.160667,3.9799962043762207,0.9945843568593686,1740481172.160668,3.9799962043762207,0.054156431406318095,1740481172.1606686,3.9799962043762207,0.08516270793441172,1740481172.1606698,3.9799962043762207,0.0,1740481172.1606705,3.9799962043762207,0.963578080331275,1740481179.5377562,11.359989166259766 +1740481172.178445,3.9999961853027344,2.5592027563078537,1740481172.1784468,3.9999961853027344,0.0,1740481172.1784492,3.9999961853027344,0.0,1740481172.178451,3.9999961853027344,6.486358916970404,1740481172.178452,3.9999961853027344,0.0,1740481172.1784532,3.9999961853027344,0.0,1740481172.1784542,3.9999961853027344,0.0,1740481172.178455,3.9999961853027344,0.0,1740481172.178456,3.9999961853027344,0.9945843568593686,1740481172.1784568,3.9999961853027344,0.054156431406318095,1740481172.1784575,3.9999961853027344,0.08516270793441172,1740481172.1784587,3.9999961853027344,0.0,1740481172.1784596,3.9999961853027344,0.963578080331275,1740481179.5577629,11.37998914718628 +1740481172.1993582,4.019996166229248,2.5592027563078537,1740481172.19936,4.019996166229248,0.0,1740481172.1993623,4.019996166229248,0.0,1740481172.1993642,4.019996166229248,6.486358916970404,1740481172.1993651,4.019996166229248,0.0,1740481172.1993663,4.019996166229248,0.0,1740481172.1993675,4.019996166229248,0.0,1740481172.1993682,4.019996166229248,0.0,1740481172.1993692,4.019996166229248,0.9945843568593686,1740481172.1993701,4.019996166229248,0.054156431406318095,1740481172.199371,4.019996166229248,0.08516270793441172,1740481172.199372,4.019996166229248,0.0,1740481172.1993728,4.019996166229248,0.963578080331275,1740481179.578207,11.399989128112793 +1740481172.222464,4.039996147155762,2.5592027563078537,1740481172.2224684,4.039996147155762,0.0,1740481172.2224712,4.039996147155762,0.0,1740481172.222474,4.039996147155762,6.486358916970404,1740481172.2224748,4.039996147155762,0.0,1740481172.222476,4.039996147155762,0.0,1740481172.2224777,4.039996147155762,0.0,1740481172.2224793,4.039996147155762,0.0,1740481172.2224803,4.039996147155762,0.9945843568593686,1740481172.2224822,4.039996147155762,0.054156431406318095,1740481172.2224832,4.039996147155762,0.08516270793441172,1740481172.2224846,4.039996147155762,0.0,1740481172.2224855,4.039996147155762,0.963578080331275,1740481179.5995076,11.419989109039307 +1740481172.238143,4.059996128082275,2.665359000707424,1740481172.2381454,4.059996128082275,0.0,1740481172.2381477,4.059996128082275,0.017241360634201,1740481172.23815,4.059996128082275,6.509882820846109,1740481172.2381508,4.059996128082275,0.0,1740481172.2381523,4.059996128082275,0.0,1740481172.2381532,4.059996128082275,0.0,1740481172.2381544,4.059996128082275,0.0,1740481172.2381556,4.059996128082275,1.0000000000000004,1740481172.2381568,4.059996128082275,6.661338147750939e-15,1740481172.2381577,4.059996128082275,0.03431445427020394,1740481172.238159,4.059996128082275,0.0,1740481172.23816,4.059996128082275,0.9667193519520267,1740481179.6196196,11.43998908996582 +1740481172.261053,4.079996109008789,2.665359000707424,1740481172.2610552,4.079996109008789,0.0,1740481172.2610574,4.079996109008789,0.017241360634201,1740481172.2610593,4.079996109008789,6.509882820846109,1740481172.2610602,4.079996109008789,0.0,1740481172.2610617,4.079996109008789,0.0,1740481172.2610624,4.079996109008789,0.0,1740481172.2610636,4.079996109008789,0.0,1740481172.2610648,4.079996109008789,1.0000000000000004,1740481172.2610657,4.079996109008789,6.661338147750939e-15,1740481172.2610664,4.079996109008789,0.033280648047980366,1740481172.2610676,4.079996109008789,0.0,1740481172.2610683,4.079996109008789,0.9667193519520267,1740481179.6374593,11.459989070892334 +1740481172.2801056,4.099996089935303,2.665359000707424,1740481172.280107,4.099996089935303,0.0,1740481172.2801092,4.099996089935303,0.017241360634201,1740481172.280111,4.099996089935303,6.509882820846109,1740481172.2801118,4.099996089935303,0.0,1740481172.2801132,4.099996089935303,0.0,1740481172.2801142,4.099996089935303,0.0,1740481172.280115,4.099996089935303,0.0,1740481172.2801156,4.099996089935303,1.0000000000000004,1740481172.2801168,4.099996089935303,6.661338147750939e-15,1740481172.2801175,4.099996089935303,0.033280648047980366,1740481172.2801182,4.099996089935303,0.0,1740481172.2801192,4.099996089935303,0.9667193519520267,1740481179.658635,11.479989051818848 +1740481172.2992628,4.119996070861816,2.665359000707424,1740481172.2992642,4.119996070861816,0.0,1740481172.2992666,4.119996070861816,0.017241360634201,1740481172.2992682,4.119996070861816,6.509882820846109,1740481172.2992694,4.119996070861816,0.0,1740481172.2992704,4.119996070861816,0.0,1740481172.2992713,4.119996070861816,0.0,1740481172.299285,4.119996070861816,0.0,1740481172.299287,4.119996070861816,1.0000000000000004,1740481172.299288,4.119996070861816,6.661338147750939e-15,1740481172.2992887,4.119996070861816,0.033280648047980366,1740481172.29929,4.119996070861816,0.0,1740481172.2992907,4.119996070861816,0.9667193519520267,1740481179.678342,11.499989032745361 +1740481172.3222828,4.13999605178833,2.665359000707424,1740481172.3222842,4.13999605178833,0.0,1740481172.3222866,4.13999605178833,0.0,1740481172.3222888,4.13999605178833,6.598797704611478,1740481172.3222897,4.13999605178833,0.0,1740481172.3222907,4.13999605178833,0.0,1740481172.3222916,4.13999605178833,0.0,1740481172.3222928,4.13999605178833,0.0,1740481172.3222935,4.13999605178833,0.9954782356702803,1740481172.3222942,4.13999605178833,0.0,1740481172.3222952,4.13999605178833,0.028758883718253525,1740481172.3222961,4.13999605178833,0.0,1740481172.3222969,4.13999605178833,0.9667193519520267,1740481179.6982167,11.519989013671875 +1740481172.3382654,4.159996032714844,2.771617677236139,1740481172.3382676,4.159996032714844,0.0,1740481172.3382707,4.159996032714844,0.017273507700469298,1740481172.338273,4.159996032714844,6.611702752244489,1740481172.338274,4.159996032714844,0.0,1740481172.3382754,4.159996032714844,0.0,1740481172.3382764,4.159996032714844,0.0,1740481172.3382773,4.159996032714844,0.0,1740481172.3382783,4.159996032714844,0.9954782356702803,1740481172.3382795,4.159996032714844,0.04521764329720179,1740481172.3382802,4.159996032714844,0.07715358982953618,1740481172.3382812,4.159996032714844,0.0,1740481172.3382819,4.159996032714844,0.964535121918298,1740481179.7186544,11.539988994598389 +1740481172.3598661,4.179996013641357,2.771617677236139,1740481172.359868,4.179996013641357,0.0,1740481172.3598707,4.179996013641357,0.017273507700469298,1740481172.3598728,4.179996013641357,6.611702752244489,1740481172.3598738,4.179996013641357,0.0,1740481172.359875,4.179996013641357,0.0,1740481172.3598762,4.179996013641357,0.0,1740481172.3598776,4.179996013641357,0.0,1740481172.3598783,4.179996013641357,0.9954782356702803,1740481172.3598795,4.179996013641357,0.04521764329720179,1740481172.3598804,4.179996013641357,0.07616075704918401,1740481172.3598814,4.179996013641357,0.0,1740481172.3598824,4.179996013641357,0.964535121918298,1740481179.7379985,11.559988975524902 +1740481172.3777785,4.199995994567871,2.771617677236139,1740481172.37778,4.199995994567871,0.0,1740481172.3777823,4.199995994567871,0.017273507700469298,1740481172.3777843,4.199995994567871,6.611702752244489,1740481172.3777854,4.199995994567871,0.0,1740481172.3777866,4.199995994567871,0.0,1740481172.3777876,4.199995994567871,0.0,1740481172.3777888,4.199995994567871,0.0,1740481172.3777895,4.199995994567871,0.9954782356702803,1740481172.3777905,4.199995994567871,0.04521764329720179,1740481172.3777914,4.199995994567871,0.07616075704918401,1740481172.3777924,4.199995994567871,0.0,1740481172.3777933,4.199995994567871,0.964535121918298,1740481179.7577453,11.579988956451416 +1740481172.398203,4.219995975494385,2.771617677236139,1740481172.3982043,4.219995975494385,0.0,1740481172.3982065,4.219995975494385,0.017273507700469298,1740481172.3982086,4.219995975494385,6.611702752244489,1740481172.3982098,4.219995975494385,0.0,1740481172.3982108,4.219995975494385,0.0,1740481172.398212,4.219995975494385,0.0,1740481172.398213,4.219995975494385,0.0,1740481172.3982139,4.219995975494385,0.9954782356702803,1740481172.3982148,4.219995975494385,0.04521764329720179,1740481172.3982158,4.219995975494385,0.07616075704918401,1740481172.3982167,4.219995975494385,0.0,1740481172.3982174,4.219995975494385,0.964535121918298,1740481179.7792456,11.59998893737793 +1740481172.422079,4.239995956420898,2.771617677236139,1740481172.4220808,4.239995956420898,0.0,1740481172.4220831,4.239995956420898,0.0,1740481172.4220848,4.239995956420898,6.700687921072735,1740481172.422086,4.239995956420898,0.0,1740481172.4220872,4.239995956420898,0.0,1740481172.4220881,4.239995956420898,0.0,1740481172.4220889,4.239995956420898,0.0,1740481172.42209,4.239995956420898,0.9948652261922886,1740481172.422091,4.239995956420898,0.0,1740481172.422092,4.239995956420898,0.03033010427399052,1740481172.422093,4.239995956420898,0.0,1740481172.4220939,4.239995956420898,0.964535121918298,1740481179.7989316,11.619988918304443 +1740481172.438392,4.259995937347412,2.771617677236139,1740481172.4384077,4.259995937347412,0.0,1740481172.4384115,4.259995937347412,0.0,1740481172.4384136,4.259995937347412,6.700687921072735,1740481172.4384146,4.259995937347412,0.0,1740481172.4384158,4.259995937347412,0.0,1740481172.4384172,4.259995937347412,0.0,1740481172.4384181,4.259995937347412,0.0,1740481172.4384189,4.259995937347412,0.9948652261922886,1740481172.4384203,4.259995937347412,0.0,1740481172.438421,4.259995937347412,0.03033010427399052,1740481172.438422,4.259995937347412,0.0,1740481172.4384227,4.259995937347412,0.964535121918298,1740481179.8181798,11.639988899230957 +1740481172.4597414,4.279995918273926,2.877816094627512,1740481172.4597447,4.279995918273926,0.0,1740481172.459748,4.279995918273926,0.01725308103054727,1740481172.4597504,4.279995918273926,6.7202324491408,1740481172.4597518,4.279995918273926,0.0,1740481172.4597535,4.279995918273926,0.0,1740481172.4597552,4.279995918273926,0.0,1740481172.4597566,4.279995918273926,0.0,1740481172.4597578,4.279995918273926,0.9948652261922886,1740481172.459759,4.279995918273926,0.05134773807711879,1740481172.4597604,4.279995918273926,0.08001133491807455,1740481172.4597614,4.279995918273926,0.0,1740481172.4597626,4.279995918273926,0.9656808454370569,1740481179.8385496,11.65998888015747 +1740481172.4780025,4.2999958992004395,2.877816094627512,1740481172.4780042,4.2999958992004395,0.0,1740481172.4780064,4.2999958992004395,0.01725308103054727,1740481172.4780083,4.2999958992004395,6.7202324491408,1740481172.4780095,4.2999958992004395,0.0,1740481172.4780107,4.2999958992004395,0.0,1740481172.4780116,4.2999958992004395,0.0,1740481172.4780126,4.2999958992004395,0.0,1740481172.4780135,4.2999958992004395,0.9948652261922886,1740481172.4780145,4.2999958992004395,0.05134773807711879,1740481172.4780152,4.2999958992004395,0.08053211883235045,1740481172.478016,4.2999958992004395,0.0,1740481172.478017,4.2999958992004395,0.9656808454370569,1740481179.8595586,11.679988861083984 +1740481172.4980793,4.319995880126953,2.877816094627512,1740481172.498081,4.319995880126953,0.0,1740481172.4980834,4.319995880126953,0.01725308103054727,1740481172.4980853,4.319995880126953,6.7202324491408,1740481172.4980865,4.319995880126953,0.0,1740481172.4980876,4.319995880126953,0.0,1740481172.4980886,4.319995880126953,0.0,1740481172.49809,4.319995880126953,0.0,1740481172.4980912,4.319995880126953,0.9948652261922886,1740481172.4980922,4.319995880126953,0.05134773807711879,1740481172.4980931,4.319995880126953,0.08053211883235045,1740481172.498094,4.319995880126953,0.0,1740481172.4980948,4.319995880126953,0.9656808454370569,1740481179.8806162,11.699988842010498 +1740481172.5227218,4.339995861053467,2.877816094627512,1740481172.5227234,4.339995861053467,0.0,1740481172.5227256,4.339995861053467,0.0,1740481172.5227275,4.339995861053467,6.8091777855016264,1740481172.5227284,4.339995861053467,0.0,1740481172.5227294,4.339995861053467,0.0,1740481172.5227306,4.339995861053467,0.0,1740481172.5227315,4.339995861053467,0.0,1740481172.5227325,4.339995861053467,0.9951916337948117,1740481172.5227332,4.339995861053467,0.0,1740481172.5227342,4.339995861053467,0.02951078835775478,1740481172.522735,4.339995861053467,0.0,1740481172.5227358,4.339995861053467,0.9656808454370569,1740481179.897898,11.719988822937012 +1740481172.5381398,4.3599958419799805,2.877816094627512,1740481172.5381417,4.3599958419799805,0.0,1740481172.538144,4.3599958419799805,0.0,1740481172.538146,4.3599958419799805,6.8091777855016264,1740481172.538147,4.3599958419799805,0.0,1740481172.5381482,4.3599958419799805,0.0,1740481172.538149,4.3599958419799805,0.0,1740481172.53815,4.3599958419799805,0.0,1740481172.538151,4.3599958419799805,0.9951916337948117,1740481172.5381517,4.3599958419799805,0.0,1740481172.5381527,4.3599958419799805,0.02951078835775478,1740481172.5381534,4.3599958419799805,0.0,1740481172.5381546,4.3599958419799805,0.9656808454370569,1740481179.9186335,11.739988803863525 +1740481172.5591023,4.379995822906494,2.9841005689551396,1740481172.559104,4.379995822906494,0.0,1740481172.5591059,4.379995822906494,0.017272727099963536,1740481172.5591078,4.379995822906494,6.827399090285288,1740481172.5591085,4.379995822906494,0.0,1740481172.5591102,4.379995822906494,0.0,1740481172.5591109,4.379995822906494,0.0,1740481172.5591123,4.379995822906494,0.0,1740481172.5591133,4.379995822906494,0.9951916337948117,1740481172.5591142,4.379995822906494,0.04808366205188763,1740481172.559115,4.379995822906494,0.07690457552499017,1740481172.5591161,4.379995822906494,0.0,1740481172.5591168,4.379995822906494,0.9661551342789061,1740481179.9389048,11.759988784790039 +1740481172.577849,4.399995803833008,2.9841005689551396,1740481172.5779047,4.399995803833008,0.0,1740481172.577908,4.399995803833008,0.017272727099963536,1740481172.57791,4.399995803833008,6.827399090285288,1740481172.5779111,4.399995803833008,0.0,1740481172.5779123,4.399995803833008,0.0,1740481172.5779133,4.399995803833008,0.0,1740481172.577915,4.399995803833008,0.0,1740481172.5779157,4.399995803833008,0.9951916337948117,1740481172.5779164,4.399995803833008,0.04808366205188763,1740481172.5779173,4.399995803833008,0.07712016156779322,1740481172.5779183,4.399995803833008,0.0,1740481172.5779192,4.399995803833008,0.9661551342789061,1740481179.9597578,11.779988765716553 +1740481172.5977962,4.4199957847595215,2.9841005689551396,1740481172.5977976,4.4199957847595215,0.0,1740481172.5977995,4.4199957847595215,0.017272727099963536,1740481172.5978014,4.4199957847595215,6.827399090285288,1740481172.5978024,4.4199957847595215,0.0,1740481172.597804,4.4199957847595215,0.0,1740481172.597805,4.4199957847595215,0.0,1740481172.597806,4.4199957847595215,0.0,1740481172.597807,4.4199957847595215,0.9951916337948117,1740481172.597808,4.4199957847595215,0.04808366205188763,1740481172.5978086,4.4199957847595215,0.07712016156779322,1740481172.5978096,4.4199957847595215,0.0,1740481172.5978105,4.4199957847595215,0.9661551342789061,1740481179.9777355,11.799988746643066 +1740481172.6223462,4.439995765686035,2.9841005689551396,1740481172.6223493,4.439995765686035,0.0,1740481172.6223526,4.439995765686035,0.0,1740481172.6223555,4.439995765686035,6.916410837512952,1740481172.6223564,4.439995765686035,0.0,1740481172.6223583,4.439995765686035,0.0,1740481172.6223593,4.439995765686035,0.0,1740481172.6223614,4.439995765686035,0.0,1740481172.622363,4.439995765686035,0.9953236181573983,1740481172.622365,4.439995765686035,0.0,1740481172.6223662,4.439995765686035,0.029168483878492246,1740481172.6223674,4.439995765686035,0.0,1740481172.6223686,4.439995765686035,0.9661551342789061,1740481179.998042,11.81998872756958 +1740481172.638083,4.459995746612549,2.9841005689551396,1740481172.638085,4.459995746612549,0.0,1740481172.6380873,4.459995746612549,0.0,1740481172.6380892,4.459995746612549,6.916410837512952,1740481172.6380901,4.459995746612549,0.0,1740481172.6380916,4.459995746612549,0.0,1740481172.6380923,4.459995746612549,0.0,1740481172.6380932,4.459995746612549,0.0,1740481172.6380942,4.459995746612549,0.9953236181573983,1740481172.6380951,4.459995746612549,0.0,1740481172.6380959,4.459995746612549,0.029168483878492246,1740481172.6380968,4.459995746612549,0.0,1740481172.6380978,4.459995746612549,0.9661551342789061,1740481191.5649443,23.339977741241455 +1740481172.6597524,4.4799957275390625,2.9841005689551396,1740481172.6597545,4.4799957275390625,0.0,1740481172.6597576,4.4799957275390625,0.0,1740481172.6597598,4.4799957275390625,6.916410837512952,1740481172.6597612,4.4799957275390625,0.0,1740481172.6597626,4.4799957275390625,0.0,1740481172.659764,4.4799957275390625,0.0,1740481172.6597652,4.4799957275390625,0.0,1740481172.6597662,4.4799957275390625,0.9953236181573983,1740481172.6597676,4.4799957275390625,0.0,1740481172.6597686,4.4799957275390625,0.029168483878492246,1740481172.6597695,4.4799957275390625,0.0,1740481172.6597707,4.4799957275390625,0.9661551342789061,1740481191.5876439,23.35997772216797 +1740481172.6784542,4.499995708465576,3.090455373258246,1740481172.678456,4.499995708465576,0.0,1740481172.6784582,4.499995708465576,0.017286448973999252,1740481172.6784601,4.499995708465576,6.934126875518829,1740481172.6784608,4.499995708465576,0.0,1740481172.6784623,4.499995708465576,0.0,1740481172.6784632,4.499995708465576,0.0,1740481172.6784642,4.499995708465576,0.0,1740481172.6784651,4.499995708465576,0.9953236181573983,1740481172.6784663,4.499995708465576,0.046763818426021064,1740481172.6784673,4.499995708465576,0.07561987382458214,1740481172.6784685,4.499995708465576,0.0,1740481172.6784694,4.499995708465576,0.966369928794845,1740481191.6032712,23.379977703094482 +1740481172.698065,4.51999568939209,3.090455373258246,1740481172.6980667,4.51999568939209,0.0,1740481172.6980686,4.51999568939209,0.017286448973999252,1740481172.6980708,4.51999568939209,6.934126875518829,1740481172.6980715,4.51999568939209,0.0,1740481172.698073,4.51999568939209,0.0,1740481172.6980739,4.51999568939209,0.0,1740481172.6980748,4.51999568939209,0.0,1740481172.698076,4.51999568939209,0.9953236181573983,1740481172.6980767,4.51999568939209,0.046763818426021064,1740481172.6980777,4.51999568939209,0.07571750778857445,1740481172.6980784,4.51999568939209,0.0,1740481172.6980796,4.51999568939209,0.966369928794845,1740481191.6233401,23.399977684020996 +1740481172.7221596,4.5399956703186035,3.090455373258246,1740481172.722162,4.5399956703186035,0.0,1740481172.7221642,4.5399956703186035,0.0,1740481172.7221663,4.5399956703186035,7.023195230847936,1740481172.7221675,4.5399956703186035,0.0,1740481172.722169,4.5399956703186035,0.0,1740481172.7221696,4.5399956703186035,0.0,1740481172.7221706,4.5399956703186035,0.0,1740481172.7221715,4.5399956703186035,0.9953827865881203,1740481172.7221727,4.5399956703186035,0.0,1740481172.7221735,4.5399956703186035,0.029012857793275337,1740481172.7221744,4.5399956703186035,0.0,1740481172.7221756,4.5399956703186035,0.966369928794845,1740481191.6448636,23.41997766494751 +1740481172.738831,4.559995651245117,3.090455373258246,1740481172.738833,4.559995651245117,0.0,1740481172.7388349,4.559995651245117,0.0,1740481172.738837,4.559995651245117,7.023195230847936,1740481172.7388382,4.559995651245117,0.0,1740481172.7388396,4.559995651245117,0.0,1740481172.7388406,4.559995651245117,0.0,1740481172.7388415,4.559995651245117,0.0,1740481172.7388427,4.559995651245117,0.9953827865881203,1740481172.7388437,4.559995651245117,0.0,1740481172.7388444,4.559995651245117,0.029012857793275337,1740481172.7388453,4.559995651245117,0.0,1740481172.7388463,4.559995651245117,0.966369928794845,1740481191.6643758,23.439977645874023 +1740481172.7595465,4.579995632171631,3.090455373258246,1740481172.7595487,4.579995632171631,0.0,1740481172.759551,4.579995632171631,0.0,1740481172.7595532,4.579995632171631,7.023195230847936,1740481172.7595544,4.579995632171631,0.0,1740481172.7595556,4.579995632171631,0.0,1740481172.7595568,4.579995632171631,0.0,1740481172.759558,4.579995632171631,0.0,1740481172.7595587,4.579995632171631,0.9953827865881203,1740481172.7595599,4.579995632171631,0.0,1740481172.759561,4.579995632171631,0.029012857793275337,1740481172.759562,4.579995632171631,0.0,1740481172.7595632,4.579995632171631,0.966369928794845,1740481191.6834335,23.459977626800537 +1740481172.7780385,4.5999956130981445,3.1967619488829992,1740481172.7780404,4.5999956130981445,0.0,1740481172.7780423,4.5999956130981445,0.017279637245229174,1740481172.7780442,4.5999956130981445,7.038841967901033,1740481172.7780452,4.5999956130981445,0.0,1740481172.7780464,4.5999956130981445,0.0,1740481172.7780476,4.5999956130981445,0.0,1740481172.7780488,4.5999956130981445,0.0,1740481172.7780495,4.5999956130981445,0.9953827865881203,1740481172.7780507,4.5999956130981445,0.0461721341188015,1740481172.7780516,4.5999956130981445,0.07637255604209527,1740481172.7780526,4.5999956130981445,0.0,1740481172.7780535,4.5999956130981445,0.9655534786987786,1740481191.7033026,23.47997760772705 +1740481172.7982173,4.619995594024658,3.1967619488829992,1740481172.7982192,4.619995594024658,0.0,1740481172.7982213,4.619995594024658,0.017279637245229174,1740481172.7982233,4.619995594024658,7.038841967901033,1740481172.7982244,4.619995594024658,0.0,1740481172.7982254,4.619995594024658,0.0,1740481172.7982264,4.619995594024658,0.0,1740481172.7982275,4.619995594024658,0.0,1740481172.7982285,4.619995594024658,0.9953827865881203,1740481172.7982295,4.619995594024658,0.0461721341188015,1740481172.7982304,4.619995594024658,0.07600144200814318,1740481172.7982314,4.619995594024658,0.0,1740481172.7982326,4.619995594024658,0.9655534786987786,1740481191.7243438,23.499977588653564 +1740481172.8203857,4.639995574951172,3.1967619488829992,1740481172.8203876,4.639995574951172,0.0,1740481172.8203897,4.639995574951172,0.0,1740481172.820392,4.639995574951172,7.127868906280557,1740481172.8203926,4.639995574951172,0.0,1740481172.820394,4.639995574951172,0.0,1740481172.820395,4.639995574951172,0.0,1740481172.8203957,4.639995574951172,0.0,1740481172.820397,4.639995574951172,0.9951558775322438,1740481172.8203976,4.639995574951172,0.0,1740481172.8203986,4.639995574951172,0.02960239883346516,1740481172.8203993,4.639995574951172,0.0,1740481172.8204005,4.639995574951172,0.9655534786987786,1740481191.7438195,23.519977569580078 +1740481172.8382857,4.6599955558776855,3.1967619488829992,1740481172.8382874,4.6599955558776855,0.0,1740481172.8382895,4.6599955558776855,0.0,1740481172.8382916,4.6599955558776855,7.127868906280557,1740481172.838293,4.6599955558776855,0.0,1740481172.8382943,4.6599955558776855,0.0,1740481172.8382952,4.6599955558776855,0.0,1740481172.8382964,4.6599955558776855,0.0,1740481172.8382971,4.6599955558776855,0.9951558775322438,1740481172.8382983,4.6599955558776855,0.0,1740481172.838299,4.6599955558776855,0.02960239883346516,1740481172.8383,4.6599955558776855,0.0,1740481172.838301,4.6599955558776855,0.9655534786987786,1740481191.7666519,23.539977550506592 +1740481172.859802,4.679995536804199,3.1967619488829992,1740481172.8598077,4.679995536804199,0.0,1740481172.8598151,4.679995536804199,0.0,1740481172.8598185,4.679995536804199,7.127868906280557,1740481172.8598208,4.679995536804199,0.0,1740481172.8598235,4.679995536804199,0.0,1740481172.859825,4.679995536804199,0.0,1740481172.8598268,4.679995536804199,0.0,1740481172.859829,4.679995536804199,0.9951558775322438,1740481172.859831,4.679995536804199,0.0,1740481172.8598323,4.679995536804199,0.02960239883346516,1740481172.8598337,4.679995536804199,0.0,1740481172.8598351,4.679995536804199,0.9655534786987786,1740481191.7835014,23.559977531433105 +1740481172.8778296,4.699995517730713,3.1967619488829992,1740481172.8778312,4.699995517730713,0.0,1740481172.8778334,4.699995517730713,0.0,1740481172.8778355,4.699995517730713,7.127868906280557,1740481172.8778365,4.699995517730713,0.0,1740481172.8778377,4.699995517730713,0.0,1740481172.8778386,4.699995517730713,0.0,1740481172.8778396,4.699995517730713,0.0,1740481172.8778403,4.699995517730713,0.9951558775322438,1740481172.8778415,4.699995517730713,0.0,1740481172.8778422,4.699995517730713,0.02960239883346516,1740481172.877843,4.699995517730713,0.0,1740481172.8778436,4.699995517730713,0.9655534786987786,1740481191.8037152,23.57997751235962 +1740481172.8982215,4.719995498657227,3.3029772034922757,1740481172.8982234,4.719995498657227,0.0,1740481172.8982463,4.719995498657227,0.017260857730786845,1740481172.8982487,4.719995498657227,7.14269631916025,1740481172.8982496,4.719995498657227,0.0,1740481172.898251,4.719995498657227,0.0,1740481172.898252,4.719995498657227,0.0,1740481172.898253,4.719995498657227,0.0,1740481172.898254,4.719995498657227,0.9951558775322438,1740481172.8982735,4.719995498657227,0.04844122467756673,1740481172.8982747,4.719995498657227,0.07981340211198937,1740481172.8982754,4.719995498657227,0.0,1740481172.8982763,4.719995498657227,0.9643367562732322,1740481191.8236918,23.599977493286133 +1740481172.9224331,4.73999547958374,3.3029772034922757,1740481172.9224353,4.73999547958374,0.0,1740481172.922438,4.73999547958374,0.0,1740481172.9224405,4.73999547958374,7.23165071603874,1740481172.9224415,4.73999547958374,0.0,1740481172.922443,4.73999547958374,0.0,1740481172.9224443,4.73999547958374,0.0,1740481172.9224453,4.73999547958374,0.0,1740481172.9224463,4.73999547958374,0.9948076249069352,1740481172.9224477,4.73999547958374,0.0,1740481172.9224486,4.73999547958374,0.030470868633702963,1740481172.9224494,4.73999547958374,0.0,1740481172.9224505,4.73999547958374,0.9643367562732322,1740481191.8445492,23.619977474212646 +1740481172.9379456,4.759995460510254,3.3029772034922757,1740481172.937947,4.759995460510254,0.0,1740481172.9379492,4.759995460510254,0.0,1740481172.9379513,4.759995460510254,7.23165071603874,1740481172.9379523,4.759995460510254,0.0,1740481172.9379532,4.759995460510254,0.0,1740481172.9379542,4.759995460510254,0.0,1740481172.9379554,4.759995460510254,0.0,1740481172.937956,4.759995460510254,0.9948076249069352,1740481172.9379568,4.759995460510254,0.0,1740481172.9379575,4.759995460510254,0.030470868633702963,1740481172.9379587,4.759995460510254,0.0,1740481172.9379594,4.759995460510254,0.9643367562732322,1740481191.8654392,23.63997745513916 +1740481172.960434,4.779995441436768,3.3029772034922757,1740481172.9604356,4.779995441436768,0.0,1740481172.960438,4.779995441436768,0.0,1740481172.9604402,4.779995441436768,7.23165071603874,1740481172.960441,4.779995441436768,0.0,1740481172.9604423,4.779995441436768,0.0,1740481172.9604435,4.779995441436768,0.0,1740481172.9604445,4.779995441436768,0.0,1740481172.9604454,4.779995441436768,0.9948076249069352,1740481172.9604461,4.779995441436768,0.0,1740481172.9604473,4.779995441436768,0.030470868633702963,1740481172.960448,4.779995441436768,0.0,1740481172.960449,4.779995441436768,0.9643367562732322,1740481191.8839915,23.659977436065674 +1740481172.9778142,4.799995422363281,3.3029772034922757,1740481172.977816,4.799995422363281,0.0,1740481172.9778187,4.799995422363281,0.0,1740481172.9778206,4.799995422363281,7.23165071603874,1740481172.9778216,4.799995422363281,0.0,1740481172.977823,4.799995422363281,0.0,1740481172.977824,4.799995422363281,0.0,1740481172.977825,4.799995422363281,0.0,1740481172.977826,4.799995422363281,0.9948076249069352,1740481172.977827,4.799995422363281,0.0,1740481172.9778278,4.799995422363281,0.030470868633702963,1740481172.977829,4.799995422363281,0.0,1740481172.9778302,4.799995422363281,0.9643367562732322,1740481191.9037452,23.679977416992188 +1740481172.9984632,4.819995403289795,3.409023071746164,1740481172.9984653,4.819995403289795,0.0,1740481172.99848,4.819995403289795,0.017227300279931405,1740481172.9984841,4.819995403289795,7.245875525216614,1740481172.9984853,4.819995403289795,0.0,1740481172.9984865,4.819995403289795,0.0,1740481172.9984875,4.819995403289795,0.0,1740481172.9984887,4.819995403289795,0.0,1740481172.9984896,4.819995403289795,0.9948076249069352,1740481172.9984906,4.819995403289795,0.05192375093060919,1740481172.9984913,4.819995403289795,0.08457825010749043,1740481172.9984925,4.819995403289795,0.0,1740481172.9984932,4.819995403289795,0.9628355107222036,1740481191.9240415,23.6999773979187 +1740481173.0219676,4.839995384216309,3.409023071746164,1740481173.0219696,4.839995384216309,0.0,1740481173.021972,4.839995384216309,0.0,1740481173.021974,4.839995384216309,7.3346940931905715,1740481173.0219753,4.839995384216309,0.0,1740481173.0219762,4.839995384216309,0.0,1740481173.0219774,4.839995384216309,0.0,1740481173.0219784,4.839995384216309,0.0,1740481173.0219793,4.839995384216309,0.9943612776197635,1740481173.0219805,4.839995384216309,0.0,1740481173.0219812,4.839995384216309,0.031525766897559815,1740481173.0219822,4.839995384216309,0.0,1740481173.021983,4.839995384216309,0.9628355107222036,1740481191.9437718,23.719977378845215 +1740481173.0382502,4.859995365142822,3.409023071746164,1740481173.0382524,4.859995365142822,0.0,1740481173.0382545,4.859995365142822,0.0,1740481173.0382566,4.859995365142822,7.3346940931905715,1740481173.0382576,4.859995365142822,0.0,1740481173.038259,4.859995365142822,0.0,1740481173.03826,4.859995365142822,0.0,1740481173.038261,4.859995365142822,0.0,1740481173.0382617,4.859995365142822,0.9943612776197635,1740481173.038263,4.859995365142822,0.0,1740481173.0382638,4.859995365142822,0.031525766897559815,1740481173.0382648,4.859995365142822,0.0,1740481173.0382657,4.859995365142822,0.9628355107222036,1740481191.9643826,23.73997735977173 +1740481173.0589054,4.879995346069336,3.409023071746164,1740481173.0589087,4.879995346069336,0.0,1740481173.0589125,4.879995346069336,0.0,1740481173.058915,4.879995346069336,7.3346940931905715,1740481173.0589159,4.879995346069336,0.0,1740481173.058917,4.879995346069336,0.0,1740481173.0589182,4.879995346069336,0.0,1740481173.0589192,4.879995346069336,0.0,1740481173.0589201,4.879995346069336,0.9943612776197635,1740481173.0589209,4.879995346069336,0.0,1740481173.058922,4.879995346069336,0.031525766897559815,1740481173.0589228,4.879995346069336,0.0,1740481173.0589237,4.879995346069336,0.9628355107222036,1740481191.9853327,23.759977340698242 +1740481173.0802686,4.89999532699585,3.409023071746164,1740481173.0802717,4.89999532699585,0.0,1740481173.080275,4.89999532699585,0.0,1740481173.0802774,4.89999532699585,7.3346940931905715,1740481173.0802786,4.89999532699585,0.0,1740481173.08028,4.89999532699585,0.0,1740481173.0802813,4.89999532699585,0.0,1740481173.0802824,4.89999532699585,0.0,1740481173.0802836,4.89999532699585,0.9943612776197635,1740481173.0802846,4.89999532699585,0.0,1740481173.0802858,4.89999532699585,0.031525766897559815,1740481173.0802867,4.89999532699585,0.0,1740481173.0802877,4.89999532699585,0.9628355107222036,1740481192.003502,23.779977321624756 +1740481173.098422,4.919995307922363,3.409023071746164,1740481173.0984244,4.919995307922363,0.0,1740481173.098427,4.919995307922363,0.0,1740481173.0984297,4.919995307922363,7.3346940931905715,1740481173.0984316,4.919995307922363,0.0,1740481173.0984335,4.919995307922363,0.0,1740481173.098435,4.919995307922363,0.0,1740481173.0984507,4.919995307922363,0.0,1740481173.0984526,4.919995307922363,0.9943612776197635,1740481173.0984538,4.919995307922363,0.0,1740481173.0984552,4.919995307922363,0.031525766897559815,1740481173.0984564,4.919995307922363,0.0,1740481173.0984576,4.919995307922363,0.9628355107222036,1740481192.0238292,23.79997730255127 +1740481173.1206872,4.939995288848877,3.514935739273505,1740481173.1206892,4.939995288848877,0.0,1740481173.1207032,4.939995288848877,0.0,1740481173.120706,4.939995288848877,7.438094766817164,1740481173.1207068,4.939995288848877,0.0,1740481173.120708,4.939995288848877,0.0,1740481173.1207092,4.939995288848877,0.0,1740481173.12071,4.939995288848877,0.0,1740481173.1207108,4.939995288848877,0.9939737091516396,1740481173.1207116,4.939995288848877,0.06026290848356486,1740481173.1207128,4.939995288848877,0.0930518444590335,1740481173.1207135,4.939995288848877,0.0,1740481173.1207147,4.939995288848877,0.9615795137718296,1740481192.0438447,23.819977283477783 +1740481173.1380413,4.959995269775391,3.514935739273505,1740481173.1380432,4.959995269775391,0.0,1740481173.1380455,4.959995269775391,0.0,1740481173.1380475,4.959995269775391,7.438094766817164,1740481173.1380484,4.959995269775391,0.0,1740481173.1380498,4.959995269775391,0.0,1740481173.1380508,4.959995269775391,0.0,1740481173.1380517,4.959995269775391,0.0,1740481173.1380527,4.959995269775391,0.9939737091516396,1740481173.1380541,4.959995269775391,0.06026290848356486,1740481173.1380548,4.959995269775391,0.09265710386337489,1740481173.138056,4.959995269775391,0.0,1740481173.1380568,4.959995269775391,0.9615795137718296,1740481192.0679011,23.839977264404297 +1740481173.1597822,4.979995250701904,3.514935739273505,1740481173.1597865,4.979995250701904,0.0,1740481173.1597915,4.979995250701904,0.0,1740481173.1597943,4.979995250701904,7.438094766817164,1740481173.1597965,4.979995250701904,0.0,1740481173.159799,4.979995250701904,0.0,1740481173.1598005,4.979995250701904,0.0,1740481173.159803,4.979995250701904,0.0,1740481173.1598043,4.979995250701904,0.9939737091516396,1740481173.159806,4.979995250701904,0.06026290848356486,1740481173.159807,4.979995250701904,0.09265710386337489,1740481173.1598084,4.979995250701904,0.0,1740481173.15981,4.979995250701904,0.9615795137718296,1740481192.0840387,23.85997724533081 +1740481173.1814733,4.999995231628418,3.514935739273505,1740481173.1814997,4.999995231628418,0.0,1740481173.1815026,4.999995231628418,0.0,1740481173.1815047,4.999995231628418,7.438094766817164,1740481173.1815062,4.999995231628418,0.0,1740481173.1815073,4.999995231628418,0.0,1740481173.1815274,4.999995231628418,0.0,1740481173.1815283,4.999995231628418,0.0,1740481173.181529,4.999995231628418,0.9939737091516396,1740481173.1815305,4.999995231628418,0.06026290848356486,1740481173.1815314,4.999995231628418,0.09265710386337489,1740481173.1815326,4.999995231628418,0.0,1740481173.181534,4.999995231628418,0.9615795137718296,1740481192.103669,23.879977226257324 +1740481173.1989486,5.019995212554932,3.514935739273505,1740481173.19895,5.019995212554932,0.0,1740481173.1989524,5.019995212554932,0.0,1740481173.1989546,5.019995212554932,7.438094766817164,1740481173.1989558,5.019995212554932,0.0,1740481173.1989567,5.019995212554932,0.0,1740481173.198958,5.019995212554932,0.0,1740481173.198959,5.019995212554932,0.0,1740481173.19896,5.019995212554932,0.9939737091516396,1740481173.1989608,5.019995212554932,0.06026290848356486,1740481173.198962,5.019995212554932,0.09265710386337489,1740481173.1989627,5.019995212554932,0.0,1740481173.1989634,5.019995212554932,0.9615795137718296,1740481192.1238554,23.899977207183838 +1740481173.2210166,5.039995193481445,3.6208431355408974,1740481173.2210183,5.039995193481445,0.0,1740481173.2210207,5.039995193481445,0.0,1740481173.2210226,5.039995193481445,7.55054980561302,1740481173.2210238,5.039995193481445,0.0,1740481173.2210248,5.039995193481445,0.0,1740481173.2210257,5.039995193481445,0.0,1740481173.2210267,5.039995193481445,0.0,1740481173.2210276,5.039995193481445,0.9949569576205534,1740481173.2210283,5.039995193481445,0.050430423794470824,1740481173.221029,5.039995193481445,0.07949287593360845,1740481173.22103,5.039995193481445,0.0,1740481173.221031,5.039995193481445,0.9648533350360611,1740481192.1439013,23.91997718811035 +1740481173.2380831,5.059995174407959,3.6208431355408974,1740481173.2380853,5.059995174407959,0.0,1740481173.2380881,5.059995174407959,0.0,1740481173.2380903,5.059995174407959,7.55054980561302,1740481173.2380912,5.059995174407959,0.0,1740481173.238093,5.059995174407959,0.0,1740481173.2380939,5.059995174407959,0.0,1740481173.2380948,5.059995174407959,0.0,1740481173.2380958,5.059995174407959,0.9949569576205534,1740481173.2380972,5.059995174407959,0.050430423794470824,1740481173.238098,5.059995174407959,0.08053404637896311,1740481173.2380989,5.059995174407959,0.0,1740481173.2380998,5.059995174407959,0.9648533350360611,1740481192.163591,23.939977169036865 +1740481173.2585278,5.079995155334473,3.6208431355408974,1740481173.2585294,5.079995155334473,0.0,1740481173.2585323,5.079995155334473,0.0,1740481173.2585342,5.079995155334473,7.55054980561302,1740481173.2585351,5.079995155334473,0.0,1740481173.2585363,5.079995155334473,0.0,1740481173.2585375,5.079995155334473,0.0,1740481173.2585385,5.079995155334473,0.0,1740481173.2585392,5.079995155334473,0.9949569576205534,1740481173.2585404,5.079995155334473,0.050430423794470824,1740481173.2585413,5.079995155334473,0.08053404637896311,1740481173.258542,5.079995155334473,0.0,1740481173.258543,5.079995155334473,0.9648533350360611,1740481192.18338,23.95997714996338 +1740481173.2777312,5.099995136260986,3.6208431355408974,1740481173.2777328,5.099995136260986,0.0,1740481173.277735,5.099995136260986,0.0,1740481173.277737,5.099995136260986,7.55054980561302,1740481173.2777376,5.099995136260986,0.0,1740481173.2777393,5.099995136260986,0.0,1740481173.2777402,5.099995136260986,0.0,1740481173.2777412,5.099995136260986,0.0,1740481173.2777424,5.099995136260986,0.9949569576205534,1740481173.2777436,5.099995136260986,0.050430423794470824,1740481173.2777443,5.099995136260986,0.08053404637896311,1740481173.2777452,5.099995136260986,0.0,1740481173.2777462,5.099995136260986,0.9648533350360611,1740481192.2041864,23.979977130889893 +1740481173.2979534,5.1199951171875,3.6208431355408974,1740481173.297955,5.1199951171875,0.0,1740481173.2979572,5.1199951171875,0.0,1740481173.297959,5.1199951171875,7.55054980561302,1740481173.2979603,5.1199951171875,0.0,1740481173.2979615,5.1199951171875,0.0,1740481173.2979624,5.1199951171875,0.0,1740481173.2979636,5.1199951171875,0.0,1740481173.2979643,5.1199951171875,0.9949569576205534,1740481173.2979653,5.1199951171875,0.050430423794470824,1740481173.2979662,5.1199951171875,0.08053404637896311,1740481173.2979672,5.1199951171875,0.0,1740481173.2979684,5.1199951171875,0.9648533350360611,1740481192.2232993,23.999977111816406 +1740481173.3230207,5.139995098114014,3.6208431355408974,1740481173.3230228,5.139995098114014,0.0,1740481173.3230252,5.139995098114014,0.0,1740481173.3230271,5.139995098114014,7.55054980561302,1740481173.3230278,5.139995098114014,0.0,1740481173.3230293,5.139995098114014,0.0,1740481173.3230302,5.139995098114014,0.0,1740481173.323031,5.139995098114014,0.0,1740481173.3230321,5.139995098114014,0.9949569576205534,1740481173.323033,5.139995098114014,0.050430423794470824,1740481173.3230338,5.139995098114014,0.08053404637896311,1740481173.3230348,5.139995098114014,0.0,1740481173.3230357,5.139995098114014,0.9648533350360611,1740481192.245339,24.01997709274292 +1740481173.3392768,5.159995079040527,3.72710116833111,1740481173.3392794,5.159995079040527,0.0,1740481173.3392823,5.159995079040527,0.01726435790787523,1740481173.3392847,5.159995079040527,7.57281133529811,1740481173.3392863,5.159995079040527,0.0,1740481173.3392878,5.159995079040527,0.0,1740481173.33929,5.159995079040527,0.0,1740481173.3392913,5.159995079040527,0.0,1740481173.3392928,5.159995079040527,1.0000000000000004,1740481173.339294,5.159995079040527,6.661338147750939e-15,1740481173.339295,5.159995079040527,0.03380465131053155,1740481173.3392963,5.159995079040527,0.0,1740481173.3392975,5.159995079040527,0.9673519209246686,1740481192.2670984,24.039977073669434 +1740481173.359935,5.179995059967041,3.72710116833111,1740481173.359937,5.179995059967041,0.0,1740481173.359939,5.179995059967041,0.01726435790787523,1740481173.359941,5.179995059967041,7.57281133529811,1740481173.3599422,5.179995059967041,0.0,1740481173.3599434,5.179995059967041,0.0,1740481173.3599443,5.179995059967041,0.0,1740481173.3599458,5.179995059967041,0.0,1740481173.3599465,5.179995059967041,1.0000000000000004,1740481173.3599477,5.179995059967041,6.661338147750939e-15,1740481173.3599489,5.179995059967041,0.03264807907533851,1740481173.3599498,5.179995059967041,0.0,1740481173.3599505,5.179995059967041,0.9673519209246686,1740481192.2861705,24.059977054595947 +1740481173.3788435,5.199995040893555,3.72710116833111,1740481173.3788457,5.199995040893555,0.0,1740481173.3788478,5.199995040893555,0.01726435790787523,1740481173.3788495,5.199995040893555,7.57281133529811,1740481173.3788505,5.199995040893555,0.0,1740481173.3788521,5.199995040893555,0.0,1740481173.378853,5.199995040893555,0.0,1740481173.3788538,5.199995040893555,0.0,1740481173.378855,5.199995040893555,1.0000000000000004,1740481173.378856,5.199995040893555,6.661338147750939e-15,1740481173.3788567,5.199995040893555,0.03264807907533851,1740481173.3788576,5.199995040893555,0.0,1740481173.3788586,5.199995040893555,0.9673519209246686,1740481192.303963,24.069977045059204 +1740481173.3989487,5.219995021820068,3.72710116833111,1740481173.3989503,5.219995021820068,0.0,1740481173.3989527,5.219995021820068,0.01726435790787523,1740481173.3989549,5.219995021820068,7.57281133529811,1740481173.3989558,5.219995021820068,0.0,1740481173.398957,5.219995021820068,0.0,1740481173.398958,5.219995021820068,0.0,1740481173.3989592,5.219995021820068,0.0,1740481173.39896,5.219995021820068,1.0000000000000004,1740481173.398961,5.219995021820068,6.661338147750939e-15,1740481173.398962,5.219995021820068,0.03264807907533851,1740481173.398963,5.219995021820068,0.0,1740481173.398964,5.219995021820068,0.9673519209246686,1740481192.3240693,24.099977016448975 +1740481173.420625,5.239995002746582,3.72710116833111,1740481173.4206266,5.239995002746582,0.0,1740481173.4206288,5.239995002746582,0.0,1740481173.4206307,5.239995002746582,7.661805010180448,1740481173.420632,5.239995002746582,0.0,1740481173.420633,5.239995002746582,0.0,1740481173.420634,5.239995002746582,0.0,1740481173.420635,5.239995002746582,0.0,1740481173.420636,5.239995002746582,0.9956484934446073,1740481173.420637,5.239995002746582,0.0,1740481173.4206376,5.239995002746582,0.028296572519938668,1740481173.4206388,5.239995002746582,0.0,1740481173.4206395,5.239995002746582,0.9673519209246686,1740481192.34381,24.11997699737549 +1740481173.438003,5.259994983673096,3.8334215041811595,1740481173.438005,5.259994983673096,0.0,1740481173.438007,5.259994983673096,0.01728648711814532,1740481173.438009,5.259994983673096,7.674416686663481,1740481173.4380102,5.259994983673096,0.0,1740481173.4380116,5.259994983673096,0.0,1740481173.4380126,5.259994983673096,0.0,1740481173.4380138,5.259994983673096,0.0,1740481173.4380147,5.259994983673096,0.9956484934446073,1740481173.4380155,5.259994983673096,0.04351506555388851,1740481173.4380164,5.259994983673096,0.07521150136714767,1740481173.4380174,5.259994983673096,0.0,1740481173.4380183,5.259994983673096,0.9650145156071125,1740481192.3640895,24.139976978302002 +1740481173.4616091,5.279994964599609,3.8334215041811595,1740481173.4616113,5.279994964599609,0.0,1740481173.4616134,5.279994964599609,0.01728648711814532,1740481173.4616153,5.279994964599609,7.674416686663481,1740481173.4616163,5.279994964599609,0.0,1740481173.4616177,5.279994964599609,0.0,1740481173.4616184,5.279994964599609,0.0,1740481173.4616194,5.279994964599609,0.0,1740481173.4616203,5.279994964599609,0.9956484934446073,1740481173.4616213,5.279994964599609,0.04351506555388851,1740481173.4616222,5.279994964599609,0.07414904339138328,1740481173.461623,5.279994964599609,0.0,1740481173.4616241,5.279994964599609,0.9650145156071125,1740481192.3851004,24.159976959228516 +1740481173.478058,5.299994945526123,3.8334215041811595,1740481173.4780598,5.299994945526123,0.0,1740481173.478062,5.299994945526123,0.01728648711814532,1740481173.478064,5.299994945526123,7.674416686663481,1740481173.478065,5.299994945526123,0.0,1740481173.4780662,5.299994945526123,0.0,1740481173.4780672,5.299994945526123,0.0,1740481173.478068,5.299994945526123,0.0,1740481173.4780693,5.299994945526123,0.9956484934446073,1740481173.4780703,5.299994945526123,0.04351506555388851,1740481173.4780712,5.299994945526123,0.07414904339138328,1740481173.4780722,5.299994945526123,0.0,1740481173.4780731,5.299994945526123,0.9650145156071125,1740481192.4032323,24.17997694015503 +1740481173.4979413,5.319994926452637,3.8334215041811595,1740481173.497943,5.319994926452637,0.0,1740481173.497945,5.319994926452637,0.01728648711814532,1740481173.4979475,5.319994926452637,7.674416686663481,1740481173.4979484,5.319994926452637,0.0,1740481173.4979496,5.319994926452637,0.0,1740481173.4979508,5.319994926452637,0.0,1740481173.4979517,5.319994926452637,0.0,1740481173.4979525,5.319994926452637,0.9956484934446073,1740481173.497954,5.319994926452637,0.04351506555388851,1740481173.4979546,5.319994926452637,0.07414904339138328,1740481173.4979556,5.319994926452637,0.0,1740481173.4979563,5.319994926452637,0.9650145156071125,1740481192.4237187,24.199976921081543 +1740481173.5223212,5.33999490737915,3.8334215041811595,1740481173.5223231,5.33999490737915,0.0,1740481173.5223253,5.33999490737915,0.0,1740481173.5223272,5.33999490737915,7.763450535395385,1740481173.5223284,5.33999490737915,0.0,1740481173.5223296,5.33999490737915,0.0,1740481173.5223303,5.33999490737915,0.0,1740481173.5223315,5.33999490737915,0.0,1740481173.5223322,5.33999490737915,0.9950031057618799,1740481173.5223331,5.33999490737915,0.0,1740481173.522334,5.33999490737915,0.029988590154767403,1740481173.522335,5.33999490737915,0.0,1740481173.5223358,5.33999490737915,0.9650145156071125,1740481192.4434695,24.219976902008057 +1740481173.538514,5.359994888305664,3.8334215041811595,1740481173.5385158,5.359994888305664,0.0,1740481173.538518,5.359994888305664,0.0,1740481173.53852,5.359994888305664,7.763450535395385,1740481173.5385208,5.359994888305664,0.0,1740481173.538522,5.359994888305664,0.0,1740481173.5385232,5.359994888305664,0.0,1740481173.5385242,5.359994888305664,0.0,1740481173.5385249,5.359994888305664,0.9950031057618799,1740481173.538526,5.359994888305664,0.0,1740481173.5385268,5.359994888305664,0.029988590154767403,1740481173.5385275,5.359994888305664,0.0,1740481173.5385284,5.359994888305664,0.9650145156071125,1740481192.4635134,24.23997688293457 +1740481173.55801,5.379994869232178,3.939661729988151,1740481173.5580125,5.379994869232178,0.0,1740481173.5580144,5.379994869232178,0.017262265326278118,1740481173.5580165,5.379994869232178,7.7826254681800044,1740481173.5580173,5.379994869232178,0.0,1740481173.5580184,5.379994869232178,0.0,1740481173.5580196,5.379994869232178,0.0,1740481173.5580204,5.379994869232178,0.0,1740481173.5580213,5.379994869232178,0.9950031057618799,1740481173.5580223,5.379994869232178,0.04996894238120553,1740481173.5580232,5.379994869232178,0.0785665012426188,1740481173.558024,5.379994869232178,0.0,1740481173.5580246,5.379994869232178,0.9659708493362835,1740481192.4833856,24.259976863861084 +1740481173.5798314,5.399994850158691,3.939661729988151,1740481173.579855,5.399994850158691,0.0,1740481173.5798597,5.399994850158691,0.017262265326278118,1740481173.579862,5.399994850158691,7.7826254681800044,1740481173.5798633,5.399994850158691,0.0,1740481173.5798645,5.399994850158691,0.0,1740481173.5798657,5.399994850158691,0.0,1740481173.5798666,5.399994850158691,0.0,1740481173.5798676,5.399994850158691,0.9950031057618799,1740481173.5798686,5.399994850158691,0.04996894238120553,1740481173.5798702,5.399994850158691,0.0790011988068019,1740481173.5798714,5.399994850158691,0.0,1740481173.5798738,5.399994850158691,0.9659708493362835,1740481192.5043118,24.279976844787598 +1740481173.5983834,5.419994831085205,3.939661729988151,1740481173.5983853,5.419994831085205,0.0,1740481173.5983875,5.419994831085205,0.017262265326278118,1740481173.5983894,5.419994831085205,7.7826254681800044,1740481173.5983906,5.419994831085205,0.0,1740481173.5983918,5.419994831085205,0.0,1740481173.5983927,5.419994831085205,0.0,1740481173.598394,5.419994831085205,0.0,1740481173.5983946,5.419994831085205,0.9950031057618799,1740481173.5983958,5.419994831085205,0.04996894238120553,1740481173.5983968,5.419994831085205,0.0790011988068019,1740481173.5983975,5.419994831085205,0.0,1740481173.5983984,5.419994831085205,0.9659708493362835,1740481192.5234537,24.29997682571411 +1740481173.6204135,5.439994812011719,3.939661729988151,1740481173.6204152,5.439994812011719,0.0,1740481173.6204176,5.439994812011719,0.0,1740481173.6204195,5.439994812011719,7.871603428660718,1740481173.6204205,5.439994812011719,0.0,1740481173.6204216,5.439994812011719,0.0,1740481173.6204224,5.439994812011719,0.0,1740481173.6204233,5.439994812011719,0.0,1740481173.6204243,5.439994812011719,0.9952725538112371,1740481173.6204252,5.439994812011719,0.0,1740481173.620426,5.439994812011719,0.029301704474953616,1740481173.6204267,5.439994812011719,0.0,1740481173.6204278,5.439994812011719,0.9659708493362835,1740481192.544881,24.319976806640625 +1740481173.6384158,5.459994792938232,3.939661729988151,1740481173.638418,5.459994792938232,0.0,1740481173.6384199,5.459994792938232,0.0,1740481173.638422,5.459994792938232,7.871603428660718,1740481173.638423,5.459994792938232,0.0,1740481173.6384244,5.459994792938232,0.0,1740481173.6384254,5.459994792938232,0.0,1740481173.6384263,5.459994792938232,0.0,1740481173.638427,5.459994792938232,0.9952725538112371,1740481173.6384282,5.459994792938232,0.0,1740481173.638429,5.459994792938232,0.029301704474953616,1740481173.6384296,5.459994792938232,0.0,1740481173.6384308,5.459994792938232,0.9659708493362835,1740481192.5671046,24.33997678756714 +1740481173.6585631,5.479994773864746,4.0459564204475225,1740481173.6585653,5.479994773864746,0.0,1740481173.6585672,5.479994773864746,0.017275791963083653,1740481173.658569,5.479994773864746,7.888602131522243,1740481173.6585863,5.479994773864746,0.0,1740481173.6585877,5.479994773864746,0.0,1740481173.6585886,5.479994773864746,0.0,1740481173.6585898,5.479994773864746,0.0,1740481173.6585908,5.479994773864746,0.9952725538112371,1740481173.6585917,5.479994773864746,0.04727446188758977,1740481173.6585927,5.479994773864746,0.07677768576918884,1740481173.658594,5.479994773864746,0.0,1740481173.6585948,5.479994773864746,0.9658323047855043,1740481192.5836554,24.359976768493652 +1740481173.6781647,5.49999475479126,4.0459564204475225,1740481173.6781664,5.49999475479126,0.0,1740481173.6781683,5.49999475479126,0.017275791963083653,1740481173.6781986,5.49999475479126,7.888602131522243,1740481173.6781993,5.49999475479126,0.0,1740481173.6782005,5.49999475479126,0.0,1740481173.6782017,5.49999475479126,0.0,1740481173.6782029,5.49999475479126,0.0,1740481173.6782038,5.49999475479126,0.9952725538112371,1740481173.6782048,5.49999475479126,0.04727446188758977,1740481173.6782057,5.49999475479126,0.0767147109133226,1740481173.6782067,5.49999475479126,0.0,1740481173.6782074,5.49999475479126,0.9658323047855043,1740481192.6033964,24.379976749420166 +1740481173.6984293,5.519994735717773,4.0459564204475225,1740481173.6984313,5.519994735717773,0.0,1740481173.6984334,5.519994735717773,0.017275791963083653,1740481173.6984353,5.519994735717773,7.888602131522243,1740481173.698437,5.519994735717773,0.0,1740481173.698438,5.519994735717773,0.0,1740481173.698439,5.519994735717773,0.0,1740481173.6984398,5.519994735717773,0.0,1740481173.698441,5.519994735717773,0.9952725538112371,1740481173.698442,5.519994735717773,0.04727446188758977,1740481173.6984427,5.519994735717773,0.0767147109133226,1740481173.698444,5.519994735717773,0.0,1740481173.6984446,5.519994735717773,0.9658323047855043,1740481192.6270502,24.39997673034668 +1740481173.721283,5.539994716644287,4.0459564204475225,1740481173.721285,5.539994716644287,0.0,1740481173.7212877,5.539994716644287,0.0,1740481173.7212896,5.539994716644287,7.977621030018531,1740481173.7212908,5.539994716644287,0.0,1740481173.7212923,5.539994716644287,0.0,1740481173.7212934,5.539994716644287,0.0,1740481173.7212954,5.539994716644287,0.0,1740481173.7212963,5.539994716644287,0.9952339812823865,1740481173.7212975,5.539994716644287,0.0,1740481173.7212985,5.539994716644287,0.02940167649688219,1740481173.7212996,5.539994716644287,0.0,1740481173.721301,5.539994716644287,0.9658323047855043,1740481192.6460357,24.419976711273193 +1740481173.7384903,5.559994697570801,4.0459564204475225,1740481173.7384923,5.559994697570801,0.0,1740481173.7384944,5.559994697570801,0.0,1740481173.7384965,5.559994697570801,7.977621030018531,1740481173.7384973,5.559994697570801,0.0,1740481173.7384984,5.559994697570801,0.0,1740481173.7384996,5.559994697570801,0.0,1740481173.7385006,5.559994697570801,0.0,1740481173.7385013,5.559994697570801,0.9952339812823865,1740481173.7385027,5.559994697570801,0.0,1740481173.7385037,5.559994697570801,0.02940167649688219,1740481173.7385044,5.559994697570801,0.0,1740481173.7385051,5.559994697570801,0.9658323047855043,1740481192.665951,24.439976692199707 +1740481173.7591774,5.5799946784973145,4.0459564204475225,1740481173.7591796,5.5799946784973145,0.0,1740481173.7591817,5.5799946784973145,0.0,1740481173.7591836,5.5799946784973145,7.977621030018531,1740481173.7591846,5.5799946784973145,0.0,1740481173.7591863,5.5799946784973145,0.0,1740481173.7591872,5.5799946784973145,0.0,1740481173.759188,5.5799946784973145,0.0,1740481173.759189,5.5799946784973145,0.9952339812823865,1740481173.75919,5.5799946784973145,0.0,1740481173.7591913,5.5799946784973145,0.02940167649688219,1740481173.7591922,5.5799946784973145,0.0,1740481173.7591934,5.5799946784973145,0.9658323047855043,1740481192.6843812,24.45997667312622 +1740481173.7794697,5.599994659423828,4.152274521718127,1740481173.779472,5.599994659423828,0.0,1740481173.7794745,5.599994659423828,0.017278927176025093,1740481173.7794766,5.599994659423828,7.995307670520598,1740481173.7794778,5.599994659423828,0.0,1740481173.779479,5.599994659423828,0.0,1740481173.77948,5.599994659423828,0.0,1740481173.7794812,5.599994659423828,0.0,1740481173.7794824,5.599994659423828,0.9952339812823865,1740481173.779483,5.599994659423828,0.047660187176096214,1740481173.7794838,5.599994659423828,0.07676534480203312,1740481173.779485,5.599994659423828,0.0,1740481173.7794862,5.599994659423828,0.9660361614485251,1740481192.7032478,24.479976654052734 +1740481173.7982159,5.619994640350342,4.152274521718127,1740481173.7982175,5.619994640350342,0.0,1740481173.7982197,5.619994640350342,0.017278927176025093,1740481173.7982218,5.619994640350342,7.995307670520598,1740481173.798223,5.619994640350342,0.0,1740481173.7982244,5.619994640350342,0.0,1740481173.7982254,5.619994640350342,0.0,1740481173.7982266,5.619994640350342,0.0,1740481173.7982275,5.619994640350342,0.9952339812823865,1740481173.7982287,5.619994640350342,0.047660187176096214,1740481173.7982295,5.619994640350342,0.0768580070099576,1740481173.7982304,5.619994640350342,0.0,1740481173.7982316,5.619994640350342,0.9660361614485251,1740481192.7234986,24.499976634979248 +1740481173.8201828,5.6399946212768555,4.152274521718127,1740481173.8201861,5.6399946212768555,0.0,1740481173.8201888,5.6399946212768555,0.0,1740481173.8201911,5.6399946212768555,8.084346844615176,1740481173.8201928,5.6399946212768555,0.0,1740481173.820195,5.6399946212768555,0.0,1740481173.8201966,5.6399946212768555,0.0,1740481173.8201976,5.6399946212768555,0.0,1740481173.820199,5.6399946212768555,0.995290683161467,1740481173.8202002,5.6399946212768555,0.0,1740481173.8202016,5.6399946212768555,0.02925452171294185,1740481173.8202028,5.6399946212768555,0.0,1740481173.8202043,5.6399946212768555,0.9660361614485251,1740481192.7458365,24.51997661590576 +1740481173.838331,5.659994602203369,4.152274521718127,1740481173.8383362,5.659994602203369,0.0,1740481173.8383424,5.659994602203369,0.0,1740481173.8383455,5.659994602203369,8.084346844615176,1740481173.8383467,5.659994602203369,0.0,1740481173.8383482,5.659994602203369,0.0,1740481173.8383496,5.659994602203369,0.0,1740481173.8383505,5.659994602203369,0.0,1740481173.8383517,5.659994602203369,0.995290683161467,1740481173.8383527,5.659994602203369,0.0,1740481173.8383534,5.659994602203369,0.02925452171294185,1740481173.8383543,5.659994602203369,0.0,1740481173.8383558,5.659994602203369,0.9660361614485251,1740481192.7659626,24.539976596832275 +1740481173.8588185,5.679994583129883,4.152274521718127,1740481173.8588216,5.679994583129883,0.0,1740481173.858824,5.679994583129883,0.0,1740481173.8588424,5.679994583129883,8.084346844615176,1740481173.8588436,5.679994583129883,0.0,1740481173.858846,5.679994583129883,0.0,1740481173.8588471,5.679994583129883,0.0,1740481173.8588483,5.679994583129883,0.0,1740481173.8588493,5.679994583129883,0.995290683161467,1740481173.858851,5.679994583129883,0.0,1740481173.8588521,5.679994583129883,0.02925452171294185,1740481173.858853,5.679994583129883,0.0,1740481173.8588538,5.679994583129883,0.9660361614485251,1740481192.7833128,24.55997657775879 +1740481173.8786516,5.6999945640563965,4.258525206621915,1740481173.878654,5.6999945640563965,0.0,1740481173.8786561,5.6999945640563965,0.017268954414009274,1740481173.8786585,5.6999945640563965,8.09918165711922,1740481173.8786597,5.6999945640563965,0.0,1740481173.8786612,5.6999945640563965,0.0,1740481173.8786623,5.6999945640563965,0.0,1740481173.8786635,5.6999945640563965,0.0,1740481173.8786645,5.6999945640563965,0.995290683161467,1740481173.8786654,5.6999945640563965,0.04709316838529154,1740481173.8786664,5.6999945640563965,0.07811797565125012,1740481173.8786676,5.6999945640563965,0.0,1740481173.8786683,5.6999945640563965,0.9648190904935419,1740481192.803506,24.579976558685303 +1740481173.8995078,5.71999454498291,4.258525206621915,1740481173.8995094,5.71999454498291,0.0,1740481173.8995113,5.71999454498291,0.017268954414009274,1740481173.8995132,5.71999454498291,8.09918165711922,1740481173.8995144,5.71999454498291,0.0,1740481173.8995154,5.71999454498291,0.0,1740481173.8995163,5.71999454498291,0.0,1740481173.8995173,5.71999454498291,0.0,1740481173.8995183,5.71999454498291,0.995290683161467,1740481173.8995194,5.71999454498291,0.04709316838529154,1740481173.8995202,5.71999454498291,0.07756476105321664,1740481173.8995214,5.71999454498291,0.0,1740481173.899522,5.71999454498291,0.9648190904935419,1740481192.8234148,24.599976539611816 +1740481173.9248567,5.739994525909424,4.258525206621915,1740481173.9248586,5.739994525909424,0.0,1740481173.9248607,5.739994525909424,0.0,1740481173.9248626,5.739994525909424,8.188163387608999,1740481173.9248636,5.739994525909424,0.0,1740481173.9248648,5.739994525909424,0.0,1740481173.9248657,5.739994525909424,0.0,1740481173.9248667,5.739994525909424,0.0,1740481173.9248674,5.739994525909424,0.0784648957130936,1740481173.9248683,5.739994525909424,0.0,1740481173.9248693,5.739994525909424,-0.8863541947804483,1740481173.9248703,5.739994525909424,0.0,1740481173.924871,5.739994525909424,0.9648190904935419,1740481192.8436036,24.61997652053833 +1740481173.9402678,5.7599945068359375,4.258525206621915,1740481173.9402695,5.7599945068359375,0.0,1740481173.940272,5.7599945068359375,0.0,1740481173.9402742,5.7599945068359375,8.188163387608999,1740481173.9402752,5.7599945068359375,0.0,1740481173.9402766,5.7599945068359375,0.0,1740481173.9402778,5.7599945068359375,0.0,1740481173.9402788,5.7599945068359375,0.0,1740481173.9402797,5.7599945068359375,0.0784648957130936,1740481173.940281,5.7599945068359375,0.0,1740481173.9402819,5.7599945068359375,-0.8863541947804483,1740481173.9402828,5.7599945068359375,0.0,1740481173.940284,5.7599945068359375,0.9648190904935419,1740481192.8648865,24.639976501464844 +1740481173.9578195,5.779994487762451,4.258525206621915,1740481173.9578211,5.779994487762451,0.0,1740481173.9578235,5.779994487762451,0.0,1740481173.9578254,5.779994487762451,8.188163387608999,1740481173.9578269,5.779994487762451,0.0,1740481173.9578283,5.779994487762451,0.0,1740481173.9578295,5.779994487762451,0.0,1740481173.9578304,5.779994487762451,0.0,1740481173.9578311,5.779994487762451,0.0784648957130936,1740481173.9578323,5.779994487762451,0.0,1740481173.9578335,5.779994487762451,-0.8863541947804483,1740481173.9578347,5.779994487762451,0.0,1740481173.9578354,5.779994487762451,0.9648190904935419,1740481192.8835857,24.659976482391357 +1740481173.9783127,5.799994468688965,4.258525206621915,1740481173.9783144,5.799994468688965,0.0,1740481173.9783168,5.799994468688965,0.0,1740481173.9783192,5.799994468688965,8.188163387608999,1740481173.9783201,5.799994468688965,0.0,1740481173.978321,5.799994468688965,0.0,1740481173.9783223,5.799994468688965,0.0,1740481173.9783232,5.799994468688965,0.0,1740481173.9783242,5.799994468688965,0.0784648957130936,1740481173.9783254,5.799994468688965,0.0,1740481173.9783263,5.799994468688965,-0.8863541947804483,1740481173.9783273,5.799994468688965,0.0,1740481173.978328,5.799994468688965,0.9648190904935419,1740481192.903419,24.67997646331787 +1740481173.9979563,5.8199944496154785,4.363321661517297,1740481173.9979582,5.8199944496154785,0.0,1740481173.99796,5.8199944496154785,0.006097030743570921,1740481173.997962,5.8199944496154785,8.083199493893048,1740481173.997963,5.8199944496154785,0.0,1740481173.9979644,5.8199944496154785,0.0,1740481173.9979653,5.8199944496154785,0.0,1740481173.997966,5.8199944496154785,0.0,1740481173.997967,5.8199944496154785,0.0784648957130936,1740481173.997968,5.8199944496154785,0.0,1740481173.997969,5.8199944496154785,-0.8055825892835112,1740481173.9979696,5.8199944496154785,0.0,1740481173.997971,5.8199944496154785,0.9092886282637808,1740481192.9233706,24.699976444244385 +1740481174.0229666,5.839994430541992,4.363321661517297,1740481174.0229683,5.839994430541992,0.0,1740481174.0229704,5.839994430541992,0.0,1740481174.022972,5.839994430541992,8.181898918044858,1740481174.0229733,5.839994430541992,0.0,1740481174.0229745,5.839994430541992,0.0,1740481174.0229754,5.839994430541992,0.0,1740481174.0229762,5.839994430541992,0.0,1740481174.0229774,5.839994430541992,0.08116400381433433,1740481174.022978,5.839994430541992,0.0,1740481174.022979,5.839994430541992,-0.8281246244494465,1740481174.0229797,5.839994430541992,0.0,1740481174.0229807,5.839994430541992,0.9092886282637808,1740481192.9437385,24.7199764251709 +1740481174.0377786,5.859994411468506,4.363321661517297,1740481174.0377805,5.859994411468506,0.0,1740481174.0377827,5.859994411468506,0.0,1740481174.0377846,5.859994411468506,8.181898918044858,1740481174.0377855,5.859994411468506,0.0,1740481174.037787,5.859994411468506,0.0,1740481174.0377877,5.859994411468506,0.0,1740481174.0377886,5.859994411468506,0.0,1740481174.0377893,5.859994411468506,0.08116400381433433,1740481174.0377905,5.859994411468506,0.0,1740481174.0377913,5.859994411468506,-0.8281246244494465,1740481174.037792,5.859994411468506,0.0,1740481174.037793,5.859994411468506,0.9092886282637808,1740481192.9660323,24.739976406097412 +1740481174.0593615,5.8799943923950195,4.363321661517297,1740481174.0593634,5.8799943923950195,0.0,1740481174.0593657,5.8799943923950195,0.0,1740481174.0593677,5.8799943923950195,8.181898918044858,1740481174.0593688,5.8799943923950195,0.0,1740481174.0593703,5.8799943923950195,0.0,1740481174.0593712,5.8799943923950195,0.0,1740481174.0593722,5.8799943923950195,0.0,1740481174.0593734,5.8799943923950195,0.08116400381433433,1740481174.059374,5.8799943923950195,0.0,1740481174.059375,5.8799943923950195,-0.8281246244494465,1740481174.0593762,5.8799943923950195,0.0,1740481174.0593772,5.8799943923950195,0.9092886282637808,1740481192.9845319,24.759976387023926 +1740481174.0800326,5.899994373321533,4.363321661517297,1740481174.0800343,5.899994373321533,0.0,1740481174.0800369,5.899994373321533,0.0,1740481174.080039,5.899994373321533,8.181898918044858,1740481174.08004,5.899994373321533,0.0,1740481174.0800412,5.899994373321533,0.0,1740481174.080042,5.899994373321533,0.0,1740481174.080043,5.899994373321533,0.0,1740481174.080044,5.899994373321533,0.08116400381433433,1740481174.080045,5.899994373321533,0.0,1740481174.080046,5.899994373321533,-0.8281246244494465,1740481174.080047,5.899994373321533,0.0,1740481174.0800476,5.899994373321533,0.9092886282637808,1740481193.0033278,24.77997636795044 +1740481174.0979693,5.919994354248047,4.458498959719952,1740481174.0979722,5.919994354248047,0.0,1740481174.097975,5.919994354248047,0.004918321442843803,1740481174.0979772,5.919994354248047,7.993651300263236,1740481174.0979779,5.919994354248047,0.0,1740481174.097979,5.919994354248047,0.0,1740481174.0979807,5.919994354248047,0.0,1740481174.0979815,5.919994354248047,0.0,1740481174.0979824,5.919994354248047,0.08116400381433433,1740481174.0979831,5.919994354248047,0.0,1740481174.0979843,5.919994354248047,-0.6876402631458411,1740481174.0979853,5.919994354248047,0.0,1740481174.097986,5.919994354248047,0.8127056586515475,1740481193.0234969,24.799976348876953 +1740481174.1231978,5.9399943351745605,4.458498959719952,1740481174.1231995,5.9399943351745605,0.0,1740481174.1232016,5.9399943351745605,0.0,1740481174.1232033,5.9399943351745605,8.083910277023048,1740481174.1232045,5.9399943351745605,0.0,1740481174.1232057,5.9399943351745605,0.0,1740481174.1232066,5.9399943351745605,0.0,1740481174.1232073,5.9399943351745605,0.0,1740481174.1232085,5.9399943351745605,0.0762337510079678,1740481174.1232097,5.9399943351745605,0.0,1740481174.1232104,5.9399943351745605,-0.7364719076435797,1740481174.1232111,5.9399943351745605,0.0,1740481174.1232123,5.9399943351745605,0.8127056586515475,1740481193.0444722,24.819976329803467 +1740481174.1382167,5.959994316101074,4.458498959719952,1740481174.138219,5.959994316101074,0.0,1740481174.1382217,5.959994316101074,0.0,1740481174.1382246,5.959994316101074,8.083910277023048,1740481174.138226,5.959994316101074,0.0,1740481174.1382277,5.959994316101074,0.0,1740481174.138229,5.959994316101074,0.0,1740481174.1382303,5.959994316101074,0.0,1740481174.1382315,5.959994316101074,0.0762337510079678,1740481174.138233,5.959994316101074,0.0,1740481174.138234,5.959994316101074,-0.7364719076435797,1740481174.138235,5.959994316101074,0.0,1740481174.138236,5.959994316101074,0.8127056586515475,1740481193.0643806,24.83997631072998 +1740481174.159897,5.979994297027588,4.458498959719952,1740481174.1598997,5.979994297027588,0.0,1740481174.1599019,5.979994297027588,0.0,1740481174.159904,5.979994297027588,8.083910277023048,1740481174.159905,5.979994297027588,0.0,1740481174.1599064,5.979994297027588,0.0,1740481174.1599073,5.979994297027588,0.0,1740481174.1599085,5.979994297027588,0.0,1740481174.1599097,5.979994297027588,0.0762337510079678,1740481174.1599104,5.979994297027588,0.0,1740481174.1599114,5.979994297027588,-0.7364719076435797,1740481174.159912,5.979994297027588,0.0,1740481174.159913,5.979994297027588,0.8127056586515475,1740481193.0840194,24.859976291656494 +1740481174.1782653,5.999994277954102,4.458498959719952,1740481174.1782691,5.999994277954102,0.0,1740481174.1782715,5.999994277954102,0.0,1740481174.1782901,5.999994277954102,8.083910277023048,1740481174.1782916,5.999994277954102,0.0,1740481174.1782951,5.999994277954102,0.0,1740481174.1782968,5.999994277954102,0.0,1740481174.1782978,5.999994277954102,0.0,1740481174.1782997,5.999994277954102,0.0762337510079678,1740481174.1783009,5.999994277954102,0.0,1740481174.178302,5.999994277954102,-0.7364719076435797,1740481174.1783032,5.999994277954102,0.0,1740481174.1783047,5.999994277954102,0.8127056586515475,1740481193.104641,24.879976272583008 +1740481174.1977243,6.019994258880615,4.458498959719952,1740481174.1977262,6.019994258880615,0.0,1740481174.1977282,6.019994258880615,0.0,1740481174.1977303,6.019994258880615,8.083910277023048,1740481174.1977313,6.019994258880615,0.0,1740481174.1977327,6.019994258880615,0.0,1740481174.1977336,6.019994258880615,0.0,1740481174.1977346,6.019994258880615,0.0,1740481174.1977353,6.019994258880615,0.0762337510079678,1740481174.1977367,6.019994258880615,0.0,1740481174.1977377,6.019994258880615,-0.7364719076435797,1740481174.1977386,6.019994258880615,0.0,1740481174.1977398,6.019994258880615,0.8127056586515475,1740481193.1232102,24.89997625350952 +1740481174.224787,6.039994239807129,4.543726168125094,1740481174.2247887,6.039994239807129,0.0,1740481174.224791,6.039994239807129,0.0,1740481174.2247927,6.039994239807129,8.000198870666292,1740481174.2247937,6.039994239807129,0.0,1740481174.224795,6.039994239807129,0.0,1740481174.224796,6.039994239807129,0.0,1740481174.2247972,6.039994239807129,0.0,1740481174.2247982,6.039994239807129,0.07264390184463282,1740481174.2247992,6.039994239807129,0.0,1740481174.2248,6.039994239807129,-0.6188290242667159,1740481174.224801,6.039994239807129,0.0,1740481174.224802,6.039994239807129,0.7282363512705986,1740481193.1447804,24.919976234436035 +1740481174.2380292,6.059994220733643,4.543726168125094,1740481174.2380314,6.059994220733643,0.0,1740481174.2380333,6.059994220733643,0.0,1740481174.2380354,6.059994220733643,8.000198870666292,1740481174.2380366,6.059994220733643,0.0,1740481174.238038,6.059994220733643,0.0,1740481174.238039,6.059994220733643,0.0,1740481174.23804,6.059994220733643,0.0,1740481174.2380412,6.059994220733643,0.07264390184463282,1740481174.238042,6.059994220733643,0.0,1740481174.238043,6.059994220733643,-0.6555924494259657,1740481174.2380438,6.059994220733643,0.0,1740481174.238045,6.059994220733643,0.7282363512705986,1740481193.1650975,24.93997621536255 +1740481174.2583518,6.079994201660156,4.543726168125094,1740481174.258354,6.079994201660156,0.0,1740481174.2583559,6.079994201660156,0.0,1740481174.258358,6.079994201660156,8.000198870666292,1740481174.258359,6.079994201660156,0.0,1740481174.2583604,6.079994201660156,0.0,1740481174.2583613,6.079994201660156,0.0,1740481174.2583623,6.079994201660156,0.0,1740481174.2583635,6.079994201660156,0.07264390184463282,1740481174.2583642,6.079994201660156,0.0,1740481174.2583652,6.079994201660156,-0.6555924494259657,1740481174.2583659,6.079994201660156,0.0,1740481174.258367,6.079994201660156,0.7282363512705986,1740481193.1845243,24.959976196289062 +1740481174.2779665,6.09999418258667,4.543726168125094,1740481174.2779682,6.09999418258667,0.0,1740481174.2779708,6.09999418258667,0.0,1740481174.2779727,6.09999418258667,8.000198870666292,1740481174.2779737,6.09999418258667,0.0,1740481174.277975,6.09999418258667,0.0,1740481174.2779765,6.09999418258667,0.0,1740481174.2779777,6.09999418258667,0.0,1740481174.277979,6.09999418258667,0.07264390184463282,1740481174.2779796,6.09999418258667,0.0,1740481174.2779806,6.09999418258667,-0.6555924494259657,1740481174.2779818,6.09999418258667,0.0,1740481174.277983,6.09999418258667,0.7282363512705986,1740481193.2037401,24.979976177215576 +1740481174.2978222,6.119994163513184,4.543726168125094,1740481174.297824,6.119994163513184,0.0,1740481174.2978263,6.119994163513184,0.0,1740481174.2978282,6.119994163513184,8.000198870666292,1740481174.2978294,6.119994163513184,0.0,1740481174.2978306,6.119994163513184,0.0,1740481174.2978318,6.119994163513184,0.0,1740481174.297833,6.119994163513184,0.0,1740481174.2978337,6.119994163513184,0.07264390184463282,1740481174.2978346,6.119994163513184,0.0,1740481174.2978358,6.119994163513184,-0.6555924494259657,1740481174.2978365,6.119994163513184,0.0,1740481174.2978375,6.119994163513184,0.7282363512705986,1740481193.2235522,24.99997615814209 +1740481174.323558,6.139994144439697,4.619880446984732,1740481174.32356,6.139994144439697,0.0,1740481174.3235621,6.139994144439697,0.0,1740481174.323564,6.139994144439697,7.920951940169915,1740481174.3235648,6.139994144439697,0.0,1740481174.3235662,6.139994144439697,0.0,1740481174.3235672,6.139994144439697,0.0,1740481174.323568,6.139994144439697,0.0,1740481174.3235688,6.139994144439697,0.06958283818830915,1740481174.3235698,6.139994144439697,0.0,1740481174.3235707,6.139994144439697,-0.5470258119481164,1740481174.3235714,6.139994144439697,0.0,1740481174.3235724,6.139994144439697,0.6505357465925913,1740481193.243731,25.019976139068604 +1740481174.3375752,6.159994125366211,4.619880446984732,1740481174.3375766,6.159994125366211,0.0,1740481174.3375788,6.159994125366211,0.0,1740481174.3375807,6.159994125366211,7.920951940169915,1740481174.3375819,6.159994125366211,0.0,1740481174.3375828,6.159994125366211,0.0,1740481174.3375838,6.159994125366211,0.0,1740481174.337585,6.159994125366211,0.0,1740481174.3375857,6.159994125366211,0.06958283818830915,1740481174.3375864,6.159994125366211,0.0,1740481174.3375874,6.159994125366211,-0.5809529084042822,1740481174.3375883,6.159994125366211,0.0,1740481174.337589,6.159994125366211,0.6505357465925913,1740481193.2645972,25.039976119995117 +1740481174.3578012,6.179994106292725,4.619880446984732,1740481174.357803,6.179994106292725,0.0,1740481174.357805,6.179994106292725,0.0,1740481174.3578072,6.179994106292725,7.920951940169915,1740481174.357808,6.179994106292725,0.0,1740481174.3578093,6.179994106292725,0.0,1740481174.3578105,6.179994106292725,0.0,1740481174.3578115,6.179994106292725,0.0,1740481174.3578122,6.179994106292725,0.06958283818830915,1740481174.3578134,6.179994106292725,0.0,1740481174.357814,6.179994106292725,-0.5809529084042822,1740481174.357815,6.179994106292725,0.0,1740481174.3578157,6.179994106292725,0.6505357465925913,1740481193.2834735,25.05997610092163 +1740481174.3775222,6.199994087219238,4.619880446984732,1740481174.377524,6.199994087219238,0.0,1740481174.377526,6.199994087219238,0.0,1740481174.377528,6.199994087219238,7.920951940169915,1740481174.377529,6.199994087219238,0.0,1740481174.37753,6.199994087219238,0.0,1740481174.377531,6.199994087219238,0.0,1740481174.377532,6.199994087219238,0.0,1740481174.3775327,6.199994087219238,0.06958283818830915,1740481174.3775337,6.199994087219238,0.0,1740481174.3775344,6.199994087219238,-0.5809529084042822,1740481174.3775353,6.199994087219238,0.0,1740481174.3775363,6.199994087219238,0.6505357465925913,, +1740481174.4006364,6.219994068145752,4.619880446984732,1740481174.4006388,6.219994068145752,0.0,1740481174.4006412,6.219994068145752,0.0,1740481174.4006436,6.219994068145752,7.920951940169915,1740481174.4006448,6.219994068145752,0.0,1740481174.4006464,6.219994068145752,0.0,1740481174.4006474,6.219994068145752,0.0,1740481174.4006486,6.219994068145752,0.0,1740481174.4006498,6.219994068145752,0.06958283818830915,1740481174.400651,6.219994068145752,0.0,1740481174.400652,6.219994068145752,-0.5809529084042822,1740481174.4006531,6.219994068145752,0.0,1740481174.400654,6.219994068145752,0.6505357465925913,, +1740481174.4182951,6.239994049072266,4.619880446984732,1740481174.4182968,6.239994049072266,0.0,1740481174.418299,6.239994049072266,0.0,1740481174.4183006,6.239994049072266,7.920951940169915,1740481174.4183016,6.239994049072266,0.0,1740481174.418303,6.239994049072266,0.0,1740481174.418304,6.239994049072266,0.0,1740481174.418305,6.239994049072266,0.0,1740481174.4183059,6.239994049072266,0.06958283818830915,1740481174.4183068,6.239994049072266,0.0,1740481174.4183075,6.239994049072266,-0.5809529084042822,1740481174.4183083,6.239994049072266,0.0,1740481174.4183092,6.239994049072266,0.6505357465925913,, +1740481174.4378195,6.259994029998779,4.688004376137906,1740481174.4378211,6.259994029998779,0.0,1740481174.4378233,6.259994029998779,0.0018018641207649835,1740481174.437825,6.259994029998779,7.786472891749344,1740481174.4378262,6.259994029998779,0.0,1740481174.4378273,6.259994029998779,0.0,1740481174.4378283,6.259994029998779,0.0,1740481174.4378295,6.259994029998779,0.0,1740481174.4378302,6.259994029998779,0.06958283818830915,1740481174.4378312,6.259994029998779,0.0,1740481174.437832,6.259994029998779,-0.48183948792700854,1740481174.437833,6.259994029998779,0.0,1740481174.4378338,6.259994029998779,0.5823952903219235,, +1740481174.4575794,6.279994010925293,4.688004376137906,1740481174.4575813,6.279994010925293,0.0,1740481174.4575834,6.279994010925293,0.0018018641207649835,1740481174.457585,6.279994010925293,7.786472891749344,1740481174.4575863,6.279994010925293,0.0,1740481174.4575875,6.279994010925293,0.0,1740481174.4575884,6.279994010925293,0.0,1740481174.4575891,6.279994010925293,0.0,1740481174.4575903,6.279994010925293,0.06958283818830915,1740481174.4575913,6.279994010925293,0.0,1740481174.457592,6.279994010925293,-0.5128124521336144,1740481174.4575932,6.279994010925293,0.0,1740481174.4575942,6.279994010925293,0.5823952903219235,, +1740481174.4791234,6.299993991851807,4.688004376137906,1740481174.479128,6.299993991851807,0.0,1740481174.479131,6.299993991851807,0.0018018641207649835,1740481174.479133,6.299993991851807,7.786472891749344,1740481174.4791346,6.299993991851807,0.0,1740481174.4791365,6.299993991851807,0.0,1740481174.4791384,6.299993991851807,0.0,1740481174.4791396,6.299993991851807,0.0,1740481174.4791417,6.299993991851807,0.06958283818830915,1740481174.4791439,6.299993991851807,0.0,1740481174.4791458,6.299993991851807,-0.5128124521336144,1740481174.479147,6.299993991851807,0.0,1740481174.479149,6.299993991851807,0.5823952903219235,, +1740481174.4997833,6.31999397277832,4.688004376137906,1740481174.499785,6.31999397277832,0.0,1740481174.499787,6.31999397277832,0.0018018641207649835,1740481174.499789,6.31999397277832,7.786472891749344,1740481174.4997902,6.31999397277832,0.0,1740481174.4997914,6.31999397277832,0.0,1740481174.4997923,6.31999397277832,0.0,1740481174.4997933,6.31999397277832,0.0,1740481174.4997945,6.31999397277832,0.06958283818830915,1740481174.4997952,6.31999397277832,0.0,1740481174.4997962,6.31999397277832,-0.5128124521336144,1740481174.4997973,6.31999397277832,0.0,1740481174.4997983,6.31999397277832,0.5823952903219235,, +1740481174.5181842,6.339993953704834,4.688004376137906,1740481174.5181856,6.339993953704834,0.0,1740481174.5181878,6.339993953704834,0.0,1740481174.51819,6.339993953704834,7.852794956781753,1740481174.5181906,6.339993953704834,0.0,1740481174.5181918,6.339993953704834,0.0,1740481174.518193,6.339993953704834,0.0,1740481174.518194,6.339993953704834,0.0,1740481174.5181947,6.339993953704834,0.06794652076976904,1740481174.5181954,6.339993953704834,0.0,1740481174.518196,6.339993953704834,-0.5144487695521545,1740481174.5181973,6.339993953704834,0.0,1740481174.518198,6.339993953704834,0.5823952903219235,, +1740481174.5384345,6.359993934631348,4.7490585078663,1740481174.5384362,6.359993934631348,0.0,1740481174.538438,6.359993934631348,0.0012942875847840602,1740481174.5384405,6.359993934631348,7.734297357610769,1740481174.5384412,6.359993934631348,0.0,1740481174.5384426,6.359993934631348,0.0,1740481174.5384436,6.359993934631348,0.0,1740481174.5384445,6.359993934631348,0.0,1740481174.5384452,6.359993934631348,0.06794652076976904,1740481174.5384464,6.359993934631348,0.0,1740481174.5384471,6.359993934631348,-0.42732737140192445,1740481174.5384479,6.359993934631348,0.0,1740481174.5384488,6.359993934631348,0.5224993469440395,, +1740481174.5579717,6.379993915557861,4.7490585078663,1740481174.5579734,6.379993915557861,0.0,1740481174.5579758,6.379993915557861,0.0012942875847840602,1740481174.5579777,6.379993915557861,7.734297357610769,1740481174.5579786,6.379993915557861,0.0,1740481174.5579796,6.379993915557861,0.0,1740481174.5579808,6.379993915557861,0.0,1740481174.5579817,6.379993915557861,0.0,1740481174.5579824,6.379993915557861,0.06794652076976904,1740481174.5579832,6.379993915557861,0.0,1740481174.5579844,6.379993915557861,-0.4545528261742705,1740481174.557985,6.379993915557861,0.0,1740481174.557986,6.379993915557861,0.5224993469440395,, +1740481174.577805,6.399993896484375,4.7490585078663,1740481174.5778067,6.399993896484375,0.0,1740481174.5778084,6.399993896484375,0.0012942875847840602,1740481174.5778105,6.399993896484375,7.734297357610769,1740481174.5778115,6.399993896484375,0.0,1740481174.5778124,6.399993896484375,0.0,1740481174.5778134,6.399993896484375,0.0,1740481174.5778143,6.399993896484375,0.0,1740481174.5778153,6.399993896484375,0.06794652076976904,1740481174.577816,6.399993896484375,0.0,1740481174.5778172,6.399993896484375,-0.4545528261742705,1740481174.577818,6.399993896484375,0.0,1740481174.5778189,6.399993896484375,0.5224993469440395,, +1740481174.5982761,6.419993877410889,4.7490585078663,1740481174.5982778,6.419993877410889,0.0,1740481174.59828,6.419993877410889,0.0012942875847840602,1740481174.5982816,6.419993877410889,7.734297357610769,1740481174.5982828,6.419993877410889,0.0,1740481174.598284,6.419993877410889,0.0,1740481174.5982847,6.419993877410889,0.0,1740481174.598286,6.419993877410889,0.0,1740481174.5982866,6.419993877410889,0.06794652076976904,1740481174.5982873,6.419993877410889,0.0,1740481174.598288,6.419993877410889,-0.4545528261742705,1740481174.5982893,6.419993877410889,0.0,1740481174.59829,6.419993877410889,0.5224993469440395,, +1740481174.6187005,6.439993858337402,4.7490585078663,1740481174.6187046,6.439993858337402,0.0,1740481174.6187084,6.439993858337402,0.0,1740481174.618711,6.439993858337402,7.794057201754379,1740481174.618712,6.439993858337402,0.0,1740481174.618714,6.439993858337402,0.0,1740481174.6187153,6.439993858337402,0.0,1740481174.6187165,6.439993858337402,0.0,1740481174.6187186,6.439993858337402,0.06799532363989615,1740481174.61872,6.439993858337402,0.0,1740481174.6187215,6.439993858337402,-0.4545040233041434,1740481174.6187227,6.439993858337402,0.0,1740481174.618724,6.439993858337402,0.5224993469440395,, +1740481174.6378224,6.459993839263916,4.7490585078663,1740481174.6378286,6.459993839263916,0.0,1740481174.6378326,6.459993839263916,0.0,1740481174.6378353,6.459993839263916,7.794057201754379,1740481174.6378362,6.459993839263916,0.0,1740481174.6378376,6.459993839263916,0.0,1740481174.6378388,6.459993839263916,0.0,1740481174.6378396,6.459993839263916,0.0,1740481174.6378407,6.459993839263916,0.06799532363989615,1740481174.6378417,6.459993839263916,0.0,1740481174.6378424,6.459993839263916,-0.4545040233041434,1740481174.6378434,6.459993839263916,0.0,1740481174.6378446,6.459993839263916,0.5224993469440395,, +1740481174.6594512,6.47999382019043,4.803931100187649,1740481174.659454,6.47999382019043,0.0,1740481174.6594589,6.47999382019043,0.0009362827006256878,1740481174.6594622,6.47999382019043,7.690048590947027,1740481174.659465,6.47999382019043,0.0,1740481174.659468,6.47999382019043,0.0,1740481174.6594698,6.47999382019043,0.0,1740481174.6594715,6.47999382019043,0.0,1740481174.6594737,6.47999382019043,0.06799532363989615,1740481174.6594756,6.47999382019043,0.0,1740481174.6594772,6.47999382019043,-0.37818044164303555,1740481174.6594794,6.47999382019043,0.0,1740481174.659481,6.47999382019043,0.47002690019005056,, +1740481174.6778462,6.499993801116943,4.803931100187649,1740481174.6778479,6.499993801116943,0.0,1740481174.67785,6.499993801116943,0.0009362827006256878,1740481174.677852,6.499993801116943,7.690048590947027,1740481174.6778529,6.499993801116943,0.0,1740481174.6778543,6.499993801116943,0.0,1740481174.6778553,6.499993801116943,0.0,1740481174.6778562,6.499993801116943,0.0,1740481174.6778574,6.499993801116943,0.06799532363989615,1740481174.6778584,6.499993801116943,0.0,1740481174.677859,6.499993801116943,-0.4020315765501544,1740481174.67786,6.499993801116943,0.0,1740481174.677861,6.499993801116943,0.47002690019005056,, +1740481174.6989336,6.519993782043457,4.803931100187649,1740481174.698936,6.519993782043457,0.0,1740481174.6989388,6.519993782043457,0.0009362827006256878,1740481174.698941,6.519993782043457,7.690048590947027,1740481174.698942,6.519993782043457,0.0,1740481174.6989431,6.519993782043457,0.0,1740481174.6989446,6.519993782043457,0.0,1740481174.6989455,6.519993782043457,0.0,1740481174.6989462,6.519993782043457,0.06799532363989615,1740481174.6989477,6.519993782043457,0.0,1740481174.6989484,6.519993782043457,-0.4020315765501544,1740481174.6989493,6.519993782043457,0.0,1740481174.69895,6.519993782043457,0.47002690019005056,, +1740481174.7193577,6.539993762969971,4.803931100187649,1740481174.7193594,6.539993762969971,0.0,1740481174.719362,6.539993762969971,0.0,1740481174.719364,6.539993762969971,7.7439849005677495,1740481174.719365,6.539993762969971,0.0,1740481174.7193658,6.539993762969971,0.0,1740481174.719367,6.539993762969971,0.0,1740481174.719368,6.539993762969971,0.0,1740481174.7193687,6.539993762969971,0.07042335854694941,1740481174.71937,6.539993762969971,0.0,1740481174.7193708,6.539993762969971,-0.39960354164310113,1740481174.7193716,6.539993762969971,0.0,1740481174.7193725,6.539993762969971,0.47002690019005056,, +1740481174.7379563,6.559993743896484,4.803931100187649,1740481174.7379582,6.559993743896484,0.0,1740481174.73796,6.559993743896484,0.0,1740481174.7379622,6.559993743896484,7.7439849005677495,1740481174.7379632,6.559993743896484,0.0,1740481174.737965,6.559993743896484,0.0,1740481174.7379658,6.559993743896484,0.0,1740481174.7379668,6.559993743896484,0.0,1740481174.7379677,6.559993743896484,0.07042335854694941,1740481174.737969,6.559993743896484,0.0,1740481174.7379696,6.559993743896484,-0.39960354164310113,1740481174.7379706,6.559993743896484,0.0,1740481174.7379715,6.559993743896484,0.47002690019005056,, +1740481174.759699,6.579993724822998,4.853275229652686,1740481174.7597013,6.579993724822998,0.0,1740481174.7597034,6.579993724822998,0.0006813353724378463,1740481174.759705,6.579993724822998,7.650940621381178,1740481174.759706,6.579993724822998,0.0,1740481174.7597075,6.579993724822998,0.0,1740481174.7597084,6.579993724822998,0.0,1740481174.7597094,6.579993724822998,0.0,1740481174.7597103,6.579993724822998,0.07042335854694941,1740481174.7597113,6.579993724822998,-0.704233585469494,1740481174.759712,6.579993724822998,-1.0356730234824518,1740481174.7597127,6.579993724822998,0.0,1740481174.759714,6.579993724822998,0.4231640929105453,, +1740481174.7784526,6.599993705749512,4.853275229652686,1740481174.7784545,6.599993705749512,0.0,1740481174.7784567,6.599993705749512,0.0006813353724378463,1740481174.7784584,6.599993705749512,7.650940621381178,1740481174.7784593,6.599993705749512,0.0,1740481174.7784605,6.599993705749512,0.0,1740481174.7784615,6.599993705749512,0.0,1740481174.7784624,6.599993705749512,0.0,1740481174.7784631,6.599993705749512,0.07042335854694941,1740481174.7784643,6.599993705749512,-0.704233585469494,1740481174.778465,6.599993705749512,-1.0569743198330899,1740481174.778466,6.599993705749512,0.0,1740481174.7784672,6.599993705749512,0.4231640929105453,, +1740481174.7983735,6.619993686676025,4.853275229652686,1740481174.7983756,6.619993686676025,0.0,1740481174.7983782,6.619993686676025,0.0006813353724378463,1740481174.7983809,6.619993686676025,7.650940621381178,1740481174.798382,6.619993686676025,0.0,1740481174.7983837,6.619993686676025,0.0,1740481174.7983847,6.619993686676025,0.0,1740481174.7983859,6.619993686676025,0.0,1740481174.798387,6.619993686676025,0.07042335854694941,1740481174.7983882,6.619993686676025,-0.704233585469494,1740481174.798389,6.619993686676025,-1.0569743198330899,1740481174.7983904,6.619993686676025,0.0,1740481174.7983913,6.619993686676025,0.4231640929105453,, +1740481174.8184056,6.639993667602539,4.853275229652686,1740481174.818407,6.639993667602539,0.0,1740481174.8184092,6.639993667602539,0.0,1740481174.8184114,6.639993667602539,7.699603415473777,1740481174.8184123,6.639993667602539,0.0,1740481174.8184133,6.639993667602539,0.0,1740481174.8184144,6.639993667602539,0.0,1740481174.8184154,6.639993667602539,0.0,1740481174.8184164,6.639993667602539,0.07627710419350667,1740481174.8184173,6.639993667602539,0.0,1740481174.8184183,6.639993667602539,-0.3468869887170386,1740481174.8184192,6.639993667602539,0.0,1740481174.8184202,6.639993667602539,0.4231640929105453,, +1740481174.8382065,6.659993648529053,4.853275229652686,1740481174.838208,6.659993648529053,0.0,1740481174.83821,6.659993648529053,0.0,1740481174.838212,6.659993648529053,7.699603415473777,1740481174.838213,6.659993648529053,0.0,1740481174.8382142,6.659993648529053,0.0,1740481174.838215,6.659993648529053,0.0,1740481174.8382158,6.659993648529053,0.0,1740481174.838217,6.659993648529053,0.07627710419350667,1740481174.838218,6.659993648529053,0.0,1740481174.8382187,6.659993648529053,-0.3468869887170386,1740481174.8382194,6.659993648529053,0.0,1740481174.8382206,6.659993648529053,0.4231640929105453,, +1740481174.8614912,6.679993629455566,4.853275229652686,1740481174.8614936,6.679993629455566,0.0,1740481174.8614962,6.679993629455566,0.0,1740481174.861501,6.679993629455566,7.699603415473777,1740481174.8615022,6.679993629455566,0.0,1740481174.8615057,6.679993629455566,0.0,1740481174.8615067,6.679993629455566,0.0,1740481174.8615086,6.679993629455566,0.0,1740481174.8615108,6.679993629455566,0.07627710419350667,1740481174.8615127,6.679993629455566,0.0,1740481174.8615146,6.679993629455566,-0.3468869887170386,1740481174.861517,6.679993629455566,0.0,1740481174.8615196,6.679993629455566,0.4231640929105453,, +1740481174.878261,6.69999361038208,4.89495712526174,1740481174.8782625,6.69999361038208,0.0,1740481174.8782647,6.69999361038208,0.00046649296318734454,1740481174.8782666,6.69999361038208,7.543475354945533,1740481174.8782673,6.69999361038208,0.0,1740481174.8782687,6.69999361038208,0.0,1740481174.8782697,6.69999361038208,0.0,1740481174.8782709,6.69999361038208,0.0,1740481174.8782718,6.69999361038208,0.07627710419350667,1740481174.8782728,6.69999361038208,-0.7627710419350666,1740481174.8782737,6.69999361038208,-0.9957710487173492,1740481174.878275,6.69999361038208,0.0,1740481174.8782756,6.69999361038208,0.34486681616482956,, +1740481174.8987336,6.719993591308594,4.89495712526174,1740481174.8987355,6.719993591308594,0.0,1740481174.898738,6.719993591308594,0.00046649296318734454,1740481174.8987403,6.719993591308594,7.543475354945533,1740481174.8987415,6.719993591308594,0.0,1740481174.8987432,6.719993591308594,0.0,1740481174.8987443,6.719993591308594,0.0,1740481174.8987455,6.719993591308594,0.0,1740481174.8987467,6.719993591308594,0.07627710419350667,1740481174.898748,6.719993591308594,-0.7627710419350666,1740481174.8987489,6.719993591308594,-1.0313607539063896,1740481174.8987503,6.719993591308594,0.0,1740481174.8987515,6.719993591308594,0.34486681616482956,, +1740481174.9241092,6.739993572235107,4.89495712526174,1740481174.9241114,6.739993572235107,0.0,1740481174.9241142,6.739993572235107,0.0,1740481174.9241168,6.739993572235107,7.5846907575913995,1740481174.9241178,6.739993572235107,0.0,1740481174.9241192,6.739993572235107,0.0,1740481174.9241211,6.739993572235107,0.0,1740481174.9241223,6.739993572235107,0.0,1740481174.9241233,6.739993572235107,0.07076462895985312,1740481174.9241247,6.739993572235107,0.0,1740481174.9241257,6.739993572235107,-0.2741021872049764,1740481174.9241266,6.739993572235107,0.0,1740481174.9241278,6.739993572235107,0.34486681616482956,, +1740481174.9391255,6.759993553161621,4.89495712526174,1740481174.9391272,6.759993553161621,0.0,1740481174.9391294,6.759993553161621,0.0,1740481174.9391315,6.759993553161621,7.5846907575913995,1740481174.9391325,6.759993553161621,0.0,1740481174.9391336,6.759993553161621,0.0,1740481174.9391344,6.759993553161621,0.0,1740481174.9391356,6.759993553161621,0.0,1740481174.9391365,6.759993553161621,0.07076462895985312,1740481174.9391372,6.759993553161621,0.0,1740481174.939138,6.759993553161621,-0.2741021872049764,1740481174.939139,6.759993553161621,0.0,1740481174.9391398,6.759993553161621,0.34486681616482956,, +1740481174.9575496,6.779993534088135,4.89495712526174,1740481174.9575512,6.779993534088135,0.0,1740481174.9575534,6.779993534088135,0.0,1740481174.9575555,6.779993534088135,7.5846907575913995,1740481174.9575565,6.779993534088135,0.0,1740481174.9575577,6.779993534088135,0.0,1740481174.9575589,6.779993534088135,0.0,1740481174.9575598,6.779993534088135,0.0,1740481174.9575605,6.779993534088135,0.07076462895985312,1740481174.957562,6.779993534088135,0.0,1740481174.9575627,6.779993534088135,-0.2741021872049764,1740481174.9575636,6.779993534088135,0.0,1740481174.9575644,6.779993534088135,0.34486681616482956,, +1740481174.9778745,6.799993515014648,4.9287378058620135,1740481174.9778764,6.799993515014648,0.0,1740481174.9778786,6.799993515014648,0.00025110261060219544,1740481174.9778802,6.799993515014648,7.448716630024784,1740481174.9778814,6.799993515014648,0.0,1740481174.9778826,6.799993515014648,0.0,1740481174.9778836,6.799993515014648,0.0,1740481174.9778848,6.799993515014648,0.0,1740481174.9778857,6.799993515014648,0.0,1740481174.9778867,6.799993515014648,0.0,1740481174.9778874,6.799993515014648,-0.27795966307640463,1740481174.9778883,6.799993515014648,0.0,1740481174.9778893,6.799993515014648,0.27675420107622084,, +1740481174.9988692,6.819993495941162,4.9287378058620135,1740481174.9988708,6.819993495941162,0.0,1740481174.9988732,6.819993495941162,0.00025110261060219544,1740481174.9988751,6.819993495941162,7.448716630024784,1740481174.998876,6.819993495941162,0.0,1740481174.9988775,6.819993495941162,0.0,1740481174.9988785,6.819993495941162,0.0,1740481174.9988792,6.819993495941162,0.0,1740481174.9988801,6.819993495941162,0.0,1740481174.9988813,6.819993495941162,0.0,1740481174.9988823,6.819993495941162,-0.27675420107622084,1740481174.9988832,6.819993495941162,0.0,1740481174.9988847,6.819993495941162,0.27675420107622084,, +1740481175.0184753,6.839993476867676,4.9287378058620135,1740481175.018477,6.839993476867676,0.0,1740481175.018479,6.839993476867676,0.0,1740481175.0184808,6.839993476867676,7.482246208014455,1740481175.018482,6.839993476867676,0.0,1740481175.018483,6.839993476867676,0.0,1740481175.0184839,6.839993476867676,0.0,1740481175.018485,6.839993476867676,0.0,1740481175.018486,6.839993476867676,0.06717524693477835,1740481175.0184867,6.839993476867676,-0.6717524693477834,1740481175.0184877,6.839993476867676,-0.881331423489226,1740481175.0184886,6.839993476867676,0.0,1740481175.0184896,6.839993476867676,0.27675420107622084,, +1740481175.0385375,6.8599934577941895,4.9287378058620135,1740481175.0385401,6.8599934577941895,0.0,1740481175.0385425,6.8599934577941895,0.0,1740481175.0385458,6.8599934577941895,7.482246208014455,1740481175.0385478,6.8599934577941895,0.0,1740481175.0385497,6.8599934577941895,0.0,1740481175.0385513,6.8599934577941895,0.0,1740481175.0385528,6.8599934577941895,0.0,1740481175.0385544,6.8599934577941895,0.06717524693477835,1740481175.0385559,6.8599934577941895,-0.6717524693477834,1740481175.0385568,6.8599934577941895,-0.881331423489226,1740481175.0385582,6.8599934577941895,0.0,1740481175.0385594,6.8599934577941895,0.27675420107622084,, +1740481175.0599551,6.879993438720703,4.9287378058620135,1740481175.0599575,6.879993438720703,0.0,1740481175.0599606,6.879993438720703,0.0,1740481175.0599632,6.879993438720703,7.482246208014455,1740481175.0599647,6.879993438720703,0.0,1740481175.0599666,6.879993438720703,0.0,1740481175.0599675,6.879993438720703,0.0,1740481175.0599692,6.879993438720703,0.0,1740481175.0599716,6.879993438720703,0.06717524693477835,1740481175.059973,6.879993438720703,-0.6717524693477834,1740481175.0599754,6.879993438720703,-0.881331423489226,1740481175.0599773,6.879993438720703,0.0,1740481175.0599785,6.879993438720703,0.27675420107622084,, +1740481175.0784097,6.899993419647217,4.9287378058620135,1740481175.0784125,6.899993419647217,0.0,1740481175.0784166,6.899993419647217,0.0,1740481175.0784204,6.899993419647217,7.482246208014455,1740481175.078422,6.899993419647217,0.0,1740481175.0784233,6.899993419647217,0.0,1740481175.0784252,6.899993419647217,0.0,1740481175.0784266,6.899993419647217,0.0,1740481175.0784278,6.899993419647217,0.06717524693477835,1740481175.0784297,6.899993419647217,-0.6717524693477834,1740481175.0784307,6.899993419647217,-0.881331423489226,1740481175.0784323,6.899993419647217,0.0,1740481175.0784342,6.899993419647217,0.27675420107622084,, +1740481175.0985484,6.9199934005737305,4.956310224595983,1740481175.09855,6.9199934005737305,0.0,1740481175.098552,6.9199934005737305,0.00013199069842707387,1740481175.0985544,6.9199934005737305,7.333906729051828,1740481175.0985553,6.9199934005737305,0.0,1740481175.0985568,6.9199934005737305,0.0,1740481175.0985577,6.9199934005737305,0.0,1740481175.0985587,6.9199934005737305,0.0,1740481175.0985594,6.9199934005737305,0.0,1740481175.0985606,6.9199934005737305,0.0,1740481175.0985615,6.9199934005737305,-0.1993091505051658,1740481175.0985625,6.9199934005737305,0.0,1740481175.0985637,6.9199934005737305,0.20251846624569364,, +1740481175.118446,6.939993381500244,4.956310224595983,1740481175.1184478,6.939993381500244,0.0,1740481175.11845,6.939993381500244,0.0,1740481175.1184523,6.939993381500244,7.36134715708737,1740481175.1184533,6.939993381500244,0.0,1740481175.1184545,6.939993381500244,0.0,1740481175.1184556,6.939993381500244,0.0,1740481175.1184566,6.939993381500244,0.0,1740481175.1184573,6.939993381500244,0.05867180706361628,1740481175.1184583,6.939993381500244,-0.5867180706361628,1740481175.1184595,6.939993381500244,-0.7305647298182402,1740481175.1184602,6.939993381500244,0.0,1740481175.118461,6.939993381500244,0.20251846624569364,, +1740481175.1385195,6.959993362426758,4.956310224595983,1740481175.138522,6.959993362426758,0.0,1740481175.1385238,6.959993362426758,0.0,1740481175.1385267,6.959993362426758,7.36134715708737,1740481175.1385276,6.959993362426758,0.0,1740481175.1385293,6.959993362426758,0.0,1740481175.1385305,6.959993362426758,0.0,1740481175.138532,6.959993362426758,0.0,1740481175.1385329,6.959993362426758,0.05867180706361628,1740481175.138534,6.959993362426758,-0.5867180706361628,1740481175.1385353,6.959993362426758,-0.7305647298182402,1740481175.1385362,6.959993362426758,0.0,1740481175.138538,6.959993362426758,0.20251846624569364,, +1740481175.1591873,6.9799933433532715,4.956310224595983,1740481175.1591902,6.9799933433532715,0.0,1740481175.1591928,6.9799933433532715,0.0,1740481175.159196,6.9799933433532715,7.36134715708737,1740481175.1591978,6.9799933433532715,0.0,1740481175.1591992,6.9799933433532715,0.0,1740481175.1592007,6.9799933433532715,0.0,1740481175.1592162,6.9799933433532715,0.0,1740481175.15922,6.9799933433532715,0.05867180706361628,1740481175.1592214,6.9799933433532715,-0.5867180706361628,1740481175.1592228,6.9799933433532715,-0.7305647298182402,1740481175.159224,6.9799933433532715,0.0,1740481175.1592257,6.9799933433532715,0.20251846624569364,, +1740481175.1799028,6.999993324279785,4.956310224595983,1740481175.179906,6.999993324279785,0.0,1740481175.1799088,6.999993324279785,0.0,1740481175.1799119,6.999993324279785,7.36134715708737,1740481175.1799133,6.999993324279785,0.0,1740481175.179915,6.999993324279785,0.0,1740481175.1799164,6.999993324279785,0.0,1740481175.1799183,6.999993324279785,0.0,1740481175.1799197,6.999993324279785,0.05867180706361628,1740481175.1799212,6.999993324279785,-0.5867180706361628,1740481175.1799219,6.999993324279785,-0.7305647298182402,1740481175.1799233,6.999993324279785,0.0,1740481175.1799245,6.999993324279785,0.20251846624569364,, +1740481175.1983645,7.019993305206299,4.975267502031452,1740481175.198366,7.019993305206299,0.0,1740481175.198368,7.019993305206299,4.859429015928988e-05,1740481175.19837,7.019993305206299,7.216916767271533,1740481175.1983712,7.019993305206299,0.0,1740481175.1983724,7.019993305206299,0.0,1740481175.1983733,7.019993305206299,0.0,1740481175.1983745,7.019993305206299,0.0,1740481175.1983755,7.019993305206299,0.0,1740481175.1983764,7.019993305206299,0.0,1740481175.1983771,7.019993305206299,-0.12411183877062822,1740481175.1983783,7.019993305206299,0.0,1740481175.198379,7.019993305206299,0.13027897419269516,, +1740481175.2187233,7.0399932861328125,4.975267502031452,1740481175.2187252,7.0399932861328125,0.0,1740481175.2187278,7.0399932861328125,0.0,1740481175.21873,7.0399932861328125,7.235825450416842,1740481175.218731,7.0399932861328125,0.0,1740481175.2187324,7.0399932861328125,0.0,1740481175.2187333,7.0399932861328125,0.0,1740481175.2187343,7.0399932861328125,0.0,1740481175.2187355,7.0399932861328125,0.04289045919028036,1740481175.2187364,7.0399932861328125,-0.42890459190280356,1740481175.2187374,7.0399932861328125,-0.5162931069052183,1740481175.2187383,7.0399932861328125,0.0,1740481175.2187393,7.0399932861328125,0.13027897419269516,, +1740481175.2377393,7.059993267059326,4.975267502031452,1740481175.2377415,7.059993267059326,0.0,1740481175.237744,7.059993267059326,0.0,1740481175.2377467,7.059993267059326,7.235825450416842,1740481175.2377477,7.059993267059326,0.0,1740481175.2377493,7.059993267059326,0.0,1740481175.2377503,7.059993267059326,0.0,1740481175.2377512,7.059993267059326,0.0,1740481175.2377524,7.059993267059326,0.04289045919028036,1740481175.2377536,7.059993267059326,-0.42890459190280356,1740481175.2377546,7.059993267059326,-0.5162931069052183,1740481175.2377555,7.059993267059326,0.0,1740481175.2377565,7.059993267059326,0.13027897419269516,, +1740481175.2594004,7.07999324798584,4.975267502031452,1740481175.2594023,7.07999324798584,0.0,1740481175.2594042,7.07999324798584,0.0,1740481175.2594063,7.07999324798584,7.235825450416842,1740481175.2594073,7.07999324798584,0.0,1740481175.2594087,7.07999324798584,0.0,1740481175.2594097,7.07999324798584,0.0,1740481175.2594106,7.07999324798584,0.0,1740481175.2594118,7.07999324798584,0.04289045919028036,1740481175.2594128,7.07999324798584,-0.42890459190280356,1740481175.2594135,7.07999324798584,-0.5162931069052183,1740481175.2594144,7.07999324798584,0.0,1740481175.2594154,7.07999324798584,0.13027897419269516,, +1740481175.2780843,7.0999932289123535,4.975267502031452,1740481175.2780862,7.0999932289123535,0.0,1740481175.2780883,7.0999932289123535,0.0,1740481175.2780905,7.0999932289123535,7.235825450416842,1740481175.2780912,7.0999932289123535,0.0,1740481175.2780926,7.0999932289123535,0.0,1740481175.2780933,7.0999932289123535,0.0,1740481175.2780943,7.0999932289123535,0.0,1740481175.2780952,7.0999932289123535,0.04289045919028036,1740481175.2780962,7.0999932289123535,-0.42890459190280356,1740481175.2780972,7.0999932289123535,-0.5162931069052183,1740481175.2780979,7.0999932289123535,0.0,1740481175.278099,7.0999932289123535,0.13027897419269516,, +1740481175.2997706,7.119993209838867,4.975267502031452,1740481175.2997723,7.119993209838867,0.0,1740481175.2997742,7.119993209838867,0.0,1740481175.2997766,7.119993209838867,7.235825450416842,1740481175.2997775,7.119993209838867,0.0,1740481175.2997787,7.119993209838867,0.0,1740481175.29978,7.119993209838867,0.0,1740481175.2997808,7.119993209838867,0.0,1740481175.2997818,7.119993209838867,0.04289045919028036,1740481175.299783,7.119993209838867,-0.42890459190280356,1740481175.299784,7.119993209838867,-0.5162931069052183,1740481175.2997847,7.119993209838867,0.0,1740481175.2997856,7.119993209838867,0.13027897419269516,, +1740481175.3188553,7.139993190765381,4.98732594902868,1740481175.318857,7.139993190765381,0.0,1740481175.318859,7.139993190765381,0.0,1740481175.3188612,7.139993190765381,7.145718340569713,1740481175.318862,7.139993190765381,0.0,1740481175.3188634,7.139993190765381,0.0,1740481175.3188646,7.139993190765381,0.0,1740481175.318866,7.139993190765381,0.0,1740481175.318867,7.139993190765381,0.0,1740481175.318868,7.139993190765381,0.0,1740481175.3188689,7.139993190765381,-0.0754724107501941,1740481175.31887,7.139993190765381,0.0,1740481175.3188708,7.139993190765381,0.07919619577051679,, +1740481175.3395753,7.1599931716918945,4.98732594902868,1740481175.3395772,7.1599931716918945,0.0,1740481175.3395789,7.1599931716918945,0.0,1740481175.339581,7.1599931716918945,7.145718340569713,1740481175.339582,7.1599931716918945,0.0,1740481175.3395832,7.1599931716918945,0.0,1740481175.3395844,7.1599931716918945,0.0,1740481175.3395853,7.1599931716918945,0.0,1740481175.339586,7.1599931716918945,0.0,1740481175.3395867,7.1599931716918945,0.0,1740481175.339588,7.1599931716918945,-0.07919619577051679,1740481175.3395886,7.1599931716918945,0.0,1740481175.3395896,7.1599931716918945,0.07919619577051679,, +1740481175.3593423,7.179993152618408,4.98732594902868,1740481175.3593445,7.179993152618408,0.0,1740481175.3593464,7.179993152618408,0.0,1740481175.359349,7.179993152618408,7.145718340569713,1740481175.35935,7.179993152618408,0.0,1740481175.3593514,7.179993152618408,0.0,1740481175.3593524,7.179993152618408,0.0,1740481175.3593535,7.179993152618408,0.0,1740481175.3593547,7.179993152618408,0.0,1740481175.3593557,7.179993152618408,0.0,1740481175.3593564,7.179993152618408,-0.07919619577051679,1740481175.359357,7.179993152618408,0.0,1740481175.3593585,7.179993152618408,0.07919619577051679,, +1740481175.3789616,7.199993133544922,4.98732594902868,1740481175.3789644,7.199993133544922,0.0,1740481175.3789682,7.199993133544922,0.0,1740481175.3789716,7.199993133544922,7.145718340569713,1740481175.3789735,7.199993133544922,0.0,1740481175.3789752,7.199993133544922,0.0,1740481175.3789775,7.199993133544922,0.0,1740481175.3789785,7.199993133544922,0.0,1740481175.3789797,7.199993133544922,0.0,1740481175.378981,7.199993133544922,0.0,1740481175.3789825,7.199993133544922,-0.07919619577051679,1740481175.3789837,7.199993133544922,0.0,1740481175.3789847,7.199993133544922,0.07919619577051679,, +1740481175.3992891,7.2199931144714355,4.98732594902868,1740481175.3992906,7.2199931144714355,0.0,1740481175.399293,7.2199931144714355,0.0,1740481175.3992953,7.2199931144714355,7.145718340569713,1740481175.3992963,7.2199931144714355,0.0,1740481175.3992975,7.2199931144714355,0.0,1740481175.3992982,7.2199931144714355,0.0,1740481175.3992994,7.2199931144714355,0.0,1740481175.3993003,7.2199931144714355,0.0,1740481175.399301,7.2199931144714355,0.0,1740481175.399302,7.2199931144714355,-0.07919619577051679,1740481175.399303,7.2199931144714355,0.0,1740481175.399304,7.2199931144714355,0.07919619577051679,, +1740481175.418495,7.239993095397949,4.9946015754600595,1740481175.4184968,7.239993095397949,0.0,1740481175.4184988,7.239993095397949,0.0,1740481175.418501,7.239993095397949,7.1019308120111155,1740481175.4185019,7.239993095397949,0.0,1740481175.4185033,7.239993095397949,0.0,1740481175.4185042,7.239993095397949,0.0,1740481175.4185052,7.239993095397949,0.0,1740481175.418506,7.239993095397949,6.8607612444537835e-06,1740481175.4185069,7.239993095397949,0.0,1740481175.4185078,7.239993095397949,-0.04204936541809744,1740481175.4185085,7.239993095397949,0.0,1740481175.4185092,7.239993095397949,0.053664618275527896,, +1740481175.437816,7.259993076324463,4.9946015754600595,1740481175.4378173,7.259993076324463,0.0,1740481175.4378195,7.259993076324463,0.0,1740481175.4378214,7.259993076324463,7.1019308120111155,1740481175.4378226,7.259993076324463,0.0,1740481175.4378235,7.259993076324463,0.0,1740481175.4378245,7.259993076324463,0.0,1740481175.4378254,7.259993076324463,0.0,1740481175.4378264,7.259993076324463,6.8607612444537835e-06,1740481175.4378273,7.259993076324463,0.0,1740481175.437828,7.259993076324463,-0.05365775751428344,1740481175.4378288,7.259993076324463,0.0,1740481175.43783,7.259993076324463,0.053664618275527896,, +1740481175.4575279,7.279993057250977,4.9946015754600595,1740481175.4575295,7.279993057250977,0.0,1740481175.4575317,7.279993057250977,0.0,1740481175.4575334,7.279993057250977,7.1019308120111155,1740481175.4575346,7.279993057250977,0.0,1740481175.4575357,7.279993057250977,0.0,1740481175.4575365,7.279993057250977,0.0,1740481175.4575377,7.279993057250977,0.0,1740481175.4575384,7.279993057250977,6.8607612444537835e-06,1740481175.4575393,7.279993057250977,0.0,1740481175.45754,7.279993057250977,-0.05365775751428344,1740481175.4575408,7.279993057250977,0.0,1740481175.457542,7.279993057250977,0.053664618275527896,, +1740481175.4776907,7.29999303817749,4.9946015754600595,1740481175.4776921,7.29999303817749,0.0,1740481175.4776943,7.29999303817749,0.0,1740481175.4776962,7.29999303817749,7.1019308120111155,1740481175.4776974,7.29999303817749,0.0,1740481175.4776983,7.29999303817749,0.0,1740481175.4776993,7.29999303817749,0.0,1740481175.4777002,7.29999303817749,0.0,1740481175.4777012,7.29999303817749,6.8607612444537835e-06,1740481175.477702,7.29999303817749,0.0,1740481175.4777029,7.29999303817749,-0.05365775751428344,1740481175.4777036,7.29999303817749,0.0,1740481175.4777045,7.29999303817749,0.053664618275527896,, +1740481175.4984784,7.319993019104004,4.9946015754600595,1740481175.49848,7.319993019104004,0.0,1740481175.4984822,7.319993019104004,0.0,1740481175.4984841,7.319993019104004,7.1019308120111155,1740481175.4984853,7.319993019104004,0.0,1740481175.4984865,7.319993019104004,0.0,1740481175.4984875,7.319993019104004,0.0,1740481175.4984884,7.319993019104004,0.0,1740481175.4984891,7.319993019104004,6.8607612444537835e-06,1740481175.49849,7.319993019104004,0.0,1740481175.498491,7.319993019104004,-0.05365775751428344,1740481175.498492,7.319993019104004,0.0,1740481175.498493,7.319993019104004,0.053664618275527896,, +1740481175.518728,7.339993000030518,4.9946015754600595,1740481175.5187304,7.339993000030518,0.0,1740481175.518733,7.339993000030518,0.0,1740481175.5187366,7.339993000030518,7.1019308120111155,1740481175.5187385,7.339993000030518,0.0,1740481175.5187402,7.339993000030518,0.0,1740481175.5187416,7.339993000030518,0.0,1740481175.518743,7.339993000030518,0.0,1740481175.5187445,7.339993000030518,6.8607612444537835e-06,1740481175.518746,7.339993000030518,0.0,1740481175.5187469,7.339993000030518,-0.05365775751428344,1740481175.5187485,7.339993000030518,0.0,1740481175.5187497,7.339993000030518,0.053664618275527896,, +1740481175.5381873,7.359992980957031,4.999391470456887,1740481175.5381896,7.359992980957031,0.0,1740481175.5381918,7.359992980957031,8.292862185443946e-07,1740481175.5381942,7.359992980957031,7.057448390336796,1740481175.5381954,7.359992980957031,0.0,1740481175.538197,7.359992980957031,0.0,1740481175.538198,7.359992980957031,0.0,1740481175.5381992,7.359992980957031,0.0,1740481175.5382001,7.359992980957031,6.8607612444537835e-06,1740481175.5382023,7.359992980957031,0.0,1740481175.5382035,7.359992980957031,-0.021306292628761783,1740481175.5382044,7.359992980957031,0.0,1740481175.5382054,7.359992980957031,0.03142299279525901,, +1740481175.5586,7.379992961883545,4.999391470456887,1740481175.5586023,7.379992961883545,0.0,1740481175.5586047,7.379992961883545,8.292862185443946e-07,1740481175.5586069,7.379992961883545,7.057448390336796,1740481175.558608,7.379992961883545,0.0,1740481175.55861,7.379992961883545,0.0,1740481175.5586112,7.379992961883545,0.0,1740481175.5586126,7.379992961883545,0.0,1740481175.5586135,7.379992961883545,6.8607612444537835e-06,1740481175.5586145,7.379992961883545,0.0,1740481175.558616,7.379992961883545,-0.031416132034014554,1740481175.558617,7.379992961883545,0.0,1740481175.558618,7.379992961883545,0.03142299279525901,, +1740481175.5780513,7.399992942810059,4.999391470456887,1740481175.5780528,7.399992942810059,0.0,1740481175.578055,7.399992942810059,8.292862185443946e-07,1740481175.5780568,7.399992942810059,7.057448390336796,1740481175.578058,7.399992942810059,0.0,1740481175.5780594,7.399992942810059,0.0,1740481175.5780606,7.399992942810059,0.0,1740481175.5780618,7.399992942810059,0.0,1740481175.5780628,7.399992942810059,6.8607612444537835e-06,1740481175.578064,7.399992942810059,0.0,1740481175.5780647,7.399992942810059,-0.031416132034014554,1740481175.5780659,7.399992942810059,0.0,1740481175.5780666,7.399992942810059,0.03142299279525901,, +1740481175.5996542,7.419992923736572,4.999391470456887,1740481175.5996563,7.419992923736572,0.0,1740481175.599659,7.419992923736572,8.292862185443946e-07,1740481175.5996616,7.419992923736572,7.057448390336796,1740481175.5996628,7.419992923736572,0.0,1740481175.5996644,7.419992923736572,0.0,1740481175.5996656,7.419992923736572,0.0,1740481175.5996668,7.419992923736572,0.0,1740481175.5996683,7.419992923736572,6.8607612444537835e-06,1740481175.5996695,7.419992923736572,0.0,1740481175.5996704,7.419992923736572,-0.031416132034014554,1740481175.5996716,7.419992923736572,0.0,1740481175.5996728,7.419992923736572,0.03142299279525901,, +1740481175.618341,7.439992904663086,4.999391470456887,1740481175.6183426,7.439992904663086,0.0,1740481175.6183448,7.439992904663086,0.0,1740481175.6183465,7.439992904663086,7.062237456047405,1740481175.6183474,7.439992904663086,0.0,1740481175.6183603,7.439992904663086,0.0,1740481175.618362,7.439992904663086,0.0,1740481175.618363,7.439992904663086,0.0,1740481175.6183639,7.439992904663086,0.028988874622964175,1740481175.6183646,7.439992904663086,-0.289448024298301,1740481175.6183658,7.439992904663086,-0.29188214247059585,1740481175.6183665,7.439992904663086,0.0,1740481175.6183674,7.439992904663086,0.03142299279525901,, +1740481175.6392107,7.4599928855896,5.001731794721099,1740481175.6392124,7.4599928855896,0.0,1740481175.6392155,7.4599928855896,1.7742952393302485e-05,1740481175.6392176,7.4599928855896,7.014344792196951,1740481175.6392183,7.4599928855896,0.0,1740481175.6392198,7.4599928855896,0.0,1740481175.6392207,7.4599928855896,0.0,1740481175.6392214,7.4599928855896,0.0,1740481175.6392224,7.4599928855896,4.40721931340704e-05,1740481175.6392233,7.4599928855896,0.0,1740481175.6392243,7.4599928855896,-0.00969171892200337,1740481175.639225,7.4599928855896,0.0,1740481175.6392262,7.4599928855896,0.0074677893938357165,, +1740481175.6577368,7.479992866516113,5.001731794721099,1740481175.6577384,7.479992866516113,0.0,1740481175.6577404,7.479992866516113,1.7742952393302485e-05,1740481175.6577425,7.479992866516113,7.014344792196951,1740481175.6577435,7.479992866516113,0.0,1740481175.6577446,7.479992866516113,0.0,1740481175.6577454,7.479992866516113,0.0,1740481175.6577463,7.479992866516113,0.0,1740481175.6577475,7.479992866516113,4.40721931340704e-05,1740481175.6577485,7.479992866516113,0.0,1740481175.6577492,7.479992866516113,-0.007423717200701646,1740481175.6577501,7.479992866516113,0.0,1740481175.6577508,7.479992866516113,0.0074677893938357165,, +1740481175.6782453,7.499992847442627,5.001731794721099,1740481175.6782472,7.499992847442627,0.0,1740481175.6782491,7.499992847442627,1.7742952393302485e-05,1740481175.678251,7.499992847442627,7.014344792196951,1740481175.678252,7.499992847442627,0.0,1740481175.6782532,7.499992847442627,0.0,1740481175.6782541,7.499992847442627,0.0,1740481175.678255,7.499992847442627,0.0,1740481175.678256,7.499992847442627,4.40721931340704e-05,1740481175.678257,7.499992847442627,0.0,1740481175.678258,7.499992847442627,-0.007423717200701646,1740481175.6782587,7.499992847442627,0.0,1740481175.6782594,7.499992847442627,0.0074677893938357165,, +1740481175.6981564,7.519992828369141,5.001731794721099,1740481175.698158,7.519992828369141,0.0,1740481175.69816,7.519992828369141,1.7742952393302485e-05,1740481175.6981616,7.519992828369141,7.014344792196951,1740481175.6981628,7.519992828369141,0.0,1740481175.6981637,7.519992828369141,0.0,1740481175.6981647,7.519992828369141,0.0,1740481175.6981657,7.519992828369141,0.0,1740481175.6981666,7.519992828369141,4.40721931340704e-05,1740481175.6981676,7.519992828369141,0.0,1740481175.6981685,7.519992828369141,-0.007423717200701646,1740481175.6981692,7.519992828369141,0.0,1740481175.6981702,7.519992828369141,0.0074677893938357165,, +1740481175.7236679,7.539992809295654,5.001731794721099,1740481175.7236698,7.539992809295654,0.0,1740481175.7236722,7.539992809295654,0.0,1740481175.723674,7.539992809295654,7.016667373508771,1740481175.7236753,7.539992809295654,0.0,1740481175.7236764,7.539992809295654,0.0,1740481175.7236774,7.539992809295654,0.0,1740481175.7236784,7.539992809295654,0.0,1740481175.7236795,7.539992809295654,3.491539030228257e-06,1740481175.7236803,7.539992809295654,0.0,1740481175.7236812,7.539992809295654,-0.0074642978548054885,1740481175.7236822,7.539992809295654,0.0,1740481175.723683,7.539992809295654,0.0074677893938357165,, +1740481175.7379806,7.559992790222168,5.001731794721099,1740481175.7379823,7.559992790222168,0.0,1740481175.7379847,7.559992790222168,0.0,1740481175.737987,7.559992790222168,7.016667373508771,1740481175.7379878,7.559992790222168,0.0,1740481175.7379892,7.559992790222168,0.0,1740481175.7379901,7.559992790222168,0.0,1740481175.737991,7.559992790222168,0.0,1740481175.737992,7.559992790222168,3.491539030228257e-06,1740481175.737993,7.559992790222168,0.0,1740481175.7379937,7.559992790222168,-0.0074642978548054885,1740481175.7379947,7.559992790222168,0.0,1740481175.7379956,7.559992790222168,0.0074677893938357165,, +1740481175.7577147,7.579992771148682,5.001910322093941,1740481175.7577164,7.579992771148682,0.0,1740481175.7577188,7.579992771148682,6.222558014778727e-10,1740481175.757721,7.579992771148682,7.001731795343355,1740481175.757722,7.579992771148682,0.0,1740481175.7577233,7.579992771148682,0.0,1740481175.7577245,7.579992771148682,0.0,1740481175.7577255,7.579992771148682,0.0,1740481175.7577267,7.579992771148682,3.491539030228257e-06,1740481175.7577279,7.579992771148682,0.0,1740481175.7577288,7.579992771148682,0.0033979445007036166,1740481175.7577298,7.579992771148682,0.0,1740481175.7577305,7.579992771148682,0.0,, +1740481175.777653,7.599992752075195,5.001910322093941,1740481175.7776554,7.599992752075195,0.0,1740481175.7776573,7.599992752075195,6.222558014778727e-10,1740481175.7776597,7.599992752075195,7.001731795343355,1740481175.7776606,7.599992752075195,0.0,1740481175.777662,7.599992752075195,0.0,1740481175.777663,7.599992752075195,0.0,1740481175.777664,7.599992752075195,0.0,1740481175.7776651,7.599992752075195,3.491539030228257e-06,1740481175.777666,7.599992752075195,0.0,1740481175.7776668,7.599992752075195,3.491539030228257e-06,1740481175.7776678,7.599992752075195,0.0,1740481175.777669,7.599992752075195,0.0,, +1740481175.7987216,7.619992733001709,5.001910322093941,1740481175.7987237,7.619992733001709,0.0,1740481175.7987256,7.619992733001709,6.222558014778727e-10,1740481175.798728,7.619992733001709,7.001731795343355,1740481175.798729,7.619992733001709,0.0,1740481175.7987301,7.619992733001709,0.0,1740481175.7987313,7.619992733001709,0.0,1740481175.7987323,7.619992733001709,0.0,1740481175.7987332,7.619992733001709,3.491539030228257e-06,1740481175.7987344,7.619992733001709,0.0,1740481175.7987354,7.619992733001709,3.491539030228257e-06,1740481175.798736,7.619992733001709,0.0,1740481175.798737,7.619992733001709,0.0,, +1740481175.818356,7.639992713928223,5.001910322093941,1740481175.8183575,7.639992713928223,0.0,1740481175.8183594,7.639992713928223,0.0,1740481175.818361,7.639992713928223,7.001910322093941,1740481175.818362,7.639992713928223,0.0,1740481175.8183632,7.639992713928223,0.0,1740481175.8183641,7.639992713928223,0.0,1740481175.818365,7.639992713928223,0.0,1740481175.818366,7.639992713928223,0.0,1740481175.818367,7.639992713928223,-2.0,1740481175.818368,7.639992713928223,-2.0,1740481175.8183687,7.639992713928223,0.0,1740481175.8183696,7.639992713928223,0.0,, +1740481175.838949,7.659992694854736,5.001910322093941,1740481175.8389504,7.659992694854736,0.0,1740481175.8389525,7.659992694854736,0.0,1740481175.8389544,7.659992694854736,7.001910322093941,1740481175.8389554,7.659992694854736,0.0,1740481175.8389566,7.659992694854736,0.0,1740481175.8389575,7.659992694854736,0.0,1740481175.8389585,7.659992694854736,0.0,1740481175.8389595,7.659992694854736,0.0,1740481175.8389604,7.659992694854736,-2.0,1740481175.8389611,7.659992694854736,-2.0,1740481175.838962,7.659992694854736,0.0,1740481175.838963,7.659992694854736,0.0,, +1740481175.8575957,7.67999267578125,5.001914059077752,1740481175.8575969,7.67999267578125,0.0,1740481175.8575988,7.67999267578125,0.0,1740481175.8576007,7.67999267578125,7.001910322093941,1740481175.857602,7.67999267578125,0.0,1740481175.8576028,7.67999267578125,0.0,1740481175.8576038,7.67999267578125,0.0,1740481175.857605,7.67999267578125,0.0,1740481175.857606,7.67999267578125,0.0,1740481175.857607,7.67999267578125,-2.0,1740481175.8576076,7.67999267578125,-2.0,1740481175.8576088,7.67999267578125,0.0,1740481175.8576097,7.67999267578125,0.0,, +1740481175.8788037,7.699992656707764,5.001914059077752,1740481175.878806,7.699992656707764,0.0,1740481175.8788085,7.699992656707764,0.0,1740481175.8788106,7.699992656707764,7.001910322093941,1740481175.8788116,7.699992656707764,0.0,1740481175.8788137,7.699992656707764,0.0,1740481175.8788147,7.699992656707764,0.0,1740481175.878816,7.699992656707764,0.0,1740481175.8788176,7.699992656707764,0.0,1740481175.878819,7.699992656707764,-2.0,1740481175.8788207,7.699992656707764,-2.0,1740481175.8788218,7.699992656707764,0.0,1740481175.8788233,7.699992656707764,0.0,, +1740481175.8979528,7.719992637634277,5.001914059077752,1740481175.8979542,7.719992637634277,0.0,1740481175.8979564,7.719992637634277,0.0,1740481175.8979585,7.719992637634277,7.001910322093941,1740481175.8979597,7.719992637634277,0.0,1740481175.8979607,7.719992637634277,0.0,1740481175.8979616,7.719992637634277,0.0,1740481175.8979628,7.719992637634277,0.0,1740481175.8979635,7.719992637634277,0.0,1740481175.8979645,7.719992637634277,-2.0,1740481175.8979657,7.719992637634277,-2.0,1740481175.8979666,7.719992637634277,0.0,1740481175.8979673,7.719992637634277,0.0,, +1740481175.9188716,7.739992618560791,5.001914059077752,1740481175.918873,7.739992618560791,0.0,1740481175.9188752,7.739992618560791,0.0,1740481175.918877,7.739992618560791,7.001914059077752,1740481175.9188778,7.739992618560791,0.0,1740481175.9188793,7.739992618560791,0.0,1740481175.9188802,7.739992618560791,0.0,1740481175.9188812,7.739992618560791,0.0,1740481175.9188824,7.739992618560791,0.0,1740481175.918883,7.739992618560791,-2.0,1740481175.918884,7.739992618560791,-2.0,1740481175.9188848,7.739992618560791,0.0,1740481175.918886,7.739992618560791,0.0,, +1740481175.9376473,7.759992599487305,5.001914059077752,1740481175.9376485,7.759992599487305,0.0,1740481175.9376507,7.759992599487305,0.0,1740481175.9376526,7.759992599487305,7.001914059077752,1740481175.9376535,7.759992599487305,0.0,1740481175.937655,7.759992599487305,0.0,1740481175.9376562,7.759992599487305,0.0,1740481175.937657,7.759992599487305,0.0,1740481175.9376578,7.759992599487305,0.0,1740481175.9376588,7.759992599487305,-2.0,1740481175.93766,7.759992599487305,-2.0,1740481175.9376607,7.759992599487305,0.0,1740481175.9376616,7.759992599487305,0.0,, +1740481175.957789,7.779992580413818,5.001914059077752,1740481175.9577901,7.779992580413818,0.0,1740481175.9577925,7.779992580413818,0.0,1740481175.9577947,7.779992580413818,7.001914059077752,1740481175.9577956,7.779992580413818,0.0,1740481175.9577968,7.779992580413818,0.0,1740481175.957798,7.779992580413818,0.0,1740481175.957799,7.779992580413818,0.0,1740481175.9578,7.779992580413818,0.0,1740481175.9578009,7.779992580413818,-2.0,1740481175.9578018,7.779992580413818,-2.0,1740481175.9578028,7.779992580413818,0.0,1740481175.9578035,7.779992580413818,0.0,, +1740481175.9780893,7.799992561340332,5.001914059077752,1740481175.9780908,7.799992561340332,0.0,1740481175.9780924,7.799992561340332,0.0,1740481175.9780946,7.799992561340332,7.001914059077752,1740481175.978108,7.799992561340332,0.0,1740481175.978111,7.799992561340332,0.0,1740481175.978112,7.799992561340332,0.0,1740481175.978113,7.799992561340332,0.0,1740481175.9781141,7.799992561340332,0.0,1740481175.978115,7.799992561340332,-2.0,1740481175.9781158,7.799992561340332,-2.0,1740481175.9781168,7.799992561340332,0.0,1740481175.978118,7.799992561340332,0.0,, +1740481175.9982185,7.819992542266846,5.001914059077752,1740481175.99822,7.819992542266846,0.0,1740481175.9982219,7.819992542266846,0.0,1740481175.9982238,7.819992542266846,7.001914059077752,1740481175.998225,7.819992542266846,0.0,1740481175.9982262,7.819992542266846,0.0,1740481175.9982271,7.819992542266846,0.0,1740481175.9982283,7.819992542266846,0.0,1740481175.9982293,7.819992542266846,0.0,1740481175.9982302,7.819992542266846,-2.0,1740481175.9982314,7.819992542266846,-2.0,1740481175.9982321,7.819992542266846,0.0,1740481175.998233,7.819992542266846,0.0,, +1740481176.0186312,7.839992523193359,5.001914059077752,1740481176.0186327,7.839992523193359,0.0,1740481176.0186346,7.839992523193359,0.0,1740481176.0186365,7.839992523193359,7.001914059077752,1740481176.0186377,7.839992523193359,0.0,1740481176.0186388,7.839992523193359,0.0,1740481176.0186398,7.839992523193359,0.0,1740481176.018641,7.839992523193359,0.0,1740481176.018642,7.839992523193359,0.0,1740481176.0186427,7.839992523193359,-2.0,1740481176.0186436,7.839992523193359,-2.0,1740481176.0186446,7.839992523193359,0.0,1740481176.0186453,7.839992523193359,0.0,, +1740481176.0383449,7.859992504119873,5.001914059077752,1740481176.0383465,7.859992504119873,0.0,1740481176.0383482,7.859992504119873,0.0,1740481176.0383503,7.859992504119873,7.001914059077752,1740481176.0383642,7.859992504119873,0.0,1740481176.0383668,7.859992504119873,0.0,1740481176.0383675,7.859992504119873,0.0,1740481176.0383685,7.859992504119873,0.0,1740481176.0383694,7.859992504119873,0.0,1740481176.0383704,7.859992504119873,-2.0,1740481176.038371,7.859992504119873,-2.0,1740481176.038372,7.859992504119873,0.0,1740481176.0383728,7.859992504119873,0.0,, +1740481176.0576034,7.879992485046387,5.001914059077752,1740481176.0576048,7.879992485046387,0.0,1740481176.057607,7.879992485046387,0.0,1740481176.0576093,7.879992485046387,7.001914059077752,1740481176.0576105,7.879992485046387,0.0,1740481176.057612,7.879992485046387,0.0,1740481176.0576131,7.879992485046387,0.0,1740481176.0576138,7.879992485046387,0.0,1740481176.057615,7.879992485046387,0.0,1740481176.0576162,7.879992485046387,-2.0,1740481176.0576172,7.879992485046387,-2.0,1740481176.0576181,7.879992485046387,0.0,1740481176.057619,7.879992485046387,0.0,, +1740481176.0782528,7.8999924659729,5.001914059077752,1740481176.0782542,7.8999924659729,0.0,1740481176.0782564,7.8999924659729,0.0,1740481176.0782585,7.8999924659729,7.001914059077752,1740481176.0782595,7.8999924659729,0.0,1740481176.0782607,7.8999924659729,0.0,1740481176.0782619,7.8999924659729,0.0,1740481176.0782628,7.8999924659729,0.0,1740481176.0782635,7.8999924659729,0.0,1740481176.0782645,7.8999924659729,-2.0,1740481176.0782657,7.8999924659729,-2.0,1740481176.0782664,7.8999924659729,0.0,1740481176.0782673,7.8999924659729,0.0,, +1740481176.1017756,7.919992446899414,5.001914059077752,1740481176.101777,7.919992446899414,0.0,1740481176.1017792,7.919992446899414,0.0,1740481176.1017811,7.919992446899414,7.001914059077752,1740481176.1017823,7.919992446899414,0.0,1740481176.1017835,7.919992446899414,0.0,1740481176.101785,7.919992446899414,0.0,1740481176.101786,7.919992446899414,0.0,1740481176.1017866,7.919992446899414,0.0,1740481176.1017878,7.919992446899414,-2.0,1740481176.1017888,7.919992446899414,-2.0,1740481176.1017897,7.919992446899414,0.0,1740481176.1017904,7.919992446899414,0.0,, +1740481176.1186087,7.939992427825928,5.001914059077752,1740481176.1186101,7.939992427825928,0.0,1740481176.1186125,7.939992427825928,0.0,1740481176.1186144,7.939992427825928,7.001914059077752,1740481176.1186156,7.939992427825928,0.0,1740481176.118617,7.939992427825928,0.0,1740481176.118618,7.939992427825928,0.0,1740481176.1186192,7.939992427825928,0.0,1740481176.1186337,7.939992427825928,0.0,1740481176.118635,7.939992427825928,-2.0,1740481176.1186361,7.939992427825928,-2.0,1740481176.1186368,7.939992427825928,0.0,1740481176.1186378,7.939992427825928,0.0,, +1740481176.1386824,7.959992408752441,5.001914059077752,1740481176.1386836,7.959992408752441,0.0,1740481176.1386857,7.959992408752441,0.0,1740481176.1386886,7.959992408752441,7.001914059077752,1740481176.1386893,7.959992408752441,0.0,1740481176.1386905,7.959992408752441,0.0,1740481176.1386917,7.959992408752441,0.0,1740481176.1386926,7.959992408752441,0.0,1740481176.1386936,7.959992408752441,0.0,1740481176.1386948,7.959992408752441,-2.0,1740481176.1386955,7.959992408752441,-2.0,1740481176.1386962,7.959992408752441,0.0,1740481176.1386971,7.959992408752441,0.0,, +1740481176.1584785,7.979992389678955,5.001914059077752,1740481176.1584835,7.979992389678955,0.0,1740481176.158487,7.979992389678955,0.0,1740481176.1584892,7.979992389678955,7.001914059077752,1740481176.1584904,7.979992389678955,0.0,1740481176.1584916,7.979992389678955,0.0,1740481176.1584926,7.979992389678955,0.0,1740481176.1584938,7.979992389678955,0.0,1740481176.1584947,7.979992389678955,0.0,1740481176.1584957,7.979992389678955,-2.0,1740481176.1584969,7.979992389678955,-2.0,1740481176.1584976,7.979992389678955,0.0,1740481176.1584988,7.979992389678955,0.0,, +1740481176.1776597,7.999992370605469,5.001914059077752,1740481176.1776612,7.999992370605469,0.0,1740481176.1776633,7.999992370605469,0.0,1740481176.1776655,7.999992370605469,7.001914059077752,1740481176.1776667,7.999992370605469,0.0,1740481176.1776679,7.999992370605469,0.0,1740481176.1776688,7.999992370605469,0.0,1740481176.17767,7.999992370605469,0.0,1740481176.177671,7.999992370605469,0.0,1740481176.1776721,7.999992370605469,-2.0,1740481176.1776729,7.999992370605469,-2.0,1740481176.177674,7.999992370605469,0.0,1740481176.1776748,7.999992370605469,0.0,, +1740481176.1982331,8.019992351531982,5.001914059077752,1740481176.1982346,8.019992351531982,0.0,1740481176.1982367,8.019992351531982,0.0,1740481176.1982386,8.019992351531982,7.001914059077752,1740481176.1982398,8.019992351531982,0.0,1740481176.1982412,8.019992351531982,0.0,1740481176.1982422,8.019992351531982,0.0,1740481176.1982434,8.019992351531982,0.0,1740481176.1982443,8.019992351531982,0.0,1740481176.1982455,8.019992351531982,-2.0,1740481176.1982467,8.019992351531982,-2.0,1740481176.1982477,8.019992351531982,0.0,1740481176.1982486,8.019992351531982,0.0,, +1740481176.2188714,8.039992332458496,5.001914059077752,1740481176.2188728,8.039992332458496,0.0,1740481176.2188752,8.039992332458496,0.0,1740481176.218877,8.039992332458496,7.001914059077752,1740481176.218878,8.039992332458496,0.0,1740481176.2188792,8.039992332458496,0.0,1740481176.2188802,8.039992332458496,0.0,1740481176.2188814,8.039992332458496,0.0,1740481176.2188823,8.039992332458496,0.0,1740481176.2188833,8.039992332458496,-2.0,1740481176.218884,8.039992332458496,-2.0,1740481176.2188852,8.039992332458496,0.0,1740481176.218886,8.039992332458496,0.0,, +1740481176.2375383,8.05999231338501,5.001914059077752,1740481176.2375398,8.05999231338501,0.0,1740481176.2375422,8.05999231338501,0.0,1740481176.2375443,8.05999231338501,7.001914059077752,1740481176.2375453,8.05999231338501,0.0,1740481176.2375467,8.05999231338501,0.0,1740481176.237548,8.05999231338501,0.0,1740481176.237549,8.05999231338501,0.0,1740481176.23755,8.05999231338501,0.0,1740481176.2375512,8.05999231338501,-2.0,1740481176.2375522,8.05999231338501,-2.0,1740481176.2375531,8.05999231338501,0.0,1740481176.2375538,8.05999231338501,0.0,, +1740481176.2581446,8.079992294311523,5.001914059077752,1740481176.258146,8.079992294311523,0.0,1740481176.2581482,8.079992294311523,0.0,1740481176.2581506,8.079992294311523,7.001914059077752,1740481176.2581518,8.079992294311523,0.0,1740481176.258153,8.079992294311523,0.0,1740481176.258154,8.079992294311523,0.0,1740481176.258155,8.079992294311523,0.0,1740481176.258156,8.079992294311523,0.0,1740481176.2581573,8.079992294311523,-2.0,1740481176.258158,8.079992294311523,-2.0,1740481176.2581592,8.079992294311523,0.0,1740481176.25816,8.079992294311523,0.0,, +1740481176.277517,8.099992275238037,5.001914059077752,1740481176.2775183,8.099992275238037,0.0,1740481176.2775202,8.099992275238037,0.0,1740481176.277522,8.099992275238037,7.001914059077752,1740481176.2775233,8.099992275238037,0.0,1740481176.2775245,8.099992275238037,0.0,1740481176.2775252,8.099992275238037,0.0,1740481176.2775264,8.099992275238037,0.0,1740481176.2775273,8.099992275238037,0.0,1740481176.277528,8.099992275238037,-2.0,1740481176.2775292,8.099992275238037,-2.0,1740481176.2775302,8.099992275238037,0.0,1740481176.2775314,8.099992275238037,0.0,, +1740481176.2985659,8.11999225616455,5.001914059077752,1740481176.2985675,8.11999225616455,0.0,1740481176.2985694,8.11999225616455,0.0,1740481176.2985716,8.11999225616455,7.001914059077752,1740481176.2985725,8.11999225616455,0.0,1740481176.2985737,8.11999225616455,0.0,1740481176.298575,8.11999225616455,0.0,1740481176.298576,8.11999225616455,0.0,1740481176.298577,8.11999225616455,0.0,1740481176.2985783,8.11999225616455,-2.0,1740481176.298579,8.11999225616455,-2.0,1740481176.29858,8.11999225616455,0.0,1740481176.298581,8.11999225616455,0.0,, +1740481176.319487,8.139992237091064,5.001914059077752,1740481176.3194883,8.139992237091064,0.0,1740481176.3194902,8.139992237091064,0.0,1740481176.319492,8.139992237091064,7.001914059077752,1740481176.319493,8.139992237091064,0.0,1740481176.3194942,8.139992237091064,0.0,1740481176.319495,8.139992237091064,0.0,1740481176.319496,8.139992237091064,0.0,1740481176.3194969,8.139992237091064,0.0,1740481176.319498,8.139992237091064,-2.0,1740481176.3194988,8.139992237091064,-2.0,1740481176.3194997,8.139992237091064,0.0,1740481176.3195004,8.139992237091064,0.0,, +1740481176.339816,8.159992218017578,5.001914059077752,1740481176.3398182,8.159992218017578,0.0,1740481176.339821,8.159992218017578,0.0,1740481176.339824,8.159992218017578,7.001914059077752,1740481176.3398252,8.159992218017578,0.0,1740481176.339827,8.159992218017578,0.0,1740481176.3398287,8.159992218017578,0.0,1740481176.33983,8.159992218017578,0.0,1740481176.3398314,8.159992218017578,0.0,1740481176.3398325,8.159992218017578,-2.0,1740481176.3398335,8.159992218017578,-2.0,1740481176.3398354,8.159992218017578,0.0,1740481176.3398366,8.159992218017578,0.0,, +1740481176.3589685,8.179992198944092,5.001914059077752,1740481176.3589702,8.179992198944092,0.0,1740481176.358972,8.179992198944092,0.0,1740481176.3589742,8.179992198944092,7.001914059077752,1740481176.3589752,8.179992198944092,0.0,1740481176.3589766,8.179992198944092,0.0,1740481176.3589773,8.179992198944092,0.0,1740481176.3589783,8.179992198944092,0.0,1740481176.3589792,8.179992198944092,0.0,1740481176.3589802,8.179992198944092,-2.0,1740481176.3589811,8.179992198944092,-2.0,1740481176.359036,8.179992198944092,0.0,1740481176.359038,8.179992198944092,0.0,, +1740481176.37798,8.199992179870605,5.001914059077752,1740481176.3779812,8.199992179870605,0.0,1740481176.3779833,8.199992179870605,0.0,1740481176.3779855,8.199992179870605,7.001914059077752,1740481176.3779862,8.199992179870605,0.0,1740481176.3779876,8.199992179870605,0.0,1740481176.3779886,8.199992179870605,0.0,1740481176.3779893,8.199992179870605,0.0,1740481176.3779905,8.199992179870605,0.0,1740481176.3779914,8.199992179870605,-2.0,1740481176.3779924,8.199992179870605,-2.0,1740481176.377993,8.199992179870605,0.0,1740481176.3779943,8.199992179870605,0.0,, +1740481176.397568,8.21999216079712,5.001914059077752,1740481176.3975694,8.21999216079712,0.0,1740481176.3975902,8.21999216079712,0.0,1740481176.3975925,8.21999216079712,7.001914059077752,1740481176.3975933,8.21999216079712,0.0,1740481176.397595,8.21999216079712,0.0,1740481176.3975961,8.21999216079712,0.0,1740481176.397597,8.21999216079712,0.0,1740481176.3975983,8.21999216079712,0.0,1740481176.397599,8.21999216079712,-2.0,1740481176.3975997,8.21999216079712,-2.0,1740481176.3976007,8.21999216079712,0.0,1740481176.3976254,8.21999216079712,0.0,, +1740481176.4193244,8.239992141723633,5.001914059077752,1740481176.4193263,8.239992141723633,0.0,1740481176.419328,8.239992141723633,0.0,1740481176.4193301,8.239992141723633,7.001914059077752,1740481176.4193308,8.239992141723633,0.0,1740481176.419332,8.239992141723633,0.0,1740481176.4193332,8.239992141723633,0.0,1740481176.4193342,8.239992141723633,0.0,1740481176.419335,8.239992141723633,0.0,1740481176.4193358,8.239992141723633,-2.0,1740481176.419337,8.239992141723633,-2.0,1740481176.4193377,8.239992141723633,0.0,1740481176.4193385,8.239992141723633,0.0,, +1740481176.4394937,8.259992122650146,5.001914059077752,1740481176.439495,8.259992122650146,0.0,1740481176.4394972,8.259992122650146,0.0,1740481176.4394994,8.259992122650146,7.001914059077752,1740481176.4395006,8.259992122650146,0.0,1740481176.4395018,8.259992122650146,0.0,1740481176.4395025,8.259992122650146,0.0,1740481176.439504,8.259992122650146,0.0,1740481176.4395049,8.259992122650146,0.0,1740481176.4395058,8.259992122650146,-2.0,1740481176.439507,8.259992122650146,-2.0,1740481176.439508,8.259992122650146,0.0,1740481176.4395087,8.259992122650146,0.0,, +1740481176.4592407,8.27999210357666,5.001914059077752,1740481176.4592423,8.27999210357666,0.0,1740481176.4592443,8.27999210357666,0.0,1740481176.4592464,8.27999210357666,7.001914059077752,1740481176.4592474,8.27999210357666,0.0,1740481176.4592488,8.27999210357666,0.0,1740481176.45925,8.27999210357666,0.0,1740481176.459251,8.27999210357666,0.0,1740481176.4592519,8.27999210357666,0.0,1740481176.459253,8.27999210357666,-2.0,1740481176.4592543,8.27999210357666,-2.0,1740481176.4592552,8.27999210357666,0.0,1740481176.4592562,8.27999210357666,0.0,, +1740481176.4787219,8.299992084503174,5.001914059077752,1740481176.4787235,8.299992084503174,0.0,1740481176.4787257,8.299992084503174,0.0,1740481176.4787276,8.299992084503174,7.001914059077752,1740481176.4787288,8.299992084503174,0.0,1740481176.47873,8.299992084503174,0.0,1740481176.4787312,8.299992084503174,0.0,1740481176.4787323,8.299992084503174,0.0,1740481176.4787333,8.299992084503174,0.0,1740481176.4787343,8.299992084503174,-2.0,1740481176.4787354,8.299992084503174,-2.0,1740481176.4787364,8.299992084503174,0.0,1740481176.4787374,8.299992084503174,0.0,, +1740481176.4974728,8.319992065429688,5.001914059077752,1740481176.497474,8.319992065429688,0.0,1740481176.4974759,8.319992065429688,0.0,1740481176.4974785,8.319992065429688,7.001914059077752,1740481176.4974794,8.319992065429688,0.0,1740481176.4974804,8.319992065429688,0.0,1740481176.4974816,8.319992065429688,0.0,1740481176.4974825,8.319992065429688,0.0,1740481176.4974835,8.319992065429688,0.0,1740481176.4974844,8.319992065429688,-2.0,1740481176.4974854,8.319992065429688,-2.0,1740481176.497486,8.319992065429688,0.0,1740481176.497487,8.319992065429688,0.0,, +1740481176.52111,8.339992046356201,5.001914059077752,1740481176.5211115,8.339992046356201,0.0,1740481176.5211136,8.339992046356201,0.0,1740481176.5211155,8.339992046356201,7.001914059077752,1740481176.5211165,8.339992046356201,0.0,1740481176.5211177,8.339992046356201,0.0,1740481176.5211186,8.339992046356201,0.0,1740481176.52112,8.339992046356201,0.0,1740481176.5211213,8.339992046356201,0.0,1740481176.5211222,8.339992046356201,-2.0,1740481176.5211234,8.339992046356201,-2.0,1740481176.5211244,8.339992046356201,0.0,1740481176.5211253,8.339992046356201,0.0,, +1740481176.5377321,8.359992027282715,5.001914059077752,1740481176.537735,8.359992027282715,0.0,1740481176.537738,8.359992027282715,0.0,1740481176.537741,8.359992027282715,7.001914059077752,1740481176.537743,8.359992027282715,0.0,1740481176.537745,8.359992027282715,0.0,1740481176.537746,8.359992027282715,0.0,1740481176.5377476,8.359992027282715,0.0,1740481176.5377493,8.359992027282715,0.0,1740481176.5377507,8.359992027282715,-2.0,1740481176.537757,8.359992027282715,-2.0,1740481176.5377584,8.359992027282715,0.0,1740481176.5377598,8.359992027282715,0.0,, +1740481176.5586507,8.379992008209229,5.001914059077752,1740481176.5586524,8.379992008209229,0.0,1740481176.559082,8.379992008209229,0.0,1740481176.5590863,8.379992008209229,7.001914059077752,1740481176.5590875,8.379992008209229,0.0,1740481176.5590892,8.379992008209229,0.0,1740481176.5590901,8.379992008209229,0.0,1740481176.559091,8.379992008209229,0.0,1740481176.5590923,8.379992008209229,0.0,1740481176.5590932,8.379992008209229,-2.0,1740481176.5590947,8.379992008209229,-2.0,1740481176.5590963,8.379992008209229,0.0,1740481176.559098,8.379992008209229,0.0,, +1740481176.580332,8.399991989135742,5.001914059077752,1740481176.5803342,8.399991989135742,0.0,1740481176.580337,8.399991989135742,0.0,1740481176.58034,8.399991989135742,7.001914059077752,1740481176.5803418,8.399991989135742,0.0,1740481176.5803432,8.399991989135742,0.0,1740481176.5803447,8.399991989135742,0.0,1740481176.5803459,8.399991989135742,0.0,1740481176.580348,8.399991989135742,0.0,1740481176.5803494,8.399991989135742,-2.0,1740481176.5803509,8.399991989135742,-2.0,1740481176.580352,8.399991989135742,0.0,1740481176.580353,8.399991989135742,0.0,, +1740481176.5983229,8.419991970062256,5.001914059077752,1740481176.5983245,8.419991970062256,0.0,1740481176.5983264,8.419991970062256,0.0,1740481176.5983286,8.419991970062256,7.001914059077752,1740481176.5983298,8.419991970062256,0.0,1740481176.5983312,8.419991970062256,0.0,1740481176.5983322,8.419991970062256,0.0,1740481176.5983331,8.419991970062256,0.0,1740481176.5983343,8.419991970062256,0.0,1740481176.5983353,8.419991970062256,-2.0,1740481176.598336,8.419991970062256,-2.0,1740481176.598337,8.419991970062256,0.0,1740481176.5983381,8.419991970062256,0.0,, +1740481176.6189077,8.43999195098877,5.001914059077752,1740481176.6189108,8.43999195098877,0.0,1740481176.6189141,8.43999195098877,0.0,1740481176.618916,8.43999195098877,7.001914059077752,1740481176.6189172,8.43999195098877,0.0,1740481176.6189184,8.43999195098877,0.0,1740481176.6189194,8.43999195098877,0.0,1740481176.61892,8.43999195098877,0.0,1740481176.6189215,8.43999195098877,0.0,1740481176.6189222,8.43999195098877,-2.0,1740481176.6189232,8.43999195098877,-2.0,1740481176.6189244,8.43999195098877,0.0,1740481176.6189253,8.43999195098877,0.0,, +1740481176.6380923,8.459991931915283,5.001914059077752,1740481176.6380935,8.459991931915283,0.0,1740481176.6380956,8.459991931915283,0.0,1740481176.6380978,8.459991931915283,7.001914059077752,1740481176.6380987,8.459991931915283,0.0,1740481176.6381001,8.459991931915283,0.0,1740481176.6381013,8.459991931915283,0.0,1740481176.6381023,8.459991931915283,0.0,1740481176.6381032,8.459991931915283,0.0,1740481176.638104,8.459991931915283,-2.0,1740481176.6381052,8.459991931915283,-2.0,1740481176.6381059,8.459991931915283,0.0,1740481176.6381068,8.459991931915283,0.0,, +1740481176.6598444,8.479991912841797,5.001914059077752,1740481176.6598458,8.479991912841797,0.0,1740481176.659848,8.479991912841797,0.0,1740481176.65985,8.479991912841797,7.001914059077752,1740481176.659851,8.479991912841797,0.0,1740481176.6598525,8.479991912841797,0.0,1740481176.6598535,8.479991912841797,0.0,1740481176.6598547,8.479991912841797,0.0,1740481176.6598556,8.479991912841797,0.0,1740481176.6598566,8.479991912841797,-2.0,1740481176.6598577,8.479991912841797,-2.0,1740481176.6598587,8.479991912841797,0.0,1740481176.6598597,8.479991912841797,0.0,, +1740481176.6781893,8.49999189376831,5.001914059077752,1740481176.6781907,8.49999189376831,0.0,1740481176.6781926,8.49999189376831,0.0,1740481176.6781948,8.49999189376831,7.001914059077752,1740481176.6781957,8.49999189376831,0.0,1740481176.678197,8.49999189376831,0.0,1740481176.6781979,8.49999189376831,0.0,1740481176.6781988,8.49999189376831,0.0,1740481176.6781998,8.49999189376831,0.0,1740481176.6782007,8.49999189376831,-2.0,1740481176.6782017,8.49999189376831,-2.0,1740481176.6782026,8.49999189376831,0.0,1740481176.6782033,8.49999189376831,0.0,, +1740481176.6995814,8.519991874694824,5.001914059077752,1740481176.699583,8.519991874694824,0.0,1740481176.699585,8.519991874694824,0.0,1740481176.699587,8.519991874694824,7.001914059077752,1740481176.699588,8.519991874694824,0.0,1740481176.6995895,8.519991874694824,0.0,1740481176.6995904,8.519991874694824,0.0,1740481176.6995914,8.519991874694824,0.0,1740481176.6995924,8.519991874694824,0.0,1740481176.6995935,8.519991874694824,-2.0,1740481176.6995945,8.519991874694824,-2.0,1740481176.6995955,8.519991874694824,0.0,1740481176.6995964,8.519991874694824,0.0,, +1740481176.720019,8.539991855621338,5.001914059077752,1740481176.7200205,8.539991855621338,0.0,1740481176.7200224,8.539991855621338,0.0,1740481176.7200246,8.539991855621338,7.001914059077752,1740481176.7200255,8.539991855621338,0.0,1740481176.720027,8.539991855621338,0.0,1740481176.7200277,8.539991855621338,0.0,1740481176.7200286,8.539991855621338,0.0,1740481176.7200296,8.539991855621338,0.0,1740481176.7200308,8.539991855621338,-2.0,1740481176.7200317,8.539991855621338,-2.0,1740481176.7200325,8.539991855621338,0.0,1740481176.7200336,8.539991855621338,0.0,, +1740481176.7379687,8.559991836547852,5.001914059077752,1740481176.73797,8.559991836547852,0.0,1740481176.737972,8.559991836547852,0.0,1740481176.7379742,8.559991836547852,7.001914059077752,1740481176.7379751,8.559991836547852,0.0,1740481176.7379892,8.559991836547852,0.0,1740481176.7379916,8.559991836547852,0.0,1740481176.737993,8.559991836547852,0.0,1740481176.737994,8.559991836547852,0.0,1740481176.737995,8.559991836547852,-2.0,1740481176.7379959,8.559991836547852,-2.0,1740481176.7379968,8.559991836547852,0.0,1740481176.7379975,8.559991836547852,0.0,, +1740481176.75985,8.579991817474365,5.001914059077752,1740481176.7598515,8.579991817474365,0.0,1740481176.7598534,8.579991817474365,0.0,1740481176.7598553,8.579991817474365,7.001914059077752,1740481176.7598567,8.579991817474365,0.0,1740481176.7598581,8.579991817474365,0.0,1740481176.75986,8.579991817474365,0.0,1740481176.759861,8.579991817474365,0.0,1740481176.759862,8.579991817474365,0.0,1740481176.7598634,8.579991817474365,-2.0,1740481176.7598646,8.579991817474365,-2.0,1740481176.759866,8.579991817474365,0.0,1740481176.7598674,8.579991817474365,0.0,, +1740481176.778283,8.599991798400879,5.001914059077752,1740481176.7782843,8.599991798400879,0.0,1740481176.7782862,8.599991798400879,0.0,1740481176.7782884,8.599991798400879,7.001914059077752,1740481176.778289,8.599991798400879,0.0,1740481176.7782905,8.599991798400879,0.0,1740481176.7782915,8.599991798400879,0.0,1740481176.7782924,8.599991798400879,0.0,1740481176.7782936,8.599991798400879,0.0,1740481176.7782946,8.599991798400879,-2.0,1740481176.7782953,8.599991798400879,-2.0,1740481176.7782962,8.599991798400879,0.0,1740481176.7782974,8.599991798400879,0.0,, +1740481176.7982366,8.619991779327393,5.001914059077752,1740481176.7982383,8.619991779327393,0.0,1740481176.79824,8.619991779327393,0.0,1740481176.798242,8.619991779327393,7.001914059077752,1740481176.798243,8.619991779327393,0.0,1740481176.7982442,8.619991779327393,0.0,1740481176.7982457,8.619991779327393,0.0,1740481176.7982466,8.619991779327393,0.0,1740481176.7982476,8.619991779327393,0.0,1740481176.7982488,8.619991779327393,-2.0,1740481176.7982495,8.619991779327393,-2.0,1740481176.7982507,8.619991779327393,0.0,1740481176.7982519,8.619991779327393,0.0,, +1740481176.8189254,8.639991760253906,5.001914059077752,1740481176.8189266,8.639991760253906,0.0,1740481176.8189287,8.639991760253906,0.0,1740481176.8189304,8.639991760253906,7.001914059077752,1740481176.8189313,8.639991760253906,0.0,1740481176.8189328,8.639991760253906,0.0,1740481176.8189335,8.639991760253906,0.0,1740481176.8189347,8.639991760253906,0.0,1740481176.8189359,8.639991760253906,0.0,1740481176.8189368,8.639991760253906,-2.0,1740481176.8189375,8.639991760253906,-2.0,1740481176.8189387,8.639991760253906,0.0,1740481176.8189397,8.639991760253906,0.0,, +1740481176.8391473,8.65999174118042,5.001914059077752,1740481176.8391485,8.65999174118042,0.0,1740481176.8391507,8.65999174118042,0.0,1740481176.8391526,8.65999174118042,7.001914059077752,1740481176.8391533,8.65999174118042,0.0,1740481176.8391547,8.65999174118042,0.0,1740481176.8391557,8.65999174118042,0.0,1740481176.8391566,8.65999174118042,0.0,1740481176.8391578,8.65999174118042,0.0,1740481176.8391588,8.65999174118042,-2.0,1740481176.8391597,8.65999174118042,-2.0,1740481176.8391612,8.65999174118042,0.0,1740481176.8391619,8.65999174118042,0.0,, +1740481176.8589845,8.679991722106934,5.001914059077752,1740481176.858986,8.679991722106934,0.0,1740481176.858988,8.679991722106934,0.0,1740481176.8589904,8.679991722106934,7.001914059077752,1740481176.8589914,8.679991722106934,0.0,1740481176.8589926,8.679991722106934,0.0,1740481176.8589938,8.679991722106934,0.0,1740481176.8589947,8.679991722106934,0.0,1740481176.8589957,8.679991722106934,0.0,1740481176.8589966,8.679991722106934,-2.0,1740481176.8589978,8.679991722106934,-2.0,1740481176.8589985,8.679991722106934,0.0,1740481176.8589995,8.679991722106934,0.0,, +1740481176.8795247,8.699991703033447,5.001914059077752,1740481176.8795261,8.699991703033447,0.0,1740481176.8795285,8.699991703033447,0.0,1740481176.8795307,8.699991703033447,7.001914059077752,1740481176.8795323,8.699991703033447,0.0,1740481176.8795354,8.699991703033447,0.0,1740481176.8795369,8.699991703033447,0.0,1740481176.8795376,8.699991703033447,0.0,1740481176.8795393,8.699991703033447,0.0,1740481176.8795402,8.699991703033447,-2.0,1740481176.8795412,8.699991703033447,-2.0,1740481176.8795424,8.699991703033447,0.0,1740481176.8795433,8.699991703033447,0.0,, +1740481176.8975554,8.719991683959961,5.001914059077752,1740481176.897557,8.719991683959961,0.0,1740481176.897559,8.719991683959961,0.0,1740481176.8975608,8.719991683959961,7.001914059077752,1740481176.8975618,8.719991683959961,0.0,1740481176.8975632,8.719991683959961,0.0,1740481176.8975642,8.719991683959961,0.0,1740481176.897565,8.719991683959961,0.0,1740481176.8975663,8.719991683959961,0.0,1740481176.897567,8.719991683959961,-2.0,1740481176.897568,8.719991683959961,-2.0,1740481176.897569,8.719991683959961,0.0,1740481176.89757,8.719991683959961,0.0,, +1740481176.9193811,8.739991664886475,5.001914059077752,1740481176.9193828,8.739991664886475,0.0,1740481176.9193847,8.739991664886475,0.0,1740481176.9194171,8.739991664886475,7.001914059077752,1740481176.9194183,8.739991664886475,0.0,1740481176.9194207,8.739991664886475,0.0,1740481176.9194217,8.739991664886475,0.0,1740481176.9194226,8.739991664886475,0.0,1740481176.9194238,8.739991664886475,0.0,1740481176.9194248,8.739991664886475,-2.0,1740481176.9194255,8.739991664886475,-2.0,1740481176.9194264,8.739991664886475,0.0,1740481176.9194274,8.739991664886475,0.0,, +1740481176.938103,8.759991645812988,5.001914059077752,1740481176.9381046,8.759991645812988,0.0,1740481176.9381063,8.759991645812988,0.0,1740481176.9381084,8.759991645812988,7.001914059077752,1740481176.9381094,8.759991645812988,0.0,1740481176.9381108,8.759991645812988,0.0,1740481176.9381118,8.759991645812988,0.0,1740481176.9381125,8.759991645812988,0.0,1740481176.9381137,8.759991645812988,0.0,1740481176.9381146,8.759991645812988,-2.0,1740481176.9381158,8.759991645812988,-2.0,1740481176.9381168,8.759991645812988,0.0,1740481176.9381177,8.759991645812988,0.0,, +1740481176.9600208,8.779991626739502,5.001914059077752,1740481176.9600239,8.779991626739502,0.0,1740481176.9600277,8.779991626739502,0.0,1740481176.960031,8.779991626739502,7.001914059077752,1740481176.9600325,8.779991626739502,0.0,1740481176.9600346,8.779991626739502,0.0,1740481176.9600358,8.779991626739502,0.0,1740481176.9600375,8.779991626739502,0.0,1740481176.960039,8.779991626739502,0.0,1740481176.9600408,8.779991626739502,-2.0,1740481176.9600418,8.779991626739502,-2.0,1740481176.960043,8.779991626739502,0.0,1740481176.9600444,8.779991626739502,0.0,, +1740481176.9777925,8.799991607666016,5.001914059077752,1740481176.977794,8.799991607666016,0.0,1740481176.977796,8.799991607666016,0.0,1740481176.9777982,8.799991607666016,7.001914059077752,1740481176.9777992,8.799991607666016,0.0,1740481176.9778004,8.799991607666016,0.0,1740481176.9778016,8.799991607666016,0.0,1740481176.9778025,8.799991607666016,0.0,1740481176.9778035,8.799991607666016,0.0,1740481176.9778047,8.799991607666016,-2.0,1740481176.9778059,8.799991607666016,-2.0,1740481176.9778066,8.799991607666016,0.0,1740481176.9778075,8.799991607666016,0.0,, +1740481176.9978952,8.81999158859253,5.001914059077752,1740481176.9978971,8.81999158859253,0.0,1740481176.9979005,8.81999158859253,0.0,1740481176.9979026,8.81999158859253,7.001914059077752,1740481176.9979038,8.81999158859253,0.0,1740481176.9979048,8.81999158859253,0.0,1740481176.997906,8.81999158859253,0.0,1740481176.997907,8.81999158859253,0.0,1740481176.9979079,8.81999158859253,0.0,1740481176.997909,8.81999158859253,-2.0,1740481176.9979098,8.81999158859253,-2.0,1740481176.9979107,8.81999158859253,0.0,1740481176.9979117,8.81999158859253,0.0,, +1740481177.0184054,8.839991569519043,5.001914059077752,1740481177.0184069,8.839991569519043,0.0,1740481177.0184088,8.839991569519043,0.0,1740481177.0184107,8.839991569519043,7.001914059077752,1740481177.0184116,8.839991569519043,0.0,1740481177.0184128,8.839991569519043,0.0,1740481177.0184138,8.839991569519043,0.0,1740481177.0184147,8.839991569519043,0.0,1740481177.018416,8.839991569519043,0.0,1740481177.018417,8.839991569519043,-2.0,1740481177.0184176,8.839991569519043,-2.0,1740481177.0184186,8.839991569519043,0.0,1740481177.0184195,8.839991569519043,0.0,, +1740481177.038158,8.859991550445557,5.001914059077752,1740481177.0381594,8.859991550445557,0.0,1740481177.0381615,8.859991550445557,0.0,1740481177.0381634,8.859991550445557,7.001914059077752,1740481177.0381644,8.859991550445557,0.0,1740481177.0381658,8.859991550445557,0.0,1740481177.0381668,8.859991550445557,0.0,1740481177.0381677,8.859991550445557,0.0,1740481177.0381691,8.859991550445557,0.0,1740481177.0381699,8.859991550445557,-2.0,1740481177.0381708,8.859991550445557,-2.0,1740481177.0381722,8.859991550445557,0.0,1740481177.038173,8.859991550445557,0.0,, +1740481177.05876,8.87999153137207,5.001914059077752,1740481177.0587614,8.87999153137207,0.0,1740481177.0587637,8.87999153137207,0.0,1740481177.058766,8.87999153137207,7.001914059077752,1740481177.0587668,8.87999153137207,0.0,1740481177.0587683,8.87999153137207,0.0,1740481177.0587695,8.87999153137207,0.0,1740481177.0587704,8.87999153137207,0.0,1740481177.0587716,8.87999153137207,0.0,1740481177.0587728,8.87999153137207,-2.0,1740481177.0587738,8.87999153137207,-2.0,1740481177.058775,8.87999153137207,0.0,1740481177.0587761,8.87999153137207,0.0,, +1740481177.0777314,8.899991512298584,5.001914059077752,1740481177.0777326,8.899991512298584,0.0,1740481177.077735,8.899991512298584,0.0,1740481177.0777366,8.899991512298584,7.001914059077752,1740481177.0777378,8.899991512298584,0.0,1740481177.0777392,8.899991512298584,0.0,1740481177.0777402,8.899991512298584,0.0,1740481177.0777411,8.899991512298584,0.0,1740481177.0777423,8.899991512298584,0.0,1740481177.0777433,8.899991512298584,-2.0,1740481177.0777442,8.899991512298584,-2.0,1740481177.0777452,8.899991512298584,0.0,1740481177.077746,8.899991512298584,0.0,, +1740481177.0974758,8.919991493225098,5.001914059077752,1740481177.0974774,8.919991493225098,0.0,1740481177.0974793,8.919991493225098,0.0,1740481177.0974817,8.919991493225098,7.001914059077752,1740481177.0974827,8.919991493225098,0.0,1740481177.0974839,8.919991493225098,0.0,1740481177.0974848,8.919991493225098,0.0,1740481177.0974858,8.919991493225098,0.0,1740481177.0974872,8.919991493225098,0.0,1740481177.097488,8.919991493225098,-2.0,1740481177.0974889,8.919991493225098,-2.0,1740481177.0974898,8.919991493225098,0.0,1740481177.097491,8.919991493225098,0.0,, +1740481177.1187427,8.939991474151611,5.001914059077752,1740481177.1187441,8.939991474151611,0.0,1740481177.118746,8.939991474151611,0.0,1740481177.1187482,8.939991474151611,7.001914059077752,1740481177.118749,8.939991474151611,0.0,1740481177.11875,8.939991474151611,0.0,1740481177.1187513,8.939991474151611,0.0,1740481177.1187522,8.939991474151611,0.0,1740481177.1187532,8.939991474151611,0.0,1740481177.1187544,8.939991474151611,-2.0,1740481177.118755,8.939991474151611,-2.0,1740481177.118756,8.939991474151611,0.0,1740481177.118757,8.939991474151611,0.0,, +1740481177.1378658,8.959991455078125,5.001914059077752,1740481177.1378672,8.959991455078125,0.0,1740481177.1378691,8.959991455078125,0.0,1740481177.137871,8.959991455078125,7.001914059077752,1740481177.137872,8.959991455078125,0.0,1740481177.1378734,8.959991455078125,0.0,1740481177.1378744,8.959991455078125,0.0,1740481177.1378753,8.959991455078125,0.0,1740481177.1378767,8.959991455078125,0.0,1740481177.1378775,8.959991455078125,-2.0,1740481177.1378784,8.959991455078125,-2.0,1740481177.1378796,8.959991455078125,0.0,1740481177.1378803,8.959991455078125,0.0,, +1740481177.1576254,8.979991436004639,5.001914059077752,1740481177.157627,8.979991436004639,0.0,1740481177.157629,8.979991436004639,0.0,1740481177.1576312,8.979991436004639,7.001914059077752,1740481177.157632,8.979991436004639,0.0,1740481177.1576335,8.979991436004639,0.0,1740481177.1576343,8.979991436004639,0.0,1740481177.1576352,8.979991436004639,0.0,1740481177.1576364,8.979991436004639,0.0,1740481177.1576374,8.979991436004639,-2.0,1740481177.157638,8.979991436004639,-2.0,1740481177.1576393,8.979991436004639,0.0,1740481177.1576407,8.979991436004639,0.0,, +1740481177.178174,8.999991416931152,5.001914059077752,1740481177.1781752,8.999991416931152,0.0,1740481177.1781776,8.999991416931152,0.0,1740481177.1781795,8.999991416931152,7.001914059077752,1740481177.1781807,8.999991416931152,0.0,1740481177.178182,8.999991416931152,0.0,1740481177.1781828,8.999991416931152,0.0,1740481177.178184,8.999991416931152,0.0,1740481177.1781852,8.999991416931152,0.0,1740481177.178186,8.999991416931152,-2.0,1740481177.178187,8.999991416931152,-2.0,1740481177.178188,8.999991416931152,0.0,1740481177.178189,8.999991416931152,0.0,, +1740481177.198207,9.019991397857666,5.001914059077752,1740481177.1982086,9.019991397857666,0.0,1740481177.1982105,9.019991397857666,0.0,1740481177.1982126,9.019991397857666,7.001914059077752,1740481177.1982136,9.019991397857666,0.0,1740481177.198215,9.019991397857666,0.0,1740481177.1982162,9.019991397857666,0.0,1740481177.1982172,9.019991397857666,0.0,1740481177.1982183,9.019991397857666,0.0,1740481177.1982193,9.019991397857666,-2.0,1740481177.1982203,9.019991397857666,-2.0,1740481177.198221,9.019991397857666,0.0,1740481177.1982222,9.019991397857666,0.0,, +1740481177.2237139,9.03999137878418,5.001914059077752,1740481177.223715,9.03999137878418,0.0,1740481177.2237172,9.03999137878418,0.0,1740481177.2237191,9.03999137878418,7.001914059077752,1740481177.2237198,9.03999137878418,0.0,1740481177.2237213,9.03999137878418,0.0,1740481177.2237222,9.03999137878418,0.0,1740481177.223723,9.03999137878418,0.0,1740481177.2237244,9.03999137878418,0.0,1740481177.223725,9.03999137878418,-2.0,1740481177.2237258,9.03999137878418,-2.0,1740481177.2237267,9.03999137878418,0.0,1740481177.2237277,9.03999137878418,0.0,, +1740481177.2378802,9.059991359710693,5.001914059077752,1740481177.2378817,9.059991359710693,0.0,1740481177.2378836,9.059991359710693,0.0,1740481177.2378857,9.059991359710693,7.001914059077752,1740481177.2378867,9.059991359710693,0.0,1740481177.2378879,9.059991359710693,0.0,1740481177.2378888,9.059991359710693,0.0,1740481177.2378898,9.059991359710693,0.0,1740481177.2378907,9.059991359710693,0.0,1740481177.2378917,9.059991359710693,-2.0,1740481177.2378924,9.059991359710693,-2.0,1740481177.2378933,9.059991359710693,0.0,1740481177.237894,9.059991359710693,0.0,, +1740481177.259997,9.079991340637207,5.001914059077752,1740481177.2599983,9.079991340637207,0.0,1740481177.2600002,9.079991340637207,0.0,1740481177.2600026,9.079991340637207,7.001914059077752,1740481177.2600033,9.079991340637207,0.0,1740481177.2600048,9.079991340637207,0.0,1740481177.260006,9.079991340637207,0.0,1740481177.260007,9.079991340637207,0.0,1740481177.260008,9.079991340637207,0.0,1740481177.2600095,9.079991340637207,-2.0,1740481177.2600105,9.079991340637207,-2.0,1740481177.2600117,9.079991340637207,0.0,1740481177.260013,9.079991340637207,0.0,, +1740481177.278161,9.09999132156372,5.001914059077752,1740481177.2781627,9.09999132156372,0.0,1740481177.2781653,9.09999132156372,0.0,1740481177.2781677,9.09999132156372,7.001914059077752,1740481177.2781692,9.09999132156372,0.0,1740481177.2781706,9.09999132156372,0.0,1740481177.278172,9.09999132156372,0.0,1740481177.2781732,9.09999132156372,0.0,1740481177.2781749,9.09999132156372,0.0,1740481177.2781763,9.09999132156372,-2.0,1740481177.2781773,9.09999132156372,-2.0,1740481177.2781785,9.09999132156372,0.0,1740481177.2781796,9.09999132156372,0.0,, +1740481177.300316,9.119991302490234,5.001914059077752,1740481177.300318,9.119991302490234,0.0,1740481177.3003201,9.119991302490234,0.0,1740481177.3003225,9.119991302490234,7.001914059077752,1740481177.3003235,9.119991302490234,0.0,1740481177.3003252,9.119991302490234,0.0,1740481177.300326,9.119991302490234,0.0,1740481177.300327,9.119991302490234,0.0,1740481177.3003283,9.119991302490234,0.0,1740481177.3003292,9.119991302490234,-2.0,1740481177.3003302,9.119991302490234,-2.0,1740481177.3003314,9.119991302490234,0.0,1740481177.3003325,9.119991302490234,0.0,, +1740481177.3187237,9.139991283416748,5.001914059077752,1740481177.318725,9.139991283416748,0.0,1740481177.318727,9.139991283416748,0.0,1740481177.3187435,9.139991283416748,7.001914059077752,1740481177.318745,9.139991283416748,0.0,1740481177.318746,9.139991283416748,0.0,1740481177.318747,9.139991283416748,0.0,1740481177.3187568,9.139991283416748,0.0,1740481177.3187592,9.139991283416748,0.0,1740481177.3187602,9.139991283416748,-2.0,1740481177.318761,9.139991283416748,-2.0,1740481177.318762,9.139991283416748,0.0,1740481177.3187628,9.139991283416748,0.0,, +1740481177.3380487,9.159991264343262,5.001914059077752,1740481177.3380504,9.159991264343262,0.0,1740481177.338052,9.159991264343262,0.0,1740481177.3380542,9.159991264343262,7.001914059077752,1740481177.3380551,9.159991264343262,0.0,1740481177.3380566,9.159991264343262,0.0,1740481177.3380575,9.159991264343262,0.0,1740481177.3380585,9.159991264343262,0.0,1740481177.3380594,9.159991264343262,0.0,1740481177.3380606,9.159991264343262,-2.0,1740481177.3380616,9.159991264343262,-2.0,1740481177.3380625,9.159991264343262,0.0,1740481177.3380637,9.159991264343262,0.0,, +1740481177.3575914,9.179991245269775,5.001914059077752,1740481177.3575928,9.179991245269775,0.0,1740481177.357595,9.179991245269775,0.0,1740481177.3575969,9.179991245269775,7.001914059077752,1740481177.3575976,9.179991245269775,0.0,1740481177.3575993,9.179991245269775,0.0,1740481177.3576002,9.179991245269775,0.0,1740481177.357601,9.179991245269775,0.0,1740481177.3576021,9.179991245269775,0.0,1740481177.3576028,9.179991245269775,-2.0,1740481177.3576038,9.179991245269775,-2.0,1740481177.3576045,9.179991245269775,0.0,1740481177.3576057,9.179991245269775,0.0,, +1740481177.3792806,9.199991226196289,5.001914059077752,1740481177.3792837,9.199991226196289,0.0,1740481177.3793705,9.199991226196289,0.0,1740481177.3793757,9.199991226196289,7.001914059077752,1740481177.3793776,9.199991226196289,0.0,1740481177.3793805,9.199991226196289,0.0,1740481177.3793821,9.199991226196289,0.0,1740481177.3794043,9.199991226196289,0.0,1740481177.379407,9.199991226196289,0.0,1740481177.3794096,9.199991226196289,-2.0,1740481177.3794115,9.199991226196289,-2.0,1740481177.3794136,9.199991226196289,0.0,1740481177.379415,9.199991226196289,0.0,, +1740481177.3978448,9.219991207122803,5.001914059077752,1740481177.397846,9.219991207122803,0.0,1740481177.3978484,9.219991207122803,0.0,1740481177.3978503,9.219991207122803,7.001914059077752,1740481177.3978515,9.219991207122803,0.0,1740481177.3978524,9.219991207122803,0.0,1740481177.3978534,9.219991207122803,0.0,1740481177.3978546,9.219991207122803,0.0,1740481177.3978555,9.219991207122803,0.0,1740481177.3978565,9.219991207122803,-2.0,1740481177.3978574,9.219991207122803,-2.0,1740481177.3978584,9.219991207122803,0.0,1740481177.397859,9.219991207122803,0.0,, +1740481177.4190118,9.239991188049316,5.001914059077752,1740481177.4190133,9.239991188049316,0.0,1740481177.4190154,9.239991188049316,0.0,1740481177.4190173,9.239991188049316,7.001914059077752,1740481177.4190183,9.239991188049316,0.0,1740481177.4190192,9.239991188049316,0.0,1740481177.4190202,9.239991188049316,0.0,1740481177.4190214,9.239991188049316,0.0,1740481177.4190223,9.239991188049316,0.0,1740481177.419023,9.239991188049316,-2.0,1740481177.419024,9.239991188049316,-2.0,1740481177.419025,9.239991188049316,0.0,1740481177.4190257,9.239991188049316,0.0,, +1740481177.4387457,9.25999116897583,5.001914059077752,1740481177.4387476,9.25999116897583,0.0,1740481177.4387498,9.25999116897583,0.0,1740481177.4387522,9.25999116897583,7.001914059077752,1740481177.438754,9.25999116897583,0.0,1740481177.438756,9.25999116897583,0.0,1740481177.438758,9.25999116897583,0.0,1740481177.4387596,9.25999116897583,0.0,1740481177.4387617,9.25999116897583,0.0,1740481177.4387634,9.25999116897583,-2.0,1740481177.4387648,9.25999116897583,-2.0,1740481177.438766,9.25999116897583,0.0,1740481177.4387677,9.25999116897583,0.0,, +1740481177.4577658,9.279991149902344,5.001914059077752,1740481177.4577675,9.279991149902344,0.0,1740481177.4578965,9.279991149902344,0.0,1740481177.4579003,9.279991149902344,7.001914059077752,1740481177.4579012,9.279991149902344,0.0,1740481177.4579027,9.279991149902344,0.0,1740481177.4579039,9.279991149902344,0.0,1740481177.4579046,9.279991149902344,0.0,1740481177.457906,9.279991149902344,0.0,1740481177.457907,9.279991149902344,-2.0,1740481177.4579077,9.279991149902344,-2.0,1740481177.4579086,9.279991149902344,0.0,1740481177.4579096,9.279991149902344,0.0,, +1740481177.477983,9.299991130828857,5.001914059077752,1740481177.4779844,9.299991130828857,0.0,1740481177.4779866,9.299991130828857,0.0,1740481177.4779887,9.299991130828857,7.001914059077752,1740481177.4779897,9.299991130828857,0.0,1740481177.4779909,9.299991130828857,0.0,1740481177.4779918,9.299991130828857,0.0,1740481177.477993,9.299991130828857,0.0,1740481177.4779942,9.299991130828857,0.0,1740481177.4779952,9.299991130828857,-2.0,1740481177.477996,9.299991130828857,-2.0,1740481177.477997,9.299991130828857,0.0,1740481177.477998,9.299991130828857,0.0,, +1740481177.4974856,9.319991111755371,5.001914059077752,1740481177.4974875,9.319991111755371,0.0,1740481177.4974906,9.319991111755371,0.0,1740481177.4974928,9.319991111755371,7.001914059077752,1740481177.4974937,9.319991111755371,0.0,1740481177.4974957,9.319991111755371,0.0,1740481177.4974966,9.319991111755371,0.0,1740481177.4974973,9.319991111755371,0.0,1740481177.4974985,9.319991111755371,0.0,1740481177.4974995,9.319991111755371,-2.0,1740481177.4975004,9.319991111755371,-2.0,1740481177.4975011,9.319991111755371,0.0,1740481177.4975023,9.319991111755371,0.0,, +1740481177.5260217,9.339991092681885,5.001914059077752,1740481177.526023,9.339991092681885,0.0,1740481177.526025,9.339991092681885,0.0,1740481177.526027,9.339991092681885,7.001914059077752,1740481177.5260277,9.339991092681885,0.0,1740481177.526029,9.339991092681885,0.0,1740481177.52603,9.339991092681885,0.0,1740481177.526031,9.339991092681885,0.0,1740481177.5260324,9.339991092681885,0.0,1740481177.5260332,9.339991092681885,-2.0,1740481177.526034,9.339991092681885,-2.0,1740481177.5260348,9.339991092681885,0.0,1740481177.526036,9.339991092681885,0.0,, +1740481177.5383494,9.359991073608398,5.001914059077752,1740481177.5383515,9.359991073608398,0.0,1740481177.5383558,9.359991073608398,0.0,1740481177.5383587,9.359991073608398,7.001914059077752,1740481177.5383604,9.359991073608398,0.0,1740481177.5383623,9.359991073608398,0.0,1740481177.5383644,9.359991073608398,0.0,1740481177.5383658,9.359991073608398,0.0,1740481177.5383677,9.359991073608398,0.0,1740481177.5383692,9.359991073608398,-2.0,1740481177.5383708,9.359991073608398,-2.0,1740481177.5383723,9.359991073608398,0.0,1740481177.538374,9.359991073608398,0.0,, +1740481177.5580654,9.379991054534912,5.001914059077752,1740481177.5580668,9.379991054534912,0.0,1740481177.5580688,9.379991054534912,0.0,1740481177.558071,9.379991054534912,7.001914059077752,1740481177.5580719,9.379991054534912,0.0,1740481177.558073,9.379991054534912,0.0,1740481177.558074,9.379991054534912,0.0,1740481177.558075,9.379991054534912,0.0,1740481177.5580761,9.379991054534912,0.0,1740481177.5580769,9.379991054534912,-2.0,1740481177.5580783,9.379991054534912,-2.0,1740481177.5580792,9.379991054534912,0.0,1740481177.55808,9.379991054534912,0.0,, +1740481177.577969,9.399991035461426,5.001914059077752,1740481177.5779707,9.399991035461426,0.0,1740481177.577973,9.399991035461426,0.0,1740481177.5779748,9.399991035461426,7.001914059077752,1740481177.5779757,9.399991035461426,0.0,1740481177.5779772,9.399991035461426,0.0,1740481177.5779781,9.399991035461426,0.0,1740481177.5779788,9.399991035461426,0.0,1740481177.57798,9.399991035461426,0.0,1740481177.5779812,9.399991035461426,-2.0,1740481177.577982,9.399991035461426,-2.0,1740481177.577983,9.399991035461426,0.0,1740481177.5779839,9.399991035461426,0.0,, +1740481177.5995927,9.41999101638794,5.001914059077752,1740481177.5995939,9.41999101638794,0.0,1740481177.599596,9.41999101638794,0.0,1740481177.5995982,9.41999101638794,7.001914059077752,1740481177.599599,9.41999101638794,0.0,1740481177.5996,9.41999101638794,0.0,1740481177.5996013,9.41999101638794,0.0,1740481177.599602,9.41999101638794,0.0,1740481177.599603,9.41999101638794,0.0,1740481177.599604,9.41999101638794,-2.0,1740481177.5996048,9.41999101638794,-2.0,1740481177.5996058,9.41999101638794,0.0,1740481177.5996065,9.41999101638794,0.0,, +1740481177.6185117,9.439990997314453,5.001914059077752,1740481177.618513,9.439990997314453,0.0,1740481177.618515,9.439990997314453,0.0,1740481177.6185167,9.439990997314453,7.001914059077752,1740481177.6185179,9.439990997314453,0.0,1740481177.618519,9.439990997314453,0.0,1740481177.6185203,9.439990997314453,0.0,1740481177.6185215,9.439990997314453,0.0,1740481177.6185224,9.439990997314453,0.0,1740481177.6185231,9.439990997314453,-2.0,1740481177.618524,9.439990997314453,-2.0,1740481177.6185253,9.439990997314453,0.0,1740481177.618526,9.439990997314453,0.0,, +1740481177.6378763,9.459990978240967,5.001914059077752,1740481177.6378777,9.459990978240967,0.0,1740481177.6378798,9.459990978240967,0.0,1740481177.6378949,9.459990978240967,7.001914059077752,1740481177.6378958,9.459990978240967,0.0,1740481177.6378984,9.459990978240967,0.0,1740481177.6378996,9.459990978240967,0.0,1740481177.6379004,9.459990978240967,0.0,1740481177.6379015,9.459990978240967,0.0,1740481177.6379023,9.459990978240967,-2.0,1740481177.6379035,9.459990978240967,-2.0,1740481177.6379044,9.459990978240967,0.0,1740481177.6379051,9.459990978240967,0.0,, +1740481177.6578524,9.47999095916748,5.001914059077752,1740481177.6578538,9.47999095916748,0.0,1740481177.657856,9.47999095916748,0.0,1740481177.6578581,9.47999095916748,7.001914059077752,1740481177.6578588,9.47999095916748,0.0,1740481177.6578603,9.47999095916748,0.0,1740481177.6578612,9.47999095916748,0.0,1740481177.6578622,9.47999095916748,0.0,1740481177.6578634,9.47999095916748,0.0,1740481177.657864,9.47999095916748,-2.0,1740481177.6578653,9.47999095916748,-2.0,1740481177.6578662,9.47999095916748,0.0,1740481177.6578672,9.47999095916748,0.0,, +1740481177.6784797,9.499990940093994,5.001914059077752,1740481177.6784909,9.499990940093994,0.0,1740481177.678497,9.499990940093994,0.0,1740481177.6785028,9.499990940093994,7.001914059077752,1740481177.6785054,9.499990940093994,0.0,1740481177.6785083,9.499990940093994,0.0,1740481177.6785097,9.499990940093994,0.0,1740481177.6785152,9.499990940093994,0.0,1740481177.6785216,9.499990940093994,0.0,1740481177.6785264,9.499990940093994,-2.0,1740481177.678529,9.499990940093994,-2.0,1740481177.6785333,9.499990940093994,0.0,1740481177.678538,9.499990940093994,0.0,, +1740481177.6980753,9.519990921020508,5.001914059077752,1740481177.6980767,9.519990921020508,0.0,1740481177.6980786,9.519990921020508,0.0,1740481177.698081,9.519990921020508,7.001914059077752,1740481177.6980817,9.519990921020508,0.0,1740481177.6980832,9.519990921020508,0.0,1740481177.6980844,9.519990921020508,0.0,1740481177.6980853,9.519990921020508,0.0,1740481177.6980867,9.519990921020508,0.0,1740481177.6980877,9.519990921020508,-2.0,1740481177.6980886,9.519990921020508,-2.0,1740481177.6980898,9.519990921020508,0.0,1740481177.6980908,9.519990921020508,0.0,, +1740481177.718393,9.539990901947021,5.001914059077752,1740481177.7183943,9.539990901947021,0.0,1740481177.7183964,9.539990901947021,0.0,1740481177.718398,9.539990901947021,7.001914059077752,1740481177.7183993,9.539990901947021,0.0,1740481177.7184005,9.539990901947021,0.0,1740481177.7184012,9.539990901947021,0.0,1740481177.7184024,9.539990901947021,0.0,1740481177.7184033,9.539990901947021,0.0,1740481177.7184043,9.539990901947021,-2.0,1740481177.718405,9.539990901947021,-2.0,1740481177.718406,9.539990901947021,0.0,1740481177.718407,9.539990901947021,0.0,, +1740481177.7382565,9.559990882873535,5.001914059077752,1740481177.738258,9.559990882873535,0.0,1740481177.7382603,9.559990882873535,0.0,1740481177.7382622,9.559990882873535,7.001914059077752,1740481177.7382634,9.559990882873535,0.0,1740481177.738265,9.559990882873535,0.0,1740481177.7382662,9.559990882873535,0.0,1740481177.7382672,9.559990882873535,0.0,1740481177.7382681,9.559990882873535,0.0,1740481177.7382693,9.559990882873535,-2.0,1740481177.7382708,9.559990882873535,-2.0,1740481177.7382717,9.559990882873535,0.0,1740481177.7382727,9.559990882873535,0.0,, +1740481177.7607455,9.579990863800049,5.001914059077752,1740481177.760747,9.579990863800049,0.0,1740481177.7607489,9.579990863800049,0.0,1740481177.7607508,9.579990863800049,7.001914059077752,1740481177.760752,9.579990863800049,0.0,1740481177.760753,9.579990863800049,0.0,1740481177.7607539,9.579990863800049,0.0,1740481177.760755,9.579990863800049,0.0,1740481177.760756,9.579990863800049,0.0,1740481177.760757,9.579990863800049,-2.0,1740481177.760758,9.579990863800049,-2.0,1740481177.7607589,9.579990863800049,0.0,1740481177.7607598,9.579990863800049,0.0,, +1740481177.7788272,9.599990844726562,5.001914059077752,1740481177.7788289,9.599990844726562,0.0,1740481177.7788308,9.599990844726562,0.0,1740481177.778833,9.599990844726562,7.001914059077752,1740481177.7788339,9.599990844726562,0.0,1740481177.7788355,9.599990844726562,0.0,1740481177.7788365,9.599990844726562,0.0,1740481177.7788374,9.599990844726562,0.0,1740481177.7788389,9.599990844726562,0.0,1740481177.7788403,9.599990844726562,-2.0,1740481177.778841,9.599990844726562,-2.0,1740481177.7788422,9.599990844726562,0.0,1740481177.778843,9.599990844726562,0.0,, +1740481177.7982247,9.619990825653076,5.001914059077752,1740481177.7982264,9.619990825653076,0.0,1740481177.798229,9.619990825653076,0.0,1740481177.7982316,9.619990825653076,7.001914059077752,1740481177.7982326,9.619990825653076,0.0,1740481177.7982337,9.619990825653076,0.0,1740481177.7982352,9.619990825653076,0.0,1740481177.7982361,9.619990825653076,0.0,1740481177.7982383,9.619990825653076,0.0,1740481177.7982392,9.619990825653076,-2.0,1740481177.7982407,9.619990825653076,-2.0,1740481177.7982419,9.619990825653076,0.0,1740481177.7982428,9.619990825653076,0.0,, +1740481177.8191936,9.63999080657959,5.001914059077752,1740481177.8191955,9.63999080657959,0.0,1740481177.8191974,9.63999080657959,0.0,1740481177.8191993,9.63999080657959,7.001914059077752,1740481177.8192003,9.63999080657959,0.0,1740481177.8192012,9.63999080657959,0.0,1740481177.8192024,9.63999080657959,0.0,1740481177.8192034,9.63999080657959,0.0,1740481177.8192043,9.63999080657959,0.0,1740481177.8192053,9.63999080657959,-2.0,1740481177.8192062,9.63999080657959,-2.0,1740481177.8192072,9.63999080657959,0.0,1740481177.819208,9.63999080657959,0.0,, +1740481177.8375235,9.659990787506104,5.001914059077752,1740481177.8375247,9.659990787506104,0.0,1740481177.8375268,9.659990787506104,0.0,1740481177.838243,9.659990787506104,7.001914059077752,1740481177.8382454,9.659990787506104,0.0,1740481177.8382504,9.659990787506104,0.0,1740481177.8382518,9.659990787506104,0.0,1740481177.838253,9.659990787506104,0.0,1740481177.8382547,9.659990787506104,0.0,1740481177.8382561,9.659990787506104,-2.0,1740481177.838257,9.659990787506104,-2.0,1740481177.8382583,9.659990787506104,0.0,1740481177.8382592,9.659990787506104,0.0,, +1740481177.857534,9.679990768432617,5.001914059077752,1740481177.8575356,9.679990768432617,0.0,1740481177.8575542,9.679990768432617,0.0,1740481177.8575566,9.679990768432617,7.001914059077752,1740481177.8575573,9.679990768432617,0.0,1740481177.8575585,9.679990768432617,0.0,1740481177.8575594,9.679990768432617,0.0,1740481177.8575606,9.679990768432617,0.0,1740481177.8575618,9.679990768432617,0.0,1740481177.8575814,9.679990768432617,-2.0,1740481177.857582,9.679990768432617,-2.0,1740481177.857583,9.679990768432617,0.0,1740481177.8575838,9.679990768432617,0.0,, +1740481177.8779,9.69999074935913,5.001914059077752,1740481177.8779018,9.69999074935913,0.0,1740481177.877904,9.69999074935913,0.0,1740481177.8779058,9.69999074935913,7.001914059077752,1740481177.877907,9.69999074935913,0.0,1740481177.8779082,9.69999074935913,0.0,1740481177.8779092,9.69999074935913,0.0,1740481177.8779104,9.69999074935913,0.0,1740481177.8779113,9.69999074935913,0.0,1740481177.8779123,9.69999074935913,-2.0,1740481177.877913,9.69999074935913,-2.0,1740481177.8779142,9.69999074935913,0.0,1740481177.877915,9.69999074935913,0.0,, +1740481177.8975158,9.719990730285645,5.001914059077752,1740481177.8975172,9.719990730285645,0.0,1740481177.8975194,9.719990730285645,0.0,1740481177.8975213,9.719990730285645,7.001914059077752,1740481177.8975222,9.719990730285645,0.0,1740481177.8975234,9.719990730285645,0.0,1740481177.8975246,9.719990730285645,0.0,1740481177.8975255,9.719990730285645,0.0,1740481177.8975265,9.719990730285645,0.0,1740481177.8975275,9.719990730285645,-2.0,1740481177.8975286,9.719990730285645,-2.0,1740481177.8975294,9.719990730285645,0.0,1740481177.8975303,9.719990730285645,0.0,, +1740481177.918662,9.739990711212158,5.001914059077752,1740481177.9186637,9.739990711212158,0.0,1740481177.9186656,9.739990711212158,0.0,1740481177.9186678,9.739990711212158,7.001914059077752,1740481177.9186687,9.739990711212158,0.0,1740481177.9186702,9.739990711212158,0.0,1740481177.9186711,9.739990711212158,0.0,1740481177.918672,9.739990711212158,0.0,1740481177.918673,9.739990711212158,0.0,1740481177.9186742,9.739990711212158,-2.0,1740481177.918675,9.739990711212158,-2.0,1740481177.918676,9.739990711212158,0.0,1740481177.9186769,9.739990711212158,0.0,, +1740481177.9378774,9.759990692138672,5.001914059077752,1740481177.937879,9.759990692138672,0.0,1740481177.937881,9.759990692138672,0.0,1740481177.9378834,9.759990692138672,7.001914059077752,1740481177.9378843,9.759990692138672,0.0,1740481177.9378858,9.759990692138672,0.0,1740481177.9378867,9.759990692138672,0.0,1740481177.9378877,9.759990692138672,0.0,1740481177.937889,9.759990692138672,0.0,1740481177.93789,9.759990692138672,-2.0,1740481177.937891,9.759990692138672,-2.0,1740481177.9378922,9.759990692138672,0.0,1740481177.9378932,9.759990692138672,0.0,, +1740481177.9587533,9.779990673065186,5.001914059077752,1740481177.9587548,9.779990673065186,0.0,1740481177.9587572,9.779990673065186,0.0,1740481177.958759,9.779990673065186,7.001914059077752,1740481177.9587603,9.779990673065186,0.0,1740481177.9587615,9.779990673065186,0.0,1740481177.9587624,9.779990673065186,0.0,1740481177.9587636,9.779990673065186,0.0,1740481177.9587646,9.779990673065186,0.0,1740481177.9587655,9.779990673065186,-2.0,1740481177.9587662,9.779990673065186,-2.0,1740481177.9587674,9.779990673065186,0.0,1740481177.9587681,9.779990673065186,0.0,, +1740481177.977649,9.7999906539917,5.001914059077752,1740481177.9776504,9.7999906539917,0.0,1740481177.9776525,9.7999906539917,0.0,1740481177.9776542,9.7999906539917,7.001914059077752,1740481177.9776554,9.7999906539917,0.0,1740481177.9776566,9.7999906539917,0.0,1740481177.9776573,9.7999906539917,0.0,1740481177.9776583,9.7999906539917,0.0,1740481177.9776595,9.7999906539917,0.0,1740481177.9776602,9.7999906539917,-2.0,1740481177.9776611,9.7999906539917,-2.0,1740481177.9776618,9.7999906539917,0.0,1740481177.9776628,9.7999906539917,0.0,, +1740481177.998132,9.819990634918213,5.001914059077752,1740481177.9981337,9.819990634918213,0.0,1740481177.998136,9.819990634918213,0.0,1740481177.9981384,9.819990634918213,7.001914059077752,1740481177.9981394,9.819990634918213,0.0,1740481177.9981408,9.819990634918213,0.0,1740481177.9981422,9.819990634918213,0.0,1740481177.9981432,9.819990634918213,0.0,1740481177.9981446,9.819990634918213,0.0,1740481177.9981458,9.819990634918213,-2.0,1740481177.9981465,9.819990634918213,-2.0,1740481177.9981475,9.819990634918213,0.0,1740481177.9981487,9.819990634918213,0.0,, +1740481178.0201411,9.839990615844727,5.001914059077752,1740481178.0201426,9.839990615844727,0.0,1740481178.0201452,9.839990615844727,0.0,1740481178.0201478,9.839990615844727,7.001914059077752,1740481178.0201488,9.839990615844727,0.0,1740481178.02015,9.839990615844727,0.0,1740481178.0201514,9.839990615844727,0.0,1740481178.0201523,9.839990615844727,0.0,1740481178.0201535,9.839990615844727,0.0,1740481178.0201547,9.839990615844727,-2.0,1740481178.0201557,9.839990615844727,-2.0,1740481178.0201566,9.839990615844727,0.0,1740481178.0201578,9.839990615844727,0.0,, +1740481178.0401335,9.85999059677124,5.001914059077752,1740481178.040135,9.85999059677124,0.0,1740481178.040137,9.85999059677124,0.0,1740481178.0401394,9.85999059677124,7.001914059077752,1740481178.0401404,9.85999059677124,0.0,1740481178.0401416,9.85999059677124,0.0,1740481178.0401425,9.85999059677124,0.0,1740481178.040144,9.85999059677124,0.0,1740481178.040145,9.85999059677124,0.0,1740481178.040146,9.85999059677124,-2.0,1740481178.0401473,9.85999059677124,-2.0,1740481178.040148,9.85999059677124,0.0,1740481178.040149,9.85999059677124,0.0,, +1740481178.0577662,9.879990577697754,5.001914059077752,1740481178.0577676,9.879990577697754,0.0,1740481178.05777,9.879990577697754,0.0,1740481178.057772,9.879990577697754,7.001914059077752,1740481178.057773,9.879990577697754,0.0,1740481178.0577743,9.879990577697754,0.0,1740481178.0577753,9.879990577697754,0.0,1740481178.0577767,9.879990577697754,0.0,1740481178.0577776,9.879990577697754,0.0,1740481178.0577786,9.879990577697754,-2.0,1740481178.0577796,9.879990577697754,-2.0,1740481178.0577805,9.879990577697754,0.0,1740481178.0577815,9.879990577697754,0.0,, +1740481178.079036,9.899990558624268,5.001914059077752,1740481178.0790374,9.899990558624268,0.0,1740481178.07904,9.899990558624268,0.0,1740481178.0790422,9.899990558624268,7.001914059077752,1740481178.0790434,9.899990558624268,0.0,1740481178.0790448,9.899990558624268,0.0,1740481178.0790462,9.899990558624268,0.0,1740481178.0790474,9.899990558624268,0.0,1740481178.0790486,9.899990558624268,0.0,1740481178.07905,9.899990558624268,-2.0,1740481178.079051,9.899990558624268,-2.0,1740481178.0790522,9.899990558624268,0.0,1740481178.0790536,9.899990558624268,0.0,, +1740481178.097971,9.919990539550781,5.001914059077752,1740481178.0979724,9.919990539550781,0.0,1740481178.0979745,9.919990539550781,0.0,1740481178.0979762,9.919990539550781,7.001914059077752,1740481178.0979774,9.919990539550781,0.0,1740481178.0979786,9.919990539550781,0.0,1740481178.09798,9.919990539550781,0.0,1740481178.097981,9.919990539550781,0.0,1740481178.097982,9.919990539550781,0.0,1740481178.0979831,9.919990539550781,-2.0,1740481178.0979843,9.919990539550781,-2.0,1740481178.097985,9.919990539550781,0.0,1740481178.0979857,9.919990539550781,0.0,, +1740481178.1186078,9.939990520477295,5.001914059077752,1740481178.1186094,9.939990520477295,0.0,1740481178.1186116,9.939990520477295,0.0,1740481178.1186137,9.939990520477295,7.001914059077752,1740481178.1186147,9.939990520477295,0.0,1740481178.1186163,9.939990520477295,0.0,1740481178.1186173,9.939990520477295,0.0,1740481178.1186182,9.939990520477295,0.0,1740481178.1186197,9.939990520477295,0.0,1740481178.1186206,9.939990520477295,-2.0,1740481178.1186216,9.939990520477295,-2.0,1740481178.118623,9.939990520477295,0.0,1740481178.1186242,9.939990520477295,0.0,, +1740481178.1394978,9.959990501403809,5.001914059077752,1740481178.1394994,9.959990501403809,0.0,1740481178.139502,9.959990501403809,0.0,1740481178.1395047,9.959990501403809,7.001914059077752,1740481178.1395059,9.959990501403809,0.0,1740481178.1395075,9.959990501403809,0.0,1740481178.1395087,9.959990501403809,0.0,1740481178.13951,9.959990501403809,0.0,1740481178.1395113,9.959990501403809,0.0,1740481178.1395125,9.959990501403809,-2.0,1740481178.1395135,9.959990501403809,-2.0,1740481178.1395147,9.959990501403809,0.0,1740481178.1395159,9.959990501403809,0.0,, +1740481178.1589875,9.979990482330322,5.001914059077752,1740481178.1589894,9.979990482330322,0.0,1740481178.1589913,9.979990482330322,0.0,1740481178.1589935,9.979990482330322,7.001914059077752,1740481178.1589944,9.979990482330322,0.0,1740481178.158996,9.979990482330322,0.0,1740481178.1589973,9.979990482330322,0.0,1740481178.1589983,9.979990482330322,0.0,1740481178.1589992,9.979990482330322,0.0,1740481178.1590004,9.979990482330322,-2.0,1740481178.1590014,9.979990482330322,-2.0,1740481178.1590023,9.979990482330322,0.0,1740481178.159003,9.979990482330322,0.0,, +1740481178.17863,9.999990463256836,5.001914059077752,1740481178.1786323,9.999990463256836,0.0,1740481178.1786351,9.999990463256836,0.0,1740481178.1786375,9.999990463256836,7.001914059077752,1740481178.178639,9.999990463256836,0.0,1740481178.1786406,9.999990463256836,0.0,1740481178.1786416,9.999990463256836,0.0,1740481178.178643,9.999990463256836,0.0,1740481178.1786442,9.999990463256836,0.0,1740481178.1786456,9.999990463256836,-2.0,1740481178.1786466,9.999990463256836,-2.0,1740481178.1786478,9.999990463256836,0.0,1740481178.178649,9.999990463256836,0.0,, +1740481178.2023137,10.029990434646606,5.001914059077752,1740481178.2023156,10.029990434646606,0.0,1740481178.2023177,10.029990434646606,0.0,1740481178.20232,10.029990434646606,7.001914059077752,1740481178.202321,10.029990434646606,0.0,1740481178.2023227,10.029990434646606,0.0,1740481178.2023237,10.029990434646606,0.0,1740481178.2023246,10.029990434646606,0.0,1740481178.2023263,10.029990434646606,0.0,1740481178.2023273,10.029990434646606,-2.0,1740481178.2023282,10.029990434646606,-2.0,1740481178.2023294,10.029990434646606,0.0,1740481178.2023304,10.029990434646606,0.0,, +1740481178.2189968,10.039990425109863,5.001914059077752,1740481178.2189994,10.039990425109863,0.0,1740481178.2190032,10.039990425109863,0.0,1740481178.2190056,10.039990425109863,7.001914059077752,1740481178.219007,10.039990425109863,0.0,1740481178.2190084,10.039990425109863,0.0,1740481178.2190099,10.039990425109863,0.0,1740481178.219011,10.039990425109863,0.0,1740481178.2190123,10.039990425109863,0.0,1740481178.2190135,10.039990425109863,-2.0,1740481178.2190144,10.039990425109863,-2.0,1740481178.2190156,10.039990425109863,0.0,1740481178.2190168,10.039990425109863,0.0,, +1740481178.2380466,10.059990406036377,5.001914059077752,1740481178.2380486,10.059990406036377,0.0,1740481178.2380514,10.059990406036377,0.0,1740481178.2380538,10.059990406036377,7.001914059077752,1740481178.2380552,10.059990406036377,0.0,1740481178.2380567,10.059990406036377,0.0,1740481178.238058,10.059990406036377,0.0,1740481178.238059,10.059990406036377,0.0,1740481178.2380602,10.059990406036377,0.0,1740481178.238062,10.059990406036377,-2.0,1740481178.238063,10.059990406036377,-2.0,1740481178.238064,10.059990406036377,0.0,1740481178.2380652,10.059990406036377,0.0,, +1740481178.2579803,10.07999038696289,5.001914059077752,1740481178.2579823,10.07999038696289,0.0,1740481178.257985,10.07999038696289,0.0,1740481178.2579875,10.07999038696289,7.001914059077752,1740481178.2579887,10.07999038696289,0.0,1740481178.2579904,10.07999038696289,0.0,1740481178.2579913,10.07999038696289,0.0,1740481178.2579932,10.07999038696289,0.0,1740481178.2579944,10.07999038696289,0.0,1740481178.257996,10.07999038696289,-2.0,1740481178.257997,10.07999038696289,-2.0,1740481178.257998,10.07999038696289,0.0,1740481178.2579992,10.07999038696289,0.0,, +1740481178.2788377,10.099990367889404,5.001914059077752,1740481178.27884,10.099990367889404,0.0,1740481178.278844,10.099990367889404,0.0,1740481178.2788477,10.099990367889404,7.001914059077752,1740481178.2788503,10.099990367889404,0.0,1740481178.278853,10.099990367889404,0.0,1740481178.2788544,10.099990367889404,0.0,1740481178.2788565,10.099990367889404,0.0,1740481178.2788587,10.099990367889404,0.0,1740481178.2788608,10.099990367889404,-2.0,1740481178.2788622,10.099990367889404,-2.0,1740481178.2788644,10.099990367889404,0.0,1740481178.2788663,10.099990367889404,0.0,, +1740481178.2978802,10.119990348815918,5.001914059077752,1740481178.2978818,10.119990348815918,0.0,1740481178.2978847,10.119990348815918,0.0,1740481178.297887,10.119990348815918,7.001914059077752,1740481178.2978883,10.119990348815918,0.0,1740481178.2978897,10.119990348815918,0.0,1740481178.2978911,10.119990348815918,0.0,1740481178.297892,10.119990348815918,0.0,1740481178.2978935,10.119990348815918,0.0,1740481178.2978952,10.119990348815918,-2.0,1740481178.2978961,10.119990348815918,-2.0,1740481178.297897,10.119990348815918,0.0,1740481178.2978985,10.119990348815918,0.0,, +1740481178.318786,10.139990329742432,5.001914059077752,1740481178.318804,10.139990329742432,0.0,1740481178.3188083,10.139990329742432,0.0,1740481178.3188112,10.139990329742432,7.001914059077752,1740481178.3188121,10.139990329742432,0.0,1740481178.3188138,10.139990329742432,0.0,1740481178.318815,10.139990329742432,0.0,1740481178.318816,10.139990329742432,0.0,1740481178.3188174,10.139990329742432,0.0,1740481178.3188186,10.139990329742432,-2.0,1740481178.3188195,10.139990329742432,-2.0,1740481178.3188207,10.139990329742432,0.0,1740481178.3188221,10.139990329742432,0.0,, +1740481178.338471,10.159990310668945,5.001914059077752,1740481178.3384726,10.159990310668945,0.0,1740481178.3384755,10.159990310668945,0.0,1740481178.338478,10.159990310668945,7.001914059077752,1740481178.3384793,10.159990310668945,0.0,1740481178.3384812,10.159990310668945,0.0,1740481178.3384824,10.159990310668945,0.0,1740481178.3384838,10.159990310668945,0.0,1740481178.3384852,10.159990310668945,0.0,1740481178.3384871,10.159990310668945,-2.0,1740481178.3384883,10.159990310668945,-2.0,1740481178.3384893,10.159990310668945,0.0,1740481178.3384907,10.159990310668945,0.0,, +1740481178.3606756,10.179990291595459,5.001914059077752,1740481178.360681,10.179990291595459,0.0,1740481178.3606868,10.179990291595459,0.0,1740481178.36069,10.179990291595459,7.001914059077752,1740481178.3606915,10.179990291595459,0.0,1740481178.3606935,10.179990291595459,0.0,1740481178.3606951,10.179990291595459,0.0,1740481178.3606968,10.179990291595459,0.0,1740481178.3606994,10.179990291595459,0.0,1740481178.3607008,10.179990291595459,-2.0,1740481178.3607028,10.179990291595459,-2.0,1740481178.3607047,10.179990291595459,0.0,1740481178.3607066,10.179990291595459,0.0,, +1740481178.3776069,10.199990272521973,5.001914059077752,1740481178.3776088,10.199990272521973,0.0,1740481178.3776116,10.199990272521973,0.0,1740481178.377614,10.199990272521973,7.001914059077752,1740481178.3776155,10.199990272521973,0.0,1740481178.377617,10.199990272521973,0.0,1740481178.3776178,10.199990272521973,0.0,1740481178.3776193,10.199990272521973,0.0,1740481178.3776205,10.199990272521973,0.0,1740481178.3776217,10.199990272521973,-2.0,1740481178.3776228,10.199990272521973,-2.0,1740481178.377624,10.199990272521973,0.0,1740481178.377625,10.199990272521973,0.0,, +1740481178.3978202,10.219990253448486,5.001914059077752,1740481178.397822,10.219990253448486,0.0,1740481178.3978245,10.219990253448486,0.0,1740481178.3978267,10.219990253448486,7.001914059077752,1740481178.3978279,10.219990253448486,0.0,1740481178.3978293,10.219990253448486,0.0,1740481178.3978307,10.219990253448486,0.0,1740481178.3978317,10.219990253448486,0.0,1740481178.397833,10.219990253448486,0.0,1740481178.3978345,10.219990253448486,-2.0,1740481178.3978355,10.219990253448486,-2.0,1740481178.3978367,10.219990253448486,0.0,1740481178.3978379,10.219990253448486,0.0,, +1740481178.418393,10.239990234375,5.001914059077752,1740481178.4183943,10.239990234375,0.0,1740481178.4183967,10.239990234375,0.0,1740481178.4183989,10.239990234375,7.001914059077752,1740481178.4184003,10.239990234375,0.0,1740481178.4184015,10.239990234375,0.0,1740481178.418403,10.239990234375,0.0,1740481178.4184039,10.239990234375,0.0,1740481178.4184048,10.239990234375,0.0,1740481178.4184062,10.239990234375,-2.0,1740481178.4184072,10.239990234375,-2.0,1740481178.4184082,10.239990234375,0.0,1740481178.4184089,10.239990234375,0.0,, +1740481178.4377713,10.259990215301514,5.001914059077752,1740481178.437773,10.259990215301514,0.0,1740481178.4377754,10.259990215301514,0.0,1740481178.4377778,10.259990215301514,7.001914059077752,1740481178.4377787,10.259990215301514,0.0,1740481178.4377801,10.259990215301514,0.0,1740481178.4377813,10.259990215301514,0.0,1740481178.4377823,10.259990215301514,0.0,1740481178.4377835,10.259990215301514,0.0,1740481178.4377847,10.259990215301514,-2.0,1740481178.4377856,10.259990215301514,-2.0,1740481178.4377866,10.259990215301514,0.0,1740481178.4377875,10.259990215301514,0.0,, +1740481178.4596295,10.279990196228027,5.001914059077752,1740481178.4596312,10.279990196228027,0.0,1740481178.4596334,10.279990196228027,0.0,1740481178.459636,10.279990196228027,7.001914059077752,1740481178.4596372,10.279990196228027,0.0,1740481178.4596388,10.279990196228027,0.0,1740481178.4596553,10.279990196228027,0.0,1740481178.4596567,10.279990196228027,0.0,1740481178.4596581,10.279990196228027,0.0,1740481178.4596593,10.279990196228027,-2.0,1740481178.4596603,10.279990196228027,-2.0,1740481178.4596612,10.279990196228027,0.0,1740481178.4596627,10.279990196228027,0.0,, +1740481178.4778545,10.299990177154541,5.001914059077752,1740481178.4778562,10.299990177154541,0.0,1740481178.4778588,10.299990177154541,0.0,1740481178.4778612,10.299990177154541,7.001914059077752,1740481178.4778621,10.299990177154541,0.0,1740481178.4778638,10.299990177154541,0.0,1740481178.4778647,10.299990177154541,0.0,1740481178.4778657,10.299990177154541,0.0,1740481178.4778671,10.299990177154541,0.0,1740481178.477868,10.299990177154541,-2.0,1740481178.477869,10.299990177154541,-2.0,1740481178.47787,10.299990177154541,0.0,1740481178.4778714,10.299990177154541,0.0,, +1740481178.4978259,10.319990158081055,5.001914059077752,1740481178.4978275,10.319990158081055,0.0,1740481178.4978302,10.319990158081055,0.0,1740481178.4978325,10.319990158081055,7.001914059077752,1740481178.4978337,10.319990158081055,0.0,1740481178.497835,10.319990158081055,0.0,1740481178.4978364,10.319990158081055,0.0,1740481178.4978375,10.319990158081055,0.0,1740481178.4978387,10.319990158081055,0.0,1740481178.4978402,10.319990158081055,-2.0,1740481178.4978414,10.319990158081055,-2.0,1740481178.4978426,10.319990158081055,0.0,1740481178.4978435,10.319990158081055,0.0,, +1740481178.5190554,10.339990139007568,5.001914059077752,1740481178.519057,10.339990139007568,0.0,1740481178.51906,10.339990139007568,0.0,1740481178.5190625,10.339990139007568,7.001914059077752,1740481178.5190635,10.339990139007568,0.0,1740481178.5190651,10.339990139007568,0.0,1740481178.5190666,10.339990139007568,0.0,1740481178.5190678,10.339990139007568,0.0,1740481178.519092,10.339990139007568,0.0,1740481178.5190935,10.339990139007568,-2.0,1740481178.5190947,10.339990139007568,-2.0,1740481178.519096,10.339990139007568,0.0,1740481178.519097,10.339990139007568,0.0,, +1740481178.5378122,10.359990119934082,5.001914059077752,1740481178.537814,10.359990119934082,0.0,1740481178.5378168,10.359990119934082,0.0,1740481178.5378199,10.359990119934082,7.001914059077752,1740481178.5378213,10.359990119934082,0.0,1740481178.5378227,10.359990119934082,0.0,1740481178.5378242,10.359990119934082,0.0,1740481178.5378256,10.359990119934082,0.0,1740481178.5378275,10.359990119934082,0.0,1740481178.5378292,10.359990119934082,-2.0,1740481178.5378304,10.359990119934082,-2.0,1740481178.5378318,10.359990119934082,0.0,1740481178.5378332,10.359990119934082,0.0,, +1740481178.5590754,10.379990100860596,5.001914059077752,1740481178.559077,10.379990100860596,0.0,1740481178.5590796,10.379990100860596,0.0,1740481178.559082,10.379990100860596,7.001914059077752,1740481178.5590832,10.379990100860596,0.0,1740481178.5590851,10.379990100860596,0.0,1740481178.5590863,10.379990100860596,0.0,1740481178.5590873,10.379990100860596,0.0,1740481178.5590887,10.379990100860596,0.0,1740481178.55909,10.379990100860596,-2.0,1740481178.559091,10.379990100860596,-2.0,1740481178.5590923,10.379990100860596,0.0,1740481178.5590932,10.379990100860596,0.0,, +1740481178.578226,10.39999008178711,5.001914059077752,1740481178.578228,10.39999008178711,0.0,1740481178.5782304,10.39999008178711,0.0,1740481178.5782328,10.39999008178711,7.001914059077752,1740481178.5782342,10.39999008178711,0.0,1740481178.5782354,10.39999008178711,0.0,1740481178.5782366,10.39999008178711,0.0,1740481178.5782378,10.39999008178711,0.0,1740481178.578239,10.39999008178711,0.0,1740481178.5782402,10.39999008178711,-2.0,1740481178.5782413,10.39999008178711,-2.0,1740481178.5782423,10.39999008178711,0.0,1740481178.5782435,10.39999008178711,0.0,, +1740481178.5984643,10.419990062713623,5.001914059077752,1740481178.5984662,10.419990062713623,0.0,1740481178.5984688,10.419990062713623,0.0,1740481178.5984716,10.419990062713623,7.001914059077752,1740481178.5984726,10.419990062713623,0.0,1740481178.5984745,10.419990062713623,0.0,1740481178.5984757,10.419990062713623,0.0,1740481178.5984771,10.419990062713623,0.0,1740481178.5984783,10.419990062713623,0.0,1740481178.5984795,10.419990062713623,-2.0,1740481178.5984807,10.419990062713623,-2.0,1740481178.598482,10.419990062713623,0.0,1740481178.5984828,10.419990062713623,0.0,, +1740481178.6193986,10.439990043640137,5.001914059077752,1740481178.619402,10.439990043640137,0.0,1740481178.6194072,10.439990043640137,0.0,1740481178.6194096,10.439990043640137,7.001914059077752,1740481178.619411,10.439990043640137,0.0,1740481178.6194124,10.439990043640137,0.0,1740481178.6194139,10.439990043640137,0.0,1740481178.619415,10.439990043640137,0.0,1740481178.6194162,10.439990043640137,0.0,1740481178.6194177,10.439990043640137,-2.0,1740481178.6194186,10.439990043640137,-2.0,1740481178.6194198,10.439990043640137,0.0,1740481178.619421,10.439990043640137,0.0,, +1740481178.6382873,10.45999002456665,5.001914059077752,1740481178.6382895,10.45999002456665,0.0,1740481178.6382923,10.45999002456665,0.0,1740481178.6382945,10.45999002456665,7.001914059077752,1740481178.6382957,10.45999002456665,0.0,1740481178.6382976,10.45999002456665,0.0,1740481178.638299,10.45999002456665,0.0,1740481178.6383002,10.45999002456665,0.0,1740481178.6383014,10.45999002456665,0.0,1740481178.6383028,10.45999002456665,-2.0,1740481178.6383038,10.45999002456665,-2.0,1740481178.638305,10.45999002456665,0.0,1740481178.6383061,10.45999002456665,0.0,, +1740481178.6581042,10.479990005493164,5.001914059077752,1740481178.6581078,10.479990005493164,0.0,1740481178.6581116,10.479990005493164,0.0,1740481178.6581137,10.479990005493164,7.001914059077752,1740481178.6581151,10.479990005493164,0.0,1740481178.6581166,10.479990005493164,0.0,1740481178.6581178,10.479990005493164,0.0,1740481178.6581192,10.479990005493164,0.0,1740481178.6581204,10.479990005493164,0.0,1740481178.6581216,10.479990005493164,-2.0,1740481178.6581225,10.479990005493164,-2.0,1740481178.6581235,10.479990005493164,0.0,1740481178.6581244,10.479990005493164,0.0,, +1740481178.6781485,10.499989986419678,5.001914059077752,1740481178.6781504,10.499989986419678,0.0,1740481178.6781533,10.499989986419678,0.0,1740481178.6781554,10.499989986419678,7.001914059077752,1740481178.6781569,10.499989986419678,0.0,1740481178.6781583,10.499989986419678,0.0,1740481178.67816,10.499989986419678,0.0,1740481178.678161,10.499989986419678,0.0,1740481178.6781623,10.499989986419678,0.0,1740481178.6781635,10.499989986419678,-2.0,1740481178.6781647,10.499989986419678,-2.0,1740481178.6781657,10.499989986419678,0.0,1740481178.6781673,10.499989986419678,0.0,, +1740481178.6980817,10.519989967346191,5.001914059077752,1740481178.6980839,10.519989967346191,0.0,1740481178.6980863,10.519989967346191,0.0,1740481178.6980886,10.519989967346191,7.001914059077752,1740481178.69809,10.519989967346191,0.0,1740481178.6980917,10.519989967346191,0.0,1740481178.698093,10.519989967346191,0.0,1740481178.6980944,10.519989967346191,0.0,1740481178.6980958,10.519989967346191,0.0,1740481178.6980972,10.519989967346191,-2.0,1740481178.6980982,10.519989967346191,-2.0,1740481178.6980994,10.519989967346191,0.0,1740481178.6981006,10.519989967346191,0.0,, +1740481178.718956,10.539989948272705,5.001914059077752,1740481178.718958,10.539989948272705,0.0,1740481178.7189603,10.539989948272705,0.0,1740481178.7189627,10.539989948272705,7.001914059077752,1740481178.7189636,10.539989948272705,0.0,1740481178.7189653,10.539989948272705,0.0,1740481178.7189662,10.539989948272705,0.0,1740481178.7189674,10.539989948272705,0.0,1740481178.7189689,10.539989948272705,0.0,1740481178.7189698,10.539989948272705,-2.0,1740481178.7189713,10.539989948272705,-2.0,1740481178.7189722,10.539989948272705,0.0,1740481178.7189732,10.539989948272705,0.0,, +1740481178.738047,10.559989929199219,5.001914059077752,1740481178.7380488,10.559989929199219,0.0,1740481178.7380514,10.559989929199219,0.0,1740481178.7380698,10.559989929199219,7.001914059077752,1740481178.7380712,10.559989929199219,0.0,1740481178.7380736,10.559989929199219,0.0,1740481178.7380748,10.559989929199219,0.0,1740481178.738076,10.559989929199219,0.0,1740481178.7380774,10.559989929199219,0.0,1740481178.7380788,10.559989929199219,-2.0,1740481178.73808,10.559989929199219,-2.0,1740481178.738081,10.559989929199219,0.0,1740481178.7380824,10.559989929199219,0.0,, +1740481178.7583869,10.579989910125732,5.001914059077752,1740481178.7583888,10.579989910125732,0.0,1740481178.7583916,10.579989910125732,0.0,1740481178.7583938,10.579989910125732,7.001914059077752,1740481178.7583954,10.579989910125732,0.0,1740481178.7583969,10.579989910125732,0.0,1740481178.7583983,10.579989910125732,0.0,1740481178.7583995,10.579989910125732,0.0,1740481178.7584007,10.579989910125732,0.0,1740481178.758402,10.579989910125732,-2.0,1740481178.758403,10.579989910125732,-2.0,1740481178.758404,10.579989910125732,0.0,1740481178.7584054,10.579989910125732,0.0,, +1740481178.7789674,10.599989891052246,5.001914059077752,1740481178.7789693,10.599989891052246,0.0,1740481178.7789721,10.599989891052246,0.0,1740481178.7789748,10.599989891052246,7.001914059077752,1740481178.7789757,10.599989891052246,0.0,1740481178.7789774,10.599989891052246,0.0,1740481178.7789788,10.599989891052246,0.0,1740481178.7789798,10.599989891052246,0.0,1740481178.7789812,10.599989891052246,0.0,1740481178.7789824,10.599989891052246,-2.0,1740481178.7789834,10.599989891052246,-2.0,1740481178.7789845,10.599989891052246,0.0,1740481178.7789857,10.599989891052246,0.0,, +1740481178.797568,10.61998987197876,5.001914059077752,1740481178.7975698,10.61998987197876,0.0,1740481178.7975726,10.61998987197876,0.0,1740481178.797575,10.61998987197876,7.001914059077752,1740481178.797576,10.61998987197876,0.0,1740481178.7975774,10.61998987197876,0.0,1740481178.7975788,10.61998987197876,0.0,1740481178.7975798,10.61998987197876,0.0,1740481178.797581,10.61998987197876,0.0,1740481178.7975824,10.61998987197876,-2.0,1740481178.7975836,10.61998987197876,-2.0,1740481178.7975845,10.61998987197876,0.0,1740481178.7975857,10.61998987197876,0.0,, +1740481178.8190198,10.639989852905273,5.001914059077752,1740481178.8190215,10.639989852905273,0.0,1740481178.819024,10.639989852905273,0.0,1740481178.8190265,10.639989852905273,7.001914059077752,1740481178.8190274,10.639989852905273,0.0,1740481178.819029,10.639989852905273,0.0,1740481178.8190303,10.639989852905273,0.0,1740481178.8190312,10.639989852905273,0.0,1740481178.8190327,10.639989852905273,0.0,1740481178.8190339,10.639989852905273,-2.0,1740481178.8190348,10.639989852905273,-2.0,1740481178.819036,10.639989852905273,0.0,1740481178.8190374,10.639989852905273,0.0,, +1740481178.8390582,10.659989833831787,5.001914059077752,1740481178.8390653,10.659989833831787,0.0,1740481178.8390708,10.659989833831787,0.0,1740481178.8390741,10.659989833831787,7.001914059077752,1740481178.839075,10.659989833831787,0.0,1740481178.8390768,10.659989833831787,0.0,1740481178.8390784,10.659989833831787,0.0,1740481178.8390799,10.659989833831787,0.0,1740481178.8390813,10.659989833831787,0.0,1740481178.8390825,10.659989833831787,-2.0,1740481178.8390834,10.659989833831787,-2.0,1740481178.839085,10.659989833831787,0.0,1740481178.8390863,10.659989833831787,0.0,, +1740481178.8578994,10.6799898147583,5.001914059077752,1740481178.8579016,10.6799898147583,0.0,1740481178.8579044,10.6799898147583,0.0,1740481178.8579066,10.6799898147583,7.001914059077752,1740481178.857908,10.6799898147583,0.0,1740481178.8579097,10.6799898147583,0.0,1740481178.857911,10.6799898147583,0.0,1740481178.8579123,10.6799898147583,0.0,1740481178.857914,10.6799898147583,0.0,1740481178.8579152,10.6799898147583,-2.0,1740481178.8579164,10.6799898147583,-2.0,1740481178.8579178,10.6799898147583,0.0,1740481178.857919,10.6799898147583,0.0,, +1740481178.8786728,10.699989795684814,5.001914059077752,1740481178.8786747,10.699989795684814,0.0,1740481178.8786771,10.699989795684814,0.0,1740481178.8786802,10.699989795684814,7.001914059077752,1740481178.8786817,10.699989795684814,0.0,1740481178.878683,10.699989795684814,0.0,1740481178.878684,10.699989795684814,0.0,1740481178.8786855,10.699989795684814,0.0,1740481178.8786867,10.699989795684814,0.0,1740481178.878688,10.699989795684814,-2.0,1740481178.8786893,10.699989795684814,-2.0,1740481178.8786902,10.699989795684814,0.0,1740481178.8786914,10.699989795684814,0.0,, +1740481178.8975325,10.719989776611328,5.001914059077752,1740481178.8975341,10.719989776611328,0.0,1740481178.8975365,10.719989776611328,0.0,1740481178.897539,10.719989776611328,7.001914059077752,1740481178.89754,10.719989776611328,0.0,1740481178.8975413,10.719989776611328,0.0,1740481178.8975427,10.719989776611328,0.0,1740481178.8975437,10.719989776611328,0.0,1740481178.8975449,10.719989776611328,0.0,1740481178.8975463,10.719989776611328,-2.0,1740481178.8975475,10.719989776611328,-2.0,1740481178.8975484,10.719989776611328,0.0,1740481178.8975496,10.719989776611328,0.0,, +1740481178.9180644,10.739989757537842,5.001914059077752,1740481178.918066,10.739989757537842,0.0,1740481178.9180684,10.739989757537842,0.0,1740481178.9180708,10.739989757537842,7.001914059077752,1740481178.918072,10.739989757537842,0.0,1740481178.9181302,10.739989757537842,0.0,1740481178.9181318,10.739989757537842,0.0,1740481178.9181328,10.739989757537842,0.0,1740481178.9181342,10.739989757537842,0.0,1740481178.9181354,10.739989757537842,-2.0,1740481178.9181366,10.739989757537842,-2.0,1740481178.9181376,10.739989757537842,0.0,1740481178.9181387,10.739989757537842,0.0,, +1740481178.9390953,10.759989738464355,5.001914059077752,1740481178.939097,10.759989738464355,0.0,1740481178.9390993,10.759989738464355,0.0,1740481178.9391017,10.759989738464355,7.001914059077752,1740481178.9391026,10.759989738464355,0.0,1740481178.9391043,10.759989738464355,0.0,1740481178.9391055,10.759989738464355,0.0,1740481178.9391067,10.759989738464355,0.0,1740481178.9391081,10.759989738464355,0.0,1740481178.939109,10.759989738464355,-2.0,1740481178.93911,10.759989738464355,-2.0,1740481178.9391115,10.759989738464355,0.0,1740481178.9391124,10.759989738464355,0.0,, +1740481178.957579,10.77998971939087,5.001914059077752,1740481178.9575818,10.77998971939087,0.0,1740481178.957585,10.77998971939087,0.0,1740481178.9575875,10.77998971939087,7.001914059077752,1740481178.957589,10.77998971939087,0.0,1740481178.957591,10.77998971939087,0.0,1740481178.9575934,10.77998971939087,0.0,1740481178.9575949,10.77998971939087,0.0,1740481178.9575968,10.77998971939087,0.0,1740481178.9575982,10.77998971939087,-2.0,1740481178.9576094,10.77998971939087,-2.0,1740481178.957612,10.77998971939087,0.0,1740481178.9576135,10.77998971939087,0.0,, +1740481178.9781895,10.799989700317383,5.001914059077752,1740481178.9781926,10.799989700317383,0.0,1740481178.9781961,10.799989700317383,0.0,1740481178.9781985,10.799989700317383,7.001914059077752,1740481178.9781995,10.799989700317383,0.0,1740481178.9782012,10.799989700317383,0.0,1740481178.978202,10.799989700317383,0.0,1740481178.978203,10.799989700317383,0.0,1740481178.9782043,10.799989700317383,0.0,1740481178.9782052,10.799989700317383,-2.0,1740481178.9782062,10.799989700317383,-2.0,1740481178.9782073,10.799989700317383,0.0,1740481178.9782083,10.799989700317383,0.0,, +1740481178.9974968,10.819989681243896,5.001914059077752,1740481178.9974983,10.819989681243896,0.0,1740481178.9975007,10.819989681243896,0.0,1740481178.9975028,10.819989681243896,7.001914059077752,1740481178.9975038,10.819989681243896,0.0,1740481178.997505,10.819989681243896,0.0,1740481178.9975216,10.819989681243896,0.0,1740481178.9975228,10.819989681243896,0.0,1740481178.997524,10.819989681243896,0.0,1740481178.997525,10.819989681243896,-2.0,1740481178.997526,10.819989681243896,-2.0,1740481178.9975271,10.819989681243896,0.0,1740481178.997528,10.819989681243896,0.0,, +1740481179.0181386,10.83998966217041,5.001914059077752,1740481179.01814,10.83998966217041,0.0,1740481179.0181422,10.83998966217041,0.0,1740481179.0181444,10.83998966217041,7.001914059077752,1740481179.0181453,10.83998966217041,0.0,1740481179.0181465,10.83998966217041,0.0,1740481179.0181475,10.83998966217041,0.0,1740481179.0181487,10.83998966217041,0.0,1740481179.0181496,10.83998966217041,0.0,1740481179.0181506,10.83998966217041,-2.0,1740481179.0181518,10.83998966217041,-2.0,1740481179.0181527,10.83998966217041,0.0,1740481179.0181537,10.83998966217041,0.0,, +1740481179.038036,10.859989643096924,5.001914059077752,1740481179.0380378,10.859989643096924,0.0,1740481179.0380402,10.859989643096924,0.0,1740481179.0380423,10.859989643096924,7.001914059077752,1740481179.0380435,10.859989643096924,0.0,1740481179.0380447,10.859989643096924,0.0,1740481179.0380456,10.859989643096924,0.0,1740481179.0380468,10.859989643096924,0.0,1740481179.0380478,10.859989643096924,0.0,1740481179.038049,10.859989643096924,-2.0,1740481179.03805,10.859989643096924,-2.0,1740481179.0380514,10.859989643096924,0.0,1740481179.0380523,10.859989643096924,0.0,, +1740481179.0578086,10.879989624023438,5.001914059077752,1740481179.057826,10.879989624023438,0.0,1740481179.0578282,10.879989624023438,0.0,1740481179.0578299,10.879989624023438,7.001914059077752,1740481179.0578308,10.879989624023438,0.0,1740481179.057832,10.879989624023438,0.0,1740481179.057833,10.879989624023438,0.0,1740481179.057834,10.879989624023438,0.0,1740481179.057835,10.879989624023438,0.0,1740481179.057836,10.879989624023438,-2.0,1740481179.0578368,10.879989624023438,-2.0,1740481179.0578375,10.879989624023438,0.0,1740481179.0578387,10.879989624023438,0.0,, +1740481179.0775988,10.899989604949951,5.001914059077752,1740481179.0776,10.899989604949951,0.0,1740481179.0776021,10.899989604949951,0.0,1740481179.0776038,10.899989604949951,7.001914059077752,1740481179.0776048,10.899989604949951,0.0,1740481179.0776062,10.899989604949951,0.0,1740481179.0776072,10.899989604949951,0.0,1740481179.077608,10.899989604949951,0.0,1740481179.0776093,10.899989604949951,0.0,1740481179.0776103,10.899989604949951,-2.0,1740481179.077611,10.899989604949951,-2.0,1740481179.077612,10.899989604949951,0.0,1740481179.0776129,10.899989604949951,0.0,, +1740481179.0989885,10.919989585876465,5.001914059077752,1740481179.0989897,10.919989585876465,0.0,1740481179.0989919,10.919989585876465,0.0,1740481179.098994,10.919989585876465,7.001914059077752,1740481179.0990076,10.919989585876465,0.0,1740481179.09901,10.919989585876465,0.0,1740481179.0990112,10.919989585876465,0.0,1740481179.0990121,10.919989585876465,0.0,1740481179.0990133,10.919989585876465,0.0,1740481179.0990143,10.919989585876465,-2.0,1740481179.0990152,10.919989585876465,-2.0,1740481179.0990162,10.919989585876465,0.0,1740481179.099017,10.919989585876465,0.0,, +1740481179.1181674,10.939989566802979,5.001914059077752,1740481179.1181688,10.939989566802979,0.0,1740481179.1181712,10.939989566802979,0.0,1740481179.1181731,10.939989566802979,7.001914059077752,1740481179.1181746,10.939989566802979,0.0,1740481179.1181757,10.939989566802979,0.0,1740481179.1181767,10.939989566802979,0.0,1740481179.118178,10.939989566802979,0.0,1740481179.1181788,10.939989566802979,0.0,1740481179.11818,10.939989566802979,-2.0,1740481179.1181808,10.939989566802979,-2.0,1740481179.118182,10.939989566802979,0.0,1740481179.118183,10.939989566802979,0.0,, +1740481179.1391075,10.959989547729492,5.001914059077752,1740481179.139109,10.959989547729492,0.0,1740481179.1391115,10.959989547729492,0.0,1740481179.1391144,10.959989547729492,7.001914059077752,1740481179.1391158,10.959989547729492,0.0,1740481179.1391175,10.959989547729492,0.0,1740481179.1391191,10.959989547729492,0.0,1740481179.1391206,10.959989547729492,0.0,1740481179.1391222,10.959989547729492,0.0,1740481179.1391237,10.959989547729492,-2.0,1740481179.1391246,10.959989547729492,-2.0,1740481179.1391256,10.959989547729492,0.0,1740481179.1391268,10.959989547729492,0.0,, +1740481179.1580799,10.979989528656006,5.001914059077752,1740481179.1580813,10.979989528656006,0.0,1740481179.1580834,10.979989528656006,0.0,1740481179.158085,10.979989528656006,7.001914059077752,1740481179.158086,10.979989528656006,0.0,1740481179.1580875,10.979989528656006,0.0,1740481179.1580884,10.979989528656006,0.0,1740481179.1580894,10.979989528656006,0.0,1740481179.1580906,10.979989528656006,0.0,1740481179.1580918,10.979989528656006,-2.0,1740481179.1580925,10.979989528656006,-2.0,1740481179.1580935,10.979989528656006,0.0,1740481179.1580946,10.979989528656006,0.0,, +1740481179.1777923,10.99998950958252,5.001914059077752,1740481179.1777937,10.99998950958252,0.0,1740481179.177796,10.99998950958252,0.0,1740481179.1777976,10.99998950958252,7.001914059077752,1740481179.1777987,10.99998950958252,0.0,1740481179.1778004,10.99998950958252,0.0,1740481179.1778014,10.99998950958252,0.0,1740481179.1778023,10.99998950958252,0.0,1740481179.1778033,10.99998950958252,0.0,1740481179.1778042,10.99998950958252,-2.0,1740481179.177805,10.99998950958252,-2.0,1740481179.1778061,10.99998950958252,0.0,1740481179.177807,10.99998950958252,0.0,, +1740481179.1990416,11.019989490509033,5.001914059077752,1740481179.199043,11.019989490509033,0.0,1740481179.199045,11.019989490509033,0.0,1740481179.1990469,11.019989490509033,7.001914059077752,1740481179.199048,11.019989490509033,0.0,1740481179.199049,11.019989490509033,0.0,1740481179.1990502,11.019989490509033,0.0,1740481179.199051,11.019989490509033,0.0,1740481179.199052,11.019989490509033,0.0,1740481179.199053,11.019989490509033,-2.0,1740481179.1990538,11.019989490509033,-2.0,1740481179.1990545,11.019989490509033,0.0,1740481179.1990557,11.019989490509033,0.0,, +1740481179.2229753,11.039989471435547,5.001914059077752,1740481179.222977,11.039989471435547,0.0,1740481179.2229798,11.039989471435547,0.0,1740481179.2229822,11.039989471435547,7.001914059077752,1740481179.2229831,11.039989471435547,0.0,1740481179.2229846,11.039989471435547,0.0,1740481179.2229855,11.039989471435547,0.0,1740481179.2229862,11.039989471435547,0.0,1740481179.2229872,11.039989471435547,0.0,1740481179.2229884,11.039989471435547,-2.0,1740481179.222989,11.039989471435547,-2.0,1740481179.2229898,11.039989471435547,0.0,1740481179.2229908,11.039989471435547,0.0,, +1740481179.2385824,11.05998945236206,5.001914059077752,1740481179.2385838,11.05998945236206,0.0,1740481179.2385857,11.05998945236206,0.0,1740481179.2385876,11.05998945236206,7.001914059077752,1740481179.2385883,11.05998945236206,0.0,1740481179.2385898,11.05998945236206,0.0,1740481179.2385907,11.05998945236206,0.0,1740481179.2385917,11.05998945236206,0.0,1740481179.2385929,11.05998945236206,0.0,1740481179.2385938,11.05998945236206,-2.0,1740481179.2385945,11.05998945236206,-2.0,1740481179.2385955,11.05998945236206,0.0,1740481179.2385964,11.05998945236206,0.0,, +1740481179.2578998,11.079989433288574,5.001914059077752,1740481179.257901,11.079989433288574,0.0,1740481179.2579033,11.079989433288574,0.0,1740481179.2579052,11.079989433288574,7.001914059077752,1740481179.2579062,11.079989433288574,0.0,1740481179.2579072,11.079989433288574,0.0,1740481179.257908,11.079989433288574,0.0,1740481179.2579093,11.079989433288574,0.0,1740481179.2579103,11.079989433288574,0.0,1740481179.257911,11.079989433288574,-2.0,1740481179.2579122,11.079989433288574,-2.0,1740481179.257913,11.079989433288574,0.0,1740481179.2579138,11.079989433288574,0.0,, +1740481179.2780852,11.099989414215088,5.001914059077752,1740481179.2780867,11.099989414215088,0.0,1740481179.2780888,11.099989414215088,0.0,1740481179.2780905,11.099989414215088,7.001914059077752,1740481179.2780914,11.099989414215088,0.0,1740481179.2780926,11.099989414215088,0.0,1740481179.2780936,11.099989414215088,0.0,1740481179.2780943,11.099989414215088,0.0,1740481179.2780952,11.099989414215088,0.0,1740481179.2780964,11.099989414215088,-2.0,1740481179.2780972,11.099989414215088,-2.0,1740481179.2780979,11.099989414215088,0.0,1740481179.278099,11.099989414215088,0.0,, +1740481179.297805,11.119989395141602,5.001914059077752,1740481179.2978065,11.119989395141602,0.0,1740481179.2978084,11.119989395141602,0.0,1740481179.2978103,11.119989395141602,7.001914059077752,1740481179.2978115,11.119989395141602,0.0,1740481179.2978127,11.119989395141602,0.0,1740481179.2978134,11.119989395141602,0.0,1740481179.2978146,11.119989395141602,0.0,1740481179.2978156,11.119989395141602,0.0,1740481179.2978163,11.119989395141602,-2.0,1740481179.2978172,11.119989395141602,-2.0,1740481179.2978182,11.119989395141602,0.0,1740481179.2978194,11.119989395141602,0.0,, +1740481179.3191564,11.139989376068115,5.001914059077752,1740481179.3191578,11.139989376068115,0.0,1740481179.3191597,11.139989376068115,0.0,1740481179.319162,11.139989376068115,7.001914059077752,1740481179.3191626,11.139989376068115,0.0,1740481179.3191638,11.139989376068115,0.0,1740481179.319165,11.139989376068115,0.0,1740481179.3191657,11.139989376068115,0.0,1740481179.3191667,11.139989376068115,0.0,1740481179.3191679,11.139989376068115,-2.0,1740481179.3191688,11.139989376068115,-2.0,1740481179.3191695,11.139989376068115,0.0,1740481179.3191707,11.139989376068115,0.0,, +1740481179.3380055,11.159989356994629,5.001914059077752,1740481179.338007,11.159989356994629,0.0,1740481179.338009,11.159989356994629,0.0,1740481179.338011,11.159989356994629,7.001914059077752,1740481179.3380122,11.159989356994629,0.0,1740481179.3380134,11.159989356994629,0.0,1740481179.3380144,11.159989356994629,0.0,1740481179.3380158,11.159989356994629,0.0,1740481179.3380165,11.159989356994629,0.0,1740481179.338018,11.159989356994629,-2.0,1740481179.338019,11.159989356994629,-2.0,1740481179.3380198,11.159989356994629,0.0,1740481179.3380206,11.159989356994629,0.0,, +1740481179.3579063,11.179989337921143,5.001914059077752,1740481179.357908,11.179989337921143,0.0,1740481179.35791,11.179989337921143,0.0,1740481179.357912,11.179989337921143,7.001914059077752,1740481179.3579133,11.179989337921143,0.0,1740481179.3579152,11.179989337921143,0.0,1740481179.3579164,11.179989337921143,0.0,1740481179.3579175,11.179989337921143,0.0,1740481179.3579185,11.179989337921143,0.0,1740481179.3579202,11.179989337921143,-2.0,1740481179.3579211,11.179989337921143,-2.0,1740481179.357922,11.179989337921143,0.0,1740481179.3579228,11.179989337921143,0.0,, +1740481179.377991,11.199989318847656,5.001914059077752,1740481179.3779924,11.199989318847656,0.0,1740481179.3779945,11.199989318847656,0.0,1740481179.3779962,11.199989318847656,7.001914059077752,1740481179.3779974,11.199989318847656,0.0,1740481179.3779984,11.199989318847656,0.0,1740481179.3779993,11.199989318847656,0.0,1740481179.3780005,11.199989318847656,0.0,1740481179.3780015,11.199989318847656,0.0,1740481179.3780022,11.199989318847656,-2.0,1740481179.3780031,11.199989318847656,-2.0,1740481179.378004,11.199989318847656,0.0,1740481179.378005,11.199989318847656,0.0,, +1740481179.398106,11.21998929977417,5.001914059077752,1740481179.3981287,11.21998929977417,0.0,1740481179.3981307,11.21998929977417,0.0,1740481179.3981328,11.21998929977417,7.001914059077752,1740481179.3981338,11.21998929977417,0.0,1740481179.398135,11.21998929977417,0.0,1740481179.3981361,11.21998929977417,0.0,1740481179.398154,11.21998929977417,0.0,1740481179.3981547,11.21998929977417,0.0,1740481179.3981557,11.21998929977417,-2.0,1740481179.398157,11.21998929977417,-2.0,1740481179.3981578,11.21998929977417,0.0,1740481179.398159,11.21998929977417,0.0,, +1740481179.4198349,11.239989280700684,5.001914059077752,1740481179.419836,11.239989280700684,0.0,1740481179.419838,11.239989280700684,0.0,1740481179.41984,11.239989280700684,7.001914059077752,1740481179.419841,11.239989280700684,0.0,1740481179.4198422,11.239989280700684,0.0,1740481179.4198434,11.239989280700684,0.0,1740481179.4198442,11.239989280700684,0.0,1740481179.419845,11.239989280700684,0.0,1740481179.419846,11.239989280700684,-2.0,1740481179.4198472,11.239989280700684,-2.0,1740481179.419848,11.239989280700684,0.0,1740481179.4198487,11.239989280700684,0.0,, +1740481179.4378688,11.259989261627197,5.001914059077752,1740481179.4378703,11.259989261627197,0.0,1740481179.4378722,11.259989261627197,0.0,1740481179.4378743,11.259989261627197,7.001914059077752,1740481179.4378755,11.259989261627197,0.0,1740481179.4378767,11.259989261627197,0.0,1740481179.4378777,11.259989261627197,0.0,1740481179.4378788,11.259989261627197,0.0,1740481179.4378798,11.259989261627197,0.0,1740481179.4378805,11.259989261627197,-2.0,1740481179.4378817,11.259989261627197,-2.0,1740481179.4378827,11.259989261627197,0.0,1740481179.4378834,11.259989261627197,0.0,, +1740481179.4593956,11.279989242553711,5.001914059077752,1740481179.459397,11.279989242553711,0.0,1740481179.4593997,11.279989242553711,0.0,1740481179.4594018,11.279989242553711,7.001914059077752,1740481179.459403,11.279989242553711,0.0,1740481179.459405,11.279989242553711,0.0,1740481179.4594066,11.279989242553711,0.0,1740481179.4594076,11.279989242553711,0.0,1740481179.4594085,11.279989242553711,0.0,1740481179.4594097,11.279989242553711,-2.0,1740481179.4594107,11.279989242553711,-2.0,1740481179.4594114,11.279989242553711,0.0,1740481179.4594128,11.279989242553711,0.0,, +1740481179.4778204,11.299989223480225,5.001914059077752,1740481179.477822,11.299989223480225,0.0,1740481179.4778244,11.299989223480225,0.0,1740481179.4778266,11.299989223480225,7.001914059077752,1740481179.4778278,11.299989223480225,0.0,1740481179.4778295,11.299989223480225,0.0,1740481179.4778306,11.299989223480225,0.0,1740481179.4778316,11.299989223480225,0.0,1740481179.477833,11.299989223480225,0.0,1740481179.477834,11.299989223480225,-2.0,1740481179.477835,11.299989223480225,-2.0,1740481179.477836,11.299989223480225,0.0,1740481179.4778368,11.299989223480225,0.0,, +1740481179.498597,11.319989204406738,5.001914059077752,1740481179.4985988,11.319989204406738,0.0,1740481179.4986017,11.319989204406738,0.0,1740481179.4986043,11.319989204406738,7.001914059077752,1740481179.4986057,11.319989204406738,0.0,1740481179.4986079,11.319989204406738,0.0,1740481179.4986098,11.319989204406738,0.0,1740481179.4986112,11.319989204406738,0.0,1740481179.4986124,11.319989204406738,0.0,1740481179.4986145,11.319989204406738,-2.0,1740481179.4986155,11.319989204406738,-2.0,1740481179.4986174,11.319989204406738,0.0,1740481179.4986186,11.319989204406738,0.0,, +1740481179.5192676,11.339989185333252,5.001914059077752,1740481179.5192692,11.339989185333252,0.0,1740481179.5192711,11.339989185333252,0.0,1740481179.5192733,11.339989185333252,7.001914059077752,1740481179.5192742,11.339989185333252,0.0,1740481179.5192754,11.339989185333252,0.0,1740481179.5192766,11.339989185333252,0.0,1740481179.5192776,11.339989185333252,0.0,1740481179.5192785,11.339989185333252,0.0,1740481179.51928,11.339989185333252,-2.0,1740481179.5192807,11.339989185333252,-2.0,1740481179.5192816,11.339989185333252,0.0,1740481179.5192823,11.339989185333252,0.0,, +1740481179.5377727,11.359989166259766,5.001914059077752,1740481179.5377738,11.359989166259766,0.0,1740481179.5377758,11.359989166259766,0.0,1740481179.537778,11.359989166259766,7.001914059077752,1740481179.5377789,11.359989166259766,0.0,1740481179.5377805,11.359989166259766,0.0,1740481179.5377817,11.359989166259766,0.0,1740481179.5377827,11.359989166259766,0.0,1740481179.5377839,11.359989166259766,0.0,1740481179.5377848,11.359989166259766,-2.0,1740481179.537786,11.359989166259766,-2.0,1740481179.5377874,11.359989166259766,0.0,1740481179.5377882,11.359989166259766,0.0,, +1740481179.5577796,11.37998914718628,5.001914059077752,1740481179.557781,11.37998914718628,0.0,1740481179.557783,11.37998914718628,0.0,1740481179.5577848,11.37998914718628,7.001914059077752,1740481179.5577862,11.37998914718628,0.0,1740481179.5577874,11.37998914718628,0.0,1740481179.5577884,11.37998914718628,0.0,1740481179.5577893,11.37998914718628,0.0,1740481179.5577905,11.37998914718628,0.0,1740481179.5577915,11.37998914718628,-2.0,1740481179.5577924,11.37998914718628,-2.0,1740481179.5577934,11.37998914718628,0.0,1740481179.557794,11.37998914718628,0.0,, +1740481179.5783503,11.399989128112793,5.001914059077752,1740481179.5783525,11.399989128112793,0.0,1740481179.5783556,11.399989128112793,0.0,1740481179.5783582,11.399989128112793,7.001914059077752,1740481179.5783594,11.399989128112793,0.0,1740481179.5783608,11.399989128112793,0.0,1740481179.5783617,11.399989128112793,0.0,1740481179.578364,11.399989128112793,0.0,1740481179.5783648,11.399989128112793,0.0,1740481179.5783665,11.399989128112793,-2.0,1740481179.5783672,11.399989128112793,-2.0,1740481179.5783682,11.399989128112793,0.0,1740481179.5783696,11.399989128112793,0.0,, +1740481179.599526,11.419989109039307,5.001914059077752,1740481179.5995276,11.419989109039307,0.0,1740481179.5995297,11.419989109039307,0.0,1740481179.5995314,11.419989109039307,7.001914059077752,1740481179.5995326,11.419989109039307,0.0,1740481179.5995338,11.419989109039307,0.0,1740481179.5995345,11.419989109039307,0.0,1740481179.5995357,11.419989109039307,0.0,1740481179.5995367,11.419989109039307,0.0,1740481179.5995376,11.419989109039307,-2.0,1740481179.5995388,11.419989109039307,-2.0,1740481179.5995398,11.419989109039307,0.0,1740481179.5995405,11.419989109039307,0.0,, +1740481179.6196475,11.43998908996582,5.001914059077752,1740481179.619649,11.43998908996582,0.0,1740481179.619651,11.43998908996582,0.0,1740481179.6196527,11.43998908996582,7.001914059077752,1740481179.619654,11.43998908996582,0.0,1740481179.6196551,11.43998908996582,0.0,1740481179.619656,11.43998908996582,0.0,1740481179.6196573,11.43998908996582,0.0,1740481179.619658,11.43998908996582,0.0,1740481179.619659,11.43998908996582,-2.0,1740481179.6196601,11.43998908996582,-2.0,1740481179.6196609,11.43998908996582,0.0,1740481179.6196618,11.43998908996582,0.0,, +1740481179.6374786,11.459989070892334,5.001914059077752,1740481179.6374803,11.459989070892334,0.0,1740481179.637482,11.459989070892334,0.0,1740481179.6374843,11.459989070892334,7.001914059077752,1740481179.6374853,11.459989070892334,0.0,1740481179.6374862,11.459989070892334,0.0,1740481179.6374874,11.459989070892334,0.0,1740481179.6374884,11.459989070892334,0.0,1740481179.6374893,11.459989070892334,0.0,1740481179.6374905,11.459989070892334,-2.0,1740481179.6374915,11.459989070892334,-2.0,1740481179.6374922,11.459989070892334,0.0,1740481179.6374931,11.459989070892334,0.0,, +1740481179.658676,11.479989051818848,5.001914059077752,1740481179.6586778,11.479989051818848,0.0,1740481179.6586807,11.479989051818848,0.0,1740481179.658683,11.479989051818848,7.001914059077752,1740481179.658685,11.479989051818848,0.0,1740481179.658697,11.479989051818848,0.0,1740481179.6587007,11.479989051818848,0.0,1740481179.6587021,11.479989051818848,0.0,1740481179.6587033,11.479989051818848,0.0,1740481179.6587043,11.479989051818848,-2.0,1740481179.6587057,11.479989051818848,-2.0,1740481179.658707,11.479989051818848,0.0,1740481179.6587079,11.479989051818848,0.0,, +1740481179.6783593,11.499989032745361,5.001914059077752,1740481179.678361,11.499989032745361,0.0,1740481179.6783626,11.499989032745361,0.0,1740481179.6783648,11.499989032745361,7.001914059077752,1740481179.6783657,11.499989032745361,0.0,1740481179.678367,11.499989032745361,0.0,1740481179.678368,11.499989032745361,0.0,1740481179.6783688,11.499989032745361,0.0,1740481179.6783698,11.499989032745361,0.0,1740481179.6783707,11.499989032745361,-2.0,1740481179.678372,11.499989032745361,-2.0,1740481179.6783726,11.499989032745361,0.0,1740481179.6783733,11.499989032745361,0.0,, +1740481179.6982338,11.519989013671875,5.001914059077752,1740481179.6982353,11.519989013671875,0.0,1740481179.6982374,11.519989013671875,0.0,1740481179.6982396,11.519989013671875,7.001914059077752,1740481179.6982408,11.519989013671875,0.0,1740481179.698242,11.519989013671875,0.0,1740481179.6982431,11.519989013671875,0.0,1740481179.698244,11.519989013671875,0.0,1740481179.698245,11.519989013671875,0.0,1740481179.6982462,11.519989013671875,-2.0,1740481179.6982472,11.519989013671875,-2.0,1740481179.698248,11.519989013671875,0.0,1740481179.6982489,11.519989013671875,0.0,, +1740481179.7186706,11.539988994598389,5.001914059077752,1740481179.718672,11.539988994598389,0.0,1740481179.7186742,11.539988994598389,0.0,1740481179.7186763,11.539988994598389,7.001914059077752,1740481179.718677,11.539988994598389,0.0,1740481179.7186782,11.539988994598389,0.0,1740481179.7186792,11.539988994598389,0.0,1740481179.7186801,11.539988994598389,0.0,1740481179.718681,11.539988994598389,0.0,1740481179.718682,11.539988994598389,-2.0,1740481179.7186828,11.539988994598389,-2.0,1740481179.718684,11.539988994598389,0.0,1740481179.718685,11.539988994598389,0.0,, +1740481179.738015,11.559988975524902,5.001914059077752,1740481179.7380166,11.559988975524902,0.0,1740481179.7380183,11.559988975524902,0.0,1740481179.7380207,11.559988975524902,7.001914059077752,1740481179.7380216,11.559988975524902,0.0,1740481179.7380228,11.559988975524902,0.0,1740481179.738024,11.559988975524902,0.0,1740481179.738025,11.559988975524902,0.0,1740481179.738026,11.559988975524902,0.0,1740481179.7380273,11.559988975524902,-2.0,1740481179.7380283,11.559988975524902,-2.0,1740481179.738029,11.559988975524902,0.0,1740481179.7380302,11.559988975524902,0.0,, +1740481179.7577639,11.579988956451416,5.001914059077752,1740481179.7577653,11.579988956451416,0.0,1740481179.7577677,11.579988956451416,0.0,1740481179.7577698,11.579988956451416,7.001914059077752,1740481179.7577708,11.579988956451416,0.0,1740481179.7577722,11.579988956451416,0.0,1740481179.7577734,11.579988956451416,0.0,1740481179.757774,11.579988956451416,0.0,1740481179.757775,11.579988956451416,0.0,1740481179.7577765,11.579988956451416,-2.0,1740481179.7577775,11.579988956451416,-2.0,1740481179.7577782,11.579988956451416,0.0,1740481179.7577791,11.579988956451416,0.0,, +1740481179.779371,11.59998893737793,5.001914059077752,1740481179.7793734,11.59998893737793,0.0,1740481179.7793772,11.59998893737793,0.0,1740481179.7793796,11.59998893737793,7.001914059077752,1740481179.7793813,11.59998893737793,0.0,1740481179.7793827,11.59998893737793,0.0,1740481179.7793844,11.59998893737793,0.0,1740481179.7793856,11.59998893737793,0.0,1740481179.7793872,11.59998893737793,0.0,1740481179.779389,11.59998893737793,-2.0,1740481179.77939,11.59998893737793,-2.0,1740481179.7793913,11.59998893737793,0.0,1740481179.7793922,11.59998893737793,0.0,, +1740481179.7989485,11.619988918304443,5.001914059077752,1740481179.7989502,11.619988918304443,0.0,1740481179.7989652,11.619988918304443,0.0,1740481179.798968,11.619988918304443,7.001914059077752,1740481179.798969,11.619988918304443,0.0,1740481179.7989705,11.619988918304443,0.0,1740481179.7989714,11.619988918304443,0.0,1740481179.7989724,11.619988918304443,0.0,1740481179.7989733,11.619988918304443,0.0,1740481179.7989745,11.619988918304443,-2.0,1740481179.7989757,11.619988918304443,-2.0,1740481179.7989764,11.619988918304443,0.0,1740481179.7989776,11.619988918304443,0.0,, +1740481179.8181958,11.639988899230957,5.001914059077752,1740481179.8181973,11.639988899230957,0.0,1740481179.8181992,11.639988899230957,0.0,1740481179.818201,11.639988899230957,7.001914059077752,1740481179.8182018,11.639988899230957,0.0,1740481179.8182032,11.639988899230957,0.0,1740481179.8182042,11.639988899230957,0.0,1740481179.8182049,11.639988899230957,0.0,1740481179.8182058,11.639988899230957,0.0,1740481179.818207,11.639988899230957,-2.0,1740481179.8182077,11.639988899230957,-2.0,1740481179.8182085,11.639988899230957,0.0,1740481179.8182096,11.639988899230957,0.0,, +1740481179.838566,11.65998888015747,5.001914059077752,1740481179.8385677,11.65998888015747,0.0,1740481179.8385696,11.65998888015747,0.0,1740481179.8385718,11.65998888015747,7.001914059077752,1740481179.8385727,11.65998888015747,0.0,1740481179.8385742,11.65998888015747,0.0,1740481179.8385754,11.65998888015747,0.0,1740481179.8385763,11.65998888015747,0.0,1740481179.8385775,11.65998888015747,0.0,1740481179.8385785,11.65998888015747,-2.0,1740481179.8385792,11.65998888015747,-2.0,1740481179.8385801,11.65998888015747,0.0,1740481179.8385813,11.65998888015747,0.0,, +1740481179.8595781,11.679988861083984,5.001914059077752,1740481179.8595796,11.679988861083984,0.0,1740481179.8595822,11.679988861083984,0.0,1740481179.8595846,11.679988861083984,7.001914059077752,1740481179.8595855,11.679988861083984,0.0,1740481179.859587,11.679988861083984,0.0,1740481179.8595884,11.679988861083984,0.0,1740481179.8595898,11.679988861083984,0.0,1740481179.8595912,11.679988861083984,0.0,1740481179.8595924,11.679988861083984,-2.0,1740481179.8595934,11.679988861083984,-2.0,1740481179.8595946,11.679988861083984,0.0,1740481179.8595955,11.679988861083984,0.0,, +1740481179.8806603,11.699988842010498,5.001914059077752,1740481179.880662,11.699988842010498,0.0,1740481179.8806646,11.699988842010498,0.0,1740481179.8806672,11.699988842010498,7.001914059077752,1740481179.8806684,11.699988842010498,0.0,1740481179.8806703,11.699988842010498,0.0,1740481179.8806715,11.699988842010498,0.0,1740481179.880673,11.699988842010498,0.0,1740481179.8806746,11.699988842010498,0.0,1740481179.8806767,11.699988842010498,-2.0,1740481179.8806784,11.699988842010498,-2.0,1740481179.8806963,11.699988842010498,0.0,1740481179.8806992,11.699988842010498,0.0,, +1740481179.8979137,11.719988822937012,5.001914059077752,1740481179.8979151,11.719988822937012,0.0,1740481179.8979175,11.719988822937012,0.0,1740481179.8979192,11.719988822937012,7.001914059077752,1740481179.8979204,11.719988822937012,0.0,1740481179.8979218,11.719988822937012,0.0,1740481179.8979228,11.719988822937012,0.0,1740481179.8979242,11.719988822937012,0.0,1740481179.897925,11.719988822937012,0.0,1740481179.897926,11.719988822937012,-2.0,1740481179.8979268,11.719988822937012,-2.0,1740481179.897928,11.719988822937012,0.0,1740481179.897929,11.719988822937012,0.0,, +1740481179.9186502,11.739988803863525,5.001914059077752,1740481179.9186513,11.739988803863525,0.0,1740481179.9186535,11.739988803863525,0.0,1740481179.9186552,11.739988803863525,7.001914059077752,1740481179.9186563,11.739988803863525,0.0,1740481179.9186575,11.739988803863525,0.0,1740481179.9186585,11.739988803863525,0.0,1740481179.9186597,11.739988803863525,0.0,1740481179.9186606,11.739988803863525,0.0,1740481179.9186614,11.739988803863525,-2.0,1740481179.9186623,11.739988803863525,-2.0,1740481179.9186633,11.739988803863525,0.0,1740481179.9186642,11.739988803863525,0.0,, +1740481179.9389234,11.759988784790039,5.001914059077752,1740481179.9389248,11.759988784790039,0.0,1740481179.938927,11.759988784790039,0.0,1740481179.9389288,11.759988784790039,7.001914059077752,1740481179.9389305,11.759988784790039,0.0,1740481179.9389317,11.759988784790039,0.0,1740481179.9389327,11.759988784790039,0.0,1740481179.9389338,11.759988784790039,0.0,1740481179.9389348,11.759988784790039,0.0,1740481179.9389358,11.759988784790039,-2.0,1740481179.9389365,11.759988784790039,-2.0,1740481179.9389377,11.759988784790039,0.0,1740481179.9389384,11.759988784790039,0.0,, +1740481179.9597747,11.779988765716553,5.001914059077752,1740481179.959776,11.779988765716553,0.0,1740481179.9597778,11.779988765716553,0.0,1740481179.9597797,11.779988765716553,7.001914059077752,1740481179.9597812,11.779988765716553,0.0,1740481179.9597824,11.779988765716553,0.0,1740481179.9597833,11.779988765716553,0.0,1740481179.9597843,11.779988765716553,0.0,1740481179.9597852,11.779988765716553,0.0,1740481179.9597862,11.779988765716553,-2.0,1740481179.959787,11.779988765716553,-2.0,1740481179.959788,11.779988765716553,0.0,1740481179.9597888,11.779988765716553,0.0,, +1740481179.9777527,11.799988746643066,5.001914059077752,1740481179.977754,11.799988746643066,0.0,1740481179.9777558,11.799988746643066,0.0,1740481179.977758,11.799988746643066,7.001914059077752,1740481179.977759,11.799988746643066,0.0,1740481179.9777603,11.799988746643066,0.0,1740481179.9777613,11.799988746643066,0.0,1740481179.9777622,11.799988746643066,0.0,1740481179.9777632,11.799988746643066,0.0,1740481179.9777641,11.799988746643066,-2.0,1740481179.977765,11.799988746643066,-2.0,1740481179.9777658,11.799988746643066,0.0,1740481179.977767,11.799988746643066,0.0,, +1740481179.9980574,11.81998872756958,5.001914059077752,1740481179.998059,11.81998872756958,0.0,1740481179.998061,11.81998872756958,0.0,1740481179.9980772,11.81998872756958,7.001914059077752,1740481179.9980783,11.81998872756958,0.0,1740481179.9980805,11.81998872756958,0.0,1740481179.9980817,11.81998872756958,0.0,1740481179.9980829,11.81998872756958,0.0,1740481179.9980838,11.81998872756958,0.0,1740481179.998085,11.81998872756958,-2.0,1740481179.998086,11.81998872756958,-2.0,1740481179.998087,11.81998872756958,0.0,1740481179.998088,11.81998872756958,0.0,, +1740481180.0204206,11.839988708496094,5.001914059077752,1740481180.0204222,11.839988708496094,0.0,1740481180.0204244,11.839988708496094,0.0,1740481180.0204265,11.839988708496094,7.001914059077752,1740481180.0204272,11.839988708496094,0.0,1740481180.0204287,11.839988708496094,0.0,1740481180.0204298,11.839988708496094,0.0,1740481180.0204306,11.839988708496094,0.0,1740481180.0204315,11.839988708496094,0.061237243569578145,1740481180.0204327,11.839988708496094,0.0,1740481180.0204334,11.839988708496094,0.061237243569578145,1740481180.0204341,11.839988708496094,0.0,1740481180.020435,11.839988708496094,0.0,, +1740481180.0379238,11.859988689422607,5.00192018280211,1740481180.037926,11.859988689422607,0.0,1740481180.0379276,11.859988689422607,6.123724357820362e-08,1740481180.0379298,11.859988689422607,7.004362997610343,1740481180.0379305,11.859988689422607,0.0,1740481180.037932,11.859988689422607,0.0,1740481180.037933,11.859988689422607,0.0,1740481180.037934,11.859988689422607,0.0,1740481180.037935,11.859988689422607,0.061237243569578145,1740481180.0379362,11.859988689422607,1.0,1740481180.0379372,11.859988689422607,1.0594562413694542,1740481180.037938,11.859988689422607,0.0,1740481180.0379388,11.859988689422607,0.001224438647673715,, +1740481180.0601723,11.879988670349121,5.00192018280211,1740481180.0601747,11.879988670349121,0.0,1740481180.0601766,11.879988670349121,6.123724357820362e-08,1740481180.060179,11.879988670349121,7.004362997610343,1740481180.06018,11.879988670349121,0.0,1740481180.0601811,11.879988670349121,0.0,1740481180.0601826,11.879988670349121,0.0,1740481180.0601835,11.879988670349121,0.0,1740481180.0601842,11.879988670349121,0.061237243569578145,1740481180.0601857,11.879988670349121,1.0,1740481180.0601866,11.879988670349121,1.0600128049219044,1740481180.0601873,11.879988670349121,0.0,1740481180.060188,11.879988670349121,0.001224438647673715,, +1740481180.078867,11.899988651275635,5.00192018280211,1740481180.0788686,11.899988651275635,0.0,1740481180.0788708,11.899988651275635,6.123724357820362e-08,1740481180.0788727,11.899988651275635,7.004362997610343,1740481180.0788736,11.899988651275635,0.0,1740481180.0788755,11.899988651275635,0.0,1740481180.0788765,11.899988651275635,0.0,1740481180.0788774,11.899988651275635,0.0,1740481180.0788782,11.899988651275635,0.061237243569578145,1740481180.0788796,11.899988651275635,1.0,1740481180.0788803,11.899988651275635,1.0600128049219044,1740481180.0788813,11.899988651275635,0.0,1740481180.078882,11.899988651275635,0.001224438647673715,, +1740481180.1001308,11.919988632202148,5.00192018280211,1740481180.1001327,11.919988632202148,0.0,1740481180.1001346,11.919988632202148,6.123724357820362e-08,1740481180.1001368,11.919988632202148,7.004362997610343,1740481180.1001377,11.919988632202148,0.0,1740481180.100139,11.919988632202148,0.0,1740481180.1001406,11.919988632202148,0.0,1740481180.1001415,11.919988632202148,0.0,1740481180.1001425,11.919988632202148,0.061237243569578145,1740481180.1001437,11.919988632202148,1.0,1740481180.1001444,11.919988632202148,1.0600128049219044,1740481180.1001453,11.919988632202148,0.0,1740481180.1001463,11.919988632202148,0.001224438647673715,, +1740481180.1220446,11.939988613128662,5.00192018280211,1740481180.1220465,11.939988613128662,0.0,1740481180.1220486,11.939988613128662,0.0,1740481180.1220503,11.939988613128662,7.004369060097456,1740481180.1220512,11.939988613128662,0.0,1740481180.1220527,11.939988613128662,0.0,1740481180.1220536,11.939988613128662,0.0,1740481180.1220543,11.939988613128662,0.0,1740481180.1220555,11.939988613128662,0.062461682217254705,1740481180.1220565,11.939988613128662,0.0,1740481180.1220572,11.939988613128662,0.06123724356958099,1740481180.122058,11.939988613128662,0.0,1740481180.122059,11.939988613128662,0.001224438647673715,, +1740481180.1381142,11.959988594055176,5.00192018280211,1740481180.1381276,11.959988594055176,0.0,1740481180.138131,11.959988594055176,0.0,1740481180.1381335,11.959988594055176,7.004369060097456,1740481180.1381347,11.959988594055176,0.0,1740481180.1381361,11.959988594055176,0.0,1740481180.138137,11.959988594055176,0.0,1740481180.138138,11.959988594055176,0.0,1740481180.1381388,11.959988594055176,0.062461682217254705,1740481180.13814,11.959988594055176,0.0,1740481180.1381407,11.959988594055176,0.06123724356958099,1740481180.1381416,11.959988594055176,0.0,1740481180.1381428,11.959988594055176,0.001224438647673715,, +1740481180.1594496,11.97998857498169,5.007452330469965,1740481180.159452,11.97998857498169,0.0,1740481180.1594543,11.97998857498169,5.642762957086539e-05,1740481180.1594565,11.97998857498169,7.186314179630248,1740481180.1594574,11.97998857498169,0.0,1740481180.1594589,11.97998857498169,0.0,1740481180.15946,11.97998857498169,0.0,1740481180.159461,11.97998857498169,0.0,1740481180.159462,11.97998857498169,0.062461682217254705,1740481180.1594632,11.97998857498169,1.0,1740481180.159464,11.97998857498169,0.9289545191257074,1740481180.159465,11.97998857498169,0.0,1740481180.1594658,11.97998857498169,0.09216878459928386,, +1740481180.178171,11.999988555908203,5.007452330469965,1740481180.1781726,11.999988555908203,0.0,1740481180.1781745,11.999988555908203,5.642762957086539e-05,1740481180.1781769,11.999988555908203,7.186314179630248,1740481180.1781778,11.999988555908203,0.0,1740481180.1781793,11.999988555908203,0.0,1740481180.1781807,11.999988555908203,0.0,1740481180.1781816,11.999988555908203,0.0,1740481180.1781824,11.999988555908203,0.062461682217254705,1740481180.1781838,11.999988555908203,1.0,1740481180.1781845,11.999988555908203,0.9702928976179709,1740481180.1781855,11.999988555908203,0.0,1740481180.1781862,11.999988555908203,0.09216878459928386,, +1740481180.1990712,12.019988536834717,5.007452330469965,1740481180.1990733,12.019988536834717,0.0,1740481180.1990752,12.019988536834717,5.642762957086539e-05,1740481180.1990774,12.019988536834717,7.186314179630248,1740481180.1990786,12.019988536834717,0.0,1740481180.19908,12.019988536834717,0.0,1740481180.199081,12.019988536834717,0.0,1740481180.199082,12.019988536834717,0.0,1740481180.199083,12.019988536834717,0.062461682217254705,1740481180.199084,12.019988536834717,1.0,1740481180.199085,12.019988536834717,0.9702928976179709,1740481180.1990857,12.019988536834717,0.0,1740481180.1990871,12.019988536834717,0.09216878459928386,, +1740481180.220615,12.03998851776123,5.007452330469965,1740481180.2206163,12.03998851776123,0.0,1740481180.2206187,12.03998851776123,0.0,1740481180.220621,12.03998851776123,7.1917898996685325,1740481180.220622,12.03998851776123,0.0,1740481180.2206237,12.03998851776123,0.0,1740481180.220625,12.03998851776123,0.0,1740481180.2206259,12.03998851776123,0.0,1740481180.2206268,12.03998851776123,0.15340602816886606,1740481180.2206283,12.03998851776123,0.0,1740481180.2206292,12.03998851776123,0.0612372435695822,1740481180.2206302,12.03998851776123,0.0,1740481180.2206314,12.03998851776123,0.09216878459928386,, +1740481180.2393374,12.059988498687744,5.007452330469965,1740481180.2393396,12.059988498687744,0.0,1740481180.2393415,12.059988498687744,0.0,1740481180.239344,12.059988498687744,7.1917898996685325,1740481180.2393446,12.059988498687744,0.0,1740481180.239346,12.059988498687744,0.0,1740481180.239347,12.059988498687744,0.0,1740481180.239348,12.059988498687744,0.0,1740481180.239349,12.059988498687744,0.15340602816886606,1740481180.23935,12.059988498687744,0.0,1740481180.2393508,12.059988498687744,0.0612372435695822,1740481180.2393515,12.059988498687744,0.0,1740481180.2393525,12.059988498687744,0.09216878459928386,, +1740481180.260268,12.079988479614258,5.0213710768713025,1740481180.2602706,12.079988479614258,0.0,1740481180.2602727,12.079988479614258,0.0003486799009973053,1740481180.2602746,12.079988479614258,7.311615676629449,1740481180.2602756,12.079988479614258,0.0,1740481180.2602773,12.079988479614258,0.0,1740481180.2602782,12.079988479614258,0.0,1740481180.2602792,12.079988479614258,0.0,1740481180.2602804,12.079988479614258,0.15340602816886606,1740481180.2602813,12.079988479614258,1.0,1740481180.2602823,12.079988479614258,0.9743447834481982,1740481180.2602835,12.079988479614258,0.0,1740481180.2602844,12.079988479614258,0.15190733312924354,, +1740481180.2781234,12.099988460540771,5.0213710768713025,1740481180.278125,12.099988460540771,0.0,1740481180.2781272,12.099988460540771,0.0003486799009973053,1740481180.2781289,12.099988460540771,7.311615676629449,1740481180.2781298,12.099988460540771,0.0,1740481180.2781312,12.099988460540771,0.0,1740481180.2781322,12.099988460540771,0.0,1740481180.278133,12.099988460540771,0.0,1740481180.278134,12.099988460540771,0.15340602816886606,1740481180.278135,12.099988460540771,1.0,1740481180.2781358,12.099988460540771,1.0014986950396225,1740481180.2781367,12.099988460540771,0.0,1740481180.2781377,12.099988460540771,0.15190733312924354,, +1740481180.3000617,12.119988441467285,5.0213710768713025,1740481180.3000638,12.119988441467285,0.0,1740481180.3000662,12.119988441467285,0.0003486799009973053,1740481180.3000684,12.119988441467285,7.311615676629449,1740481180.3000693,12.119988441467285,0.0,1740481180.3000708,12.119988441467285,0.0,1740481180.300072,12.119988441467285,0.0,1740481180.300073,12.119988441467285,0.0,1740481180.3000736,12.119988441467285,0.15340602816886606,1740481180.300096,12.119988441467285,1.0,1740481180.300097,12.119988441467285,1.0014986950396225,1740481180.3000977,12.119988441467285,0.0,1740481180.300099,12.119988441467285,0.15190733312924354,, +1740481180.320104,12.139988422393799,5.0213710768713025,1740481180.3201184,12.139988422393799,0.0,1740481180.3201218,12.139988422393799,0.0,1740481180.320124,12.139988422393799,7.32518574312979,1740481180.3201249,12.139988422393799,0.0,1740481180.3201263,12.139988422393799,0.0,1740481180.320127,12.139988422393799,0.0,1740481180.320128,12.139988422393799,0.0,1740481180.3201287,12.139988422393799,0.21314457669882347,1740481180.3201299,12.139988422393799,0.0,1740481180.3201306,12.139988422393799,0.061237243569579936,1740481180.3201313,12.139988422393799,0.0,1740481180.3201323,12.139988422393799,0.15190733312924354,, +1740481180.3380485,12.159988403320312,5.0213710768713025,1740481180.3380506,12.159988403320312,0.0,1740481180.3380647,12.159988403320312,0.0,1740481180.338069,12.159988403320312,7.32518574312979,1740481180.33807,12.159988403320312,0.0,1740481180.3380716,12.159988403320312,0.0,1740481180.3380725,12.159988403320312,0.0,1740481180.3380735,12.159988403320312,0.0,1740481180.3380747,12.159988403320312,0.21314457669882347,1740481180.3380756,12.159988403320312,0.0,1740481180.3380766,12.159988403320312,0.061237243569579936,1740481180.3380775,12.159988403320312,0.0,1740481180.3380785,12.159988403320312,0.15190733312924354,, +1740481180.3593473,12.179988384246826,5.0213710768713025,1740481180.35935,12.179988384246826,0.0,1740481180.3593526,12.179988384246826,0.0,1740481180.359355,12.179988384246826,7.32518574312979,1740481180.359356,12.179988384246826,0.0,1740481180.359357,12.179988384246826,0.0,1740481180.3593585,12.179988384246826,0.0,1740481180.3593595,12.179988384246826,0.0,1740481180.3593605,12.179988384246826,0.21314457669882347,1740481180.3593616,12.179988384246826,0.0,1740481180.3593626,12.179988384246826,0.061237243569579936,1740481180.3593636,12.179988384246826,0.0,1740481180.3593645,12.179988384246826,0.15190733312924354,, +1740481180.3780887,12.19998836517334,5.042542200091958,1740481180.3780904,12.19998836517334,0.0,1740481180.3780928,12.19998836517334,0.0007368898131376633,1740481180.378095,12.19998836517334,7.448820515642424,1740481180.3780959,12.19998836517334,0.0,1740481180.378097,12.19998836517334,0.0,1740481180.3780982,12.19998836517334,0.0,1740481180.378099,12.19998836517334,0.0,1740481180.3781,12.19998836517334,0.21314457669882347,1740481180.378101,12.19998836517334,1.0,1740481180.378102,12.19998836517334,0.9718569386052489,1740481180.3781028,12.19998836517334,0.0,1740481180.3781037,12.19998836517334,0.21335627447899205,, +1740481180.3986154,12.219988346099854,5.042542200091958,1740481180.3986187,12.219988346099854,0.0,1740481180.398621,12.219988346099854,0.0007368898131376633,1740481180.3986242,12.219988346099854,7.448820515642424,1740481180.3986266,12.219988346099854,0.0,1740481180.3986282,12.219988346099854,0.0,1740481180.3986301,12.219988346099854,0.0,1740481180.3986323,12.219988346099854,0.0,1740481180.398644,12.219988346099854,0.21314457669882347,1740481180.3986454,12.219988346099854,1.0,1740481180.3986473,12.219988346099854,0.9997883022198314,1740481180.3986487,12.219988346099854,0.0,1740481180.3986502,12.219988346099854,0.21335627447899205,, +1740481180.4209282,12.239988327026367,5.042542200091958,1740481180.4209301,12.239988327026367,0.0,1740481180.420932,12.239988327026367,0.0,1740481180.4209342,12.239988327026367,7.469254749049942,1740481180.4209352,12.239988327026367,0.0,1740481180.4209363,12.239988327026367,0.0,1740481180.4209375,12.239988327026367,0.0,1740481180.4209383,12.239988327026367,0.0,1740481180.4209392,12.239988327026367,0.27459351804857035,1740481180.4209404,12.239988327026367,0.0,1740481180.420941,12.239988327026367,0.0612372435695783,1740481180.420942,12.239988327026367,0.0,1740481180.4209428,12.239988327026367,0.21335627447899205,, +1740481180.4392996,12.25998830795288,5.042542200091958,1740481180.4393015,12.25998830795288,0.0,1740481180.4393034,12.25998830795288,0.0,1740481180.4393055,12.25998830795288,7.469254749049942,1740481180.4393067,12.25998830795288,0.0,1740481180.439308,12.25998830795288,0.0,1740481180.4393091,12.25998830795288,0.0,1740481180.43931,12.25998830795288,0.0,1740481180.4393108,12.25998830795288,0.27459351804857035,1740481180.439312,12.25998830795288,0.0,1740481180.439313,12.25998830795288,0.0612372435695783,1740481180.4393137,12.25998830795288,0.0,1740481180.4393146,12.25998830795288,0.21335627447899205,, +1740481180.4599204,12.279988288879395,5.042542200091958,1740481180.4599223,12.279988288879395,0.0,1740481180.4599245,12.279988288879395,0.0,1740481180.4599266,12.279988288879395,7.469254749049942,1740481180.4599276,12.279988288879395,0.0,1740481180.4599285,12.279988288879395,0.0,1740481180.4599297,12.279988288879395,0.0,1740481180.4599304,12.279988288879395,0.0,1740481180.4599314,12.279988288879395,0.27459351804857035,1740481180.4599323,12.279988288879395,0.0,1740481180.4599333,12.279988288879395,0.0612372435695783,1740481180.4599345,12.279988288879395,0.0,1740481180.4599352,12.279988288879395,0.21335627447899205,, +1740481180.4780855,12.299988269805908,5.069049716268669,1740481180.4780872,12.299988269805908,0.0,1740481180.4780893,12.299988269805908,0.0011886217761291023,1740481180.4780912,12.299988269805908,7.555103309723497,1740481180.4780922,12.299988269805908,0.0,1740481180.4780936,12.299988269805908,0.0,1740481180.4780946,12.299988269805908,0.0,1740481180.4780955,12.299988269805908,0.0,1740481180.4780967,12.299988269805908,0.27459351804857035,1740481180.4780977,12.299988269805908,1.0,1740481180.4780986,12.299988269805908,0.9996663605673398,1740481180.4780993,12.299988269805908,0.0,1740481180.4781005,12.299988269805908,0.25568624392770506,, +1740481180.4985926,12.319988250732422,5.069049716268669,1740481180.4985976,12.319988250732422,0.0,1740481180.4986012,12.319988250732422,0.0011886217761291023,1740481180.4986045,12.319988250732422,7.555103309723497,1740481180.498606,12.319988250732422,0.0,1740481180.4986084,12.319988250732422,0.0,1740481180.4986103,12.319988250732422,0.0,1740481180.4986129,12.319988250732422,0.0,1740481180.498615,12.319988250732422,0.27459351804857035,1740481180.498617,12.319988250732422,1.0,1740481180.4986181,12.319988250732422,1.0189072741208653,1740481180.4986193,12.319988250732422,0.0,1740481180.4986217,12.319988250732422,0.25568624392770506,, +1740481180.5215201,12.339988231658936,5.069049716268669,1740481180.5215218,12.339988231658936,0.0,1740481180.5215242,12.339988231658936,0.0,1740481180.5215418,12.339988231658936,7.580422204124079,1740481180.5215433,12.339988231658936,0.0,1740481180.5215456,12.339988231658936,0.0,1740481180.5215468,12.339988231658936,0.0,1740481180.5215478,12.339988231658936,0.0,1740481180.521549,12.339988231658936,0.31692348749728594,1740481180.5215502,12.339988231658936,0.0,1740481180.5215511,12.339988231658936,0.06123724356958088,1740481180.5215518,12.339988231658936,0.0,1740481180.521553,12.339988231658936,0.25568624392770506,, +1740481180.5408585,12.35998821258545,5.069049716268669,1740481180.5408607,12.35998821258545,0.0,1740481180.5408633,12.35998821258545,0.0,1740481180.540865,12.35998821258545,7.580422204124079,1740481180.5408661,12.35998821258545,0.0,1740481180.5408673,12.35998821258545,0.0,1740481180.5408683,12.35998821258545,0.0,1740481180.5408697,12.35998821258545,0.0,1740481180.5408704,12.35998821258545,0.31692348749728594,1740481180.5408714,12.35998821258545,0.0,1740481180.5408723,12.35998821258545,0.06123724356958088,1740481180.5408733,12.35998821258545,0.0,1740481180.5408742,12.35998821258545,0.25568624392770506,, +1740481180.5600405,12.379988193511963,5.069049716268669,1740481180.5600429,12.379988193511963,0.0,1740481180.560045,12.379988193511963,0.0,1740481180.5600474,12.379988193511963,7.580422204124079,1740481180.5600483,12.379988193511963,0.0,1740481180.5600498,12.379988193511963,0.0,1740481180.5600507,12.379988193511963,0.0,1740481180.5600514,12.379988193511963,0.0,1740481180.5600524,12.379988193511963,0.31692348749728594,1740481180.5600536,12.379988193511963,0.0,1740481180.5600543,12.379988193511963,0.06123724356958088,1740481180.5600555,12.379988193511963,0.0,1740481180.5600562,12.379988193511963,0.25568624392770506,, +1740481180.580196,12.399988174438477,5.069049716268669,1740481180.5801988,12.399988174438477,0.0,1740481180.580201,12.399988174438477,0.0,1740481180.5802033,12.399988174438477,7.580422204124079,1740481180.5802042,12.399988174438477,0.0,1740481180.580206,12.399988174438477,0.0,1740481180.580207,12.399988174438477,0.0,1740481180.5802085,12.399988174438477,0.0,1740481180.58021,12.399988174438477,0.31692348749728594,1740481180.580212,12.399988174438477,0.0,1740481180.5802138,12.399988174438477,0.06123724356958088,1740481180.5802155,12.399988174438477,0.0,1740481180.5802171,12.399988174438477,0.25568624392770506,, +1740481180.5990236,12.41998815536499,5.101184533156012,1740481180.5990257,12.41998815536499,0.0,1740481180.5990276,12.41998815536499,0.0016630856721125417,1740481180.5990298,12.41998815536499,7.686018469567536,1740481180.5990307,12.41998815536499,0.0,1740481180.5990322,12.41998815536499,0.0,1740481180.599033,12.41998815536499,0.0,1740481180.599034,12.41998815536499,0.0,1740481180.599035,12.41998815536499,0.31692348749728594,1740481180.5990362,12.41998815536499,1.0,1740481180.5990372,12.41998815536499,0.9856494539362171,1740481180.5990381,12.41998815536499,0.0,1740481180.599039,12.41998815536499,0.30765283381337716,, +1740481180.680607,12.439988136291504,5.101184533156012,1740481180.680609,12.439988136291504,0.0,1740481180.6806111,12.439988136291504,0.0,1740481180.680613,12.439988136291504,7.716490200782766,1740481180.6806142,12.439988136291504,0.0,1740481180.6806154,12.439988136291504,0.0,1740481180.6806164,12.439988136291504,0.0,1740481180.6806176,12.439988136291504,0.0,1740481180.6806185,12.439988136291504,0.36889007738295815,1740481180.6806195,12.439988136291504,0.0,1740481180.6806202,12.439988136291504,0.06123724356958099,1740481180.6806214,12.439988136291504,0.0,1740481180.680622,12.439988136291504,0.30765283381337716,, +1740481180.6835814,12.459988117218018,5.101184533156012,1740481180.6835833,12.459988117218018,0.0,1740481180.6835852,12.459988117218018,0.0,1740481180.6835873,12.459988117218018,7.716490200782766,1740481180.6835883,12.459988117218018,0.0,1740481180.6835897,12.459988117218018,0.0,1740481180.6835907,12.459988117218018,0.0,1740481180.6835914,12.459988117218018,0.0,1740481180.6835926,12.459988117218018,0.36889007738295815,1740481180.6835933,12.459988117218018,0.0,1740481180.683594,12.459988117218018,0.06123724356958099,1740481180.683595,12.459988117218018,0.0,1740481180.6835957,12.459988117218018,0.30765283381337716,, +1740481180.7056513,12.479988098144531,5.101184533156012,1740481180.7056532,12.479988098144531,0.0,1740481180.7056553,12.479988098144531,0.0,1740481180.7056572,12.479988098144531,7.716490200782766,1740481180.7056584,12.479988098144531,0.0,1740481180.7056596,12.479988098144531,0.0,1740481180.7056603,12.479988098144531,0.0,1740481180.7056615,12.479988098144531,0.0,1740481180.7056625,12.479988098144531,0.36889007738295815,1740481180.7056632,12.479988098144531,0.0,1740481180.7056642,12.479988098144531,0.06123724356958099,1740481180.705665,12.479988098144531,0.0,1740481180.705666,12.479988098144531,0.30765283381337716,, +1740481180.7269907,12.499988079071045,5.101184533156012,1740481180.7269928,12.499988079071045,0.0,1740481180.7269955,12.499988079071045,0.0,1740481180.7269976,12.499988079071045,7.716490200782766,1740481180.7269988,12.499988079071045,0.0,1740481180.7270002,12.499988079071045,0.0,1740481180.7270014,12.499988079071045,0.0,1740481180.7270024,12.499988079071045,0.0,1740481180.727003,12.499988079071045,0.36889007738295815,1740481180.7270048,12.499988079071045,0.0,1740481180.7270055,12.499988079071045,0.06123724356958099,1740481180.7270064,12.499988079071045,0.0,1740481180.7270072,12.499988079071045,0.30765283381337716,, +1740481180.7479312,12.519988059997559,5.138040942771699,1740481180.7479334,12.519988059997559,0.0,1740481180.7479358,12.519988059997559,0.00222021159063778,1740481180.7479374,12.519988059997559,7.802202394660881,1740481180.7479386,12.519988059997559,0.0,1740481180.7479396,12.519988059997559,0.0,1740481180.7479405,12.519988059997559,0.0,1740481180.7479415,12.519988059997559,0.0,1740481180.7479424,12.519988059997559,0.36889007738295815,1740481180.7479436,12.519988059997559,1.0,1740481180.7479446,12.519988059997559,1.0005157838095442,1740481180.7479455,12.519988059997559,0.0,1740481180.7479465,12.519988059997559,0.34939882495711583,, +1740481180.7664402,12.539988040924072,5.138040942771699,1740481180.766442,12.539988040924072,0.0,1740481180.7664576,12.539988040924072,0.0,1740481180.7664611,12.539988040924072,7.836838592685931,1740481180.7664623,12.539988040924072,0.0,1740481180.7664635,12.539988040924072,0.0,1740481180.7664645,12.539988040924072,0.0,1740481180.7664652,12.539988040924072,0.0,1740481180.7664664,12.539988040924072,0.4106360685266966,1740481180.766467,12.539988040924072,0.0,1740481180.766468,12.539988040924072,0.06123724356958077,1740481180.7664688,12.539988040924072,0.0,1740481180.76647,12.539988040924072,0.34939882495711583,, +1740481180.7843246,12.559988021850586,5.138040942771699,1740481180.7843263,12.559988021850586,0.0,1740481180.7843287,12.559988021850586,0.0,1740481180.7843306,12.559988021850586,7.836838592685931,1740481180.7843316,12.559988021850586,0.0,1740481180.784333,12.559988021850586,0.0,1740481180.7843342,12.559988021850586,0.0,1740481180.7843351,12.559988021850586,0.0,1740481180.7843359,12.559988021850586,0.4106360685266966,1740481180.784337,12.559988021850586,0.0,1740481180.7843382,12.559988021850586,0.06123724356958077,1740481180.784339,12.559988021850586,0.0,1740481180.7843397,12.559988021850586,0.34939882495711583,, +1740481180.80722,12.5799880027771,5.138040942771699,1740481180.8072217,12.5799880027771,0.0,1740481180.8072367,12.5799880027771,0.0,1740481180.80724,12.5799880027771,7.836838592685931,1740481180.807241,12.5799880027771,0.0,1740481180.8072422,12.5799880027771,0.0,1740481180.8072433,12.5799880027771,0.0,1740481180.8072443,12.5799880027771,0.0,1740481180.8072453,12.5799880027771,0.4106360685266966,1740481180.8072464,12.5799880027771,0.0,1740481180.8072472,12.5799880027771,0.06123724356958077,1740481180.8072479,12.5799880027771,0.0,1740481180.8072488,12.5799880027771,0.34939882495711583,, +1740481180.829262,12.599987983703613,5.138040942771699,1740481180.8292642,12.599987983703613,0.0,1740481180.8292668,12.599987983703613,0.0,1740481180.8292685,12.599987983703613,7.836838592685931,1740481180.8292694,12.599987983703613,0.0,1740481180.829271,12.599987983703613,0.0,1740481180.8292718,12.599987983703613,0.0,1740481180.8292727,12.599987983703613,0.0,1740481180.8292737,12.599987983703613,0.4106360685266966,1740481180.8292747,12.599987983703613,0.0,1740481180.8292754,12.599987983703613,0.06123724356958077,1740481180.8292763,12.599987983703613,0.0,1740481180.8292773,12.599987983703613,0.34939882495711583,, +1740481180.8446515,12.619987964630127,5.138040942771699,1740481180.8446536,12.619987964630127,0.0,1740481180.844656,12.619987964630127,0.0,1740481180.8446577,12.619987964630127,7.836838592685931,1740481180.8446584,12.619987964630127,0.0,1740481180.84466,12.619987964630127,0.0,1740481180.8446612,12.619987964630127,0.0,1740481180.844662,12.619987964630127,0.0,1740481180.8446631,12.619987964630127,0.4106360685266966,1740481180.8446639,12.619987964630127,0.0,1740481180.8446646,12.619987964630127,0.06123724356958077,1740481180.8446655,12.619987964630127,0.0,1740481180.8446667,12.619987964630127,0.34939882495711583,, +1740481180.868065,12.63998794555664,5.178487725666972,1740481180.8680668,12.63998794555664,0.0,1740481180.868069,12.63998794555664,0.0,1740481180.8680708,12.63998794555664,7.923965857720077,1740481180.868072,12.63998794555664,0.0,1740481180.8680732,12.63998794555664,0.0,1740481180.868074,12.63998794555664,0.0,1740481180.868075,12.63998794555664,0.0,1740481180.8680758,12.63998794555664,0.43397630959612915,1740481180.868077,12.63998794555664,1.0,1740481180.8680778,12.63998794555664,1.061237243569575,1740481180.868079,12.63998794555664,0.0,1740481180.8680797,12.63998794555664,0.37273906602655243,, +1740481180.8841748,12.659987926483154,5.178487725666972,1740481180.8841767,12.659987926483154,0.0,1740481180.8841786,12.659987926483154,0.0,1740481180.8841808,12.659987926483154,7.923965857720077,1740481180.8841817,12.659987926483154,0.0,1740481180.8841827,12.659987926483154,0.0,1740481180.8841841,12.659987926483154,0.0,1740481180.884185,12.659987926483154,0.0,1740481180.884186,12.659987926483154,0.43397630959612915,1740481180.8841872,12.659987926483154,1.0,1740481180.8841882,12.659987926483154,1.0612372435695767,1740481180.884189,12.659987926483154,0.0,1740481180.8841903,12.659987926483154,0.37273906602655243,, +1740481180.9050875,12.679987907409668,5.178487725666972,1740481180.9050899,12.679987907409668,0.0,1740481180.9050927,12.679987907409668,0.0,1740481180.9050946,12.679987907409668,7.923965857720077,1740481180.9050956,12.679987907409668,0.0,1740481180.905097,12.679987907409668,0.0,1740481180.905098,12.679987907409668,0.0,1740481180.9050992,12.679987907409668,0.0,1740481180.9051,12.679987907409668,0.43397630959612915,1740481180.9051013,12.679987907409668,1.0,1740481180.9051023,12.679987907409668,1.0612372435695767,1740481180.9051034,12.679987907409668,0.0,1740481180.9051044,12.679987907409668,0.37273906602655243,, +1740481180.9277186,12.699987888336182,5.178487725666972,1740481180.927721,12.699987888336182,0.0,1740481180.9277232,12.699987888336182,0.0,1740481180.9277253,12.699987888336182,7.923965857720077,1740481180.9277265,12.699987888336182,0.0,1740481180.9277465,12.699987888336182,0.0,1740481180.9277475,12.699987888336182,0.0,1740481180.927749,12.699987888336182,0.0,1740481180.9277496,12.699987888336182,0.43397630959612915,1740481180.9277508,12.699987888336182,1.0,1740481180.9277518,12.699987888336182,1.0612372435695767,1740481180.9277527,12.699987888336182,0.0,1740481180.9277537,12.699987888336182,0.37273906602655243,, +1740481180.9440837,12.719987869262695,5.178487725666972,1740481180.9440868,12.719987869262695,0.0,1740481180.9440897,12.719987869262695,0.0,1740481180.9440925,12.719987869262695,7.923965857720077,1740481180.944094,12.719987869262695,0.0,1740481180.9440963,12.719987869262695,0.0,1740481180.944098,12.719987869262695,0.0,1740481180.9440997,12.719987869262695,0.0,1740481180.9441018,12.719987869262695,0.43397630959612915,1740481180.9441037,12.719987869262695,1.0,1740481180.944105,12.719987869262695,1.0612372435695767,1740481180.9441063,12.719987869262695,0.0,1740481180.9441075,12.719987869262695,0.37273906602655243,, +1740481180.9697506,12.739987850189209,5.223933206777517,1740481180.9697528,12.739987850189209,0.0,1740481180.9697552,12.739987850189209,0.0,1740481180.969757,12.739987850189209,8.165714091726372,1740481180.9697585,12.739987850189209,0.0,1740481180.9697602,12.739987850189209,0.0,1740481180.9697616,12.739987850189209,0.0,1740481180.9697626,12.739987850189209,0.0,1740481180.9697635,12.739987850189209,0.5321276860440062,1740481180.9697647,12.739987850189209,1.0,1740481180.9697657,12.739987850189209,1.0612372435695796,1740481180.9697666,12.739987850189209,0.0,1740481180.9697676,12.739987850189209,0.4708904424744274,, +1740481180.9846766,12.759987831115723,5.223933206777517,1740481180.9846785,12.759987831115723,0.0,1740481180.984681,12.759987831115723,0.0,1740481180.9846828,12.759987831115723,8.165714091726372,1740481180.9846838,12.759987831115723,0.0,1740481180.984685,12.759987831115723,0.0,1740481180.9846861,12.759987831115723,0.0,1740481180.9846869,12.759987831115723,0.0,1740481180.9846878,12.759987831115723,0.5321276860440062,1740481180.9846888,12.759987831115723,1.0,1740481180.9846897,12.759987831115723,1.0612372435695787,1740481180.9846904,12.759987831115723,0.0,1740481180.9846914,12.759987831115723,0.4708904424744274,, +1740481181.003739,12.779987812042236,5.223933206777517,1740481181.003741,12.779987812042236,0.0,1740481181.0037432,12.779987812042236,0.0,1740481181.003745,12.779987812042236,8.165714091726372,1740481181.003746,12.779987812042236,0.0,1740481181.0037472,12.779987812042236,0.0,1740481181.0037484,12.779987812042236,0.0,1740481181.0037494,12.779987812042236,0.0,1740481181.0037503,12.779987812042236,0.5321276860440062,1740481181.0037515,12.779987812042236,1.0,1740481181.0037522,12.779987812042236,1.0612372435695787,1740481181.0037532,12.779987812042236,0.0,1740481181.003754,12.779987812042236,0.4708904424744274,, +1740481181.0238867,12.79998779296875,5.223933206777517,1740481181.0238883,12.79998779296875,0.0,1740481181.0238907,12.79998779296875,0.0,1740481181.0238929,12.79998779296875,8.165714091726372,1740481181.023894,12.79998779296875,0.0,1740481181.0238953,12.79998779296875,0.0,1740481181.0238962,12.79998779296875,0.0,1740481181.0238974,12.79998779296875,0.0,1740481181.0238986,12.79998779296875,0.5321276860440062,1740481181.0238996,12.79998779296875,1.0,1740481181.0239007,12.79998779296875,1.0612372435695787,1740481181.0239015,12.79998779296875,0.0,1740481181.0239024,12.79998779296875,0.4708904424744274,, +1740481181.0435474,12.819987773895264,5.223933206777517,1740481181.04355,12.819987773895264,0.0,1740481181.0435543,12.819987773895264,0.0,1740481181.0435567,12.819987773895264,8.165714091726372,1740481181.043558,12.819987773895264,0.0,1740481181.0435598,12.819987773895264,0.0,1740481181.0435612,12.819987773895264,0.0,1740481181.0435627,12.819987773895264,0.0,1740481181.0435638,12.819987773895264,0.5321276860440062,1740481181.0435658,12.819987773895264,1.0,1740481181.0435672,12.819987773895264,1.0612372435695787,1740481181.0435686,12.819987773895264,0.0,1740481181.0435703,12.819987773895264,0.4708904424744274,, +1740481181.066799,12.839987754821777,5.223933206777517,1740481181.0668006,12.839987754821777,0.0,1740481181.0668027,12.839987754821777,0.0,1740481181.0668044,12.839987754821777,8.165714091726372,1740481181.0668056,12.839987754821777,0.0,1740481181.0668068,12.839987754821777,0.0,1740481181.0668077,12.839987754821777,0.0,1740481181.066809,12.839987754821777,0.0,1740481181.0668097,12.839987754821777,0.5321276860440062,1740481181.0668106,12.839987754821777,1.0,1740481181.0668116,12.839987754821777,1.0612372435695787,1740481181.0668128,12.839987754821777,0.0,1740481181.0668137,12.839987754821777,0.4708904424744274,, +1740481181.0837624,12.859987735748291,5.281079846967561,1740481181.083764,12.859987735748291,0.0,1740481181.0837662,12.859987735748291,0.004965819432248915,1740481181.0837681,12.859987735748291,8.384369399637807,1740481181.083769,12.859987735748291,0.0,1740481181.0837703,12.859987735748291,0.0,1740481181.0837717,12.859987735748291,0.0,1740481181.0837727,12.859987735748291,0.0,1740481181.0837736,12.859987735748291,0.6546021731831678,1740481181.0837748,12.859987735748291,0.0,1740481181.0837755,12.859987735748291,0.08397142183517822,1740481181.0837765,12.859987735748291,0.0,1740481181.0837772,12.859987735748291,0.5777351867140202,, +1740481181.1048238,12.879987716674805,5.281079846967561,1740481181.1048255,12.879987716674805,0.0,1740481181.104828,12.879987716674805,0.004965819432248915,1740481181.1048298,12.879987716674805,8.384369399637807,1740481181.1048307,12.879987716674805,0.0,1740481181.104832,12.879987716674805,0.0,1740481181.1048331,12.879987716674805,0.0,1740481181.104834,12.879987716674805,0.0,1740481181.1048348,12.879987716674805,0.6546021731831678,1740481181.1048357,12.879987716674805,0.0,1740481181.1048367,12.879987716674805,0.07686698646914758,1740481181.1048377,12.879987716674805,0.0,1740481181.1048386,12.879987716674805,0.5777351867140202,, +1740481181.1240883,12.899987697601318,5.281079846967561,1740481181.1240907,12.899987697601318,0.0,1740481181.1240926,12.899987697601318,0.004965819432248915,1740481181.1240947,12.899987697601318,8.384369399637807,1740481181.1240957,12.899987697601318,0.0,1740481181.124097,12.899987697601318,0.0,1740481181.124098,12.899987697601318,0.0,1740481181.124099,12.899987697601318,0.0,1740481181.1241002,12.899987697601318,0.6546021731831678,1740481181.1241012,12.899987697601318,0.0,1740481181.1241019,12.899987697601318,0.07686698646914758,1740481181.1241028,12.899987697601318,0.0,1740481181.1241038,12.899987697601318,0.5777351867140202,, +1740481181.1454885,12.919987678527832,5.281079846967561,1740481181.1454902,12.919987678527832,0.0,1740481181.1454926,12.919987678527832,0.004965819432248915,1740481181.1454945,12.919987678527832,8.384369399637807,1740481181.145496,12.919987678527832,0.0,1740481181.145497,12.919987678527832,0.0,1740481181.145498,12.919987678527832,0.0,1740481181.1454992,12.919987678527832,0.0,1740481181.1455002,12.919987678527832,0.6546021731831678,1740481181.1455011,12.919987678527832,0.0,1740481181.145502,12.919987678527832,0.07686698646914758,1740481181.1455033,12.919987678527832,0.0,1740481181.1455042,12.919987678527832,0.5777351867140202,, +1740481181.166621,12.939987659454346,5.281079846967561,1740481181.1666224,12.939987659454346,0.0,1740481181.1666245,12.939987659454346,0.0,1740481181.1666265,12.939987659454346,8.436550220395603,1740481181.1666276,12.939987659454346,0.0,1740481181.166629,12.939987659454346,0.0,1740481181.16663,12.939987659454346,0.0,1740481181.1666312,12.939987659454346,0.0,1740481181.166632,12.939987659454346,0.6389724302836005,1740481181.166633,12.939987659454346,0.0,1740481181.1666338,12.939987659454346,0.06123724356958027,1740481181.1666348,12.939987659454346,0.0,1740481181.1666358,12.939987659454346,0.5777351867140202,, +1740481181.1839092,12.95998764038086,5.345806859456825,1740481181.1839132,12.95998764038086,0.0,1740481181.1839166,12.95998764038086,0.0067538599166811234,1740481181.183919,12.95998764038086,8.471101992745144,1740481181.18392,12.95998764038086,0.0,1740481181.183921,12.95998764038086,0.0,1740481181.1839223,12.95998764038086,0.0,1740481181.1839232,12.95998764038086,0.0,1740481181.1839242,12.95998764038086,0.6389724302836005,1740481181.183925,12.95998764038086,1.0,1740481181.183926,12.95998764038086,1.0410205739570033,1740481181.183927,12.95998764038086,0.0,1740481181.183928,12.95998764038086,0.5916341429304511,, +1740481181.203452,12.979987621307373,5.345806859456825,1740481181.203454,12.979987621307373,0.0,1740481181.203456,12.979987621307373,0.0067538599166811234,1740481181.2034578,12.979987621307373,8.471101992745144,1740481181.2034588,12.979987621307373,0.0,1740481181.20346,12.979987621307373,0.0,1740481181.2034612,12.979987621307373,0.0,1740481181.2034621,12.979987621307373,0.0,1740481181.203463,12.979987621307373,0.6389724302836005,1740481181.2034643,12.979987621307373,1.0,1740481181.2034652,12.979987621307373,1.0473382873531494,1740481181.203466,12.979987621307373,0.0,1740481181.203467,12.979987621307373,0.5916341429304511,, +1740481181.22535,12.999987602233887,5.345806859456825,1740481181.2253551,12.999987602233887,0.0,1740481181.2253604,12.999987602233887,0.0067538599166811234,1740481181.225363,12.999987602233887,8.471101992745144,1740481181.225364,12.999987602233887,0.0,1740481181.2253654,12.999987602233887,0.0,1740481181.2253666,12.999987602233887,0.0,1740481181.2253678,12.999987602233887,0.0,1740481181.2253687,12.999987602233887,0.6389724302836005,1740481181.22537,12.999987602233887,1.0,1740481181.225371,12.999987602233887,1.0473382873531494,1740481181.2253718,12.999987602233887,0.0,1740481181.225373,12.999987602233887,0.5916341429304511,, +1740481181.2450511,13.0199875831604,5.345806859456825,1740481181.2450533,13.0199875831604,0.0,1740481181.2450552,13.0199875831604,0.0067538599166811234,1740481181.245057,13.0199875831604,8.471101992745144,1740481181.245058,13.0199875831604,0.0,1740481181.2450595,13.0199875831604,0.0,1740481181.2450607,13.0199875831604,0.0,1740481181.2450616,13.0199875831604,0.0,1740481181.2450626,13.0199875831604,0.6389724302836005,1740481181.245064,13.0199875831604,1.0,1740481181.245065,13.0199875831604,1.0473382873531494,1740481181.2450657,13.0199875831604,0.0,1740481181.2450666,13.0199875831604,0.5916341429304511,, +1740481181.2673166,13.039987564086914,5.345806859456825,1740481181.2673187,13.039987564086914,0.0,1740481181.267321,13.039987564086914,0.0,1740481181.267323,13.039987564086914,8.529075145317726,1740481181.2673242,13.039987564086914,0.0,1740481181.2673254,13.039987564086914,0.0,1740481181.2673268,13.039987564086914,0.0,1740481181.2673278,13.039987564086914,0.0,1740481181.2673287,13.039987564086914,0.6528713865000293,1740481181.2673297,13.039987564086914,0.0,1740481181.267331,13.039987564086914,0.06123724356957816,1740481181.2673318,13.039987564086914,0.0,1740481181.2673326,13.039987564086914,0.5916341429304511,, +1740481181.2839003,13.059987545013428,5.345806859456825,1740481181.2839017,13.059987545013428,0.0,1740481181.2839043,13.059987545013428,0.0,1740481181.2839062,13.059987545013428,8.529075145317726,1740481181.2839072,13.059987545013428,0.0,1740481181.2839084,13.059987545013428,0.0,1740481181.2839093,13.059987545013428,0.0,1740481181.2839105,13.059987545013428,0.0,1740481181.2839112,13.059987545013428,0.6528713865000293,1740481181.2839122,13.059987545013428,0.0,1740481181.283913,13.059987545013428,0.06123724356957816,1740481181.283914,13.059987545013428,0.0,1740481181.283915,13.059987545013428,0.5916341429304511,, +1740481181.3037357,13.079987525939941,5.415913165338189,1740481181.3037376,13.079987525939941,0.0,1740481181.3038213,13.079987525939941,0.007474275204950325,1740481181.3038454,13.079987525939941,8.692317794801673,1740481181.3038473,13.079987525939941,0.0,1740481181.3038497,13.079987525939941,0.0,1740481181.3038516,13.079987525939941,0.0,1740481181.3038533,13.079987525939941,0.0,1740481181.3038552,13.079987525939941,0.6528713865000293,1740481181.303857,13.079987525939941,1.0,1740481181.3038588,13.079987525939941,0.9479511194229369,1740481181.3038607,13.079987525939941,0.0,1740481181.3038628,13.079987525939941,0.6695183300699483,, +1740481181.324158,13.099987506866455,5.415913165338189,1740481181.3241599,13.099987506866455,0.0,1740481181.3241618,13.099987506866455,0.007474275204950325,1740481181.324164,13.099987506866455,8.692317794801673,1740481181.3241649,13.099987506866455,0.0,1740481181.324166,13.099987506866455,0.0,1740481181.3241673,13.099987506866455,0.0,1740481181.3241682,13.099987506866455,0.0,1740481181.3241692,13.099987506866455,0.6528713865000293,1740481181.3241704,13.099987506866455,1.0,1740481181.3241713,13.099987506866455,0.983353056430081,1740481181.3241723,13.099987506866455,0.0,1740481181.324173,13.099987506866455,0.6695183300699483,, +1740481181.3440688,13.119987487792969,5.415913165338189,1740481181.344071,13.119987487792969,0.0,1740481181.344073,13.119987487792969,0.007474275204950325,1740481181.344075,13.119987487792969,8.692317794801673,1740481181.344076,13.119987487792969,0.0,1740481181.3440776,13.119987487792969,0.0,1740481181.3440785,13.119987487792969,0.0,1740481181.3440797,13.119987487792969,0.0,1740481181.3440807,13.119987487792969,0.6528713865000293,1740481181.3440819,13.119987487792969,1.0,1740481181.3440826,13.119987487792969,0.983353056430081,1740481181.344084,13.119987487792969,0.0,1740481181.344085,13.119987487792969,0.6695183300699483,, +1740481181.3673885,13.139987468719482,5.415913165338189,1740481181.3673902,13.139987468719482,0.0,1740481181.3673925,13.139987468719482,0.0,1740481181.3673942,13.139987468719482,8.754949825478086,1740481181.3673954,13.139987468719482,0.0,1740481181.3673966,13.139987468719482,0.0,1740481181.3673975,13.139987468719482,0.0,1740481181.3673987,13.139987468719482,0.0,1740481181.3673995,13.139987468719482,0.7307555736395281,1740481181.3674002,13.139987468719482,0.0,1740481181.3674011,13.139987468719482,0.061237243569579825,1740481181.367402,13.139987468719482,0.0,1740481181.367403,13.139987468719482,0.6695183300699483,, +1740481181.3836367,13.159987449645996,5.415913165338189,1740481181.3836384,13.159987449645996,0.0,1740481181.3836405,13.159987449645996,0.0,1740481181.3836427,13.159987449645996,8.754949825478086,1740481181.3836436,13.159987449645996,0.0,1740481181.3836448,13.159987449645996,0.0,1740481181.383646,13.159987449645996,0.0,1740481181.383647,13.159987449645996,0.0,1740481181.3836477,13.159987449645996,0.7307555736395281,1740481181.3836489,13.159987449645996,0.0,1740481181.3836498,13.159987449645996,0.061237243569579825,1740481181.3836505,13.159987449645996,0.0,1740481181.3836515,13.159987449645996,0.6695183300699483,, +1740481181.4038584,13.17998743057251,5.493217368318382,1740481181.403861,13.17998743057251,0.0,1740481181.403863,13.17998743057251,0.009224856296699741,1740481181.403865,13.17998743057251,8.878066666875243,1740481181.403866,13.17998743057251,0.0,1740481181.403868,13.17998743057251,0.0,1740481181.4038687,13.17998743057251,0.0,1740481181.4038696,13.17998743057251,0.0,1740481181.4038708,13.17998743057251,0.7307555736395281,1740481181.4038718,13.17998743057251,1.0,1740481181.4038727,13.17998743057251,0.9784066842656188,1740481181.4038737,13.17998743057251,0.0,1740481181.4038746,13.17998743057251,0.726464322620177,, +1740481181.4238591,13.199987411499023,5.493217368318382,1740481181.4238615,13.199987411499023,0.0,1740481181.4238641,13.199987411499023,0.009224856296699741,1740481181.423866,13.199987411499023,8.878066666875243,1740481181.4238672,13.199987411499023,0.0,1740481181.4238682,13.199987411499023,0.0,1740481181.4238691,13.199987411499023,0.0,1740481181.4238703,13.199987411499023,0.0,1740481181.4238713,13.199987411499023,0.7307555736395281,1740481181.4238722,13.199987411499023,1.0,1740481181.423873,13.199987411499023,1.0042912510193511,1740481181.4238744,13.199987411499023,0.0,1740481181.423875,13.199987411499023,0.726464322620177,, +1740481181.44476,13.219987392425537,5.493217368318382,1740481181.4447849,13.219987392425537,0.0,1740481181.4447873,13.219987392425537,0.009224856296699741,1740481181.4447894,13.219987392425537,8.878066666875243,1740481181.4447908,13.219987392425537,0.0,1740481181.4448164,13.219987392425537,0.0,1740481181.4448173,13.219987392425537,0.0,1740481181.4448185,13.219987392425537,0.0,1740481181.4448195,13.219987392425537,0.7307555736395281,1740481181.4448216,13.219987392425537,1.0,1740481181.4448225,13.219987392425537,1.0042912510193511,1740481181.4448235,13.219987392425537,0.0,1740481181.444842,13.219987392425537,0.726464322620177,, +1740481181.4669876,13.23998737335205,5.493217368318382,1740481181.4669893,13.23998737335205,0.0,1740481181.4669914,13.23998737335205,0.0,1740481181.4669933,13.23998737335205,8.946146013558735,1740481181.4669945,13.23998737335205,0.0,1740481181.4670062,13.23998737335205,0.0,1740481181.4670086,13.23998737335205,0.0,1740481181.4670095,13.23998737335205,0.0,1740481181.4670103,13.23998737335205,0.7877015661897561,1740481181.4670112,13.23998737335205,0.0,1740481181.4670122,13.23998737335205,0.06123724356957905,1740481181.4670131,13.23998737335205,0.0,1740481181.4670138,13.23998737335205,0.726464322620177,, +1740481181.4840307,13.259987354278564,5.493217368318382,1740481181.4840326,13.259987354278564,0.0,1740481181.4840345,13.259987354278564,0.0,1740481181.4840367,13.259987354278564,8.946146013558735,1740481181.4840376,13.259987354278564,0.0,1740481181.4840388,13.259987354278564,0.0,1740481181.4840403,13.259987354278564,0.0,1740481181.4840412,13.259987354278564,0.0,1740481181.4840422,13.259987354278564,0.7877015661897561,1740481181.4840434,13.259987354278564,0.0,1740481181.484044,13.259987354278564,0.06123724356957905,1740481181.484045,13.259987354278564,0.0,1740481181.484046,13.259987354278564,0.726464322620177,, +1740481181.5050364,13.279987335205078,5.493217368318382,1740481181.5050387,13.279987335205078,0.0,1740481181.5050414,13.279987335205078,0.0,1740481181.505044,13.279987335205078,8.946146013558735,1740481181.5050452,13.279987335205078,0.0,1740481181.5050468,13.279987335205078,0.0,1740481181.5050483,13.279987335205078,0.0,1740481181.5050492,13.279987335205078,0.0,1740481181.5050507,13.279987335205078,0.7877015661897561,1740481181.5050523,13.279987335205078,0.0,1740481181.5050538,13.279987335205078,0.06123724356957905,1740481181.5050547,13.279987335205078,0.0,1740481181.505056,13.279987335205078,0.726464322620177,, +1740481181.523896,13.299987316131592,5.577410315180376,1740481181.523899,13.299987316131592,0.0,1740481181.5239022,13.299987316131592,0.010829833650165993,1740481181.5239043,13.299987316131592,9.072526800533833,1740481181.5239053,13.299987316131592,0.0,1740481181.5239065,13.299987316131592,0.0,1740481181.5239077,13.299987316131592,0.0,1740481181.5239086,13.299987316131592,0.0,1740481181.5239093,13.299987316131592,0.7877015661897561,1740481181.52391,13.299987316131592,1.0,1740481181.5239112,13.299987316131592,0.9772001615609737,1740481181.523912,13.299987316131592,0.0,1740481181.523913,13.299987316131592,0.7842397992826429,, +1740481181.5445962,13.319987297058105,5.577410315180376,1740481181.5445986,13.319987297058105,0.0,1740481181.5446005,13.319987297058105,0.010829833650165993,1740481181.5446026,13.319987297058105,9.072526800533833,1740481181.5446038,13.319987297058105,0.0,1740481181.5446053,13.319987297058105,0.0,1740481181.5446064,13.319987297058105,0.0,1740481181.5446076,13.319987297058105,0.0,1740481181.5446086,13.319987297058105,0.7877015661897561,1740481181.5446098,13.319987297058105,1.0,1740481181.5446107,13.319987297058105,1.003461766907113,1740481181.544612,13.319987297058105,0.0,1740481181.544613,13.319987297058105,0.7842397992826429,, +1740481181.5669894,13.33998727798462,5.577410315180376,1740481181.566991,13.33998727798462,0.0,1740481181.5669935,13.33998727798462,0.0,1740481181.5669959,13.33998727798462,9.145889913745663,1740481181.566997,13.33998727798462,0.0,1740481181.5669982,13.33998727798462,0.0,1740481181.566999,13.33998727798462,0.0,1740481181.5670002,13.33998727798462,0.0,1740481181.5670009,13.33998727798462,0.8454770428522242,1740481181.5670018,13.33998727798462,0.0,1740481181.5670025,13.33998727798462,0.06123724356958138,1740481181.5670037,13.33998727798462,0.0,1740481181.5670044,13.33998727798462,0.7842397992826429,, +1740481181.5839179,13.359987258911133,5.577410315180376,1740481181.5839195,13.359987258911133,0.0,1740481181.5839217,13.359987258911133,0.0,1740481181.5839238,13.359987258911133,9.145889913745663,1740481181.5839245,13.359987258911133,0.0,1740481181.583926,13.359987258911133,0.0,1740481181.5839274,13.359987258911133,0.0,1740481181.5839283,13.359987258911133,0.0,1740481181.5839293,13.359987258911133,0.8454770428522242,1740481181.5839303,13.359987258911133,0.0,1740481181.5839312,13.359987258911133,0.06123724356958138,1740481181.5839322,13.359987258911133,0.0,1740481181.5839329,13.359987258911133,0.7842397992826429,, +1740481181.604953,13.379987239837646,5.577410315180376,1740481181.6049552,13.379987239837646,0.0,1740481181.604957,13.379987239837646,0.0,1740481181.6049595,13.379987239837646,9.145889913745663,1740481181.6049604,13.379987239837646,0.0,1740481181.6049619,13.379987239837646,0.0,1740481181.6049628,13.379987239837646,0.0,1740481181.6049638,13.379987239837646,0.0,1740481181.6049645,13.379987239837646,0.8454770428522242,1740481181.6049662,13.379987239837646,0.0,1740481181.6049669,13.379987239837646,0.06123724356958138,1740481181.6049678,13.379987239837646,0.0,1740481181.604969,13.379987239837646,0.7842397992826429,, +1740481181.623981,13.39998722076416,5.66653526964325,1740481181.6239827,13.39998722076416,0.0,1740481181.6239848,13.39998722076416,0.012305110183150367,1740481181.6239867,13.39998722076416,9.235499007343524,1740481181.6239877,13.39998722076416,0.0,1740481181.623989,13.39998722076416,0.0,1740481181.62399,13.39998722076416,0.0,1740481181.623991,13.39998722076416,0.0,1740481181.623992,13.39998722076416,0.8454770428522242,1740481181.623993,13.39998722076416,1.0,1740481181.6239939,13.39998722076416,1.0050161479673159,1740481181.6239946,13.39998722076416,0.0,1740481181.623996,13.39998722076416,0.8228917909899981,, +1740481181.643693,13.419987201690674,5.66653526964325,1740481181.6436949,13.419987201690674,0.0,1740481181.6436968,13.419987201690674,0.012305110183150367,1740481181.643699,13.419987201690674,9.235499007343524,1740481181.6437,13.419987201690674,0.0,1740481181.643701,13.419987201690674,0.0,1740481181.643702,13.419987201690674,0.0,1740481181.643703,13.419987201690674,0.0,1740481181.6437042,13.419987201690674,0.8454770428522242,1740481181.643705,13.419987201690674,1.0,1740481181.6437056,13.419987201690674,1.022585251862226,1740481181.643707,13.419987201690674,0.0,1740481181.643708,13.419987201690674,0.8228917909899981,, +1740481181.6666584,13.439987182617188,5.66653526964325,1740481181.66666,13.439987182617188,0.0,1740481181.6666625,13.439987182617188,0.0,1740481181.6666644,13.439987182617188,9.312318851623246,1740481181.6666653,13.439987182617188,0.0,1740481181.6666665,13.439987182617188,0.0,1740481181.6666675,13.439987182617188,0.0,1740481181.6666687,13.439987182617188,0.0,1740481181.6666696,13.439987182617188,0.8841290345595755,1740481181.6666703,13.439987182617188,0.0,1740481181.6666713,13.439987182617188,0.06123724356957738,1740481181.6666725,13.439987182617188,0.0,1740481181.6666732,13.439987182617188,0.8228917909899981,, +1740481181.685005,13.459987163543701,5.66653526964325,1740481181.6850097,13.459987163543701,0.0,1740481181.6850138,13.459987163543701,0.0,1740481181.685016,13.459987163543701,9.312318851623246,1740481181.685017,13.459987163543701,0.0,1740481181.6850195,13.459987163543701,0.0,1740481181.6850204,13.459987163543701,0.0,1740481181.6850214,13.459987163543701,0.0,1740481181.6850228,13.459987163543701,0.8841290345595755,1740481181.685024,13.459987163543701,0.0,1740481181.685025,13.459987163543701,0.06123724356957738,1740481181.6850264,13.459987163543701,0.0,1740481181.6850274,13.459987163543701,0.8228917909899981,, +1740481181.7037246,13.479987144470215,5.66653526964325,1740481181.7037263,13.479987144470215,0.0,1740481181.7037284,13.479987144470215,0.0,1740481181.7037432,13.479987144470215,9.312318851623246,1740481181.7037444,13.479987144470215,0.0,1740481181.7037468,13.479987144470215,0.0,1740481181.703748,13.479987144470215,0.0,1740481181.7037492,13.479987144470215,0.0,1740481181.7037501,13.479987144470215,0.8841290345595755,1740481181.703751,13.479987144470215,0.0,1740481181.703752,13.479987144470215,0.06123724356957738,1740481181.703753,13.479987144470215,0.0,1740481181.7037537,13.479987144470215,0.8228917909899981,, +1740481181.7248585,13.499987125396729,5.66653526964325,1740481181.7248604,13.499987125396729,0.0,1740481181.7248633,13.499987125396729,0.0,1740481181.7248654,13.499987125396729,9.312318851623246,1740481181.7248666,13.499987125396729,0.0,1740481181.7248678,13.499987125396729,0.0,1740481181.7248688,13.499987125396729,0.0,1740481181.7248697,13.499987125396729,0.0,1740481181.7248707,13.499987125396729,0.8841290345595755,1740481181.7248714,13.499987125396729,0.0,1740481181.7248724,13.499987125396729,0.06123724356957738,1740481181.7248735,13.499987125396729,0.0,1740481181.7248743,13.499987125396729,0.8228917909899981,, +1740481181.7451797,13.519987106323242,5.760310142154793,1740481181.7451825,13.519987106323242,0.0,1740481181.7451851,13.519987106323242,0.013538997294248688,1740481181.745187,13.519987106323242,9.403454330250991,1740481181.7451882,13.519987106323242,0.0,1740481181.7451906,13.519987106323242,0.0,1740481181.7451925,13.519987106323242,0.0,1740481181.7451937,13.519987106323242,0.0,1740481181.7451952,13.519987106323242,0.8841290345595755,1740481181.7451966,13.519987106323242,1.0,1740481181.7451975,13.519987106323242,1.0048034221447981,1740481181.7451985,13.519987106323242,0.0,1740481181.7451997,13.519987106323242,0.8616900316567461,, +1740481181.7697563,13.539987087249756,5.760310142154793,1740481181.7697616,13.539987087249756,0.0,1740481181.7697973,13.539987087249756,0.0,1740481181.7698064,13.539987087249756,9.483690205468285,1740481181.76981,13.539987087249756,0.0,1740481181.769816,13.539987087249756,0.0,1740481181.7698195,13.539987087249756,0.0,1740481181.7698228,13.539987087249756,0.0,1740481181.769826,13.539987087249756,0.9229272752263241,1740481181.769861,13.539987087249756,0.0,1740481181.7698648,13.539987087249756,0.06123724356957805,1740481181.7698684,13.539987087249756,0.0,1740481181.7698717,13.539987087249756,0.8616900316567461,, +1740481181.7835677,13.55998706817627,5.760310142154793,1740481181.783569,13.55998706817627,0.0,1740481181.7835712,13.55998706817627,0.0,1740481181.783573,13.55998706817627,9.483690205468285,1740481181.783574,13.55998706817627,0.0,1740481181.7835753,13.55998706817627,0.0,1740481181.7835763,13.55998706817627,0.0,1740481181.7835772,13.55998706817627,0.0,1740481181.783578,13.55998706817627,0.9229272752263241,1740481181.7835789,13.55998706817627,0.0,1740481181.7835796,13.55998706817627,0.06123724356957805,1740481181.7835803,13.55998706817627,0.0,1740481181.7835815,13.55998706817627,0.8616900316567461,, +1740481181.804323,13.579987049102783,5.760310142154793,1740481181.8043249,13.579987049102783,0.0,1740481181.8043516,13.579987049102783,0.0,1740481181.8043532,13.579987049102783,9.483690205468285,1740481181.8043542,13.579987049102783,0.0,1740481181.8043556,13.579987049102783,0.0,1740481181.8043568,13.579987049102783,0.0,1740481181.804358,13.579987049102783,0.0,1740481181.8043587,13.579987049102783,0.9229272752263241,1740481181.8043833,13.579987049102783,0.0,1740481181.8043842,13.579987049102783,0.06123724356957805,1740481181.804385,13.579987049102783,0.0,1740481181.8043861,13.579987049102783,0.8616900316567461,, +1740481181.8253825,13.599987030029297,5.760310142154793,1740481181.8253841,13.599987030029297,0.0,1740481181.8253863,13.599987030029297,0.0,1740481181.8253882,13.599987030029297,9.483690205468285,1740481181.8253894,13.599987030029297,0.0,1740481181.8253903,13.599987030029297,0.0,1740481181.8253913,13.599987030029297,0.0,1740481181.8253925,13.599987030029297,0.0,1740481181.8254042,13.599987030029297,0.9229272752263241,1740481181.8254056,13.599987030029297,0.0,1740481181.8254066,13.599987030029297,0.06123724356957805,1740481181.8254075,13.599987030029297,0.0,1740481181.8254082,13.599987030029297,0.8616900316567461,, +1740481181.8444629,13.61998701095581,5.857402581377343,1740481181.8444653,13.61998701095581,0.0,1740481181.8444676,13.61998701095581,0.014633130943414997,1740481181.8444695,13.61998701095581,9.556697773827736,1740481181.8444705,13.61998701095581,0.0,1740481181.8444717,13.61998701095581,0.0,1740481181.844473,13.61998701095581,0.0,1740481181.8444736,13.61998701095581,0.0,1740481181.8444748,13.61998701095581,0.9229272752263241,1740481181.8444767,13.61998701095581,0.76048991297329,1740481181.844478,13.61998701095581,0.779273007587967,1740481181.8444793,13.61998701095581,0.0,1740481181.8444803,13.61998701095581,0.8908772503647633,, +1740481181.8681438,13.639986991882324,5.857402581377343,1740481181.868146,13.639986991882324,0.0,1740481181.8681483,13.639986991882324,0.0,1740481181.8681502,13.639986991882324,9.63915708210687,1740481181.868151,13.639986991882324,0.0,1740481181.8681526,13.639986991882324,0.0,1740481181.8681533,13.639986991882324,0.0,1740481181.8681543,13.639986991882324,0.0,1740481181.8681552,13.639986991882324,0.9513867142206324,1740481181.868156,13.639986991882324,0.0,1740481181.868157,13.639986991882324,0.06050946385586908,1740481181.8681579,13.639986991882324,0.0,1740481181.8681588,13.639986991882324,0.8908772503647633,, +1740481181.8846438,13.659986972808838,5.857402581377343,1740481181.8846457,13.659986972808838,0.0,1740481181.8846478,13.659986972808838,0.0,1740481181.8846498,13.659986972808838,9.63915708210687,1740481181.8846507,13.659986972808838,0.0,1740481181.8846521,13.659986972808838,0.0,1740481181.884653,13.659986972808838,0.0,1740481181.884654,13.659986972808838,0.0,1740481181.8846548,13.659986972808838,0.9513867142206324,1740481181.884656,13.659986972808838,0.0,1740481181.884657,13.659986972808838,0.06050946385586908,1740481181.8846576,13.659986972808838,0.0,1740481181.8846586,13.659986972808838,0.8908772503647633,, +1740481181.9095962,13.679986953735352,5.857402581377343,1740481181.909598,13.679986953735352,0.0,1740481181.9096005,13.679986953735352,0.0,1740481181.9096026,13.679986953735352,9.63915708210687,1740481181.9096036,13.679986953735352,0.0,1740481181.9096048,13.679986953735352,0.0,1740481181.909606,13.679986953735352,0.0,1740481181.9096067,13.679986953735352,0.0,1740481181.9096076,13.679986953735352,0.9513867142206324,1740481181.9096084,13.679986953735352,0.0,1740481181.9096093,13.679986953735352,0.06050946385586908,1740481181.90961,13.679986953735352,0.0,1740481181.9096117,13.679986953735352,0.8908772503647633,, +1740481181.924972,13.699986934661865,5.857402581377343,1740481181.9249737,13.699986934661865,0.0,1740481181.924976,13.699986934661865,0.0,1740481181.924978,13.699986934661865,9.63915708210687,1740481181.9249787,13.699986934661865,0.0,1740481181.9249802,13.699986934661865,0.0,1740481181.9249814,13.699986934661865,0.0,1740481181.924982,13.699986934661865,0.0,1740481181.924983,13.699986934661865,0.9513867142206324,1740481181.9249837,13.699986934661865,0.0,1740481181.9249847,13.699986934661865,0.06050946385586908,1740481181.9249856,13.699986934661865,0.0,1740481181.9249864,13.699986934661865,0.8908772503647633,, +1740481181.945264,13.719986915588379,5.857402581377343,1740481181.9452684,13.719986915588379,0.0,1740481181.9452727,13.719986915588379,0.0,1740481181.945276,13.719986915588379,9.63915708210687,1740481181.9452775,13.719986915588379,0.0,1740481181.945279,13.719986915588379,0.0,1740481181.9452803,13.719986915588379,0.0,1740481181.9452817,13.719986915588379,0.0,1740481181.9452837,13.719986915588379,0.9513867142206324,1740481181.9452848,13.719986915588379,0.0,1740481181.945286,13.719986915588379,0.06050946385586908,1740481181.9452884,13.719986915588379,0.0,1740481181.9452908,13.719986915588379,0.8908772503647633,, +1740481181.9708145,13.739986896514893,5.9568048494835875,1740481181.970816,13.739986896514893,0.0,1740481181.9708183,13.739986896514893,0.0,1740481181.9708204,13.739986896514893,9.768885189891838,1740481181.9708214,13.739986896514893,0.0,1740481181.9708226,13.739986896514893,0.0,1740481181.9708235,13.739986896514893,0.0,1740481181.9708245,13.739986896514893,0.0,1740481181.9708254,13.739986896514893,0.9639580053711966,1740481181.9708261,13.739986896514893,0.36041994628808305,1740481181.970827,13.739986896514893,0.41715976729134985,1740481181.9708278,13.739986896514893,0.0,1740481181.9708288,13.739986896514893,0.9060401702041253,, +1740481181.9840388,13.759986877441406,5.9568048494835875,1740481181.9840405,13.759986877441406,0.0,1740481181.9840424,13.759986877441406,0.0,1740481181.9840446,13.759986877441406,9.768885189891838,1740481181.9840457,13.759986877441406,0.0,1740481181.9840472,13.759986877441406,0.0,1740481181.9840481,13.759986877441406,0.0,1740481181.984049,13.759986877441406,0.0,1740481181.9840503,13.759986877441406,0.9639580053711966,1740481181.9840515,13.759986877441406,0.36041994628808305,1740481181.9840522,13.759986877441406,0.4183377814551543,1740481181.9840531,13.759986877441406,0.0,1740481181.984054,13.759986877441406,0.9060401702041253,, +1740481182.004445,13.77998685836792,5.9568048494835875,1740481182.0044475,13.77998685836792,0.0,1740481182.0044503,13.77998685836792,0.0,1740481182.0044525,13.77998685836792,9.768885189891838,1740481182.0044537,13.77998685836792,0.0,1740481182.004455,13.77998685836792,0.0,1740481182.0044563,13.77998685836792,0.0,1740481182.0044572,13.77998685836792,0.0,1740481182.0044582,13.77998685836792,0.9639580053711966,1740481182.0044596,13.77998685836792,0.36041994628808305,1740481182.0044606,13.77998685836792,0.4183377814551543,1740481182.0044618,13.77998685836792,0.0,1740481182.004463,13.77998685836792,0.9060401702041253,, +1740481182.0236325,13.799986839294434,5.9568048494835875,1740481182.0236344,13.799986839294434,0.0,1740481182.0236366,13.799986839294434,0.0,1740481182.0236382,13.799986839294434,9.768885189891838,1740481182.0236392,13.799986839294434,0.0,1740481182.0236406,13.799986839294434,0.0,1740481182.0236416,13.799986839294434,0.0,1740481182.0236425,13.799986839294434,0.0,1740481182.0236435,13.799986839294434,0.9639580053711966,1740481182.0236444,13.799986839294434,0.36041994628808305,1740481182.0236452,13.799986839294434,0.4183377814551543,1740481182.023646,13.799986839294434,0.0,1740481182.0236473,13.799986839294434,0.9060401702041253,, +1740481182.0444348,13.819986820220947,5.9568048494835875,1740481182.0444367,13.819986820220947,0.0,1740481182.0444396,13.819986820220947,0.0,1740481182.0444417,13.819986820220947,9.768885189891838,1740481182.0444427,13.819986820220947,0.0,1740481182.044444,13.819986820220947,0.0,1740481182.0444453,13.819986820220947,0.0,1740481182.0444462,13.819986820220947,0.0,1740481182.0444472,13.819986820220947,0.9639580053711966,1740481182.0444481,13.819986820220947,0.36041994628808305,1740481182.0444493,13.819986820220947,0.4183377814551543,1740481182.0444503,13.819986820220947,0.0,1740481182.0444512,13.819986820220947,0.9060401702041253,, +1740481182.0671172,13.839986801147461,6.057792872457066,1740481182.0671196,13.839986801147461,0.0,1740481182.0671232,13.839986801147461,0.0,1740481182.0671256,13.839986801147461,9.935617512830827,1740481182.0671327,13.839986801147461,0.0,1740481182.067136,13.839986801147461,0.0,1740481182.0671382,13.839986801147461,0.0,1740481182.0671396,13.839986801147461,0.0,1740481182.067141,13.839986801147461,0.9847653796634791,1740481182.0671427,13.839986801147461,0.15234620336525784,1740481182.067144,13.839986801147461,0.1927152686616968,1740481182.0671458,13.839986801147461,0.0,1740481182.0671487,13.839986801147461,0.9389123201868808,, +1740481182.0839403,13.859986782073975,6.057792872457066,1740481182.0839422,13.859986782073975,0.0,1740481182.083944,13.859986782073975,0.0,1740481182.0839465,13.859986782073975,9.935617512830827,1740481182.0839474,13.859986782073975,0.0,1740481182.0839489,13.859986782073975,0.0,1740481182.0839498,13.859986782073975,0.0,1740481182.083951,13.859986782073975,0.0,1740481182.083952,13.859986782073975,0.9847653796634791,1740481182.0839531,13.859986782073975,0.15234620336525784,1740481182.083954,13.859986782073975,0.19819926284185618,1740481182.0839553,13.859986782073975,0.0,1740481182.0839562,13.859986782073975,0.9389123201868808,, +1740481182.1039217,13.879986763000488,6.057792872457066,1740481182.1039238,13.879986763000488,0.0,1740481182.1039262,13.879986763000488,0.0,1740481182.1039283,13.879986763000488,9.935617512830827,1740481182.1039295,13.879986763000488,0.0,1740481182.103931,13.879986763000488,0.0,1740481182.1039317,13.879986763000488,0.0,1740481182.1039326,13.879986763000488,0.0,1740481182.1039338,13.879986763000488,0.9847653796634791,1740481182.103935,13.879986763000488,0.15234620336525784,1740481182.103936,13.879986763000488,0.19819926284185618,1740481182.103937,13.879986763000488,0.0,1740481182.103938,13.879986763000488,0.9389123201868808,, +1740481182.124321,13.899986743927002,6.057792872457066,1740481182.124323,13.899986743927002,0.0,1740481182.124325,13.899986743927002,0.0,1740481182.124327,13.899986743927002,9.935617512830827,1740481182.124328,13.899986743927002,0.0,1740481182.1243293,13.899986743927002,0.0,1740481182.1243303,13.899986743927002,0.0,1740481182.124331,13.899986743927002,0.0,1740481182.1243317,13.899986743927002,0.9847653796634791,1740481182.124333,13.899986743927002,0.15234620336525784,1740481182.1243339,13.899986743927002,0.19819926284185618,1740481182.124335,13.899986743927002,0.0,1740481182.1243362,13.899986743927002,0.9389123201868808,, +1740481182.143814,13.919986724853516,6.057792872457066,1740481182.143816,13.919986724853516,0.0,1740481182.143818,13.919986724853516,0.0,1740481182.14382,13.919986724853516,9.935617512830827,1740481182.143821,13.919986724853516,0.0,1740481182.1438224,13.919986724853516,0.0,1740481182.1438234,13.919986724853516,0.0,1740481182.1438367,13.919986724853516,0.0,1740481182.1438396,13.919986724853516,0.9847653796634791,1740481182.1438408,13.919986724853516,0.15234620336525784,1740481182.1438417,13.919986724853516,0.19819926284185618,1740481182.1438425,13.919986724853516,0.0,1740481182.1438437,13.919986724853516,0.9389123201868808,, +1740481182.1664793,13.93998670578003,6.057792872457066,1740481182.1664813,13.93998670578003,0.0,1740481182.1664832,13.93998670578003,0.0,1740481182.166485,13.93998670578003,9.935617512830827,1740481182.166486,13.93998670578003,0.0,1740481182.1664872,13.93998670578003,0.0,1740481182.1664884,13.93998670578003,0.0,1740481182.1664891,13.93998670578003,0.0,1740481182.1664898,13.93998670578003,0.9847653796634791,1740481182.1664908,13.93998670578003,0.15234620336525784,1740481182.1664917,13.93998670578003,0.19819926284185618,1740481182.1664927,13.93998670578003,0.0,1740481182.1664934,13.93998670578003,0.9389123201868808,, +1740481182.1844523,13.959986686706543,6.161844632204554,1740481182.1844542,13.959986686706543,0.0,1740481182.1844563,13.959986686706543,0.016732720925944834,1740481182.1844585,13.959986686706543,9.983360988509261,1740481182.1844594,13.959986686706543,0.0,1740481182.1844609,13.959986686706543,0.0,1740481182.1844792,13.959986686706543,0.0,1740481182.1844802,13.959986686706543,0.0,1740481182.1844814,13.959986686706543,1.0000000000000049,1740481182.1844823,13.959986686706543,-8.215650382226158e-14,1740481182.1844833,13.959986686706543,0.045459230937736746,1740481182.184484,13.959986686706543,0.0,1740481182.1844854,13.959986686706543,0.9544176975631254,, +1740481182.2051914,13.979986667633057,6.161844632204554,1740481182.2051954,13.979986667633057,0.0,1740481182.2051983,13.979986667633057,0.016732720925944834,1740481182.2052016,13.979986667633057,9.983360988509261,1740481182.205203,13.979986667633057,0.0,1740481182.2052042,13.979986667633057,0.0,1740481182.2052054,13.979986667633057,0.0,1740481182.2052076,13.979986667633057,0.0,1740481182.205209,13.979986667633057,1.0000000000000049,1740481182.2052107,13.979986667633057,-8.215650382226158e-14,1740481182.2052119,13.979986667633057,0.045582302436797284,1740481182.2052138,13.979986667633057,0.0,1740481182.2052152,13.979986667633057,0.9544176975631254,, +1740481182.2241313,13.99998664855957,6.161844632204554,1740481182.2241335,13.99998664855957,0.0,1740481182.2241352,13.99998664855957,0.016732720925944834,1740481182.2241373,13.99998664855957,9.983360988509261,1740481182.2241383,13.99998664855957,0.0,1740481182.2241395,13.99998664855957,0.0,1740481182.2241404,13.99998664855957,0.0,1740481182.2241414,13.99998664855957,0.0,1740481182.224142,13.99998664855957,1.0000000000000049,1740481182.224143,13.99998664855957,-8.215650382226158e-14,1740481182.2241442,13.99998664855957,0.045582302436797284,1740481182.2241452,13.99998664855957,0.0,1740481182.224146,13.99998664855957,0.9544176975631254,, +1740481182.2449832,14.019986629486084,6.161844632204554,1740481182.2449865,14.019986629486084,0.0,1740481182.2449915,14.019986629486084,0.016732720925944834,1740481182.2449946,14.019986629486084,9.983360988509261,1740481182.2449963,14.019986629486084,0.0,1740481182.2449985,14.019986629486084,0.0,1740481182.2450001,14.019986629486084,0.0,1740481182.245002,14.019986629486084,0.0,1740481182.2450037,14.019986629486084,1.0000000000000049,1740481182.2450054,14.019986629486084,-8.215650382226158e-14,1740481182.245007,14.019986629486084,0.045582302436797284,1740481182.2450087,14.019986629486084,0.0,1740481182.2450101,14.019986629486084,0.9544176975631254,, +1740481182.2678702,14.039986610412598,6.161844632204554,1740481182.267872,14.039986610412598,0.0,1740481182.267874,14.039986610412598,0.0,1740481182.2678761,14.039986610412598,10.070680027330805,1740481182.267877,14.039986610412598,0.0,1740481182.2678783,14.039986610412598,0.0,1740481182.2678792,14.039986610412598,0.0,1740481182.2678802,14.039986610412598,0.0,1740481182.267881,14.039986610412598,0.9915176362686652,1740481182.2678819,14.039986610412598,0.0,1740481182.2678828,14.039986610412598,0.03709993870553974,1740481182.2678835,14.039986610412598,0.0,1740481182.2678845,14.039986610412598,0.9544176975631254,, +1740481182.2839196,14.059986591339111,6.266919930930852,1740481182.2839217,14.059986591339111,0.0,1740481182.2839234,14.059986591339111,0.017013177888215412,1740481182.2839258,14.059986591339111,10.087914481778029,1740481182.2839267,14.059986591339111,0.0,1740481182.283928,14.059986591339111,0.0,1740481182.2839289,14.059986591339111,0.0,1740481182.2839298,14.059986591339111,0.0,1740481182.2839305,14.059986591339111,0.9915176362686652,1740481182.2839317,14.059986591339111,0.08482363731330933,1740481182.2839327,14.059986591339111,0.12176264756433658,1740481182.2839336,14.059986591339111,0.0,1740481182.2839344,14.059986591339111,0.95452833584263,, +1740481182.303965,14.079986572265625,6.266919930930852,1740481182.303967,14.079986572265625,0.0,1740481182.303969,14.079986572265625,0.017013177888215412,1740481182.3039713,14.079986572265625,10.087914481778029,1740481182.3039727,14.079986572265625,0.0,1740481182.303974,14.079986572265625,0.0,1740481182.3039749,14.079986572265625,0.0,1740481182.3039758,14.079986572265625,0.0,1740481182.3039768,14.079986572265625,0.9915176362686652,1740481182.3039777,14.079986572265625,0.08482363731330933,1740481182.3039787,14.079986572265625,0.12181293773934454,1740481182.3039799,14.079986572265625,0.0,1740481182.3039808,14.079986572265625,0.95452833584263,, +1740481182.3246064,14.099986553192139,6.266919930930852,1740481182.324608,14.099986553192139,0.0,1740481182.32461,14.099986553192139,0.017013177888215412,1740481182.3246348,14.099986553192139,10.087914481778029,1740481182.324636,14.099986553192139,0.0,1740481182.3246372,14.099986553192139,0.0,1740481182.3246381,14.099986553192139,0.0,1740481182.3246393,14.099986553192139,0.0,1740481182.32464,14.099986553192139,0.9915176362686652,1740481182.324641,14.099986553192139,0.08482363731330933,1740481182.324642,14.099986553192139,0.12181293773934454,1740481182.3246434,14.099986553192139,0.0,1740481182.3246608,14.099986553192139,0.95452833584263,, +1740481182.3436775,14.119986534118652,6.266919930930852,1740481182.3436794,14.119986534118652,0.0,1740481182.3436816,14.119986534118652,0.017013177888215412,1740481182.3436835,14.119986534118652,10.087914481778029,1740481182.3436847,14.119986534118652,0.0,1740481182.3436859,14.119986534118652,0.0,1740481182.3436866,14.119986534118652,0.0,1740481182.3436882,14.119986534118652,0.0,1740481182.343689,14.119986534118652,0.9915176362686652,1740481182.34369,14.119986534118652,0.08482363731330933,1740481182.343691,14.119986534118652,0.12181293773934454,1740481182.3436918,14.119986534118652,0.0,1740481182.3436928,14.119986534118652,0.95452833584263,, +1740481182.3665466,14.139986515045166,6.266919930930852,1740481182.3665488,14.139986515045166,0.0,1740481182.3665524,14.139986515045166,0.0,1740481182.3665543,14.139986515045166,10.175976602616112,1740481182.3665555,14.139986515045166,0.0,1740481182.3665566,14.139986515045166,0.0,1740481182.3665576,14.139986515045166,0.0,1740481182.3665588,14.139986515045166,0.0,1740481182.3665595,14.139986515045166,0.9915587634227395,1740481182.3665607,14.139986515045166,0.0,1740481182.366562,14.139986515045166,0.03703042758010955,1740481182.3665626,14.139986515045166,0.0,1740481182.3665636,14.139986515045166,0.95452833584263,, +1740481182.3850095,14.15998649597168,6.266919930930852,1740481182.385012,14.15998649597168,0.0,1740481182.3850155,14.15998649597168,0.0,1740481182.3850176,14.15998649597168,10.175976602616112,1740481182.3850183,14.15998649597168,0.0,1740481182.3850195,14.15998649597168,0.0,1740481182.385021,14.15998649597168,0.0,1740481182.385022,14.15998649597168,0.0,1740481182.3850229,14.15998649597168,0.9915587634227395,1740481182.385024,14.15998649597168,0.0,1740481182.385025,14.15998649597168,0.03703042758010955,1740481182.385026,14.15998649597168,0.0,1740481182.385027,14.15998649597168,0.95452833584263,, +1740481182.4038305,14.179986476898193,6.3722491477047605,1740481182.4038324,14.179986476898193,0.0,1740481182.4038343,14.179986476898193,0.017054998208394952,1740481182.4038365,14.179986476898193,10.20219142121987,1740481182.4038374,14.179986476898193,0.0,1740481182.4038386,14.179986476898193,0.0,1740481182.4038398,14.179986476898193,0.0,1740481182.403841,14.179986476898193,0.0,1740481182.403842,14.179986476898193,0.9915587634227395,1740481182.403843,14.179986476898193,0.08441236577256594,1740481182.4038439,14.179986476898193,0.11478110380707159,1740481182.4038448,14.179986476898193,0.0,1740481182.4038458,14.179986476898193,0.9591082460403118,, +1740481182.4242606,14.199986457824707,6.3722491477047605,1740481182.424264,14.199986457824707,0.0,1740481182.424267,14.199986457824707,0.017054998208394952,1740481182.4242692,14.199986457824707,10.20219142121987,1740481182.424271,14.199986457824707,0.0,1740481182.4242723,14.199986457824707,0.0,1740481182.4242744,14.199986457824707,0.0,1740481182.424277,14.199986457824707,0.0,1740481182.4242783,14.199986457824707,0.9915587634227395,1740481182.4242802,14.199986457824707,0.08441236577256594,1740481182.4242816,14.199986457824707,0.11686288315499371,1740481182.4242837,14.199986457824707,0.0,1740481182.4242857,14.199986457824707,0.9591082460403118,, +1740481182.4439096,14.21998643875122,6.3722491477047605,1740481182.443911,14.21998643875122,0.0,1740481182.4439132,14.21998643875122,0.017054998208394952,1740481182.4439154,14.21998643875122,10.20219142121987,1740481182.4439163,14.21998643875122,0.0,1740481182.4439175,14.21998643875122,0.0,1740481182.4439187,14.21998643875122,0.0,1740481182.4439197,14.21998643875122,0.0,1740481182.4439204,14.21998643875122,0.9915587634227395,1740481182.4439213,14.21998643875122,0.08441236577256594,1740481182.4439225,14.21998643875122,0.11686288315499371,1740481182.4439235,14.21998643875122,0.0,1740481182.4439244,14.21998643875122,0.9591082460403118,, +1740481182.4672546,14.239986419677734,6.3722491477047605,1740481182.4672563,14.239986419677734,0.0,1740481182.4672797,14.239986419677734,0.0,1740481182.4672818,14.239986419677734,10.290465639785385,1740481182.4672828,14.239986419677734,0.0,1740481182.467284,14.239986419677734,0.0,1740481182.467285,14.239986419677734,0.0,1740481182.467286,14.239986419677734,0.0,1740481182.4672868,14.239986419677734,0.9931735352359532,1740481182.4672878,14.239986419677734,0.0,1740481182.4672885,14.239986419677734,0.034065289195641446,1740481182.4672897,14.239986419677734,0.0,1740481182.4672906,14.239986419677734,0.9591082460403118,, +1740481182.4836433,14.259986400604248,6.3722491477047605,1740481182.483645,14.259986400604248,0.0,1740481182.4836473,14.259986400604248,0.0,1740481182.4836493,14.259986400604248,10.290465639785385,1740481182.4836502,14.259986400604248,0.0,1740481182.4836516,14.259986400604248,0.0,1740481182.4836526,14.259986400604248,0.0,1740481182.4836533,14.259986400604248,0.0,1740481182.4836545,14.259986400604248,0.9931735352359532,1740481182.4836555,14.259986400604248,0.0,1740481182.4836564,14.259986400604248,0.034065289195641446,1740481182.4836571,14.259986400604248,0.0,1740481182.4836583,14.259986400604248,0.9591082460403118,, +1740481182.5036323,14.279986381530762,6.477946001365115,1740481182.5036342,14.279986381530762,0.0,1740481182.5036366,14.279986381530762,0.017142397615251246,1740481182.5036383,14.279986381530762,10.312413214252938,1740481182.5036395,14.279986381530762,0.0,1740481182.503641,14.279986381530762,0.0,1740481182.5036418,14.279986381530762,0.0,1740481182.5036428,14.279986381530762,0.0,1740481182.5036438,14.279986381530762,0.9931735352359532,1740481182.5036447,14.279986381530762,0.06826464764051687,1740481182.5036457,14.279986381530762,0.09883526172026129,1740481182.5036464,14.279986381530762,0.0,1740481182.5036476,14.279986381530762,0.9615108344664631,, +1740481182.526981,14.299986362457275,6.477946001365115,1740481182.5269835,14.299986362457275,0.0,1740481182.5269856,14.299986362457275,0.017142397615251246,1740481182.5269878,14.299986362457275,10.312413214252938,1740481182.5269887,14.299986362457275,0.0,1740481182.5269904,14.299986362457275,0.0,1740481182.5269911,14.299986362457275,0.0,1740481182.5269923,14.299986362457275,0.0,1740481182.526993,14.299986362457275,0.9931735352359532,1740481182.5269942,14.299986362457275,0.06826464764051687,1740481182.526995,14.299986362457275,0.09992734841000694,1740481182.526996,14.299986362457275,0.0,1740481182.5269973,14.299986362457275,0.9615108344664631,, +1740481182.5451622,14.319986343383789,6.477946001365115,1740481182.5451639,14.319986343383789,0.0,1740481182.5451658,14.319986343383789,0.017142397615251246,1740481182.545168,14.319986343383789,10.312413214252938,1740481182.5451689,14.319986343383789,0.0,1740481182.54517,14.319986343383789,0.0,1740481182.5451713,14.319986343383789,0.0,1740481182.5451722,14.319986343383789,0.0,1740481182.545173,14.319986343383789,0.9931735352359532,1740481182.5451741,14.319986343383789,0.06826464764051687,1740481182.5451748,14.319986343383789,0.09992734841000694,1740481182.5451758,14.319986343383789,0.0,1740481182.5451765,14.319986343383789,0.9615108344664631,, +1740481182.5693192,14.339986324310303,6.477946001365115,1740481182.569321,14.339986324310303,0.0,1740481182.569323,14.339986324310303,0.0,1740481182.5693247,14.339986324310303,10.40096767029804,1740481182.569326,14.339986324310303,0.0,1740481182.569327,14.339986324310303,0.0,1740481182.569328,14.339986324310303,0.0,1740481182.5693288,14.339986324310303,0.0,1740481182.56933,14.339986324310303,0.9939521450627331,1740481182.5693307,14.339986324310303,0.0,1740481182.5693316,14.339986324310303,0.03244131059626998,1740481182.5693324,14.339986324310303,0.0,1740481182.5693336,14.339986324310303,0.9615108344664631,, +1740481182.5868127,14.359986305236816,6.477946001365115,1740481182.5868142,14.359986305236816,0.0,1740481182.5868165,14.359986305236816,0.0,1740481182.5868185,14.359986305236816,10.40096767029804,1740481182.5868196,14.359986305236816,0.0,1740481182.5868208,14.359986305236816,0.0,1740481182.5868216,14.359986305236816,0.0,1740481182.5868227,14.359986305236816,0.0,1740481182.5868235,14.359986305236816,0.9939521450627331,1740481182.5868244,14.359986305236816,0.0,1740481182.5868251,14.359986305236816,0.03244131059626998,1740481182.5868263,14.359986305236816,0.0,1740481182.586827,14.359986305236816,0.9615108344664631,, +1740481182.604713,14.37998628616333,6.477946001365115,1740481182.6047156,14.37998628616333,0.0,1740481182.604718,14.37998628616333,0.0,1740481182.6047206,14.37998628616333,10.40096767029804,1740481182.6047215,14.37998628616333,0.0,1740481182.6047232,14.37998628616333,0.0,1740481182.6047242,14.37998628616333,0.0,1740481182.6047256,14.37998628616333,0.0,1740481182.6047268,14.37998628616333,0.9939521450627331,1740481182.604728,14.37998628616333,0.0,1740481182.604729,14.37998628616333,0.03244131059626998,1740481182.60473,14.37998628616333,0.0,1740481182.6047308,14.37998628616333,0.9615108344664631,, +1740481182.6244116,14.399986267089844,6.583903502481709,1740481182.6244135,14.399986267089844,0.0,1740481182.6244156,14.399986267089844,0.017198142728397214,1740481182.6244175,14.399986267089844,10.422070239845095,1740481182.6244185,14.399986267089844,0.0,1740481182.62442,14.399986267089844,0.0,1740481182.624421,14.399986267089844,0.0,1740481182.6244216,14.399986267089844,0.0,1740481182.6244226,14.399986267089844,0.9939521450627331,1740481182.6244235,14.399986267089844,0.060478549372630086,1740481182.6244245,14.399986267089844,0.09008027598179755,1740481182.6244252,14.399986267089844,0.0,1740481182.6244261,14.399986267089844,0.9634630478757906,, +1740481182.6442099,14.419986248016357,6.583903502481709,1740481182.6442118,14.419986248016357,0.0,1740481182.644214,14.419986248016357,0.017198142728397214,1740481182.6442158,14.419986248016357,10.422070239845095,1740481182.6442168,14.419986248016357,0.0,1740481182.6442182,14.419986248016357,0.0,1740481182.6442194,14.419986248016357,0.0,1740481182.6442204,14.419986248016357,0.0,1740481182.6442215,14.419986248016357,0.9939521450627331,1740481182.6442225,14.419986248016357,0.060478549372630086,1740481182.6442237,14.419986248016357,0.09096764655957257,1740481182.644225,14.419986248016357,0.0,1740481182.6442258,14.419986248016357,0.9634630478757906,, +1740481182.6669223,14.439986228942871,6.583903502481709,1740481182.6669242,14.439986228942871,0.0,1740481182.6669264,14.439986228942871,0.0,1740481182.6669283,14.439986228942871,10.51082959823329,1740481182.6669292,14.439986228942871,0.0,1740481182.6669304,14.439986228942871,0.0,1740481182.6669316,14.439986228942871,0.0,1740481182.6669328,14.439986228942871,0.0,1740481182.6669335,14.439986228942871,0.9945500940575076,1740481182.6669347,14.439986228942871,0.0,1740481182.6669354,14.439986228942871,0.031087046181716982,1740481182.6669369,14.439986228942871,0.0,1740481182.6669378,14.439986228942871,0.9634630478757906,, +1740481182.6856015,14.459986209869385,6.583903502481709,1740481182.6856034,14.459986209869385,0.0,1740481182.6856053,14.459986209869385,0.0,1740481182.6856077,14.459986209869385,10.51082959823329,1740481182.6856086,14.459986209869385,0.0,1740481182.68561,14.459986209869385,0.0,1740481182.685611,14.459986209869385,0.0,1740481182.685612,14.459986209869385,0.0,1740481182.685613,14.459986209869385,0.9945500940575076,1740481182.6856139,14.459986209869385,0.0,1740481182.6856146,14.459986209869385,0.031087046181716982,1740481182.6856155,14.459986209869385,0.0,1740481182.6856165,14.459986209869385,0.9634630478757906,, +1740481182.7054434,14.479986190795898,6.583903502481709,1740481182.7054465,14.479986190795898,0.0,1740481182.7054498,14.479986190795898,0.0,1740481182.7054522,14.479986190795898,10.51082959823329,1740481182.7054534,14.479986190795898,0.0,1740481182.7054555,14.479986190795898,0.0,1740481182.7054572,14.479986190795898,0.0,1740481182.7054713,14.479986190795898,0.0,1740481182.7054746,14.479986190795898,0.9945500940575076,1740481182.7054768,14.479986190795898,0.0,1740481182.7054787,14.479986190795898,0.031087046181716982,1740481182.7054803,14.479986190795898,0.0,1740481182.7054822,14.479986190795898,0.9634630478757906,, +1740481182.724045,14.499986171722412,6.689918783775488,1740481182.7240474,14.499986171722412,0.0,1740481182.7240496,14.499986171722412,0.01721787295381114,1740481182.7240515,14.499986171722412,10.527023633167808,1740481182.7240524,14.499986171722412,0.0,1740481182.7240539,14.499986171722412,0.0,1740481182.7240548,14.499986171722412,0.0,1740481182.7240558,14.499986171722412,0.0,1740481182.7240572,14.499986171722412,0.9945500940575076,1740481182.7240582,14.499986171722412,0.054499059424972796,1740481182.7240589,14.499986171722412,0.08633071529717735,1740481182.7240598,14.499986171722412,0.0,1740481182.724061,14.499986171722412,0.9629511288661443,, +1740481182.7441602,14.519986152648926,6.689918783775488,1740481182.7442513,14.519986152648926,0.0,1740481182.7442558,14.519986152648926,0.01721787295381114,1740481182.7442808,14.519986152648926,10.527023633167808,1740481182.7442825,14.519986152648926,0.0,1740481182.744284,14.519986152648926,0.0,1740481182.7442849,14.519986152648926,0.0,1740481182.7442863,14.519986152648926,0.0,1740481182.7442873,14.519986152648926,0.9945500940575076,1740481182.7442884,14.519986152648926,0.054499059424972796,1740481182.7442896,14.519986152648926,0.08609802461633609,1740481182.7442906,14.519986152648926,0.0,1740481182.7442915,14.519986152648926,0.9629511288661443,, +1740481182.765964,14.53998613357544,6.689918783775488,1740481182.765966,14.53998613357544,0.0,1740481182.7659678,14.53998613357544,0.0,1740481182.76597,14.53998613357544,10.615821041507775,1740481182.765971,14.53998613357544,0.0,1740481182.7659721,14.53998613357544,0.0,1740481182.7659733,14.53998613357544,0.0,1740481182.765974,14.53998613357544,0.0,1740481182.765975,14.53998613357544,0.9943963070009302,1740481182.7659757,14.53998613357544,0.0,1740481182.7659767,14.53998613357544,0.03144517813478587,1740481182.7659776,14.53998613357544,0.0,1740481182.7659783,14.53998613357544,0.9629511288661443,, +1740481182.7842677,14.559986114501953,6.689918783775488,1740481182.7842696,14.559986114501953,0.0,1740481182.7842724,14.559986114501953,0.0,1740481182.784274,14.559986114501953,10.615821041507775,1740481182.7842753,14.559986114501953,0.0,1740481182.7842765,14.559986114501953,0.0,1740481182.7842774,14.559986114501953,0.0,1740481182.7842782,14.559986114501953,0.0,1740481182.7842796,14.559986114501953,0.9943963070009302,1740481182.7842803,14.559986114501953,0.0,1740481182.7842813,14.559986114501953,0.03144517813478587,1740481182.7842824,14.559986114501953,0.0,1740481182.7842834,14.559986114501953,0.9629511288661443,, +1740481182.8034785,14.579986095428467,6.689918783775488,1740481182.8034804,14.579986095428467,0.0,1740481182.8034823,14.579986095428467,0.0,1740481182.8034844,14.579986095428467,10.615821041507775,1740481182.8034854,14.579986095428467,0.0,1740481182.8034863,14.579986095428467,0.0,1740481182.8034875,14.579986095428467,0.0,1740481182.8034885,14.579986095428467,0.0,1740481182.8034894,14.579986095428467,0.9943963070009302,1740481182.8034904,14.579986095428467,0.0,1740481182.8034914,14.579986095428467,0.03144517813478587,1740481182.803492,14.579986095428467,0.0,1740481182.803493,14.579986095428467,0.9629511288661443,, +1740481182.8241558,14.59998607635498,6.689918783775488,1740481182.8241577,14.59998607635498,0.0,1740481182.8241603,14.59998607635498,0.0,1740481182.8241622,14.59998607635498,10.615821041507775,1740481182.8241637,14.59998607635498,0.0,1740481182.8241649,14.59998607635498,0.0,1740481182.824166,14.59998607635498,0.0,1740481182.8241673,14.59998607635498,0.0,1740481182.8241682,14.59998607635498,0.9943963070009302,1740481182.8241692,14.59998607635498,0.0,1740481182.8241704,14.59998607635498,0.03144517813478587,1740481182.8241713,14.59998607635498,0.0,1740481182.824172,14.59998607635498,0.9629511288661443,, +1740481182.8435836,14.619986057281494,6.795886610338917,1740481182.8435853,14.619986057281494,0.0,1740481182.8435874,14.619986057281494,0.01720750465782477,1740481182.8435893,14.619986057281494,10.63168956844136,1740481182.8435905,14.619986057281494,0.0,1740481182.8435917,14.619986057281494,0.0,1740481182.8435926,14.619986057281494,0.0,1740481182.8435938,14.619986057281494,0.0,1740481182.8435948,14.619986057281494,0.9943963070009302,1740481182.8435957,14.619986057281494,0.056036929990659345,1740481182.8435965,14.619986057281494,0.08845591039692709,1740481182.8435977,14.619986057281494,0.0,1740481182.8435984,14.619986057281494,0.9622816400040239,, +1740481182.8674262,14.639986038208008,6.795886610338917,1740481182.8674278,14.639986038208008,0.0,1740481182.8674302,14.639986038208008,0.0,1740481182.8674319,14.639986038208008,10.720449890346964,1740481182.867433,14.639986038208008,0.0,1740481182.8674343,14.639986038208008,0.0,1740481182.8674352,14.639986038208008,0.0,1740481182.867436,14.639986038208008,0.0,1740481182.867437,14.639986038208008,0.9941919549368307,1740481182.8674378,14.639986038208008,0.0,1740481182.8674388,14.639986038208008,0.031910314932806716,1740481182.8674395,14.639986038208008,0.0,1740481182.867441,14.639986038208008,0.9622816400040239,, +1740481182.8838902,14.659986019134521,6.795886610338917,1740481182.8838923,14.659986019134521,0.0,1740481182.8838944,14.659986019134521,0.0,1740481182.8838966,14.659986019134521,10.720449890346964,1740481182.8838975,14.659986019134521,0.0,1740481182.883899,14.659986019134521,0.0,1740481182.8839,14.659986019134521,0.0,1740481182.883901,14.659986019134521,0.0,1740481182.8839016,14.659986019134521,0.9941919549368307,1740481182.8839028,14.659986019134521,0.0,1740481182.8839037,14.659986019134521,0.031910314932806716,1740481182.8839047,14.659986019134521,0.0,1740481182.883906,14.659986019134521,0.9622816400040239,, +1740481182.904197,14.679986000061035,6.795886610338917,1740481182.9041986,14.679986000061035,0.0,1740481182.9042013,14.679986000061035,0.0,1740481182.9042032,14.679986000061035,10.720449890346964,1740481182.9042044,14.679986000061035,0.0,1740481182.9042056,14.679986000061035,0.0,1740481182.9042063,14.679986000061035,0.0,1740481182.9042077,14.679986000061035,0.0,1740481182.9042087,14.679986000061035,0.9941919549368307,1740481182.9042096,14.679986000061035,0.0,1740481182.9042108,14.679986000061035,0.031910314932806716,1740481182.9042115,14.679986000061035,0.0,1740481182.9042273,14.679986000061035,0.9622816400040239,, +1740481182.9238398,14.699985980987549,6.795886610338917,1740481182.9238412,14.699985980987549,0.0,1740481182.9238434,14.699985980987549,0.0,1740481182.9238453,14.699985980987549,10.720449890346964,1740481182.9238467,14.699985980987549,0.0,1740481182.923848,14.699985980987549,0.0,1740481182.9238486,14.699985980987549,0.0,1740481182.9238498,14.699985980987549,0.0,1740481182.9238508,14.699985980987549,0.9941919549368307,1740481182.9238515,14.699985980987549,0.0,1740481182.9238524,14.699985980987549,0.031910314932806716,1740481182.9238534,14.699985980987549,0.0,1740481182.9238546,14.699985980987549,0.9622816400040239,, +1740481182.9442127,14.719985961914062,6.901693244926349,1740481182.9442148,14.719985961914062,0.0,1740481182.9442167,14.719985961914062,0.01717779879596383,1740481182.9442189,14.719985961914062,10.734284352874024,1740481182.9442198,14.719985961914062,0.0,1740481182.9442213,14.719985961914062,0.0,1740481182.9442222,14.719985961914062,0.0,1740481182.9442232,14.719985961914062,0.0,1740481182.944224,14.719985961914062,0.9941919549368307,1740481182.944225,14.719985961914062,0.05808045063165457,1740481182.9442263,14.719985961914062,0.09242228357558731,1740481182.944227,14.719985961914062,0.0,1740481182.944228,14.719985961914062,0.9606099718695712,, +1740481182.965683,14.739985942840576,6.901693244926349,1740481182.9656847,14.739985942840576,0.0,1740481182.9656868,14.739985942840576,0.0,1740481182.965689,14.739985942840576,10.822913188665492,1740481182.9656897,14.739985942840576,0.0,1740481182.9656909,14.739985942840576,0.0,1740481182.9656916,14.739985942840576,0.0,1740481182.9656928,14.739985942840576,0.0,1740481182.9656935,14.739985942840576,0.9936657243791785,1740481182.9656944,14.739985942840576,0.0,1740481182.9656954,14.739985942840576,0.03305575250960735,1740481182.9656963,14.739985942840576,0.0,1740481182.965697,14.739985942840576,0.9606099718695712,, +1740481182.9849348,14.75998592376709,6.901693244926349,1740481182.984937,14.75998592376709,0.0,1740481182.9849393,14.75998592376709,0.0,1740481182.984941,14.75998592376709,10.822913188665492,1740481182.9849422,14.75998592376709,0.0,1740481182.9849434,14.75998592376709,0.0,1740481182.9849443,14.75998592376709,0.0,1740481182.9849453,14.75998592376709,0.0,1740481182.9849463,14.75998592376709,0.9936657243791785,1740481182.9849474,14.75998592376709,0.0,1740481182.9849484,14.75998592376709,0.03305575250960735,1740481182.9849494,14.75998592376709,0.0,1740481182.9849503,14.75998592376709,0.9606099718695712,, +1740481183.0034075,14.779985904693604,6.901693244926349,1740481183.003409,14.779985904693604,0.0,1740481183.0034106,14.779985904693604,0.0,1740481183.0034127,14.779985904693604,10.822913188665492,1740481183.0034137,14.779985904693604,0.0,1740481183.0034149,14.779985904693604,0.0,1740481183.0034158,14.779985904693604,0.0,1740481183.0034168,14.779985904693604,0.0,1740481183.003418,14.779985904693604,0.9936657243791785,1740481183.0034187,14.779985904693604,0.0,1740481183.0034199,14.779985904693604,0.03305575250960735,1740481183.0034206,14.779985904693604,0.0,1740481183.0034218,14.779985904693604,0.9606099718695712,, +1740481183.0234256,14.799985885620117,6.901693244926349,1740481183.023427,14.799985885620117,0.0,1740481183.0234294,14.799985885620117,0.0,1740481183.0234315,14.799985885620117,10.822913188665492,1740481183.0234325,14.799985885620117,0.0,1740481183.0234337,14.799985885620117,0.0,1740481183.0234346,14.799985885620117,0.0,1740481183.0234356,14.799985885620117,0.0,1740481183.0234365,14.799985885620117,0.9936657243791785,1740481183.0234373,14.799985885620117,0.0,1740481183.023438,14.799985885620117,0.03305575250960735,1740481183.023439,14.799985885620117,0.0,1740481183.02344,14.799985885620117,0.9606099718695712,, +1740481183.045695,14.81998586654663,6.901693244926349,1740481183.045697,14.81998586654663,0.0,1740481183.0456994,14.81998586654663,0.0,1740481183.0457013,14.81998586654663,10.822913188665492,1740481183.0457025,14.81998586654663,0.0,1740481183.0457034,14.81998586654663,0.0,1740481183.0457044,14.81998586654663,0.0,1740481183.0457056,14.81998586654663,0.0,1740481183.0457063,14.81998586654663,0.9936657243791785,1740481183.0457072,14.81998586654663,0.0,1740481183.045708,14.81998586654663,0.03305575250960735,1740481183.0457091,14.81998586654663,0.0,1740481183.0457215,14.81998586654663,0.9606099718695712,, +1740481183.0707984,14.839985847473145,7.0073399684638265,1740481183.0708,14.839985847473145,0.0,1740481183.0708022,14.839985847473145,0.0,1740481183.070804,14.839985847473145,10.92561285128479,1740481183.0708053,14.839985847473145,0.0,1740481183.0708065,14.839985847473145,0.0,1740481183.0708072,14.839985847473145,0.0,1740481183.0708084,14.839985847473145,0.0,1740481183.0708091,14.839985847473145,0.9931829458542611,1740481183.07081,14.839985847473145,0.06817054145734969,1740481183.0708108,14.839985847473145,0.10266738811886848,1740481183.0708117,14.839985847473145,0.0,1740481183.0708127,14.839985847473145,0.959136441410482,, +1740481183.0859134,14.859985828399658,7.0073399684638265,1740481183.0859149,14.859985828399658,0.0,1740481183.0859172,14.859985828399658,0.0,1740481183.085919,14.859985828399658,10.92561285128479,1740481183.08592,14.859985828399658,0.0,1740481183.0859213,14.859985828399658,0.0,1740481183.085922,14.859985828399658,0.0,1740481183.0859234,14.859985828399658,0.0,1740481183.0859241,14.859985828399658,0.9931829458542611,1740481183.085925,14.859985828399658,0.06817054145734969,1740481183.0859258,14.859985828399658,0.10221704590112879,1740481183.085927,14.859985828399658,0.0,1740481183.0859277,14.859985828399658,0.959136441410482,, +1740481183.103705,14.879985809326172,7.0073399684638265,1740481183.1037066,14.879985809326172,0.0,1740481183.1037087,14.879985809326172,0.0,1740481183.1037107,14.879985809326172,10.92561285128479,1740481183.1037118,14.879985809326172,0.0,1740481183.1037128,14.879985809326172,0.0,1740481183.1037138,14.879985809326172,0.0,1740481183.1037147,14.879985809326172,0.0,1740481183.103716,14.879985809326172,0.9931829458542611,1740481183.1037166,14.879985809326172,0.06817054145734969,1740481183.1037173,14.879985809326172,0.10221704590112879,1740481183.1037188,14.879985809326172,0.0,1740481183.1037197,14.879985809326172,0.959136441410482,, +1740481183.1260521,14.899985790252686,7.0073399684638265,1740481183.1260543,14.899985790252686,0.0,1740481183.1260567,14.899985790252686,0.0,1740481183.1260588,14.899985790252686,10.92561285128479,1740481183.1260598,14.899985790252686,0.0,1740481183.126061,14.899985790252686,0.0,1740481183.126062,14.899985790252686,0.0,1740481183.126063,14.899985790252686,0.0,1740481183.126064,14.899985790252686,0.9931829458542611,1740481183.1260648,14.899985790252686,0.06817054145734969,1740481183.126066,14.899985790252686,0.10221704590112879,1740481183.1260667,14.899985790252686,0.0,1740481183.1260679,14.899985790252686,0.959136441410482,, +1740481183.144791,14.9199857711792,7.0073399684638265,1740481183.144793,14.9199857711792,0.0,1740481183.1447957,14.9199857711792,0.0,1740481183.1447978,14.9199857711792,10.92561285128479,1740481183.1447985,14.9199857711792,0.0,1740481183.1448,14.9199857711792,0.0,1740481183.1448011,14.9199857711792,0.0,1740481183.144802,14.9199857711792,0.0,1740481183.144803,14.9199857711792,0.9931829458542611,1740481183.144804,14.9199857711792,0.06817054145734969,1740481183.1448052,14.9199857711792,0.10221704590112879,1740481183.1448061,14.9199857711792,0.0,1740481183.1448069,14.9199857711792,0.959136441410482,, +1740481183.1660097,14.939985752105713,7.112961637532111,1740481183.1660113,14.939985752105713,0.0,1740481183.1660135,14.939985752105713,0.0,1740481183.1660154,14.939985752105713,11.038374303356237,1740481183.1660166,14.939985752105713,0.0,1740481183.1660178,14.939985752105713,0.0,1740481183.1660187,14.939985752105713,0.0,1740481183.1660197,14.939985752105713,0.0,1740481183.1660206,14.939985752105713,0.9943220109046655,1740481183.1660213,14.939985752105713,0.05677989095330571,1740481183.1660223,14.939985752105713,0.08729064677800075,1740481183.1660235,14.939985752105713,0.0,1740481183.1660242,14.939985752105713,0.9627063329120633,, +1740481183.1837943,14.959985733032227,7.112961637532111,1740481183.1837976,14.959985733032227,0.0,1740481183.1838005,14.959985733032227,0.0,1740481183.1838033,14.959985733032227,11.038374303356237,1740481183.183805,14.959985733032227,0.0,1740481183.1838064,14.959985733032227,0.0,1740481183.183808,14.959985733032227,0.0,1740481183.18381,14.959985733032227,0.0,1740481183.183812,14.959985733032227,0.9943220109046655,1740481183.1838133,14.959985733032227,0.05677989095330571,1740481183.1838148,14.959985733032227,0.08839556894590794,1740481183.1838162,14.959985733032227,0.0,1740481183.1838174,14.959985733032227,0.9627063329120633,, +1740481183.2040248,14.97998571395874,7.112961637532111,1740481183.2040272,14.97998571395874,0.0,1740481183.2040293,14.97998571395874,0.0,1740481183.2040315,14.97998571395874,11.038374303356237,1740481183.2040324,14.97998571395874,0.0,1740481183.2040336,14.97998571395874,0.0,1740481183.2040348,14.97998571395874,0.0,1740481183.2040355,14.97998571395874,0.0,1740481183.204037,14.97998571395874,0.9943220109046655,1740481183.204038,14.97998571395874,0.05677989095330571,1740481183.2040389,14.97998571395874,0.08839556894590794,1740481183.20404,14.97998571395874,0.0,1740481183.204041,14.97998571395874,0.9627063329120633,, +1740481183.224252,14.999985694885254,7.112961637532111,1740481183.224254,14.999985694885254,0.0,1740481183.224256,14.999985694885254,0.0,1740481183.2242584,14.999985694885254,11.038374303356237,1740481183.2242594,14.999985694885254,0.0,1740481183.2242603,14.999985694885254,0.0,1740481183.2242613,14.999985694885254,0.0,1740481183.2242625,14.999985694885254,0.0,1740481183.2242634,14.999985694885254,0.9943220109046655,1740481183.2242644,14.999985694885254,0.05677989095330571,1740481183.2242656,14.999985694885254,0.08839556894590794,1740481183.2242668,14.999985694885254,0.0,1740481183.2242675,14.999985694885254,0.9627063329120633,, +1740481183.2444644,15.019985675811768,7.112961637532111,1740481183.244467,15.019985675811768,0.0,1740481183.2444701,15.019985675811768,0.0,1740481183.244472,15.019985675811768,11.038374303356237,1740481183.2444735,15.019985675811768,0.0,1740481183.2444754,15.019985675811768,0.0,1740481183.2444777,15.019985675811768,0.0,1740481183.2444794,15.019985675811768,0.0,1740481183.244481,15.019985675811768,0.9943220109046655,1740481183.2444825,15.019985675811768,0.05677989095330571,1740481183.244484,15.019985675811768,0.08839556894590794,1740481183.2444856,15.019985675811768,0.0,1740481183.2445004,15.019985675811768,0.9627063329120633,, +1740481183.2671514,15.039985656738281,7.112961637532111,1740481183.2671533,15.039985656738281,0.0,1740481183.2671552,15.039985656738281,0.0,1740481183.2671573,15.039985656738281,11.038374303356237,1740481183.267158,15.039985656738281,0.0,1740481183.2671592,15.039985656738281,0.0,1740481183.2671604,15.039985656738281,0.0,1740481183.2671614,15.039985656738281,0.0,1740481183.267162,15.039985656738281,0.9943220109046655,1740481183.2671628,15.039985656738281,0.05677989095330571,1740481183.267164,15.039985656738281,0.08839556894590794,1740481183.2671647,15.039985656738281,0.0,1740481183.2671657,15.039985656738281,0.9627063329120633,, +1740481183.2842221,15.059985637664795,7.219027344451137,1740481183.2842238,15.059985637664795,0.0,1740481183.2842257,15.059985637664795,0.017222112042309667,1740481183.2842278,15.059985637664795,11.062347228327912,1740481183.2842288,15.059985637664795,0.0,1740481183.28423,15.059985637664795,0.0,1740481183.284231,15.059985637664795,0.0,1740481183.2842317,15.059985637664795,0.0,1740481183.2842326,15.059985637664795,0.9999999999999961,1740481183.2842338,15.059985637664795,9.43689570931383e-14,1740481183.2842345,15.059985637664795,0.03496489008996554,1740481183.2842352,15.059985637664795,0.0,1740481183.284236,15.059985637664795,0.9660817393767452,, +1740481183.303911,15.079985618591309,7.219027344451137,1740481183.303913,15.079985618591309,0.0,1740481183.3039153,15.079985618591309,0.017222112042309667,1740481183.3039172,15.079985618591309,11.062347228327912,1740481183.3039186,15.079985618591309,0.0,1740481183.30392,15.079985618591309,0.0,1740481183.3039212,15.079985618591309,0.0,1740481183.3039222,15.079985618591309,0.0,1740481183.303923,15.079985618591309,0.9999999999999961,1740481183.303924,15.079985618591309,9.43689570931383e-14,1740481183.303925,15.079985618591309,0.03391826062334524,1740481183.3039262,15.079985618591309,0.0,1740481183.3039277,15.079985618591309,0.9660817393767452,, +1740481183.323864,15.099985599517822,7.219027344451137,1740481183.3238657,15.099985599517822,0.0,1740481183.3238816,15.099985599517822,0.017222112042309667,1740481183.3238845,15.099985599517822,11.062347228327912,1740481183.3238857,15.099985599517822,0.0,1740481183.3238869,15.099985599517822,0.0,1740481183.3238878,15.099985599517822,0.0,1740481183.3238885,15.099985599517822,0.0,1740481183.3238897,15.099985599517822,0.9999999999999961,1740481183.3238907,15.099985599517822,9.43689570931383e-14,1740481183.3238914,15.099985599517822,0.03391826062334524,1740481183.3238926,15.099985599517822,0.0,1740481183.3238935,15.099985599517822,0.9660817393767452,, +1740481183.343732,15.119985580444336,7.219027344451137,1740481183.343734,15.119985580444336,0.0,1740481183.3437362,15.119985580444336,0.017222112042309667,1740481183.3437386,15.119985580444336,11.062347228327912,1740481183.3437397,15.119985580444336,0.0,1740481183.343741,15.119985580444336,0.0,1740481183.343742,15.119985580444336,0.0,1740481183.3437426,15.119985580444336,0.0,1740481183.3437438,15.119985580444336,0.9999999999999961,1740481183.3437445,15.119985580444336,9.43689570931383e-14,1740481183.3437455,15.119985580444336,0.03391826062334524,1740481183.3437467,15.119985580444336,0.0,1740481183.3437479,15.119985580444336,0.9660817393767452,, +1740481183.3664496,15.13998556137085,7.219027344451137,1740481183.3664513,15.13998556137085,0.0,1740481183.3664534,15.13998556137085,0.0,1740481183.3664556,15.13998556137085,11.151190823204626,1740481183.3664565,15.13998556137085,0.0,1740481183.3664577,15.13998556137085,0.0,1740481183.3664587,15.13998556137085,0.0,1740481183.3664596,15.13998556137085,0.0,1740481183.3664603,15.13998556137085,0.9953033140591997,1740481183.3664615,15.13998556137085,0.0,1740481183.3664622,15.13998556137085,0.029221574682454454,1740481183.3664632,15.13998556137085,0.0,1740481183.3664641,15.13998556137085,0.9660817393767452,, +1740481183.3851955,15.159985542297363,7.3252217650253755,1740481183.3851998,15.159985542297363,0.0,1740481183.3852031,15.159985542297363,0.01726002879473863,1740481183.385206,15.159985542297363,11.164186560159598,1740481183.385207,15.159985542297363,0.0,1740481183.3852086,15.159985542297363,0.0,1740481183.3852096,15.159985542297363,0.0,1740481183.3852112,15.159985542297363,0.0,1740481183.3852131,15.159985542297363,0.9953033140591997,1740481183.385215,15.159985542297363,0.04696685940796419,1740481183.385216,15.159985542297363,0.07928973817087477,1740481183.385217,15.159985542297363,0.0,1740481183.3852184,15.159985542297363,0.9639495934568613,, +1740481183.4039547,15.179985523223877,7.3252217650253755,1740481183.4039564,15.179985523223877,0.0,1740481183.4039586,15.179985523223877,0.01726002879473863,1740481183.4039605,15.179985523223877,11.164186560159598,1740481183.4039614,15.179985523223877,0.0,1740481183.4039626,15.179985523223877,0.0,1740481183.4039636,15.179985523223877,0.0,1740481183.4039648,15.179985523223877,0.0,1740481183.4039655,15.179985523223877,0.9953033140591997,1740481183.4039664,15.179985523223877,0.04696685940796419,1740481183.4039674,15.179985523223877,0.07832058001030262,1740481183.4039686,15.179985523223877,0.0,1740481183.4039695,15.179985523223877,0.9639495934568613,, +1740481183.4251766,15.19998550415039,7.3252217650253755,1740481183.4251788,15.19998550415039,0.0,1740481183.4251816,15.19998550415039,0.01726002879473863,1740481183.4251842,15.19998550415039,11.164186560159598,1740481183.4251857,15.19998550415039,0.0,1740481183.4251876,15.19998550415039,0.0,1740481183.4251888,15.19998550415039,0.0,1740481183.4251902,15.19998550415039,0.0,1740481183.4251912,15.19998550415039,0.9953033140591997,1740481183.4251924,15.19998550415039,0.04696685940796419,1740481183.4251935,15.19998550415039,0.07832058001030262,1740481183.4251945,15.19998550415039,0.0,1740481183.4251957,15.19998550415039,0.9639495934568613,, +1740481183.443668,15.219985485076904,7.3252217650253755,1740481183.4436698,15.219985485076904,0.0,1740481183.4436717,15.219985485076904,0.01726002879473863,1740481183.443674,15.219985485076904,11.164186560159598,1740481183.443675,15.219985485076904,0.0,1740481183.4436765,15.219985485076904,0.0,1740481183.4436774,15.219985485076904,0.0,1740481183.4436786,15.219985485076904,0.0,1740481183.4436796,15.219985485076904,0.9953033140591997,1740481183.4436805,15.219985485076904,0.04696685940796419,1740481183.4436812,15.219985485076904,0.07832058001030262,1740481183.4436827,15.219985485076904,0.0,1740481183.4436839,15.219985485076904,0.9639495934568613,, +1740481183.4677296,15.239985466003418,7.3252217650253755,1740481183.4677327,15.239985466003418,0.0,1740481183.467736,15.239985466003418,0.0,1740481183.4677384,15.239985466003418,11.2531209519391,1740481183.467739,15.239985466003418,0.0,1740481183.4677403,15.239985466003418,0.0,1740481183.4677415,15.239985466003418,0.0,1740481183.4677424,15.239985466003418,0.0,1740481183.4677434,15.239985466003418,0.9946942753454907,1740481183.4677444,15.239985466003418,0.0,1740481183.467745,15.239985466003418,0.030744681888629444,1740481183.4677458,15.239985466003418,0.0,1740481183.4677567,15.239985466003418,0.9639495934568613,, +1740481183.48371,15.259985446929932,7.3252217650253755,1740481183.4837117,15.259985446929932,0.0,1740481183.483714,15.259985446929932,0.0,1740481183.4837158,15.259985446929932,11.2531209519391,1740481183.483717,15.259985446929932,0.0,1740481183.4837182,15.259985446929932,0.0,1740481183.4837189,15.259985446929932,0.0,1740481183.4837203,15.259985446929932,0.0,1740481183.483721,15.259985446929932,0.9946942753454907,1740481183.483722,15.259985446929932,0.0,1740481183.483723,15.259985446929932,0.030744681888629444,1740481183.483724,15.259985446929932,0.0,1740481183.483725,15.259985446929932,0.9639495934568613,, +1740481183.5039093,15.279985427856445,7.431358120093588,1740481183.5039115,15.279985427856445,0.0,1740481183.5039134,15.279985427856445,0.017240035416099683,1740481183.5039158,15.279985427856445,11.27211392295522,1740481183.5039167,15.279985427856445,0.0,1740481183.5039182,15.279985427856445,0.0,1740481183.503919,15.279985427856445,0.0,1740481183.5039198,15.279985427856445,0.0,1740481183.5039208,15.279985427856445,0.9946942753454907,1740481183.503922,15.279985427856445,0.05305724654505406,1740481183.5039227,15.279985427856445,0.08252706579918241,1740481183.5039237,15.279985427856445,0.0,1740481183.5039248,15.279985427856445,0.9648260612568728,, +1740481183.5236702,15.299985408782959,7.431358120093588,1740481183.5236723,15.299985408782959,0.0,1740481183.5236742,15.299985408782959,0.017240035416099683,1740481183.5236764,15.299985408782959,11.27211392295522,1740481183.5236773,15.299985408782959,0.0,1740481183.5236788,15.299985408782959,0.0,1740481183.5236795,15.299985408782959,0.0,1740481183.523681,15.299985408782959,0.0,1740481183.523682,15.299985408782959,0.9946942753454907,1740481183.5236828,15.299985408782959,0.05305724654505406,1740481183.5236838,15.299985408782959,0.08292546063367201,1740481183.5236845,15.299985408782959,0.0,1740481183.5236857,15.299985408782959,0.9648260612568728,, +1740481183.544224,15.319985389709473,7.431358120093588,1740481183.544226,15.319985389709473,0.0,1740481183.5442283,15.319985389709473,0.017240035416099683,1740481183.5442305,15.319985389709473,11.27211392295522,1740481183.5442317,15.319985389709473,0.0,1740481183.5442328,15.319985389709473,0.0,1740481183.544234,15.319985389709473,0.0,1740481183.544235,15.319985389709473,0.0,1740481183.544236,15.319985389709473,0.9946942753454907,1740481183.5442371,15.319985389709473,0.05305724654505406,1740481183.5442379,15.319985389709473,0.08292546063367201,1740481183.5442388,15.319985389709473,0.0,1740481183.5442398,15.319985389709473,0.9648260612568728,, +1740481183.5662422,15.339985370635986,7.431358120093588,1740481183.566244,15.339985370635986,0.0,1740481183.5662458,15.339985370635986,0.0,1740481183.566248,15.339985370635986,11.361010242607334,1740481183.566249,15.339985370635986,0.0,1740481183.5662503,15.339985370635986,0.0,1740481183.566251,15.339985370635986,0.0,1740481183.566252,15.339985370635986,0.0,1740481183.566253,15.339985370635986,0.994949127791408,1740481183.566254,15.339985370635986,0.0,1740481183.5662549,15.339985370635986,0.030123066534535226,1740481183.5662556,15.339985370635986,0.0,1740481183.566257,15.339985370635986,0.9648260612568728,, +1740481183.5838606,15.3599853515625,7.431358120093588,1740481183.5838625,15.3599853515625,0.0,1740481183.5838652,15.3599853515625,0.0,1740481183.583867,15.3599853515625,11.361010242607334,1740481183.5838683,15.3599853515625,0.0,1740481183.5838692,15.3599853515625,0.0,1740481183.5838702,15.3599853515625,0.0,1740481183.5838711,15.3599853515625,0.0,1740481183.5838723,15.3599853515625,0.994949127791408,1740481183.583873,15.3599853515625,0.0,1740481183.583874,15.3599853515625,0.030123066534535226,1740481183.5838747,15.3599853515625,0.0,1740481183.583876,15.3599853515625,0.9648260612568728,, +1740481183.6041532,15.379985332489014,7.537543900360738,1740481183.604156,15.379985332489014,0.0,1740481183.6041586,15.379985332489014,0.017252482852303692,1740481183.6041613,15.379985332489014,11.378553929065106,1740481183.6041625,15.379985332489014,0.0,1740481183.6041644,15.379985332489014,0.0,1740481183.6041656,15.379985332489014,0.0,1740481183.604167,15.379985332489014,0.0,1740481183.6041682,15.379985332489014,0.994949127791408,1740481183.6041694,15.379985332489014,0.050508722085969016,1740481183.6041706,15.379985332489014,0.08042000411704675,1740481183.6041718,15.379985332489014,0.0,1740481183.6041727,15.379985332489014,0.964971663059607,, +1740481183.6241055,15.399985313415527,7.537543900360738,1740481183.6241074,15.399985313415527,0.0,1740481183.6241093,15.399985313415527,0.017252482852303692,1740481183.6241114,15.399985313415527,11.378553929065106,1740481183.6241124,15.399985313415527,0.0,1740481183.6241133,15.399985313415527,0.0,1740481183.6241145,15.399985313415527,0.0,1740481183.6241155,15.399985313415527,0.0,1740481183.6241164,15.399985313415527,0.994949127791408,1740481183.6241176,15.399985313415527,0.050508722085969016,1740481183.6241186,15.399985313415527,0.08048618681776998,1740481183.6241193,15.399985313415527,0.0,1740481183.6241202,15.399985313415527,0.964971663059607,, +1740481183.6436422,15.419985294342041,7.537543900360738,1740481183.6436436,15.419985294342041,0.0,1740481183.6436465,15.419985294342041,0.017252482852303692,1740481183.6436489,15.419985294342041,11.378553929065106,1740481183.6436498,15.419985294342041,0.0,1740481183.643651,15.419985294342041,0.0,1740481183.6436522,15.419985294342041,0.0,1740481183.6436532,15.419985294342041,0.0,1740481183.643654,15.419985294342041,0.994949127791408,1740481183.643655,15.419985294342041,0.050508722085969016,1740481183.643656,15.419985294342041,0.08048618681776998,1740481183.643657,15.419985294342041,0.0,1740481183.6436577,15.419985294342041,0.964971663059607,, +1740481183.6681788,15.439985275268555,7.537543900360738,1740481183.668181,15.439985275268555,0.0,1740481183.6681833,15.439985275268555,0.0,1740481183.6681857,15.439985275268555,11.467487226479953,1740481183.6681864,15.439985275268555,0.0,1740481183.6681876,15.439985275268555,0.0,1740481183.6681886,15.439985275268555,0.0,1740481183.6681898,15.439985275268555,0.0,1740481183.6681907,15.439985275268555,0.9949908572084273,1740481183.6681914,15.439985275268555,0.0,1740481183.6681921,15.439985275268555,0.03001919414882026,1740481183.6681933,15.439985275268555,0.0,1740481183.668194,15.439985275268555,0.964971663059607,, +1740481183.6838841,15.459985256195068,7.537543900360738,1740481183.6838858,15.459985256195068,0.0,1740481183.683889,15.459985256195068,0.0,1740481183.683891,15.459985256195068,11.467487226479953,1740481183.683892,15.459985256195068,0.0,1740481183.6838934,15.459985256195068,0.0,1740481183.6838949,15.459985256195068,0.0,1740481183.6838958,15.459985256195068,0.0,1740481183.6838968,15.459985256195068,0.9949908572084273,1740481183.683898,15.459985256195068,0.0,1740481183.683899,15.459985256195068,0.03001919414882026,1740481183.6838996,15.459985256195068,0.0,1740481183.6839006,15.459985256195068,0.964971663059607,, +1740481183.7038958,15.479985237121582,7.537543900360738,1740481183.7038972,15.479985237121582,0.0,1740481183.7038996,15.479985237121582,0.0,1740481183.7039015,15.479985237121582,11.467487226479953,1740481183.7039025,15.479985237121582,0.0,1740481183.703904,15.479985237121582,0.0,1740481183.703905,15.479985237121582,0.0,1740481183.703906,15.479985237121582,0.0,1740481183.703907,15.479985237121582,0.9949908572084273,1740481183.7039082,15.479985237121582,0.0,1740481183.703909,15.479985237121582,0.03001919414882026,1740481183.7039099,15.479985237121582,0.0,1740481183.7039108,15.479985237121582,0.964971663059607,, +1740481183.7238822,15.499985218048096,7.64376605653184,1740481183.7238843,15.499985218048096,0.0,1740481183.7238863,15.499985218048096,0.017259116848250013,1740481183.7238882,15.499985218048096,11.484730260692226,1740481183.723889,15.499985218048096,0.0,1740481183.72389,15.499985218048096,0.0,1740481183.7238915,15.499985218048096,0.0,1740481183.7238927,15.499985218048096,0.0,1740481183.7238941,15.499985218048096,0.9949908572084273,1740481183.7238948,15.499985218048096,0.050091427915688325,1740481183.7238955,15.499985218048096,0.08012231853052279,1740481183.7238965,15.499985218048096,0.0,1740481183.7238977,15.499985218048096,0.9649636217416188,, +1740481183.7440896,15.51998519897461,7.64376605653184,1740481183.7440917,15.51998519897461,0.0,1740481183.744094,15.51998519897461,0.017259116848250013,1740481183.7440958,15.51998519897461,11.484730260692226,1740481183.744097,15.51998519897461,0.0,1740481183.744098,15.51998519897461,0.0,1740481183.7440991,15.51998519897461,0.0,1740481183.7441,15.51998519897461,0.0,1740481183.7441008,15.51998519897461,0.9949908572084273,1740481183.7441015,15.51998519897461,0.050091427915688325,1740481183.7441027,15.51998519897461,0.08011866338249685,1740481183.7441037,15.51998519897461,0.0,1740481183.7441049,15.51998519897461,0.9649636217416188,, +1740481183.7652707,15.539985179901123,7.64376605653184,1740481183.7652726,15.539985179901123,0.0,1740481183.7652745,15.539985179901123,0.0,1740481183.7652767,15.539985179901123,11.573693300015076,1740481183.7652774,15.539985179901123,0.0,1740481183.7652788,15.539985179901123,0.0,1740481183.7652795,15.539985179901123,0.0,1740481183.7652805,15.539985179901123,0.0,1740481183.7652812,15.539985179901123,0.9949885570858942,1740481183.7652824,15.539985179901123,0.0,1740481183.765283,15.539985179901123,0.030024935344275416,1740481183.7652838,15.539985179901123,0.0,1740481183.7652848,15.539985179901123,0.9649636217416188,, +1740481183.7839804,15.559985160827637,7.64376605653184,1740481183.783982,15.559985160827637,0.0,1740481183.7839842,15.559985160827637,0.0,1740481183.783986,15.559985160827637,11.573693300015076,1740481183.7839873,15.559985160827637,0.0,1740481183.7839885,15.559985160827637,0.0,1740481183.7839894,15.559985160827637,0.0,1740481183.7839909,15.559985160827637,0.0,1740481183.7839918,15.559985160827637,0.9949885570858942,1740481183.7839925,15.559985160827637,0.0,1740481183.7839935,15.559985160827637,0.030024935344275416,1740481183.7839947,15.559985160827637,0.0,1740481183.7839954,15.559985160827637,0.9649636217416188,, +1740481183.8054621,15.57998514175415,7.64376605653184,1740481183.8054638,15.57998514175415,0.0,1740481183.8054664,15.57998514175415,0.0,1740481183.8054686,15.57998514175415,11.573693300015076,1740481183.8054698,15.57998514175415,0.0,1740481183.8054707,15.57998514175415,0.0,1740481183.8054717,15.57998514175415,0.0,1740481183.805473,15.57998514175415,0.0,1740481183.805474,15.57998514175415,0.9949885570858942,1740481183.805475,15.57998514175415,0.0,1740481183.8054762,15.57998514175415,0.030024935344275416,1740481183.8054771,15.57998514175415,0.0,1740481183.805478,15.57998514175415,0.9649636217416188,, +1740481183.8236613,15.599985122680664,7.749910862942164,1740481183.8236628,15.599985122680664,0.0,1740481183.8236802,15.599985122680664,0.017246509087622378,1740481183.8236835,15.599985122680664,11.588889849006218,1740481183.8236847,15.599985122680664,0.0,1740481183.823686,15.599985122680664,0.0,1740481183.823687,15.599985122680664,0.0,1740481183.8236883,15.599985122680664,0.0,1740481183.823689,15.599985122680664,0.9949885570858942,1740481183.8236897,15.599985122680664,0.050114429141107086,1740481183.823691,15.599985122680664,0.08163024499986875,1740481183.823692,15.599985122680664,0.0,1740481183.823693,15.599985122680664,0.9639386416933776,, +1740481183.8457994,15.619985103607178,7.749910862942164,1740481183.8458538,15.619985103607178,0.0,1740481183.8458583,15.619985103607178,0.017246509087622378,1740481183.8458838,15.619985103607178,11.588889849006218,1740481183.845885,15.619985103607178,0.0,1740481183.8458865,15.619985103607178,0.0,1740481183.8458874,15.619985103607178,0.0,1740481183.8458889,15.619985103607178,0.0,1740481183.8458898,15.619985103607178,0.9949885570858942,1740481183.8458908,15.619985103607178,0.050114429141107086,1740481183.8458915,15.619985103607178,0.08116434453362364,1740481183.8458927,15.619985103607178,0.0,1740481183.8458936,15.619985103607178,0.9639386416933776,, +1740481183.86856,15.639985084533691,7.749910862942164,1740481183.868562,15.639985084533691,0.0,1740481183.8685641,15.639985084533691,0.0,1740481183.8685665,15.639985084533691,11.677788146328918,1740481183.8685675,15.639985084533691,0.0,1740481183.8685687,15.639985084533691,0.0,1740481183.8685696,15.639985084533691,0.0,1740481183.8685706,15.639985084533691,0.0,1740481183.8685718,15.639985084533691,0.994691051200559,1740481183.8685725,15.639985084533691,0.0,1740481183.8685734,15.639985084533691,0.03075240950718139,1740481183.8685741,15.639985084533691,0.0,1740481183.8685753,15.639985084533691,0.9639386416933776,, +1740481183.8839326,15.659985065460205,7.749910862942164,1740481183.8839343,15.659985065460205,0.0,1740481183.8839364,15.659985065460205,0.0,1740481183.8839386,15.659985065460205,11.677788146328918,1740481183.8839397,15.659985065460205,0.0,1740481183.883941,15.659985065460205,0.0,1740481183.883942,15.659985065460205,0.0,1740481183.8839426,15.659985065460205,0.0,1740481183.8839438,15.659985065460205,0.994691051200559,1740481183.8839447,15.659985065460205,0.0,1740481183.8839457,15.659985065460205,0.03075240950718139,1740481183.8839464,15.659985065460205,0.0,1740481183.8839476,15.659985065460205,0.9639386416933776,, +1740481183.903542,15.679985046386719,7.749910862942164,1740481183.9035444,15.679985046386719,0.0,1740481183.9035468,15.679985046386719,0.0,1740481183.9035509,15.679985046386719,11.677788146328918,1740481183.9035552,15.679985046386719,0.0,1740481183.9035618,15.679985046386719,0.0,1740481183.9035635,15.679985046386719,0.0,1740481183.9035654,15.679985046386719,0.0,1740481183.9035687,15.679985046386719,0.994691051200559,1740481183.903572,15.679985046386719,0.0,1740481183.9035735,15.679985046386719,0.03075240950718139,1740481183.903576,15.679985046386719,0.0,1740481183.9035773,15.679985046386719,0.9639386416933776,, +1740481183.9236648,15.699985027313232,7.749910862942164,1740481183.9236667,15.699985027313232,0.0,1740481183.9236686,15.699985027313232,0.0,1740481183.9236708,15.699985027313232,11.677788146328918,1740481183.9236717,15.699985027313232,0.0,1740481183.9236732,15.699985027313232,0.0,1740481183.923674,15.699985027313232,0.0,1740481183.923675,15.699985027313232,0.0,1740481183.923676,15.699985027313232,0.994691051200559,1740481183.923677,15.699985027313232,0.0,1740481183.923678,15.699985027313232,0.03075240950718139,1740481183.9236786,15.699985027313232,0.0,1740481183.9236798,15.699985027313232,0.9639386416933776,, +1740481183.9438567,15.719985008239746,7.855969198936354,1740481183.9438581,15.719985008239746,0.0,1740481183.9438605,15.719985008239746,0.01722730671225854,1740481183.9438622,15.719985008239746,11.693181581576459,1740481183.9438634,15.719985008239746,0.0,1740481183.9438646,15.719985008239746,0.0,1740481183.9438655,15.719985008239746,0.0,1740481183.9438663,15.719985008239746,0.0,1740481183.9438674,15.719985008239746,0.994691051200559,1740481183.9438682,15.719985008239746,0.053089487994458784,1740481183.943869,15.719985008239746,0.08517562260073468,1740481183.9438703,15.719985008239746,0.0,1740481183.9438713,15.719985008239746,0.9630217059610185,, +1740481183.9669354,15.73998498916626,7.855969198936354,1740481183.9669397,15.73998498916626,0.0,1740481183.966945,15.73998498916626,0.0,1740481183.9669487,15.73998498916626,11.782012610858391,1740481183.9669516,15.73998498916626,0.0,1740481183.966954,15.73998498916626,0.0,1740481183.9669554,15.73998498916626,0.0,1740481183.966957,15.73998498916626,0.0,1740481183.9669597,15.73998498916626,0.994417636431985,1740481183.966962,15.73998498916626,0.0,1740481183.9669635,15.73998498916626,0.03139593047096645,1740481183.9669664,15.73998498916626,0.0,1740481183.966969,15.73998498916626,0.9630217059610185,, +1740481183.9838066,15.759984970092773,7.855969198936354,1740481183.9838083,15.759984970092773,0.0,1740481183.9838107,15.759984970092773,0.0,1740481183.9838123,15.759984970092773,11.782012610858391,1740481183.9838133,15.759984970092773,0.0,1740481183.983815,15.759984970092773,0.0,1740481183.983816,15.759984970092773,0.0,1740481183.9838169,15.759984970092773,0.0,1740481183.9838178,15.759984970092773,0.994417636431985,1740481183.9838185,15.759984970092773,0.0,1740481183.9838195,15.759984970092773,0.03139593047096645,1740481183.9838204,15.759984970092773,0.0,1740481183.9838216,15.759984970092773,0.9630217059610185,, +1740481184.003502,15.779984951019287,7.855969198936354,1740481184.0035033,15.779984951019287,0.0,1740481184.0035057,15.779984951019287,0.0,1740481184.0035076,15.779984951019287,11.782012610858391,1740481184.0035088,15.779984951019287,0.0,1740481184.00351,15.779984951019287,0.0,1740481184.003511,15.779984951019287,0.0,1740481184.003512,15.779984951019287,0.0,1740481184.0035129,15.779984951019287,0.994417636431985,1740481184.0035136,15.779984951019287,0.0,1740481184.0035143,15.779984951019287,0.03139593047096645,1740481184.0035155,15.779984951019287,0.0,1740481184.0035164,15.779984951019287,0.9630217059610185,, +1740481184.0234916,15.7999849319458,7.855969198936354,1740481184.0234933,15.7999849319458,0.0,1740481184.0234957,15.7999849319458,0.0,1740481184.0234978,15.7999849319458,11.782012610858391,1740481184.0234988,15.7999849319458,0.0,1740481184.0235,15.7999849319458,0.0,1740481184.0235012,15.7999849319458,0.0,1740481184.023502,15.7999849319458,0.0,1740481184.0235028,15.7999849319458,0.994417636431985,1740481184.0235038,15.7999849319458,0.0,1740481184.023505,15.7999849319458,0.03139593047096645,1740481184.0235057,15.7999849319458,0.0,1740481184.0235066,15.7999849319458,0.9630217059610185,, +1740481184.043809,15.819984912872314,7.96184926861933,1740481184.043811,15.819984912872314,0.0,1740481184.0438135,15.819984912872314,0.01719362311266791,1740481184.0438151,15.819984912872314,11.795625359331584,1740481184.043816,15.819984912872314,0.0,1740481184.0438175,15.819984912872314,0.0,1740481184.0438187,15.819984912872314,0.0,1740481184.0438194,15.819984912872314,0.0,1740481184.0438206,15.819984912872314,0.994417636431985,1740481184.0438218,15.819984912872314,0.05582363568011117,1740481184.0438225,15.819984912872314,0.08982383939228443,1740481184.043824,15.819984912872314,0.0,1740481184.043825,15.819984912872314,0.9612312686412813,, +1740481184.06916,15.839984893798828,7.96184926861933,1740481184.0691617,15.839984893798828,0.0,1740481184.069164,15.839984893798828,0.0,1740481184.0691662,15.839984893798828,11.884311805901893,1740481184.0691671,15.839984893798828,0.0,1740481184.0691683,15.839984893798828,0.0,1740481184.0691695,15.839984893798828,0.0,1740481184.0691702,15.839984893798828,0.0,1740481184.0691712,15.839984893798828,0.9938639688710971,1740481184.069172,15.839984893798828,0.0,1740481184.0691726,15.839984893798828,0.03263270022981579,1740481184.0691738,15.839984893798828,0.0,1740481184.0691748,15.839984893798828,0.9612312686412813,, +1740481184.0839884,15.859984874725342,7.96184926861933,1740481184.0839903,15.859984874725342,0.0,1740481184.0839922,15.859984874725342,0.0,1740481184.0839946,15.859984874725342,11.884311805901893,1740481184.0839956,15.859984874725342,0.0,1740481184.083997,15.859984874725342,0.0,1740481184.083998,15.859984874725342,0.0,1740481184.0839987,15.859984874725342,0.0,1740481184.0839996,15.859984874725342,0.9938639688710971,1740481184.0840008,15.859984874725342,0.0,1740481184.0840015,15.859984874725342,0.03263270022981579,1740481184.0840025,15.859984874725342,0.0,1740481184.0840032,15.859984874725342,0.9612312686412813,, +1740481184.1037815,15.879984855651855,7.96184926861933,1740481184.1037831,15.879984855651855,0.0,1740481184.1037855,15.879984855651855,0.0,1740481184.1037874,15.879984855651855,11.884311805901893,1740481184.1037889,15.879984855651855,0.0,1740481184.10379,15.879984855651855,0.0,1740481184.1037908,15.879984855651855,0.0,1740481184.1037922,15.879984855651855,0.0,1740481184.103793,15.879984855651855,0.9938639688710971,1740481184.1037939,15.879984855651855,0.0,1740481184.103795,15.879984855651855,0.03263270022981579,1740481184.103796,15.879984855651855,0.0,1740481184.103797,15.879984855651855,0.9612312686412813,, +1740481184.1240425,15.89998483657837,7.96184926861933,1740481184.1240451,15.89998483657837,0.0,1740481184.1240473,15.89998483657837,0.0,1740481184.1240497,15.89998483657837,11.884311805901893,1740481184.1240509,15.89998483657837,0.0,1740481184.1240525,15.89998483657837,0.0,1740481184.1240537,15.89998483657837,0.0,1740481184.1240547,15.89998483657837,0.0,1740481184.1240563,15.89998483657837,0.9938639688710971,1740481184.1240573,15.89998483657837,0.0,1740481184.1240587,15.89998483657837,0.03263270022981579,1740481184.1240597,15.89998483657837,0.0,1740481184.1240606,15.89998483657837,0.9612312686412813,, +1740481184.1436696,15.919984817504883,7.96184926861933,1740481184.1436713,15.919984817504883,0.0,1740481184.143674,15.919984817504883,0.0,1740481184.1436758,15.919984817504883,11.884311805901893,1740481184.143677,15.919984817504883,0.0,1740481184.1436782,15.919984817504883,0.0,1740481184.1436794,15.919984817504883,0.0,1740481184.1436806,15.919984817504883,0.0,1740481184.1436818,15.919984817504883,0.9938639688710971,1740481184.1436827,15.919984817504883,0.0,1740481184.143684,15.919984817504883,0.03263270022981579,1740481184.1436849,15.919984817504883,0.0,1740481184.1436858,15.919984817504883,0.9612312686412813,, +1740481184.1654892,15.939984798431396,8.067603297929363,1740481184.165492,15.939984798431396,0.0,1740481184.1654944,15.939984798431396,0.0,1740481184.165508,15.939984798431396,11.988067655067846,1740481184.1655104,15.939984798431396,0.0,1740481184.165513,15.939984798431396,0.0,1740481184.1657388,15.939984798431396,0.0,1740481184.16574,15.939984798431396,0.0,1740481184.1657572,15.939984798431396,0.9935436364818048,1740481184.1657581,15.939984798431396,0.06456363518208996,1740481184.1657593,15.939984798431396,0.09818361960831774,1740481184.1657603,15.939984798431396,0.0,1740481184.1657612,15.939984798431396,0.9602321785692415,, +1740481184.18417,15.95998477935791,8.067603297929363,1740481184.184172,15.95998477935791,0.0,1740481184.1841745,15.95998477935791,0.0,1740481184.1841767,15.95998477935791,11.988067655067846,1740481184.1841779,15.95998477935791,0.0,1740481184.1841795,15.95998477935791,0.0,1740481184.1841807,15.95998477935791,0.0,1740481184.184182,15.95998477935791,0.0,1740481184.1841834,15.95998477935791,0.9935436364818048,1740481184.1841843,15.95998477935791,0.06456363518208996,1740481184.1841855,15.95998477935791,0.09787509309465325,1740481184.1841867,15.95998477935791,0.0,1740481184.1841877,15.95998477935791,0.9602321785692415,, +1740481184.2038589,15.979984760284424,8.067603297929363,1740481184.2038608,15.979984760284424,0.0,1740481184.2038631,15.979984760284424,0.0,1740481184.203865,15.979984760284424,11.988067655067846,1740481184.203866,15.979984760284424,0.0,1740481184.2038674,15.979984760284424,0.0,1740481184.2038686,15.979984760284424,0.0,1740481184.2038696,15.979984760284424,0.0,1740481184.2038705,15.979984760284424,0.9935436364818048,1740481184.2038717,15.979984760284424,0.06456363518208996,1740481184.2038727,15.979984760284424,0.09787509309465325,1740481184.2038739,15.979984760284424,0.0,1740481184.2038746,15.979984760284424,0.9602321785692415,, +1740481184.2254028,15.999984741210938,8.067603297929363,1740481184.2254055,15.999984741210938,0.0,1740481184.2254078,15.999984741210938,0.0,1740481184.2254097,15.999984741210938,11.988067655067846,1740481184.2254112,15.999984741210938,0.0,1740481184.2254124,15.999984741210938,0.0,1740481184.2254133,15.999984741210938,0.0,1740481184.2254145,15.999984741210938,0.0,1740481184.2254155,15.999984741210938,0.9935436364818048,1740481184.2254162,15.999984741210938,0.06456363518208996,1740481184.2254171,15.999984741210938,0.09787509309465325,1740481184.2254186,15.999984741210938,0.0,1740481184.2254195,15.999984741210938,0.9602321785692415,, +1740481184.2439463,16.01998472213745,8.067603297929363,1740481184.2439482,16.01998472213745,0.0,1740481184.2439666,16.01998472213745,0.0,1740481184.2439685,16.01998472213745,11.988067655067846,1740481184.2439697,16.01998472213745,0.0,1740481184.2439709,16.01998472213745,0.0,1740481184.2439718,16.01998472213745,0.0,1740481184.2439728,16.01998472213745,0.0,1740481184.243974,16.01998472213745,0.9935436364818048,1740481184.2439747,16.01998472213745,0.06456363518208996,1740481184.2439756,16.01998472213745,0.09787509309465325,1740481184.2439766,16.01998472213745,0.0,1740481184.2439778,16.01998472213745,0.9602321785692415,, +1740481184.270517,16.039984703063965,8.173387394235935,1740481184.270519,16.039984703063965,0.0,1740481184.2705214,16.039984703063965,0.0,1740481184.2705233,16.039984703063965,12.101478756791485,1740481184.2705245,16.039984703063965,0.0,1740481184.2705257,16.039984703063965,0.0,1740481184.2705266,16.039984703063965,0.0,1740481184.2705278,16.039984703063965,0.0,1740481184.2705288,16.039984703063965,0.9947225211349098,1740481184.2705297,16.039984703063965,0.05277478865086338,1740481184.2705307,16.039984703063965,0.08225407370436262,1740481184.270532,16.039984703063965,0.0,1740481184.2705326,16.039984703063965,0.9640456812777749,, +1740481184.2835634,16.05998468399048,8.173387394235935,1740481184.2835648,16.05998468399048,0.0,1740481184.283567,16.05998468399048,0.0,1740481184.2835689,16.05998468399048,12.101478756791485,1740481184.2835698,16.05998468399048,0.0,1740481184.2835712,16.05998468399048,0.0,1740481184.2835722,16.05998468399048,0.0,1740481184.283573,16.05998468399048,0.0,1740481184.283574,16.05998468399048,0.9947225211349098,1740481184.283575,16.05998468399048,0.05277478865086338,1740481184.2835758,16.05998468399048,0.08345162850799825,1740481184.2835765,16.05998468399048,0.0,1740481184.2835777,16.05998468399048,0.9640456812777749,, +1740481184.3039687,16.079984664916992,8.173387394235935,1740481184.3039706,16.079984664916992,0.0,1740481184.303973,16.079984664916992,0.0,1740481184.3039749,16.079984664916992,12.101478756791485,1740481184.3039758,16.079984664916992,0.0,1740481184.3039773,16.079984664916992,0.0,1740481184.3039782,16.079984664916992,0.0,1740481184.3039792,16.079984664916992,0.0,1740481184.30398,16.079984664916992,0.9947225211349098,1740481184.303981,16.079984664916992,0.05277478865086338,1740481184.303982,16.079984664916992,0.08345162850799825,1740481184.3039827,16.079984664916992,0.0,1740481184.303984,16.079984664916992,0.9640456812777749,, +1740481184.3236508,16.099984645843506,8.173387394235935,1740481184.3236525,16.099984645843506,0.0,1740481184.3236547,16.099984645843506,0.0,1740481184.323657,16.099984645843506,12.101478756791485,1740481184.3236578,16.099984645843506,0.0,1740481184.323659,16.099984645843506,0.0,1740481184.3236601,16.099984645843506,0.0,1740481184.3236609,16.099984645843506,0.0,1740481184.3236616,16.099984645843506,0.9947225211349098,1740481184.3236625,16.099984645843506,0.05277478865086338,1740481184.3236637,16.099984645843506,0.08345162850799825,1740481184.3236644,16.099984645843506,0.0,1740481184.3236654,16.099984645843506,0.9640456812777749,, +1740481184.343997,16.11998462677002,8.173387394235935,1740481184.3439987,16.11998462677002,0.0,1740481184.344001,16.11998462677002,0.0,1740481184.344003,16.11998462677002,12.101478756791485,1740481184.3440042,16.11998462677002,0.0,1740481184.3440053,16.11998462677002,0.0,1740481184.3440063,16.11998462677002,0.0,1740481184.3440075,16.11998462677002,0.0,1740481184.3440084,16.11998462677002,0.9947225211349098,1740481184.3440094,16.11998462677002,0.05277478865086338,1740481184.3440104,16.11998462677002,0.08345162850799825,1740481184.3440113,16.11998462677002,0.0,1740481184.344012,16.11998462677002,0.9640456812777749,, +1740481184.367072,16.139984607696533,8.173387394235935,1740481184.3670743,16.139984607696533,0.0,1740481184.3670766,16.139984607696533,0.0,1740481184.367133,16.139984607696533,12.101478756791485,1740481184.367134,16.139984607696533,0.0,1740481184.3671355,16.139984607696533,0.0,1740481184.3671365,16.139984607696533,0.0,1740481184.3671374,16.139984607696533,0.0,1740481184.3671386,16.139984607696533,0.9947225211349098,1740481184.3671398,16.139984607696533,0.05277478865086338,1740481184.3671618,16.139984607696533,0.08345162850799825,1740481184.367163,16.139984607696533,0.0,1740481184.367164,16.139984607696533,0.9640456812777749,, +1740481184.384567,16.159984588623047,8.279588181846634,1740481184.3845716,16.159984588623047,0.0,1740481184.3845763,16.159984588623047,0.017250991233561445,1740481184.384581,16.159984588623047,12.124682888321944,1740481184.3845835,16.159984588623047,0.0,1740481184.3845856,16.159984588623047,0.0,1740481184.3845873,16.159984588623047,0.0,1740481184.3845887,16.159984588623047,0.0,1740481184.3845904,16.159984588623047,0.9999999999999961,1740481184.384592,16.159984588623047,5.551115123125783e-15,1740481184.3845935,16.159984588623047,0.034023617169667154,1740481184.384595,16.159984588623047,0.0,1740481184.3845966,16.159984588623047,0.967022251426224,, +1740481184.4049273,16.17998456954956,8.279588181846634,1740481184.4049287,16.17998456954956,0.0,1740481184.4049313,16.17998456954956,0.017250991233561445,1740481184.4049332,16.17998456954956,12.124682888321944,1740481184.4049342,16.17998456954956,0.0,1740481184.4049354,16.17998456954956,0.0,1740481184.4049366,16.17998456954956,0.0,1740481184.4049375,16.17998456954956,0.0,1740481184.4049382,16.17998456954956,0.9999999999999961,1740481184.40494,16.17998456954956,5.551115123125783e-15,1740481184.4049406,16.17998456954956,0.032977748573777665,1740481184.4049416,16.17998456954956,0.0,1740481184.4049423,16.17998456954956,0.967022251426224,, +1740481184.4238462,16.199984550476074,8.279588181846634,1740481184.423851,16.199984550476074,0.0,1740481184.423855,16.199984550476074,0.017250991233561445,1740481184.4238577,16.199984550476074,12.124682888321944,1740481184.423859,16.199984550476074,0.0,1740481184.4238603,16.199984550476074,0.0,1740481184.4238617,16.199984550476074,0.0,1740481184.4238627,16.199984550476074,0.0,1740481184.423864,16.199984550476074,0.9999999999999961,1740481184.4238648,16.199984550476074,5.551115123125783e-15,1740481184.4238663,16.199984550476074,0.032977748573777665,1740481184.4238675,16.199984550476074,0.0,1740481184.4238687,16.199984550476074,0.967022251426224,, +1740481184.4442825,16.219984531402588,8.279588181846634,1740481184.4442844,16.219984531402588,0.0,1740481184.4442863,16.219984531402588,0.017250991233561445,1740481184.4442885,16.219984531402588,12.124682888321944,1740481184.4442894,16.219984531402588,0.0,1740481184.4442909,16.219984531402588,0.0,1740481184.4442918,16.219984531402588,0.0,1740481184.4442928,16.219984531402588,0.0,1740481184.444294,16.219984531402588,0.9999999999999961,1740481184.4442947,16.219984531402588,5.551115123125783e-15,1740481184.4442954,16.219984531402588,0.032977748573777665,1740481184.4442964,16.219984531402588,0.0,1740481184.4442976,16.219984531402588,0.967022251426224,, +1740481184.4665623,16.2399845123291,8.279588181846634,1740481184.4665647,16.2399845123291,0.0,1740481184.4665668,16.2399845123291,0.0,1740481184.4665701,16.2399845123291,12.213632684699082,1740481184.466572,16.2399845123291,0.0,1740481184.4665742,16.2399845123291,0.0,1740481184.4665754,16.2399845123291,0.0,1740481184.4665763,16.2399845123291,0.0,1740481184.4665773,16.2399845123291,0.99556016960594,1740481184.4665785,16.2399845123291,0.0,1740481184.4665794,16.2399845123291,0.02853791817971596,1740481184.4665804,16.2399845123291,0.0,1740481184.4665816,16.2399845123291,0.967022251426224,, +1740481184.4842525,16.259984493255615,8.385876572242696,1740481184.484254,16.259984493255615,0.0,1740481184.4842565,16.259984493255615,0.017279760126631703,1740481184.4842587,16.259984493255615,12.226358388107364,1740481184.4842596,16.259984493255615,0.0,1740481184.4842608,16.259984493255615,0.0,1740481184.484262,16.259984493255615,0.0,1740481184.4842627,16.259984493255615,0.0,1740481184.4842637,16.259984493255615,0.99556016960594,1740481184.4842646,16.259984493255615,0.044398303940561545,1740481184.4842656,16.259984493255615,0.0762482643570532,1740481184.4842665,16.259984493255615,0.0,1740481184.4842675,16.259984493255615,0.9647452230670487,, +1740481184.5039654,16.27998447418213,8.385876572242696,1740481184.503967,16.27998447418213,0.0,1740481184.5039692,16.27998447418213,0.017279760126631703,1740481184.503971,16.27998447418213,12.226358388107364,1740481184.503972,16.27998447418213,0.0,1740481184.5039735,16.27998447418213,0.0,1740481184.5039744,16.27998447418213,0.0,1740481184.5039752,16.27998447418213,0.0,1740481184.503976,16.27998447418213,0.99556016960594,1740481184.5039773,16.27998447418213,0.044398303940561545,1740481184.503978,16.27998447418213,0.07521325047945282,1740481184.503979,16.27998447418213,0.0,1740481184.50398,16.27998447418213,0.9647452230670487,, +1740481184.5235274,16.299984455108643,8.385876572242696,1740481184.523529,16.299984455108643,0.0,1740481184.5235312,16.299984455108643,0.017279760126631703,1740481184.5235333,16.299984455108643,12.226358388107364,1740481184.5235343,16.299984455108643,0.0,1740481184.5235357,16.299984455108643,0.0,1740481184.5235367,16.299984455108643,0.0,1740481184.5235376,16.299984455108643,0.0,1740481184.5235384,16.299984455108643,0.99556016960594,1740481184.5235398,16.299984455108643,0.044398303940561545,1740481184.5235405,16.299984455108643,0.07521325047945282,1740481184.5235415,16.299984455108643,0.0,1740481184.5235426,16.299984455108643,0.9647452230670487,, +1740481184.545763,16.319984436035156,8.385876572242696,1740481184.5457697,16.319984436035156,0.0,1740481184.5457733,16.319984436035156,0.017279760126631703,1740481184.5457766,16.319984436035156,12.226358388107364,1740481184.545779,16.319984436035156,0.0,1740481184.5457816,16.319984436035156,0.0,1740481184.5457838,16.319984436035156,0.0,1740481184.545786,16.319984436035156,0.0,1740481184.5457888,16.319984436035156,0.99556016960594,1740481184.5457914,16.319984436035156,0.044398303940561545,1740481184.5457942,16.319984436035156,0.07521325047945282,1740481184.5457969,16.319984436035156,0.0,1740481184.5457995,16.319984436035156,0.9647452230670487,, +1740481184.5652034,16.33998441696167,8.385876572242696,1740481184.565205,16.33998441696167,0.0,1740481184.5652072,16.33998441696167,0.0,1740481184.5652096,16.33998441696167,12.315367018376794,1740481184.5652106,16.33998441696167,0.0,1740481184.565212,16.33998441696167,0.0,1740481184.565213,16.33998441696167,0.0,1740481184.565214,16.33998441696167,0.0,1740481184.5652146,16.33998441696167,0.9949258848694771,1740481184.5652158,16.33998441696167,0.0,1740481184.5652165,16.33998441696167,0.0301806618024284,1740481184.5652175,16.33998441696167,0.0,1740481184.5652182,16.33998441696167,0.9647452230670487,, +1740481184.5841286,16.359984397888184,8.385876572242696,1740481184.5841305,16.359984397888184,0.0,1740481184.584133,16.359984397888184,0.0,1740481184.5841348,16.359984397888184,12.315367018376794,1740481184.584136,16.359984397888184,0.0,1740481184.5841374,16.359984397888184,0.0,1740481184.5841384,16.359984397888184,0.0,1740481184.5841396,16.359984397888184,0.0,1740481184.5841403,16.359984397888184,0.9949258848694771,1740481184.5841413,16.359984397888184,0.0,1740481184.584142,16.359984397888184,0.0301806618024284,1740481184.5841432,16.359984397888184,0.0,1740481184.584144,16.359984397888184,0.9647452230670487,, +1740481184.607188,16.379984378814697,8.4920839766951,1740481184.6071906,16.379984378814697,0.0,1740481184.6071944,16.379984378814697,0.017255593115394933,1740481184.6071978,16.379984378814697,12.333837319558828,1740481184.6071994,16.379984378814697,0.0,1740481184.6072025,16.379984378814697,0.0,1740481184.6072037,16.379984378814697,0.0,1740481184.6072052,16.379984378814697,0.0,1740481184.6072063,16.379984378814697,0.9949258848694771,1740481184.6072078,16.379984378814697,0.0507411513051903,1740481184.607209,16.379984378814697,0.08003838879587144,1740481184.6072102,16.379984378814697,0.0,1740481184.6072118,16.379984378814697,0.9653525771003691,, +1740481184.6262903,16.39998435974121,8.4920839766951,1740481184.6262953,16.39998435974121,0.0,1740481184.6262982,16.39998435974121,0.017255593115394933,1740481184.6263008,16.39998435974121,12.333837319558828,1740481184.6263032,16.39998435974121,0.0,1740481184.6263056,16.39998435974121,0.0,1740481184.626307,16.39998435974121,0.0,1740481184.6263087,16.39998435974121,0.0,1740481184.6263094,16.39998435974121,0.9949258848694771,1740481184.6263115,16.39998435974121,0.0507411513051903,1740481184.626313,16.39998435974121,0.08031445907429824,1740481184.626314,16.39998435974121,0.0,1740481184.6263158,16.39998435974121,0.9653525771003691,, +1740481184.6444757,16.419984340667725,8.4920839766951,1740481184.6444795,16.419984340667725,0.0,1740481184.644484,16.419984340667725,0.017255593115394933,1740481184.6444876,16.419984340667725,12.333837319558828,1740481184.6444895,16.419984340667725,0.0,1740481184.6444921,16.419984340667725,0.0,1740481184.644494,16.419984340667725,0.0,1740481184.6444962,16.419984340667725,0.0,1740481184.6444983,16.419984340667725,0.9949258848694771,1740481184.6445005,16.419984340667725,0.0507411513051903,1740481184.644503,16.419984340667725,0.08031445907429824,1740481184.644505,16.419984340667725,0.0,1740481184.644508,16.419984340667725,0.9653525771003691,, +1740481184.665617,16.43998432159424,8.4920839766951,1740481184.6656187,16.43998432159424,0.0,1740481184.6656208,16.43998432159424,0.0,1740481184.6656353,16.43998432159424,12.42278913089584,1740481184.665638,16.43998432159424,0.0,1740481184.66564,16.43998432159424,0.0,1740481184.6656413,16.43998432159424,0.0,1740481184.6656423,16.43998432159424,0.0,1740481184.665643,16.43998432159424,0.9950992082448111,1740481184.6656442,16.43998432159424,0.0,1740481184.6656451,16.43998432159424,0.029746631144441982,1740481184.665646,16.43998432159424,0.0,1740481184.665647,16.43998432159424,0.9653525771003691,, +1740481184.6839917,16.459984302520752,8.4920839766951,1740481184.6839938,16.459984302520752,0.0,1740481184.683997,16.459984302520752,0.0,1740481184.6839993,16.459984302520752,12.42278913089584,1740481184.6840005,16.459984302520752,0.0,1740481184.6840022,16.459984302520752,0.0,1740481184.684003,16.459984302520752,0.0,1740481184.6840043,16.459984302520752,0.0,1740481184.684005,16.459984302520752,0.9950992082448111,1740481184.6840065,16.459984302520752,0.0,1740481184.6840072,16.459984302520752,0.029746631144441982,1740481184.6840084,16.459984302520752,0.0,1740481184.6840093,16.459984302520752,0.9653525771003691,, +1740481184.7034178,16.479984283447266,8.598316730870444,1740481184.7034209,16.479984283447266,0.0,1740481184.703424,16.479984283447266,0.017262718471225173,1740481184.7034261,16.479984283447266,12.43998671903938,1740481184.703427,16.479984283447266,0.0,1740481184.7034283,16.479984283447266,0.0,1740481184.7034295,16.479984283447266,0.0,1740481184.7034304,16.479984283447266,0.0,1740481184.7034311,16.479984283447266,0.9950992082448111,1740481184.703432,16.479984283447266,0.049007917551849856,1740481184.703433,16.479984283447266,0.07880191622145119,1740481184.7034338,16.479984283447266,0.0,1740481184.7034347,16.479984283447266,0.9653200119365273,, +1740481184.7246869,16.49998426437378,8.598316730870444,1740481184.724689,16.49998426437378,0.0,1740481184.7246912,16.49998426437378,0.017262718471225173,1740481184.724693,16.49998426437378,12.43998671903938,1740481184.724694,16.49998426437378,0.0,1740481184.7246954,16.49998426437378,0.0,1740481184.7246966,16.49998426437378,0.0,1740481184.7246976,16.49998426437378,0.0,1740481184.7246985,16.49998426437378,0.9950992082448111,1740481184.7246995,16.49998426437378,0.049007917551849856,1740481184.7247005,16.49998426437378,0.0787871138601337,1740481184.7247014,16.49998426437378,0.0,1740481184.7247024,16.49998426437378,0.9653200119365273,, +1740481184.7440403,16.519984245300293,8.598316730870444,1740481184.744043,16.519984245300293,0.0,1740481184.7440457,16.519984245300293,0.017262718471225173,1740481184.7440479,16.519984245300293,12.43998671903938,1740481184.7440493,16.519984245300293,0.0,1740481184.744051,16.519984245300293,0.0,1740481184.7440524,16.519984245300293,0.0,1740481184.7440536,16.519984245300293,0.0,1740481184.7440548,16.519984245300293,0.9950992082448111,1740481184.744056,16.519984245300293,0.049007917551849856,1740481184.7440577,16.519984245300293,0.0787871138601337,1740481184.7440588,16.519984245300293,0.0,1740481184.7440598,16.519984245300293,0.9653200119365273,, +1740481184.767452,16.539984226226807,8.598316730870444,1740481184.7674544,16.539984226226807,0.0,1740481184.7674582,16.539984226226807,0.0,1740481184.7674606,16.539984226226807,12.528956754743499,1740481184.7674623,16.539984226226807,0.0,1740481184.767464,16.539984226226807,0.0,1740481184.7674649,16.539984226226807,0.0,1740481184.767467,16.539984226226807,0.0,1740481184.7674682,16.539984226226807,0.9950899913925906,1740481184.76747,16.539984226226807,0.0,1740481184.7674706,16.539984226226807,0.0297699794560633,1740481184.7674716,16.539984226226807,0.0,1740481184.767474,16.539984226226807,0.9653200119365273,, +1740481184.7836432,16.55998420715332,8.598316730870444,1740481184.783645,16.55998420715332,0.0,1740481184.783647,16.55998420715332,0.0,1740481184.783649,16.55998420715332,12.528956754743499,1740481184.7836502,16.55998420715332,0.0,1740481184.7836514,16.55998420715332,0.0,1740481184.7836525,16.55998420715332,0.0,1740481184.7836533,16.55998420715332,0.0,1740481184.7836545,16.55998420715332,0.9950899913925906,1740481184.7836554,16.55998420715332,0.0,1740481184.7836561,16.55998420715332,0.0297699794560633,1740481184.7836573,16.55998420715332,0.0,1740481184.783658,16.55998420715332,0.9653200119365273,, +1740481184.803673,16.579984188079834,8.598316730870444,1740481184.8036747,16.579984188079834,0.0,1740481184.8036768,16.579984188079834,0.0,1740481184.8036792,16.579984188079834,12.528956754743499,1740481184.8036802,16.579984188079834,0.0,1740481184.8036816,16.579984188079834,0.0,1740481184.8036826,16.579984188079834,0.0,1740481184.8036835,16.579984188079834,0.0,1740481184.8036842,16.579984188079834,0.9950899913925906,1740481184.8036854,16.579984188079834,0.0,1740481184.8036864,16.579984188079834,0.0297699794560633,1740481184.8036876,16.579984188079834,0.0,1740481184.8036885,16.579984188079834,0.9653200119365273,, +1740481184.8236978,16.599984169006348,8.704569349669976,1740481184.8236997,16.599984169006348,0.0,1740481184.8237028,16.599984169006348,0.017265786531774928,1740481184.8237047,16.599984169006348,12.545976664767675,1740481184.823706,16.599984169006348,0.0,1740481184.8237073,16.599984169006348,0.0,1740481184.8237085,16.599984169006348,0.0,1740481184.8237092,16.599984169006348,0.0,1740481184.82371,16.599984169006348,0.9950899913925906,1740481184.823711,16.599984169006348,0.04910008607405536,1740481184.823712,16.599984169006348,0.07904888486166482,1740481184.8237128,16.599984169006348,0.0,1740481184.8237138,16.599984169006348,0.9651970736827278,, +1740481184.844431,16.61998414993286,8.704569349669976,1740481184.8444324,16.61998414993286,0.0,1740481184.8444345,16.61998414993286,0.017265786531774928,1740481184.8444364,16.61998414993286,12.545976664767675,1740481184.8444376,16.61998414993286,0.0,1740481184.844439,16.61998414993286,0.0,1740481184.84444,16.61998414993286,0.0,1740481184.8444412,16.61998414993286,0.0,1740481184.8444421,16.61998414993286,0.9950899913925906,1740481184.8444428,16.61998414993286,0.04910008607405536,1740481184.8444438,16.61998414993286,0.07899300378391816,1740481184.844445,16.61998414993286,0.0,1740481184.844446,16.61998414993286,0.9651970736827278,, +1740481184.8664424,16.639984130859375,8.704569349669976,1740481184.8664446,16.639984130859375,0.0,1740481184.8664467,16.639984130859375,0.0,1740481184.8664489,16.639984130859375,12.634963497035432,1740481184.8664496,16.639984130859375,0.0,1740481184.8664513,16.639984130859375,0.0,1740481184.866452,16.639984130859375,0.0,1740481184.866453,16.639984130859375,0.0,1740481184.8664536,16.639984130859375,0.9950551183820491,1740481184.8664546,16.639984130859375,0.0,1740481184.8664556,16.639984130859375,0.029858044699321296,1740481184.8664565,16.639984130859375,0.0,1740481184.8664575,16.639984130859375,0.9651970736827278,, +1740481184.8837838,16.65998411178589,8.704569349669976,1740481184.8837855,16.65998411178589,0.0,1740481184.8837879,16.65998411178589,0.0,1740481184.8837898,16.65998411178589,12.634963497035432,1740481184.8837907,16.65998411178589,0.0,1740481184.8837922,16.65998411178589,0.0,1740481184.8837934,16.65998411178589,0.0,1740481184.8837945,16.65998411178589,0.0,1740481184.8837953,16.65998411178589,0.9950551183820491,1740481184.8837962,16.65998411178589,0.0,1740481184.8837972,16.65998411178589,0.029858044699321296,1740481184.8837984,16.65998411178589,0.0,1740481184.8838136,16.65998411178589,0.9651970736827278,, +1740481184.9038281,16.679984092712402,8.704569349669976,1740481184.9038308,16.679984092712402,0.0,1740481184.9038336,16.679984092712402,0.0,1740481184.9038355,16.679984092712402,12.634963497035432,1740481184.9038367,16.679984092712402,0.0,1740481184.903838,16.679984092712402,0.0,1740481184.9038389,16.679984092712402,0.0,1740481184.90384,16.679984092712402,0.0,1740481184.9038408,16.679984092712402,0.9950551183820491,1740481184.9038417,16.679984092712402,0.0,1740481184.9038424,16.679984092712402,0.029858044699321296,1740481184.9038436,16.679984092712402,0.0,1740481184.9038446,16.679984092712402,0.9651970736827278,, +1740481184.9237876,16.699984073638916,8.810735967815697,1740481184.923789,16.699984073638916,0.0,1740481184.923791,16.699984073638916,0.017251207048073532,1740481184.9237928,16.699984073638916,12.650048745929766,1740481184.923794,16.699984073638916,0.0,1740481184.9237952,16.699984073638916,0.0,1740481184.9237962,16.699984073638916,0.0,1740481184.9237971,16.699984073638916,0.0,1740481184.923798,16.699984073638916,0.9950551183820491,1740481184.923799,16.699984073638916,0.04944881617947039,1740481184.9238,16.699984073638916,0.0808821036418796,1740481184.923801,16.699984073638916,0.0,1740481184.923802,16.699984073638916,0.9641140946058581,, +1740481184.9438019,16.71998405456543,8.810735967815697,1740481184.9438035,16.71998405456543,0.0,1740481184.9438057,16.71998405456543,0.017251207048073532,1740481184.9438078,16.71998405456543,12.650048745929766,1740481184.9438088,16.71998405456543,0.0,1740481184.94381,16.71998405456543,0.0,1740481184.9438112,16.71998405456543,0.0,1740481184.9438121,16.71998405456543,0.0,1740481184.9438128,16.71998405456543,0.9950551183820491,1740481184.9438138,16.71998405456543,0.04944881617947039,1740481184.943815,16.71998405456543,0.0803898399556614,1740481184.9438157,16.71998405456543,0.0,1740481184.9438167,16.71998405456543,0.9641140946058581,, +1740481184.9663813,16.739984035491943,8.810735967815697,1740481184.9663837,16.739984035491943,0.0,1740481184.9663863,16.739984035491943,0.0,1740481184.9663885,16.739984035491943,12.738964157027414,1740481184.966406,16.739984035491943,0.0,1740481184.9664078,16.739984035491943,0.0,1740481184.966409,16.739984035491943,0.0,1740481184.96641,16.739984035491943,0.0,1740481184.966411,16.739984035491943,0.9947425858395518,1740481184.966412,16.739984035491943,0.0,1740481184.966413,16.739984035491943,0.03062849123369371,1740481184.966414,16.739984035491943,0.0,1740481184.966415,16.739984035491943,0.9641140946058581,, +1740481184.9840121,16.759984016418457,8.810735967815697,1740481184.9840164,16.759984016418457,0.0,1740481184.9840195,16.759984016418457,0.0,1740481184.9840217,16.759984016418457,12.738964157027414,1740481184.9840229,16.759984016418457,0.0,1740481184.984024,16.759984016418457,0.0,1740481184.984025,16.759984016418457,0.0,1740481184.984026,16.759984016418457,0.0,1740481184.984027,16.759984016418457,0.9947425858395518,1740481184.9840276,16.759984016418457,0.0,1740481184.9840286,16.759984016418457,0.03062849123369371,1740481184.9840295,16.759984016418457,0.0,1740481184.9840305,16.759984016418457,0.9641140946058581,, +1740481185.0034347,16.77998399734497,8.810735967815697,1740481185.0034366,16.77998399734497,0.0,1740481185.0034387,16.77998399734497,0.0,1740481185.0034409,16.77998399734497,12.738964157027414,1740481185.0034418,16.77998399734497,0.0,1740481185.0034435,16.77998399734497,0.0,1740481185.0034442,16.77998399734497,0.0,1740481185.0034451,16.77998399734497,0.0,1740481185.0034463,16.77998399734497,0.9947425858395518,1740481185.003447,16.77998399734497,0.0,1740481185.003448,16.77998399734497,0.03062849123369371,1740481185.0034487,16.77998399734497,0.0,1740481185.00345,16.77998399734497,0.9641140946058581,, +1740481185.0235472,16.799983978271484,8.810735967815697,1740481185.023549,16.799983978271484,0.0,1740481185.0235515,16.799983978271484,0.0,1740481185.0235534,16.799983978271484,12.738964157027414,1740481185.0235543,16.799983978271484,0.0,1740481185.0235558,16.799983978271484,0.0,1740481185.023557,16.799983978271484,0.0,1740481185.023558,16.799983978271484,0.0,1740481185.0235586,16.799983978271484,0.9947425858395518,1740481185.0235596,16.799983978271484,0.0,1740481185.0235605,16.799983978271484,0.03062849123369371,1740481185.0235615,16.799983978271484,0.0,1740481185.0235622,16.799983978271484,0.9641140946058581,, +1740481185.0444603,16.819983959197998,8.916810700570888,1740481185.0444617,16.819983959197998,0.0,1740481185.044464,16.819983959197998,0.01723086275646076,1740481185.044466,16.819983959197998,12.75428062182436,1740481185.044467,16.819983959197998,0.0,1740481185.044468,16.819983959197998,0.0,1740481185.0444694,16.819983959197998,0.0,1740481185.04447,16.819983959197998,0.0,1740481185.044471,16.819983959197998,0.9947425858395518,1740481185.044472,16.819983959197998,0.05257414160461993,1740481185.044473,16.819983959197998,0.08459492267834937,1740481185.044474,16.819983959197998,0.0,1740481185.0444748,16.819983959197998,0.9631568956261013,, +1740481185.067491,16.83998394012451,8.916810700570888,1740481185.067493,16.83998394012451,0.0,1740481185.067495,16.83998394012451,0.0,1740481185.0674973,16.83998394012451,12.84312449182309,1740481185.0674982,16.83998394012451,0.0,1740481185.0674996,16.83998394012451,0.0,1740481185.0675006,16.83998394012451,0.0,1740481185.0675013,16.83998394012451,0.0,1740481185.0675023,16.83998394012451,0.9944583791628212,1740481185.0675037,16.83998394012451,0.0,1740481185.0675046,16.83998394012451,0.03130148353671991,1740481185.0675054,16.83998394012451,0.0,1740481185.0675063,16.83998394012451,0.9631568956261013,, +1740481185.08352,16.859983921051025,8.916810700570888,1740481185.0835216,16.859983921051025,0.0,1740481185.0835238,16.859983921051025,0.0,1740481185.083526,16.859983921051025,12.84312449182309,1740481185.0835268,16.859983921051025,0.0,1740481185.0835283,16.859983921051025,0.0,1740481185.0835295,16.859983921051025,0.0,1740481185.0835307,16.859983921051025,0.0,1740481185.0835319,16.859983921051025,0.9944583791628212,1740481185.0835328,16.859983921051025,0.0,1740481185.0835335,16.859983921051025,0.03130148353671991,1740481185.0835342,16.859983921051025,0.0,1740481185.0835354,16.859983921051025,0.9631568956261013,, +1740481185.104139,16.87998390197754,8.916810700570888,1740481185.1041405,16.87998390197754,0.0,1740481185.104143,16.87998390197754,0.0,1740481185.1041448,16.87998390197754,12.84312449182309,1740481185.104146,16.87998390197754,0.0,1740481185.1041472,16.87998390197754,0.0,1740481185.104148,16.87998390197754,0.0,1740481185.1041493,16.87998390197754,0.0,1740481185.10415,16.87998390197754,0.9944583791628212,1740481185.104151,16.87998390197754,0.0,1740481185.1041517,16.87998390197754,0.03130148353671991,1740481185.104153,16.87998390197754,0.0,1740481185.1041539,16.87998390197754,0.9631568956261013,, +1740481185.1243625,16.899983882904053,8.916810700570888,1740481185.1243687,16.899983882904053,0.0,1740481185.1243722,16.899983882904053,0.0,1740481185.1243753,16.899983882904053,12.84312449182309,1740481185.124377,16.899983882904053,0.0,1740481185.1243796,16.899983882904053,0.0,1740481185.124382,16.899983882904053,0.0,1740481185.1243837,16.899983882904053,0.0,1740481185.1243863,16.899983882904053,0.9944583791628212,1740481185.124388,16.899983882904053,0.0,1740481185.12439,16.899983882904053,0.03130148353671991,1740481185.1244135,16.899983882904053,0.0,1740481185.1244164,16.899983882904053,0.9631568956261013,, +1740481185.1449168,16.919983863830566,9.022704217489116,1740481185.1449192,16.919983863830566,0.0,1740481185.1449215,16.919983863830566,0.017196511315650382,1740481185.1449234,16.919983863830566,12.856697448116773,1740481185.1449244,16.919983863830566,0.0,1740481185.1449256,16.919983863830566,0.0,1740481185.144927,16.919983863830566,0.0,1740481185.144928,16.919983863830566,0.0,1740481185.1449287,16.919983863830566,0.9944583791628212,1740481185.14493,16.919983863830566,0.0554162083717491,1740481185.1449308,16.919983863830566,0.08935300543710416,1740481185.1449316,16.919983863830566,0.0,1740481185.1449325,16.919983863830566,0.9613451181151169,, +1740481185.16779,16.93998384475708,9.022704217489116,1740481185.1678133,16.93998384475708,0.0,1740481185.167818,16.93998384475708,0.0,1740481185.1678226,16.93998384475708,12.945394453719349,1740481185.1678255,16.93998384475708,0.0,1740481185.1678283,16.93998384475708,0.0,1740481185.1678305,16.93998384475708,0.0,1740481185.1678338,16.93998384475708,0.0,1740481185.167836,16.93998384475708,0.9938999544785341,1740481185.1678379,16.93998384475708,0.0,1740481185.1678407,16.93998384475708,0.03255483636341716,1740481185.167843,16.93998384475708,0.0,1740481185.1678455,16.93998384475708,0.9613451181151169,, +1740481185.1834831,16.959983825683594,9.022704217489116,1740481185.183485,16.959983825683594,0.0,1740481185.183487,16.959983825683594,0.0,1740481185.183489,16.959983825683594,12.945394453719349,1740481185.18349,16.959983825683594,0.0,1740481185.1834912,16.959983825683594,0.0,1740481185.1834924,16.959983825683594,0.0,1740481185.1834934,16.959983825683594,0.0,1740481185.1834943,16.959983825683594,0.9938999544785341,1740481185.1834953,16.959983825683594,0.0,1740481185.1834962,16.959983825683594,0.03255483636341716,1740481185.183497,16.959983825683594,0.0,1740481185.183498,16.959983825683594,0.9613451181151169,, +1740481185.2034278,16.979983806610107,9.022704217489116,1740481185.2034295,16.979983806610107,0.0,1740481185.2034316,16.979983806610107,0.0,1740481185.2034338,16.979983806610107,12.945394453719349,1740481185.2034347,16.979983806610107,0.0,1740481185.2034364,16.979983806610107,0.0,1740481185.2034373,16.979983806610107,0.0,1740481185.203438,16.979983806610107,0.0,1740481185.2034395,16.979983806610107,0.9938999544785341,1740481185.2034402,16.979983806610107,0.0,1740481185.2034411,16.979983806610107,0.03255483636341716,1740481185.203442,16.979983806610107,0.0,1740481185.2034433,16.979983806610107,0.9613451181151169,, +1740481185.2256553,16.99998378753662,9.022704217489116,1740481185.225657,16.99998378753662,0.0,1740481185.2256594,16.99998378753662,0.0,1740481185.2256613,16.99998378753662,12.945394453719349,1740481185.2256622,16.99998378753662,0.0,1740481185.2256637,16.99998378753662,0.0,1740481185.2256649,16.99998378753662,0.0,1740481185.2256658,16.99998378753662,0.0,1740481185.2256665,16.99998378753662,0.9938999544785341,1740481185.2256675,16.99998378753662,0.0,1740481185.2256687,16.99998378753662,0.03255483636341716,1740481185.2256694,16.99998378753662,0.0,1740481185.22567,16.99998378753662,0.9613451181151169,, +1740481185.2447307,17.019983768463135,9.022704217489116,1740481185.2447324,17.019983768463135,0.0,1740481185.244735,17.019983768463135,0.0,1740481185.2447367,17.019983768463135,12.945394453719349,1740481185.2447379,17.019983768463135,0.0,1740481185.244739,17.019983768463135,0.0,1740481185.24474,17.019983768463135,0.0,1740481185.244741,17.019983768463135,0.0,1740481185.244742,17.019983768463135,0.9938999544785341,1740481185.2447426,17.019983768463135,0.0,1740481185.2447433,17.019983768463135,0.03255483636341716,1740481185.2447445,17.019983768463135,0.0,1740481185.2447455,17.019983768463135,0.9613451181151169,, +1740481185.2650235,17.03998374938965,9.128423912970664,1740481185.2650254,17.03998374938965,0.0,1740481185.2650282,17.03998374938965,0.0,1740481185.2650301,17.03998374938965,13.04794405067448,1740481185.265031,17.03998374938965,0.0,1740481185.2650325,17.03998374938965,0.0,1740481185.2650335,17.03998374938965,0.0,1740481185.2650344,17.03998374938965,0.0,1740481185.2650352,17.03998374938965,0.9933894311516384,1740481185.2650363,17.03998374938965,0.06610568848357756,1740481185.265037,17.03998374938965,0.10022347212924484,1740481185.265038,17.03998374938965,0.0,1740481185.265039,17.03998374938965,0.9597600688519082,, +1740481185.284057,17.059983730316162,9.128423912970664,1740481185.2840583,17.059983730316162,0.0,1740481185.2840607,17.059983730316162,0.0,1740481185.2840626,17.059983730316162,13.04794405067448,1740481185.2840638,17.059983730316162,0.0,1740481185.284065,17.059983730316162,0.0,1740481185.284066,17.059983730316162,0.0,1740481185.284067,17.059983730316162,0.0,1740481185.2840676,17.059983730316162,0.9933894311516384,1740481185.2840686,17.059983730316162,0.06610568848357756,1740481185.2840693,17.059983730316162,0.09973505078330769,1740481185.2840703,17.059983730316162,0.0,1740481185.2840712,17.059983730316162,0.9597600688519082,, +1740481185.3061411,17.079983711242676,9.128423912970664,1740481185.3061433,17.079983711242676,0.0,1740481185.3061464,17.079983711242676,0.0,1740481185.3061483,17.079983711242676,13.04794405067448,1740481185.3061495,17.079983711242676,0.0,1740481185.3061507,17.079983711242676,0.0,1740481185.3061516,17.079983711242676,0.0,1740481185.3061528,17.079983711242676,0.0,1740481185.3061535,17.079983711242676,0.9933894311516384,1740481185.3061545,17.079983711242676,0.06610568848357756,1740481185.3061554,17.079983711242676,0.09973505078330769,1740481185.3061564,17.079983711242676,0.0,1740481185.3061574,17.079983711242676,0.9597600688519082,, +1740481185.32652,17.09998369216919,9.128423912970664,1740481185.326546,17.09998369216919,0.0,1740481185.3265495,17.09998369216919,0.0,1740481185.3265514,17.09998369216919,13.04794405067448,1740481185.3265529,17.09998369216919,0.0,1740481185.3265538,17.09998369216919,0.0,1740481185.3265548,17.09998369216919,0.0,1740481185.326556,17.09998369216919,0.0,1740481185.3265567,17.09998369216919,0.9933894311516384,1740481185.3265576,17.09998369216919,0.06610568848357756,1740481185.3265584,17.09998369216919,0.09973505078330769,1740481185.3265595,17.09998369216919,0.0,1740481185.3265603,17.09998369216919,0.9597600688519082,, +1740481185.3450909,17.119983673095703,9.128423912970664,1740481185.345093,17.119983673095703,0.0,1740481185.3450956,17.119983673095703,0.0,1740481185.345098,17.119983673095703,13.04794405067448,1740481185.345099,17.119983673095703,0.0,1740481185.3451006,17.119983673095703,0.0,1740481185.3451018,17.119983673095703,0.0,1740481185.345103,17.119983673095703,0.0,1740481185.3451042,17.119983673095703,0.9933894311516384,1740481185.3451052,17.119983673095703,0.06610568848357756,1740481185.3451061,17.119983673095703,0.09973505078330769,1740481185.3451073,17.119983673095703,0.0,1740481185.3451083,17.119983673095703,0.9597600688519082,, +1740481185.3676796,17.139983654022217,9.234164838336826,1740481185.3676815,17.139983654022217,0.0,1740481185.3676836,17.139983654022217,0.0,1740481185.3676856,17.139983654022217,13.161695588606307,1740481185.3676867,17.139983654022217,0.0,1740481185.367688,17.139983654022217,0.0,1740481185.367689,17.139983654022217,0.0,1740481185.36769,17.139983654022217,0.0,1740481185.3676908,17.139983654022217,0.9946399120755887,1740481185.3676918,17.139983654022217,0.05360087924407453,1740481185.3676925,17.139983654022217,0.08322322164579125,1740481185.3676937,17.139983654022217,0.0,1740481185.3676944,17.139983654022217,0.96376537513474,, +1740481185.3851306,17.15998363494873,9.234164838336826,1740481185.385134,17.15998363494873,0.0,1740481185.3851366,17.15998363494873,0.0,1740481185.385139,17.15998363494873,13.161695588606307,1740481185.3851402,17.15998363494873,0.0,1740481185.3851418,17.15998363494873,0.0,1740481185.3851428,17.15998363494873,0.0,1740481185.385144,17.15998363494873,0.0,1740481185.3851452,17.15998363494873,0.9946399120755887,1740481185.3851461,17.15998363494873,0.05360087924407453,1740481185.3851476,17.15998363494873,0.08447541618492316,1740481185.3851488,17.15998363494873,0.0,1740481185.3851497,17.15998363494873,0.96376537513474,, +1740481185.4055455,17.179983615875244,9.234164838336826,1740481185.40555,17.179983615875244,0.0,1740481185.4055536,17.179983615875244,0.0,1740481185.4055698,17.179983615875244,13.161695588606307,1740481185.405571,17.179983615875244,0.0,1740481185.4055727,17.179983615875244,0.0,1740481185.4055736,17.179983615875244,0.0,1740481185.4055746,17.179983615875244,0.0,1740481185.4055758,17.179983615875244,0.9946399120755887,1740481185.4055767,17.179983615875244,0.05360087924407453,1740481185.4055777,17.179983615875244,0.08447541618492316,1740481185.4055786,17.179983615875244,0.0,1740481185.405592,17.179983615875244,0.96376537513474,, +1740481185.4235687,17.199983596801758,9.234164838336826,1740481185.4235704,17.199983596801758,0.0,1740481185.4235725,17.199983596801758,0.0,1740481185.4235744,17.199983596801758,13.161695588606307,1740481185.4235756,17.199983596801758,0.0,1740481185.4235768,17.199983596801758,0.0,1740481185.4235778,17.199983596801758,0.0,1740481185.4235787,17.199983596801758,0.0,1740481185.4235797,17.199983596801758,0.9946399120755887,1740481185.4235804,17.199983596801758,0.05360087924407453,1740481185.4235814,17.199983596801758,0.08447541618492316,1740481185.4235823,17.199983596801758,0.0,1740481185.4235833,17.199983596801758,0.96376537513474,, +1740481185.44482,17.21998357772827,9.234164838336826,1740481185.444822,17.21998357772827,0.0,1740481185.4448242,17.21998357772827,0.0,1740481185.4448266,17.21998357772827,13.161695588606307,1740481185.4448276,17.21998357772827,0.0,1740481185.444829,17.21998357772827,0.0,1740481185.44483,17.21998357772827,0.0,1740481185.4448311,17.21998357772827,0.0,1740481185.4448323,17.21998357772827,0.9946399120755887,1740481185.4448333,17.21998357772827,0.05360087924407453,1740481185.444834,17.21998357772827,0.08447541618492316,1740481185.4448352,17.21998357772827,0.0,1740481185.4448361,17.21998357772827,0.96376537513474,, +1740481185.4655285,17.239983558654785,9.234164838336826,1740481185.4655437,17.239983558654785,0.0,1740481185.4655476,17.239983558654785,0.0,1740481185.4655497,17.239983558654785,13.161695588606307,1740481185.465551,17.239983558654785,0.0,1740481185.465552,17.239983558654785,0.0,1740481185.4655535,17.239983558654785,0.0,1740481185.4655542,17.239983558654785,0.0,1740481185.4655552,17.239983558654785,0.9946399120755887,1740481185.4655561,17.239983558654785,0.05360087924407453,1740481185.465557,17.239983558654785,0.08447541618492316,1740481185.465558,17.239983558654785,0.0,1740481185.465559,17.239983558654785,0.96376537513474,, +1740481185.4843736,17.2599835395813,9.340324842116338,1740481185.4843752,17.2599835395813,0.0,1740481185.4843774,17.2599835395813,0.017242934310918702,1740481185.4843793,17.2599835395813,13.184807943579198,1740481185.4843805,17.2599835395813,0.0,1740481185.4843817,17.2599835395813,0.0,1740481185.4843824,17.2599835395813,0.0,1740481185.4843836,17.2599835395813,0.0,1740481185.4843843,17.2599835395813,0.9999999999999961,1740481185.4843853,17.2599835395813,5.551115123125783e-15,1740481185.484386,17.2599835395813,0.034402359946293815,1740481185.4843872,17.2599835395813,0.0,1740481185.4843879,17.2599835395813,0.9667000854657273,, +1740481185.503899,17.279983520507812,9.340324842116338,1740481185.503901,17.279983520507812,0.0,1740481185.503903,17.279983520507812,0.017242934310918702,1740481185.503905,17.279983520507812,13.184807943579198,1740481185.503906,17.279983520507812,0.0,1740481185.5039074,17.279983520507812,0.0,1740481185.5039084,17.279983520507812,0.0,1740481185.503909,17.279983520507812,0.0,1740481185.50391,17.279983520507812,0.9999999999999961,1740481185.503911,17.279983520507812,5.551115123125783e-15,1740481185.503912,17.279983520507812,0.03329991453427439,1740481185.5039127,17.279983520507812,0.0,1740481185.5039136,17.279983520507812,0.9667000854657273,, +1740481185.5238984,17.299983501434326,9.340324842116338,1740481185.5239003,17.299983501434326,0.0,1740481185.5239024,17.299983501434326,0.017242934310918702,1740481185.5239046,17.299983501434326,13.184807943579198,1740481185.5239058,17.299983501434326,0.0,1740481185.5239074,17.299983501434326,0.0,1740481185.5239084,17.299983501434326,0.0,1740481185.5239096,17.299983501434326,0.0,1740481185.5239108,17.299983501434326,0.9999999999999961,1740481185.523912,17.299983501434326,5.551115123125783e-15,1740481185.523913,17.299983501434326,0.03329991453427439,1740481185.523914,17.299983501434326,0.0,1740481185.523915,17.299983501434326,0.9667000854657273,, +1740481185.5444143,17.31998348236084,9.340324842116338,1740481185.54442,17.31998348236084,0.0,1740481185.5444243,17.31998348236084,0.017242934310918702,1740481185.5444267,17.31998348236084,13.184807943579198,1740481185.5444283,17.31998348236084,0.0,1740481185.5444298,17.31998348236084,0.0,1740481185.5444314,17.31998348236084,0.0,1740481185.5444336,17.31998348236084,0.0,1740481185.5444546,17.31998348236084,0.9999999999999961,1740481185.5444567,17.31998348236084,5.551115123125783e-15,1740481185.544458,17.31998348236084,0.03329991453427439,1740481185.544459,17.31998348236084,0.0,1740481185.54446,17.31998348236084,0.9667000854657273,, +1740481185.566287,17.339983463287354,9.340324842116338,1740481185.566289,17.339983463287354,0.0,1740481185.5662909,17.339983463287354,0.0,1740481185.5662932,17.339983463287354,13.273725013047793,1740481185.5662942,17.339983463287354,0.0,1740481185.5662956,17.339983463287354,0.0,1740481185.5662968,17.339983463287354,0.0,1740481185.56631,17.339983463287354,0.0,1740481185.5663111,17.339983463287354,0.9954729987694119,1740481185.566312,17.339983463287354,0.0,1740481185.566313,17.339983463287354,0.02877291330368459,1740481185.5663145,17.339983463287354,0.0,1740481185.566316,17.339983463287354,0.9667000854657273,, +1740481185.584655,17.359983444213867,9.446580471732716,1740481185.5846574,17.359983444213867,0.0,1740481185.5846598,17.359983444213867,0.0172729215236743,1740481185.5846617,17.359983444213867,13.286532105171661,1740481185.5846627,17.359983444213867,0.0,1740481185.584664,17.359983444213867,0.0,1740481185.584665,17.359983444213867,0.0,1740481185.584666,17.359983444213867,0.0,1740481185.584667,17.359983444213867,0.9954729987694119,1740481185.5846682,17.359983444213867,0.04527001230584249,1740481185.5846689,17.359983444213867,0.07729080250460266,1740481185.58467,17.359983444213867,0.0,1740481185.5846708,17.359983444213867,0.9644671707658239,, +1740481185.6040154,17.37998342514038,9.446580471732716,1740481185.6040173,17.37998342514038,0.0,1740481185.6040194,17.37998342514038,0.0172729215236743,1740481185.6040213,17.37998342514038,13.286532105171661,1740481185.6040225,17.37998342514038,0.0,1740481185.6040237,17.37998342514038,0.0,1740481185.604025,17.37998342514038,0.0,1740481185.6040258,17.37998342514038,0.0,1740481185.6040266,17.37998342514038,0.9954729987694119,1740481185.6040277,17.37998342514038,0.04527001230584249,1740481185.6040287,17.37998342514038,0.07627584030943046,1740481185.60403,17.37998342514038,0.0,1740481185.604031,17.37998342514038,0.9644671707658239,, +1740481185.6235387,17.399983406066895,9.446580471732716,1740481185.6235404,17.399983406066895,0.0,1740481185.623543,17.399983406066895,0.0172729215236743,1740481185.6235454,17.399983406066895,13.286532105171661,1740481185.6235464,17.399983406066895,0.0,1740481185.6235476,17.399983406066895,0.0,1740481185.6235487,17.399983406066895,0.0,1740481185.6235495,17.399983406066895,0.0,1740481185.6235504,17.399983406066895,0.9954729987694119,1740481185.6235523,17.399983406066895,0.04527001230584249,1740481185.6235535,17.399983406066895,0.07627584030943046,1740481185.6235547,17.399983406066895,0.0,1740481185.6235566,17.399983406066895,0.9644671707658239,, +1740481185.6455703,17.419983386993408,9.446580471732716,1740481185.6455762,17.419983386993408,0.0,1740481185.6455812,17.419983386993408,0.0172729215236743,1740481185.6455843,17.419983386993408,13.286532105171661,1740481185.6455867,17.419983386993408,0.0,1740481185.6455886,17.419983386993408,0.0,1740481185.6455915,17.419983386993408,0.0,1740481185.645594,17.419983386993408,0.0,1740481185.6456175,17.419983386993408,0.9954729987694119,1740481185.6456192,17.419983386993408,0.04527001230584249,1740481185.6456227,17.419983386993408,0.07627584030943046,1740481185.645625,17.419983386993408,0.0,1740481185.645627,17.419983386993408,0.9644671707658239,, +1740481185.6664293,17.439983367919922,9.446580471732716,1740481185.666431,17.439983367919922,0.0,1740481185.666433,17.439983367919922,0.0,1740481185.666435,17.439983367919922,13.375514813264363,1740481185.6664364,17.439983367919922,0.0,1740481185.6664376,17.439983367919922,0.0,1740481185.6664386,17.439983367919922,0.0,1740481185.6664395,17.439983367919922,0.0,1740481185.6664405,17.439983367919922,0.9948455307596042,1740481185.6664414,17.439983367919922,0.0,1740481185.6664422,17.439983367919922,0.030378359993780357,1740481185.666443,17.439983367919922,0.0,1740481185.666444,17.439983367919922,0.9644671707658239,, +1740481185.6841104,17.459983348846436,9.446580471732716,1740481185.6841123,17.459983348846436,0.0,1740481185.6841147,17.459983348846436,0.0,1740481185.6841168,17.459983348846436,13.375514813264363,1740481185.6841178,17.459983348846436,0.0,1740481185.684119,17.459983348846436,0.0,1740481185.6841202,17.459983348846436,0.0,1740481185.6841211,17.459983348846436,0.0,1740481185.6841218,17.459983348846436,0.9948455307596042,1740481185.684123,17.459983348846436,0.0,1740481185.684124,17.459983348846436,0.030378359993780357,1740481185.684125,17.459983348846436,0.0,1740481185.6841257,17.459983348846436,0.9644671707658239,, +1740481185.7039576,17.47998332977295,9.55276293091197,1740481185.7039592,17.47998332977295,0.0,1740481185.7039614,17.47998332977295,0.017250146937054518,1740481185.7039638,17.47998332977295,13.394164200230561,1740481185.7039645,17.47998332977295,0.0,1740481185.703966,17.47998332977295,0.0,1740481185.703967,17.47998332977295,0.0,1740481185.7039678,17.47998332977295,0.0,1740481185.7039688,17.47998332977295,0.9948455307596042,1740481185.7039697,17.47998332977295,0.05154469240391868,1740481185.7039707,17.47998332977295,0.08090542298231818,1740481185.7039716,17.47998332977295,0.0,1740481185.7039723,17.47998332977295,0.965166790780395,, +1740481185.7236257,17.499983310699463,9.55276293091197,1740481185.7236276,17.499983310699463,0.0,1740481185.7236295,17.499983310699463,0.017250146937054518,1740481185.7236316,17.499983310699463,13.394164200230561,1740481185.7236326,17.499983310699463,0.0,1740481185.723634,17.499983310699463,0.0,1740481185.7236352,17.499983310699463,0.0,1740481185.723636,17.499983310699463,0.0,1740481185.723637,17.499983310699463,0.9948455307596042,1740481185.723638,17.499983310699463,0.05154469240391868,1740481185.723639,17.499983310699463,0.0812234323831279,1740481185.7236397,17.499983310699463,0.0,1740481185.723641,17.499983310699463,0.965166790780395,, +1740481185.7457528,17.519983291625977,9.55276293091197,1740481185.7457557,17.519983291625977,0.0,1740481185.7457583,17.519983291625977,0.017250146937054518,1740481185.7457607,17.519983291625977,13.394164200230561,1740481185.7457619,17.519983291625977,0.0,1740481185.7457633,17.519983291625977,0.0,1740481185.7457645,17.519983291625977,0.0,1740481185.745766,17.519983291625977,0.0,1740481185.745767,17.519983291625977,0.9948455307596042,1740481185.7457685,17.519983291625977,0.05154469240391868,1740481185.7457697,17.519983291625977,0.0812234323831279,1740481185.745771,17.519983291625977,0.0,1740481185.7457724,17.519983291625977,0.965166790780395,, +1740481185.7671733,17.53998327255249,9.55276293091197,1740481185.7671752,17.53998327255249,0.0,1740481185.7671776,17.53998327255249,0.0,1740481185.7671797,17.53998327255249,13.483096512472759,1740481185.7671807,17.53998327255249,0.0,1740481185.767182,17.53998327255249,0.0,1740481185.767183,17.53998327255249,0.0,1740481185.767184,17.53998327255249,0.0,1740481185.767185,17.53998327255249,0.9950465093062307,1740481185.767186,17.53998327255249,0.0,1740481185.7671869,17.53998327255249,0.029879718525835708,1740481185.7671876,17.53998327255249,0.0,1740481185.7671888,17.53998327255249,0.965166790780395,, +1740481185.7836154,17.559983253479004,9.55276293091197,1740481185.7836175,17.559983253479004,0.0,1740481185.78362,17.559983253479004,0.0,1740481185.7836225,17.559983253479004,13.483096512472759,1740481185.7836235,17.559983253479004,0.0,1740481185.7836246,17.559983253479004,0.0,1740481185.7836258,17.559983253479004,0.0,1740481185.7836268,17.559983253479004,0.0,1740481185.7836277,17.559983253479004,0.9950465093062307,1740481185.7836294,17.559983253479004,0.0,1740481185.7836304,17.559983253479004,0.029879718525835708,1740481185.7836316,17.559983253479004,0.0,1740481185.7836323,17.559983253479004,0.965166790780395,, +1740481185.804513,17.579983234405518,9.658979062751342,1740481185.8045151,17.579983234405518,0.0,1740481185.804518,17.579983234405518,0.017259103293682816,1740481185.80452,17.579983234405518,13.500414789897995,1740481185.8045208,17.579983234405518,0.0,1740481185.8045223,17.579983234405518,0.0,1740481185.8045232,17.579983234405518,0.0,1740481185.8045242,17.579983234405518,0.0,1740481185.8045254,17.579983234405518,0.9950465093062307,1740481185.8045263,17.579983234405518,0.04953490693765383,1740481185.804527,17.579983234405518,0.07937158971862518,1740481185.8045282,17.579983234405518,0.0,1740481185.804529,17.579983234405518,0.9651963778461716,, +1740481185.8249288,17.59998321533203,9.658979062751342,1740481185.8249316,17.59998321533203,0.0,1740481185.8249347,17.59998321533203,0.017259103293682816,1740481185.8249369,17.59998321533203,13.500414789897995,1740481185.824938,17.59998321533203,0.0,1740481185.8249393,17.59998321533203,0.0,1740481185.8249402,17.59998321533203,0.0,1740481185.8249419,17.59998321533203,0.0,1740481185.8249426,17.59998321533203,0.9950465093062307,1740481185.824944,17.59998321533203,0.04953490693765383,1740481185.8249452,17.59998321533203,0.07938503839771294,1740481185.8249464,17.59998321533203,0.0,1740481185.8249476,17.59998321533203,0.9651963778461716,, +1740481185.8462698,17.619983196258545,9.658979062751342,1740481185.8462722,17.619983196258545,0.0,1740481185.8462746,17.619983196258545,0.017259103293682816,1740481185.8462765,17.619983196258545,13.500414789897995,1740481185.8462777,17.619983196258545,0.0,1740481185.846279,17.619983196258545,0.0,1740481185.8462799,17.619983196258545,0.0,1740481185.846281,17.619983196258545,0.0,1740481185.8462818,17.619983196258545,0.9950465093062307,1740481185.8463,17.619983196258545,0.04953490693765383,1740481185.846301,17.619983196258545,0.07938503839771294,1740481185.8463123,17.619983196258545,0.0,1740481185.8463159,17.619983196258545,0.9651963778461716,, +1740481185.8678372,17.63998317718506,9.658979062751342,1740481185.8678389,17.63998317718506,0.0,1740481185.8678412,17.63998317718506,0.0,1740481185.8678434,17.63998317718506,13.589371818443686,1740481185.8678443,17.63998317718506,0.0,1740481185.8678455,17.63998317718506,0.0,1740481185.867847,17.63998317718506,0.0,1740481185.867848,17.63998317718506,0.0,1740481185.8678486,17.63998317718506,0.9950549206478815,1740481185.86785,17.63998317718506,0.0,1740481185.8678508,17.63998317718506,0.029858542801709853,1740481185.8678515,17.63998317718506,0.0,1740481185.8678524,17.63998317718506,0.9651963778461716,, +1740481185.8840127,17.659983158111572,9.658979062751342,1740481185.8840153,17.659983158111572,0.0,1740481185.8840196,17.659983158111572,0.0,1740481185.8840218,17.659983158111572,13.589371818443686,1740481185.8840232,17.659983158111572,0.0,1740481185.8840246,17.659983158111572,0.0,1740481185.8840253,17.659983158111572,0.0,1740481185.8840265,17.659983158111572,0.0,1740481185.8840284,17.659983158111572,0.9950549206478815,1740481185.8840296,17.659983158111572,0.0,1740481185.8840318,17.659983158111572,0.029858542801709853,1740481185.884033,17.659983158111572,0.0,1740481185.8840342,17.659983158111572,0.9651963778461716,, +1740481185.9034276,17.679983139038086,9.658979062751342,1740481185.903429,17.679983139038086,0.0,1740481185.9034314,17.679983139038086,0.0,1740481185.9034336,17.679983139038086,13.589371818443686,1740481185.9034345,17.679983139038086,0.0,1740481185.9034357,17.679983139038086,0.0,1740481185.903437,17.679983139038086,0.0,1740481185.9034376,17.679983139038086,0.0,1740481185.9034383,17.679983139038086,0.9950549206478815,1740481185.9034393,17.679983139038086,0.0,1740481185.9034402,17.679983139038086,0.029858542801709853,1740481185.903441,17.679983139038086,0.0,1740481185.903442,17.679983139038086,0.9651963778461716,, +1740481185.92353,17.6999831199646,9.765220848065695,1740481185.9235315,17.6999831199646,0.0,1740481185.9235332,17.6999831199646,0.017263417667606935,1740481185.9235353,17.6999831199646,13.606470338732366,1740481185.923536,17.6999831199646,0.0,1740481185.9235375,17.6999831199646,0.0,1740481185.9235384,17.6999831199646,0.0,1740481185.9235392,17.6999831199646,0.0,1740481185.9235399,17.6999831199646,0.9950549206478815,1740481185.923541,17.6999831199646,0.04945079352114634,1740481185.9235418,17.6999831199646,0.07942926172508881,1740481185.9235425,17.6999831199646,0.0,1740481185.9235435,17.6999831199646,0.9651139291567084,, +1740481185.9442055,17.719983100891113,9.765220848065695,1740481185.9442093,17.719983100891113,0.0,1740481185.9442399,17.719983100891113,0.017263417667606935,1740481185.9442434,17.719983100891113,13.606470338732366,1740481185.944245,17.719983100891113,0.0,1740481185.944247,17.719983100891113,0.0,1740481185.9442503,17.719983100891113,0.0,1740481185.9442537,17.719983100891113,0.0,1740481185.9442556,17.719983100891113,0.9950549206478815,1740481185.944257,17.719983100891113,0.04945079352114634,1740481185.9442585,17.719983100891113,0.07939178501231947,1740481185.94426,17.719983100891113,0.0,1740481185.9442618,17.719983100891113,0.9651139291567084,, +1740481185.9698703,17.739983081817627,9.765220848065695,1740481185.9698758,17.739983081817627,0.0,1740481185.9698818,17.739983081817627,0.0,1740481185.9698849,17.739983081817627,13.695448706379112,1740481185.9698985,17.739983081817627,0.0,1740481185.9699016,17.739983081817627,0.0,1740481185.969904,17.739983081817627,0.0,1740481185.9699068,17.739983081817627,0.0,1740481185.9699113,17.739983081817627,0.9950314634202134,1740481185.9699135,17.739983081817627,0.0,1740481185.969918,17.739983081817627,0.029917534263505074,1740481185.9699223,17.739983081817627,0.0,1740481185.9699237,17.739983081817627,0.9651139291567084,, +1740481185.9863057,17.75998306274414,9.765220848065695,1740481185.9863076,17.75998306274414,0.0,1740481185.98631,17.75998306274414,0.0,1740481185.986312,17.75998306274414,13.695448706379112,1740481185.9863129,17.75998306274414,0.0,1740481185.986314,17.75998306274414,0.0,1740481185.9863155,17.75998306274414,0.0,1740481185.9863164,17.75998306274414,0.0,1740481185.9863174,17.75998306274414,0.9950314634202134,1740481185.9863183,17.75998306274414,0.0,1740481185.986319,17.75998306274414,0.029917534263505074,1740481185.98632,17.75998306274414,0.0,1740481185.986321,17.75998306274414,0.9651139291567084,, +1740481186.0049915,17.779983043670654,9.765220848065695,1740481186.0049953,17.779983043670654,0.0,1740481186.0050142,17.779983043670654,0.0,1740481186.005019,17.779983043670654,13.695448706379112,1740481186.00502,17.779983043670654,0.0,1740481186.005021,17.779983043670654,0.0,1740481186.0050223,17.779983043670654,0.0,1740481186.0050237,17.779983043670654,0.0,1740481186.0050259,17.779983043670654,0.9950314634202134,1740481186.0050273,17.779983043670654,0.0,1740481186.005029,17.779983043670654,0.029917534263505074,1740481186.0050306,17.779983043670654,0.0,1740481186.0050323,17.779983043670654,0.9651139291567084,, +1740481186.0240731,17.799983024597168,9.871404394617036,1740481186.024075,17.799983024597168,0.0,1740481186.024077,17.799983024597168,0.017253547605564534,1740481186.024079,17.799983024597168,13.711563510818493,1740481186.0240798,17.799983024597168,0.0,1740481186.0240812,17.799983024597168,0.0,1740481186.0240822,17.799983024597168,0.0,1740481186.0240831,17.799983024597168,0.0,1740481186.0240843,17.799983024597168,0.9950314634202134,1740481186.0240853,17.799983024597168,0.0496853657978269,1740481186.024086,17.799983024597168,0.08043107715628213,1740481186.024087,17.799983024597168,0.0,1740481186.0240881,17.799983024597168,0.9645445575736162,, +1740481186.0440319,17.81998300552368,9.871404394617036,1740481186.0440335,17.81998300552368,0.0,1740481186.0440357,17.81998300552368,0.017253547605564534,1740481186.0440376,17.81998300552368,13.711563510818493,1740481186.0440383,17.81998300552368,0.0,1740481186.0440397,17.81998300552368,0.0,1740481186.044041,17.81998300552368,0.0,1740481186.0440416,17.81998300552368,0.0,1740481186.0440433,17.81998300552368,0.9950314634202134,1740481186.044044,17.81998300552368,0.0496853657978269,1740481186.044045,17.81998300552368,0.08017227164442409,1740481186.0440462,17.81998300552368,0.0,1740481186.044047,17.81998300552368,0.9645445575736162,, +1740481186.066615,17.839982986450195,9.871404394617036,1740481186.0666168,17.839982986450195,0.0,1740481186.0666192,17.839982986450195,0.0,1740481186.066621,17.839982986450195,13.80049350976427,1740481186.0666223,17.839982986450195,0.0,1740481186.0666232,17.839982986450195,0.0,1740481186.0666242,17.839982986450195,0.0,1740481186.0666254,17.839982986450195,0.0,1740481186.0666263,17.839982986450195,0.9948679581069698,1740481186.066627,17.839982986450195,0.0,1740481186.0666287,17.839982986450195,0.030323400533353584,1740481186.0666294,17.839982986450195,0.0,1740481186.0666301,17.839982986450195,0.9645445575736162,, +1740481186.0865884,17.85998296737671,9.871404394617036,1740481186.086591,17.85998296737671,0.0,1740481186.0865934,17.85998296737671,0.0,1740481186.086595,17.85998296737671,13.80049350976427,1740481186.086596,17.85998296737671,0.0,1740481186.0865974,17.85998296737671,0.0,1740481186.0865989,17.85998296737671,0.0,1740481186.0865998,17.85998296737671,0.0,1740481186.0866008,17.85998296737671,0.9948679581069698,1740481186.0866017,17.85998296737671,0.0,1740481186.0866027,17.85998296737671,0.030323400533353584,1740481186.0866034,17.85998296737671,0.0,1740481186.0866046,17.85998296737671,0.9645445575736162,, +1740481186.104246,17.879982948303223,9.871404394617036,1740481186.104248,17.879982948303223,0.0,1740481186.104252,17.879982948303223,0.0,1740481186.1042542,17.879982948303223,13.80049350976427,1740481186.1042552,17.879982948303223,0.0,1740481186.1042566,17.879982948303223,0.0,1740481186.1042743,17.879982948303223,0.0,1740481186.1042752,17.879982948303223,0.0,1740481186.1042764,17.879982948303223,0.9948679581069698,1740481186.1042776,17.879982948303223,0.0,1740481186.1042783,17.879982948303223,0.030323400533353584,1740481186.1042793,17.879982948303223,0.0,1740481186.1042802,17.879982948303223,0.9645445575736162,, +1740481186.1243026,17.899982929229736,9.871404394617036,1740481186.1243043,17.899982929229736,0.0,1740481186.124307,17.899982929229736,0.0,1740481186.124309,17.899982929229736,13.80049350976427,1740481186.12431,17.899982929229736,0.0,1740481186.1243112,17.899982929229736,0.0,1740481186.1243126,17.899982929229736,0.0,1740481186.1243134,17.899982929229736,0.0,1740481186.124314,17.899982929229736,0.9948679581069698,1740481186.124315,17.899982929229736,0.0,1740481186.1243162,17.899982929229736,0.030323400533353584,1740481186.124317,17.899982929229736,0.0,1740481186.124318,17.899982929229736,0.9645445575736162,, +1740481186.144739,17.91998291015625,9.977524494593599,1740481186.1447408,17.91998291015625,0.0,1740481186.1447434,17.91998291015625,0.017240404862088988,1740481186.1447456,17.91998291015625,13.815743773134912,1740481186.1447465,17.91998291015625,0.0,1740481186.1447475,17.91998291015625,0.0,1740481186.1447484,17.91998291015625,0.0,1740481186.1447496,17.91998291015625,0.0,1740481186.1447508,17.91998291015625,0.9948679581069698,1740481186.1447515,17.91998291015625,0.05132041893026296,1740481186.1447527,17.91998291015625,0.08309119552511028,1740481186.1447537,17.91998291015625,0.0,1740481186.1447544,17.91998291015625,0.9635494868278938,, +1740481186.1678925,17.939982891082764,9.977524494593599,1740481186.1678944,17.939982891082764,0.0,1740481186.1678963,17.939982891082764,0.0,1740481186.1678984,17.939982891082764,13.904623468249387,1740481186.1678994,17.939982891082764,0.0,1740481186.1679006,17.939982891082764,0.0,1740481186.1679018,17.939982891082764,0.0,1740481186.1679027,17.939982891082764,0.0,1740481186.1679034,17.939982891082764,0.9945758502789234,1740481186.1679046,17.939982891082764,0.0,1740481186.1679053,17.939982891082764,0.031026363451029604,1740481186.1679063,17.939982891082764,0.0,1740481186.167907,17.939982891082764,0.9635494868278938,, +1740481186.184318,17.959982872009277,9.977524494593599,1740481186.184331,17.959982872009277,0.0,1740481186.1843343,17.959982872009277,0.0,1740481186.1843364,17.959982872009277,13.904623468249387,1740481186.1843374,17.959982872009277,0.0,1740481186.1843386,17.959982872009277,0.0,1740481186.1843398,17.959982872009277,0.0,1740481186.1843407,17.959982872009277,0.0,1740481186.1843414,17.959982872009277,0.9945758502789234,1740481186.1843426,17.959982872009277,0.0,1740481186.1843436,17.959982872009277,0.031026363451029604,1740481186.1843443,17.959982872009277,0.0,1740481186.1843452,17.959982872009277,0.9635494868278938,, +1740481186.2035723,17.97998285293579,9.977524494593599,1740481186.2035744,17.97998285293579,0.0,1740481186.2035768,17.97998285293579,0.0,1740481186.203579,17.97998285293579,13.904623468249387,1740481186.20358,17.97998285293579,0.0,1740481186.203581,17.97998285293579,0.0,1740481186.2035823,17.97998285293579,0.0,1740481186.2035835,17.97998285293579,0.0,1740481186.2035844,17.97998285293579,0.9945758502789234,1740481186.2035854,17.97998285293579,0.0,1740481186.203586,17.97998285293579,0.031026363451029604,1740481186.2035873,17.97998285293579,0.0,1740481186.2035882,17.97998285293579,0.9635494868278938,, +1740481186.2237372,17.999982833862305,9.977524494593599,1740481186.2237391,17.999982833862305,0.0,1740481186.2237415,17.999982833862305,0.0,1740481186.2237434,17.999982833862305,13.904623468249387,1740481186.2237446,17.999982833862305,0.0,1740481186.2237458,17.999982833862305,0.0,1740481186.2237468,17.999982833862305,0.0,1740481186.2237477,17.999982833862305,0.0,1740481186.223749,17.999982833862305,0.9945758502789234,1740481186.2237499,17.999982833862305,0.0,1740481186.2237506,17.999982833862305,0.031026363451029604,1740481186.2237518,17.999982833862305,0.0,1740481186.2237525,17.999982833862305,0.9635494868278938,, +1740481186.2456453,18.01998281478882,10.083457424204878,1740481186.2456474,18.01998281478882,0.0,1740481186.2456498,18.01998281478882,0.01720494382164095,1740481186.245652,18.01998281478882,13.918089127698194,1740481186.2456532,18.01998281478882,0.0,1740481186.2456546,18.01998281478882,0.0,1740481186.2456558,18.01998281478882,0.0,1740481186.2456572,18.01998281478882,0.0,1740481186.2456582,18.01998281478882,0.9945758502789234,1740481186.245659,18.01998281478882,0.05424149721072746,1740481186.24566,18.01998281478882,0.0879873410161046,1740481186.2456613,18.01998281478882,0.0,1740481186.2456622,18.01998281478882,0.9616798446414772,, +1740481186.2653143,18.039982795715332,10.083457424204878,1740481186.265316,18.039982795715332,0.0,1740481186.2653184,18.039982795715332,0.0,1740481186.2653208,18.039982795715332,14.006817113487832,1740481186.2653215,18.039982795715332,0.0,1740481186.2653227,18.039982795715332,0.0,1740481186.2653239,18.039982795715332,0.0,1740481186.2653248,18.039982795715332,0.0,1740481186.2653258,18.039982795715332,0.9940051420463041,1740481186.2653265,18.039982795715332,0.0,1740481186.2653275,18.039982795715332,0.032325297404826925,1740481186.2653284,18.039982795715332,0.0,1740481186.2653291,18.039982795715332,0.9616798446414772,, +1740481186.2839475,18.059982776641846,10.083457424204878,1740481186.2839499,18.059982776641846,0.0,1740481186.2839522,18.059982776641846,0.0,1740481186.2839541,18.059982776641846,14.006817113487832,1740481186.283955,18.059982776641846,0.0,1740481186.2839565,18.059982776641846,0.0,1740481186.2839575,18.059982776641846,0.0,1740481186.2839587,18.059982776641846,0.0,1740481186.2839599,18.059982776641846,0.9940051420463041,1740481186.2839608,18.059982776641846,0.0,1740481186.2839618,18.059982776641846,0.032325297404826925,1740481186.2839627,18.059982776641846,0.0,1740481186.2839637,18.059982776641846,0.9616798446414772,, +1740481186.3069644,18.07998275756836,10.083457424204878,1740481186.3069668,18.07998275756836,0.0,1740481186.3069696,18.07998275756836,0.0,1740481186.3069723,18.07998275756836,14.006817113487832,1740481186.3069735,18.07998275756836,0.0,1740481186.3069746,18.07998275756836,0.0,1740481186.3069763,18.07998275756836,0.0,1740481186.3069773,18.07998275756836,0.0,1740481186.3069785,18.07998275756836,0.9940051420463041,1740481186.3069797,18.07998275756836,0.0,1740481186.3069806,18.07998275756836,0.032325297404826925,1740481186.306982,18.07998275756836,0.0,1740481186.3069832,18.07998275756836,0.9616798446414772,, +1740481186.323836,18.099982738494873,10.083457424204878,1740481186.323838,18.099982738494873,0.0,1740481186.32384,18.099982738494873,0.0,1740481186.323842,18.099982738494873,14.006817113487832,1740481186.323843,18.099982738494873,0.0,1740481186.3238444,18.099982738494873,0.0,1740481186.3238456,18.099982738494873,0.0,1740481186.3238466,18.099982738494873,0.0,1740481186.323848,18.099982738494873,0.9940051420463041,1740481186.323849,18.099982738494873,0.0,1740481186.3238606,18.099982738494873,0.032325297404826925,1740481186.323863,18.099982738494873,0.0,1740481186.323864,18.099982738494873,0.9616798446414772,, +1740481186.3447142,18.119982719421387,10.083457424204878,1740481186.3447163,18.119982719421387,0.0,1740481186.3447187,18.119982719421387,0.0,1740481186.3447206,18.119982719421387,14.006817113487832,1740481186.3447213,18.119982719421387,0.0,1740481186.3447227,18.119982719421387,0.0,1740481186.3447237,18.119982719421387,0.0,1740481186.3447247,18.119982719421387,0.0,1740481186.344726,18.119982719421387,0.9940051420463041,1740481186.344727,18.119982719421387,0.0,1740481186.3447282,18.119982719421387,0.032325297404826925,1740481186.3447292,18.119982719421387,0.0,1740481186.3447304,18.119982719421387,0.9616798446414772,, +1740481186.3706157,18.1399827003479,10.189210400288738,1740481186.3706174,18.1399827003479,0.0,1740481186.3706195,18.1399827003479,0.0,1740481186.3706214,18.1399827003479,14.109299439745927,1740481186.3706224,18.1399827003479,0.0,1740481186.3706238,18.1399827003479,0.0,1740481186.3706248,18.1399827003479,0.0,1740481186.3706255,18.1399827003479,0.0,1740481186.3706264,18.1399827003479,0.9934825593435489,1740481186.3706274,18.1399827003479,0.06517440656447215,1740481186.3706284,18.1399827003479,0.09911823857548305,1740481186.370629,18.1399827003479,0.0,1740481186.3706298,18.1399827003479,0.9600445197285938,, +1740481186.3865602,18.159982681274414,10.189210400288738,1740481186.3865633,18.159982681274414,0.0,1740481186.3865666,18.159982681274414,0.0,1740481186.3865688,18.159982681274414,14.109299439745927,1740481186.3865697,18.159982681274414,0.0,1740481186.3865707,18.159982681274414,0.0,1740481186.386572,18.159982681274414,0.0,1740481186.3865728,18.159982681274414,0.0,1740481186.3865738,18.159982681274414,0.9934825593435489,1740481186.3865745,18.159982681274414,0.06517440656447215,1740481186.3865757,18.159982681274414,0.09861244617942722,1740481186.3865764,18.159982681274414,0.0,1740481186.3865771,18.159982681274414,0.9600445197285938,, +1740481186.4047318,18.179982662200928,10.189210400288738,1740481186.4047334,18.179982662200928,0.0,1740481186.4047358,18.179982662200928,0.0,1740481186.4047375,18.179982662200928,14.109299439745927,1740481186.4047387,18.179982662200928,0.0,1740481186.4047399,18.179982662200928,0.0,1740481186.4047408,18.179982662200928,0.0,1740481186.404742,18.179982662200928,0.0,1740481186.404743,18.179982662200928,0.9934825593435489,1740481186.404744,18.179982662200928,0.06517440656447215,1740481186.4047446,18.179982662200928,0.09861244617942722,1740481186.4047456,18.179982662200928,0.0,1740481186.4047465,18.179982662200928,0.9600445197285938,, +1740481186.4259036,18.19998264312744,10.189210400288738,1740481186.4259074,18.19998264312744,0.0,1740481186.4259098,18.19998264312744,0.0,1740481186.4259121,18.19998264312744,14.109299439745927,1740481186.425913,18.19998264312744,0.0,1740481186.4259143,18.19998264312744,0.0,1740481186.425916,18.19998264312744,0.0,1740481186.4259171,18.19998264312744,0.0,1740481186.4259179,18.19998264312744,0.9934825593435489,1740481186.4259198,18.19998264312744,0.06517440656447215,1740481186.4259207,18.19998264312744,0.09861244617942722,1740481186.4259217,18.19998264312744,0.0,1740481186.4259229,18.19998264312744,0.9600445197285938,, +1740481186.4446785,18.219982624053955,10.189210400288738,1740481186.444702,18.219982624053955,0.0,1740481186.4447043,18.219982624053955,0.0,1740481186.444707,18.219982624053955,14.109299439745927,1740481186.4447079,18.219982624053955,0.0,1740481186.444709,18.219982624053955,0.0,1740481186.4447103,18.219982624053955,0.0,1740481186.4447112,18.219982624053955,0.0,1740481186.4447122,18.219982624053955,0.9934825593435489,1740481186.444713,18.219982624053955,0.06517440656447215,1740481186.4447143,18.219982624053955,0.09861244617942722,1740481186.444715,18.219982624053955,0.0,1740481186.4447598,18.219982624053955,0.9600445197285938,, +1740481186.4694004,18.23998260498047,10.2949173179372,1740481186.469402,18.23998260498047,0.0,1740481186.4694042,18.23998260498047,0.0,1740481186.469406,18.23998260498047,14.221457403369758,1740481186.469407,18.23998260498047,0.0,1740481186.4694083,18.23998260498047,0.0,1740481186.469409,18.23998260498047,0.0,1740481186.46941,18.23998260498047,0.0,1740481186.4694111,18.23998260498047,0.9944923641095539,1740481186.469412,18.23998260498047,0.05507635890442231,1740481186.4694128,18.23998260498047,0.08529153469099048,1740481186.4694135,18.23998260498047,0.0,1740481186.4694145,18.23998260498047,0.9632700427162787,, +1740481186.4845397,18.259982585906982,10.2949173179372,1740481186.4845433,18.259982585906982,0.0,1740481186.484548,18.259982585906982,0.0,1740481186.4845505,18.259982585906982,14.221457403369758,1740481186.4845514,18.259982585906982,0.0,1740481186.4845526,18.259982585906982,0.0,1740481186.484554,18.259982585906982,0.0,1740481186.4845552,18.259982585906982,0.0,1740481186.4845564,18.259982585906982,0.9944923641095539,1740481186.4845583,18.259982585906982,0.05507635890442231,1740481186.4845598,18.259982585906982,0.0862986802976975,1740481186.4845612,18.259982585906982,0.0,1740481186.4845629,18.259982585906982,0.9632700427162787,, +1740481186.5038788,18.279982566833496,10.2949173179372,1740481186.5038812,18.279982566833496,0.0,1740481186.5038838,18.279982566833496,0.0,1740481186.5038857,18.279982566833496,14.221457403369758,1740481186.503887,18.279982566833496,0.0,1740481186.5038881,18.279982566833496,0.0,1740481186.503889,18.279982566833496,0.0,1740481186.5038905,18.279982566833496,0.0,1740481186.5038915,18.279982566833496,0.9944923641095539,1740481186.5038924,18.279982566833496,0.05507635890442231,1740481186.5038936,18.279982566833496,0.0862986802976975,1740481186.5038943,18.279982566833496,0.0,1740481186.503895,18.279982566833496,0.9632700427162787,, +1740481186.525964,18.29998254776001,10.2949173179372,1740481186.5259664,18.29998254776001,0.0,1740481186.5259686,18.29998254776001,0.0,1740481186.5259707,18.29998254776001,14.221457403369758,1740481186.5259717,18.29998254776001,0.0,1740481186.525973,18.29998254776001,0.0,1740481186.525974,18.29998254776001,0.0,1740481186.5259748,18.29998254776001,0.0,1740481186.5259762,18.29998254776001,0.9944923641095539,1740481186.5259774,18.29998254776001,0.05507635890442231,1740481186.525978,18.29998254776001,0.0862986802976975,1740481186.525979,18.29998254776001,0.0,1740481186.5259802,18.29998254776001,0.9632700427162787,, +1740481186.5455716,18.319982528686523,10.2949173179372,1740481186.5455735,18.319982528686523,0.0,1740481186.5455754,18.319982528686523,0.0,1740481186.5455775,18.319982528686523,14.221457403369758,1740481186.5455785,18.319982528686523,0.0,1740481186.5455794,18.319982528686523,0.0,1740481186.5455806,18.319982528686523,0.0,1740481186.5455816,18.319982528686523,0.0,1740481186.5455825,18.319982528686523,0.9944923641095539,1740481186.5455832,18.319982528686523,0.05507635890442231,1740481186.5455844,18.319982528686523,0.0862986802976975,1740481186.5455852,18.319982528686523,0.0,1740481186.5455863,18.319982528686523,0.9632700427162787,, +1740481186.5685804,18.339982509613037,10.2949173179372,1740481186.5685823,18.339982509613037,0.0,1740481186.5685844,18.339982509613037,0.0,1740481186.5685866,18.339982509613037,14.221457403369758,1740481186.5685875,18.339982509613037,0.0,1740481186.5685887,18.339982509613037,0.0,1740481186.56859,18.339982509613037,0.0,1740481186.5685909,18.339982509613037,0.0,1740481186.5685916,18.339982509613037,0.9944923641095539,1740481186.5685925,18.339982509613037,0.05507635890442231,1740481186.5685937,18.339982509613037,0.0862986802976975,1740481186.5685947,18.339982509613037,0.0,1740481186.5685954,18.339982509613037,0.9632700427162787,, +1740481186.5848248,18.35998249053955,10.40104677432711,1740481186.584827,18.35998249053955,0.0,1740481186.5848289,18.35998249053955,0.017235415546903304,1740481186.584831,18.35998249053955,14.245243811372855,1740481186.5848317,18.35998249053955,0.0,1740481186.584833,18.35998249053955,0.0,1740481186.584834,18.35998249053955,0.0,1740481186.584835,18.35998249053955,0.0,1740481186.584836,18.35998249053955,0.9999999999999961,1740481186.584837,18.35998249053955,5.551115123125783e-15,1740481186.5848377,18.35998249053955,0.034469070960662096,1740481186.5848389,18.35998249053955,0.0,1740481186.5848396,18.35998249053955,0.9665455389443763,, +1740481186.6058142,18.379982471466064,10.40104677432711,1740481186.6058168,18.379982471466064,0.0,1740481186.6058192,18.379982471466064,0.017235415546903304,1740481186.6058214,18.379982471466064,14.245243811372855,1740481186.6058226,18.379982471466064,0.0,1740481186.605824,18.379982471466064,0.0,1740481186.6058252,18.379982471466064,0.0,1740481186.6058266,18.379982471466064,0.0,1740481186.6058276,18.379982471466064,0.9999999999999961,1740481186.6058288,18.379982471466064,5.551115123125783e-15,1740481186.60583,18.379982471466064,0.03345446105562533,1740481186.6058311,18.379982471466064,0.0,1740481186.605832,18.379982471466064,0.9665455389443763,, +1740481186.6265132,18.399982452392578,10.40104677432711,1740481186.6265152,18.399982452392578,0.0,1740481186.626518,18.399982452392578,0.017235415546903304,1740481186.6265204,18.399982452392578,14.245243811372855,1740481186.6265213,18.399982452392578,0.0,1740481186.6265225,18.399982452392578,0.0,1740481186.6265237,18.399982452392578,0.0,1740481186.6265247,18.399982452392578,0.0,1740481186.6265256,18.399982452392578,0.9999999999999961,1740481186.626527,18.399982452392578,5.551115123125783e-15,1740481186.626528,18.399982452392578,0.03345446105562533,1740481186.6265287,18.399982452392578,0.0,1740481186.6265297,18.399982452392578,0.9665455389443763,, +1740481186.6450808,18.419982433319092,10.40104677432711,1740481186.6450849,18.419982433319092,0.0,1740481186.6450882,18.419982433319092,0.017235415546903304,1740481186.6450903,18.419982433319092,14.245243811372855,1740481186.6450918,18.419982433319092,0.0,1740481186.6450937,18.419982433319092,0.0,1740481186.6450958,18.419982433319092,0.0,1740481186.6450975,18.419982433319092,0.0,1740481186.6450992,18.419982433319092,0.9999999999999961,1740481186.6451015,18.419982433319092,5.551115123125783e-15,1740481186.6451037,18.419982433319092,0.03345446105562533,1740481186.6451051,18.419982433319092,0.0,1740481186.6451073,18.419982433319092,0.9665455389443763,, +1740481186.6673524,18.439982414245605,10.40104677432711,1740481186.6673543,18.439982414245605,0.0,1740481186.6673565,18.439982414245605,0.0,1740481186.6673584,18.439982414245605,14.334137852215862,1740481186.6673596,18.439982414245605,0.0,1740481186.6673608,18.439982414245605,0.0,1740481186.6673617,18.439982414245605,0.0,1740481186.667363,18.439982414245605,0.0,1740481186.6673636,18.439982414245605,0.9954308811954881,1740481186.6673646,18.439982414245605,0.0,1740481186.6673656,18.439982414245605,0.028885342251111723,1740481186.6673665,18.439982414245605,0.0,1740481186.6673672,18.439982414245605,0.9665455389443763,, +1740481186.6836257,18.45998239517212,10.507287821250857,1740481186.6836276,18.45998239517212,0.0,1740481186.6836295,18.45998239517212,0.017269820258691847,1740481186.6836314,18.45998239517212,14.347006041239649,1740481186.6836324,18.45998239517212,0.0,1740481186.6836336,18.45998239517212,0.0,1740481186.6836348,18.45998239517212,0.0,1740481186.6836357,18.45998239517212,0.0,1740481186.6836367,18.45998239517212,0.9954308811954881,1740481186.6836376,18.45998239517212,0.045691188045080544,1740481186.6836386,18.45998239517212,0.07777771760287931,1740481186.6836395,18.45998239517212,0.0,1740481186.6836402,18.45998239517212,0.9643447233269238,, +1740481186.7043273,18.479982376098633,10.507287821250857,1740481186.7043293,18.479982376098633,0.0,1740481186.7043316,18.479982376098633,0.017269820258691847,1740481186.7043335,18.479982376098633,14.347006041239649,1740481186.7043345,18.479982376098633,0.0,1740481186.7043357,18.479982376098633,0.0,1740481186.7043366,18.479982376098633,0.0,1740481186.7043376,18.479982376098633,0.0,1740481186.7043393,18.479982376098633,0.9954308811954881,1740481186.7043402,18.479982376098633,0.045691188045080544,1740481186.7043412,18.479982376098633,0.07677734591364482,1740481186.7043424,18.479982376098633,0.0,1740481186.704343,18.479982376098633,0.9643447233269238,, +1740481186.7237387,18.499982357025146,10.507287821250857,1740481186.7237408,18.499982357025146,0.0,1740481186.723743,18.499982357025146,0.017269820258691847,1740481186.7237453,18.499982357025146,14.347006041239649,1740481186.7237465,18.499982357025146,0.0,1740481186.7237477,18.499982357025146,0.0,1740481186.723749,18.499982357025146,0.0,1740481186.7237499,18.499982357025146,0.0,1740481186.7237506,18.499982357025146,0.9954308811954881,1740481186.723752,18.499982357025146,0.045691188045080544,1740481186.723753,18.499982357025146,0.07677734591364482,1740481186.723754,18.499982357025146,0.0,1740481186.7237546,18.499982357025146,0.9643447233269238,, +1740481186.7440987,18.51998233795166,10.507287821250857,1740481186.7441003,18.51998233795166,0.0,1740481186.7441027,18.51998233795166,0.017269820258691847,1740481186.7441046,18.51998233795166,14.347006041239649,1740481186.7441056,18.51998233795166,0.0,1740481186.7441068,18.51998233795166,0.0,1740481186.744108,18.51998233795166,0.0,1740481186.7441092,18.51998233795166,0.0,1740481186.7441103,18.51998233795166,0.9954308811954881,1740481186.7441113,18.51998233795166,0.045691188045080544,1740481186.7441125,18.51998233795166,0.07677734591364482,1740481186.7441134,18.51998233795166,0.0,1740481186.7441144,18.51998233795166,0.9643447233269238,, +1740481186.7670758,18.539982318878174,10.507287821250857,1740481186.7670798,18.539982318878174,0.0,1740481186.7670848,18.539982318878174,0.0,1740481186.767089,18.539982318878174,14.435977267904704,1740481186.767091,18.539982318878174,0.0,1740481186.7670934,18.539982318878174,0.0,1740481186.7670958,18.539982318878174,0.0,1740481186.767098,18.539982318878174,0.0,1740481186.7671003,18.539982318878174,0.9948099445675228,1740481186.7671025,18.539982318878174,0.0,1740481186.7671046,18.539982318878174,0.030465221240599027,1740481186.7671068,18.539982318878174,0.0,1740481186.7671094,18.539982318878174,0.9643447233269238,, +1740481186.7835572,18.559982299804688,10.507287821250857,1740481186.7835588,18.559982299804688,0.0,1740481186.7835612,18.559982299804688,0.0,1740481186.7835634,18.559982299804688,14.435977267904704,1740481186.7835643,18.559982299804688,0.0,1740481186.7835653,18.559982299804688,0.0,1740481186.7835662,18.559982299804688,0.0,1740481186.7835674,18.559982299804688,0.0,1740481186.7835684,18.559982299804688,0.9948099445675228,1740481186.7835693,18.559982299804688,0.0,1740481186.7835703,18.559982299804688,0.030465221240599027,1740481186.7835712,18.559982299804688,0.0,1740481186.783572,18.559982299804688,0.9643447233269238,, +1740481186.8034077,18.5799822807312,10.613459458334486,1740481186.8034093,18.5799822807312,0.0,1740481186.8034115,18.5799822807312,0.017247771820721874,1740481186.8034134,18.5799822807312,14.454710648726502,1740481186.8034143,18.5799822807312,0.0,1740481186.8034155,18.5799822807312,0.0,1740481186.8034165,18.5799822807312,0.0,1740481186.8034174,18.5799822807312,0.0,1740481186.8034184,18.5799822807312,0.9948099445675228,1740481186.8034196,18.5799822807312,0.05190055432473306,1740481186.8034203,18.5799822807312,0.08128533233346176,1740481186.8034215,18.5799822807312,0.0,1740481186.8034225,18.5799822807312,0.9650875278274614,, +1740481186.8233912,18.599982261657715,10.613459458334486,1740481186.823393,18.599982261657715,0.0,1740481186.823395,18.599982261657715,0.017247771820721874,1740481186.823397,18.599982261657715,14.454710648726502,1740481186.8233979,18.599982261657715,0.0,1740481186.823399,18.599982261657715,0.0,1740481186.8234,18.599982261657715,0.0,1740481186.823401,18.599982261657715,0.0,1740481186.8234017,18.599982261657715,0.9948099445675228,1740481186.8234026,18.599982261657715,0.05190055432473306,1740481186.8234038,18.599982261657715,0.08162297106479444,1740481186.8234046,18.599982261657715,0.0,1740481186.8234055,18.599982261657715,0.9650875278274614,, +1740481186.845877,18.61998224258423,10.613459458334486,1740481186.845879,18.61998224258423,0.0,1740481186.845881,18.61998224258423,0.017247771820721874,1740481186.845883,18.61998224258423,14.454710648726502,1740481186.8458838,18.61998224258423,0.0,1740481186.8458853,18.61998224258423,0.0,1740481186.8458865,18.61998224258423,0.0,1740481186.8458874,18.61998224258423,0.0,1740481186.8458886,18.61998224258423,0.9948099445675228,1740481186.8458896,18.61998224258423,0.05190055432473306,1740481186.8458903,18.61998224258423,0.08162297106479444,1740481186.845891,18.61998224258423,0.0,1740481186.8458922,18.61998224258423,0.9650875278274614,, +1740481186.8667853,18.639982223510742,10.613459458334486,1740481186.8667867,18.639982223510742,0.0,1740481186.866789,18.639982223510742,0.0,1740481186.8667912,18.639982223510742,14.543634513989408,1740481186.866792,18.639982223510742,0.0,1740481186.8667932,18.639982223510742,0.0,1740481186.8667943,18.639982223510742,0.0,1740481186.8667953,18.639982223510742,0.0,1740481186.8667963,18.639982223510742,0.9950239403255775,1740481186.8667972,18.639982223510742,0.0,1740481186.8667982,18.639982223510742,0.029936412498116072,1740481186.866799,18.639982223510742,0.0,1740481186.8667998,18.639982223510742,0.9650875278274614,, +1740481186.88587,18.659982204437256,10.613459458334486,1740481186.885872,18.659982204437256,0.0,1740481186.8858743,18.659982204437256,0.0,1740481186.885876,18.659982204437256,14.543634513989408,1740481186.885877,18.659982204437256,0.0,1740481186.8858783,18.659982204437256,0.0,1740481186.8858793,18.659982204437256,0.0,1740481186.8858802,18.659982204437256,0.0,1740481186.8858814,18.659982204437256,0.9950239403255775,1740481186.885896,18.659982204437256,0.0,1740481186.8858979,18.659982204437256,0.029936412498116072,1740481186.885899,18.659982204437256,0.0,1740481186.8859,18.659982204437256,0.9650875278274614,, +1740481186.9039137,18.67998218536377,10.719668543701626,1740481186.903916,18.67998218536377,0.0,1740481186.9039183,18.67998218536377,0.01725756687599937,1740481186.9039202,18.67998218536377,14.56100566399455,1740481186.9039211,18.67998218536377,0.0,1740481186.9039223,18.67998218536377,0.0,1740481186.9039235,18.67998218536377,0.0,1740481186.9039245,18.67998218536377,0.0,1740481186.9039254,18.67998218536377,0.9950239403255775,1740481186.9039264,18.67998218536377,0.04976059674418609,1740481186.9039273,18.67998218536377,0.07961440330558063,1740481186.9039283,18.67998218536377,0.0,1740481186.9039292,18.67998218536377,0.9651443193920323,, +1740481186.9262974,18.699982166290283,10.719668543701626,1740481186.9262993,18.699982166290283,0.0,1740481186.9263015,18.699982166290283,0.01725756687599937,1740481186.9263031,18.699982166290283,14.56100566399455,1740481186.9263043,18.699982166290283,0.0,1740481186.9263055,18.699982166290283,0.0,1740481186.9263065,18.699982166290283,0.0,1740481186.9263077,18.699982166290283,0.0,1740481186.9263086,18.699982166290283,0.9950239403255775,1740481186.9264796,18.699982166290283,0.04976059674418609,1740481186.9264839,18.699982166290283,0.07964021767773133,1740481186.926485,18.699982166290283,0.0,1740481186.9264858,18.699982166290283,0.9651443193920323,, +1740481186.9449685,18.719982147216797,10.719668543701626,1740481186.9449701,18.719982147216797,0.0,1740481186.9449723,18.719982147216797,0.01725756687599937,1740481186.9449744,18.719982147216797,14.56100566399455,1740481186.9449756,18.719982147216797,0.0,1740481186.9449766,18.719982147216797,0.0,1740481186.9449778,18.719982147216797,0.0,1740481186.944979,18.719982147216797,0.0,1740481186.94498,18.719982147216797,0.9950239403255775,1740481186.9449806,18.719982147216797,0.04976059674418609,1740481186.9449816,18.719982147216797,0.07964021767773133,1740481186.9449825,18.719982147216797,0.0,1740481186.9449835,18.719982147216797,0.9651443193920323,, +1740481186.9701383,18.73998212814331,10.719668543701626,1740481186.9701402,18.73998212814331,0.0,1740481186.9701424,18.73998212814331,0.0,1740481186.9701443,18.73998212814331,14.649957182485691,1740481186.9701452,18.73998212814331,0.0,1740481186.9701467,18.73998212814331,0.0,1740481186.9701478,18.73998212814331,0.0,1740481186.970149,18.73998212814331,0.0,1740481186.9701502,18.73998212814331,0.995040116113063,1740481186.9701512,18.73998212814331,0.0,1740481186.970152,18.73998212814331,0.02989579672103071,1740481186.9701526,18.73998212814331,0.0,1740481186.9701538,18.73998212814331,0.9651443193920323,, +1740481186.9846973,18.759982109069824,10.719668543701626,1740481186.9846992,18.759982109069824,0.0,1740481186.9847014,18.759982109069824,0.0,1740481186.9847033,18.759982109069824,14.649957182485691,1740481186.9847043,18.759982109069824,0.0,1740481186.9847054,18.759982109069824,0.0,1740481186.9847064,18.759982109069824,0.0,1740481186.9847074,18.759982109069824,0.0,1740481186.9847083,18.759982109069824,0.995040116113063,1740481186.984709,18.759982109069824,0.0,1740481186.9847102,18.759982109069824,0.02989579672103071,1740481186.984711,18.759982109069824,0.0,1740481186.984712,18.759982109069824,0.9651443193920323,, +1740481187.0060513,18.779982089996338,10.719668543701626,1740481187.0060534,18.779982089996338,0.0,1740481187.0060565,18.779982089996338,0.0,1740481187.0060585,18.779982089996338,14.649957182485691,1740481187.0060594,18.779982089996338,0.0,1740481187.0060608,18.779982089996338,0.0,1740481187.0060618,18.779982089996338,0.0,1740481187.0060632,18.779982089996338,0.0,1740481187.0060642,18.779982089996338,0.995040116113063,1740481187.006065,18.779982089996338,0.0,1740481187.0060658,18.779982089996338,0.02989579672103071,1740481187.006067,18.779982089996338,0.0,1740481187.0060678,18.779982089996338,0.9651443193920323,, +1740481187.0239363,18.79998207092285,10.825925658849366,1740481187.0239384,18.79998207092285,0.0,1740481187.0239403,18.79998207092285,0.017265651755587672,1740481187.0239425,18.79998207092285,14.668084552175264,1740481187.0239434,18.79998207092285,0.0,1740481187.0239444,18.79998207092285,0.0,1740481187.0239456,18.79998207092285,0.0,1740481187.0239468,18.79998207092285,0.0,1740481187.0239477,18.79998207092285,0.995040116113063,1740481187.0239484,18.79998207092285,0.04959883886933136,1740481187.0239496,18.79998207092285,0.07886793145159987,1740481187.0239506,18.79998207092285,0.0,1740481187.0239513,18.79998207092285,0.9655751783590252,, +1740481187.0437365,18.819982051849365,10.825925658849366,1740481187.0437384,18.819982051849365,0.0,1740481187.0437407,18.819982051849365,0.017265651755587672,1740481187.0437427,18.819982051849365,14.668084552175264,1740481187.0437438,18.819982051849365,0.0,1740481187.0437448,18.819982051849365,0.0,1740481187.0437458,18.819982051849365,0.0,1740481187.0437467,18.819982051849365,0.0,1740481187.0437481,18.819982051849365,0.995040116113063,1740481187.043749,18.819982051849365,0.04959883886933136,1740481187.0437498,18.819982051849365,0.07906377662336916,1740481187.043751,18.819982051849365,0.0,1740481187.043752,18.819982051849365,0.9655751783590252,, +1740481187.0649254,18.83998203277588,10.825925658849366,1740481187.0649276,18.83998203277588,0.0,1740481187.0649297,18.83998203277588,0.0,1740481187.0649319,18.83998203277588,14.757076015567417,1740481187.0649328,18.83998203277588,0.0,1740481187.0649345,18.83998203277588,0.0,1740481187.0649354,18.83998203277588,0.0,1740481187.0649364,18.83998203277588,0.0,1740481187.0649374,18.83998203277588,0.9951619787406595,1740481187.0649385,18.83998203277588,0.0,1740481187.0649393,18.83998203277588,0.029586800381634304,1740481187.0649402,18.83998203277588,0.0,1740481187.0649414,18.83998203277588,0.9655751783590252,, +1740481187.084891,18.859982013702393,10.825925658849366,1740481187.084893,18.859982013702393,0.0,1740481187.0848958,18.859982013702393,0.0,1740481187.0848978,18.859982013702393,14.757076015567417,1740481187.0848987,18.859982013702393,0.0,1740481187.0849001,18.859982013702393,0.0,1740481187.084901,18.859982013702393,0.0,1740481187.084902,18.859982013702393,0.0,1740481187.084903,18.859982013702393,0.9951619787406595,1740481187.084904,18.859982013702393,0.0,1740481187.0849047,18.859982013702393,0.029586800381634304,1740481187.0849056,18.859982013702393,0.0,1740481187.0849066,18.859982013702393,0.9655751783590252,, +1740481187.1039379,18.879981994628906,10.825925658849366,1740481187.1039393,18.879981994628906,0.0,1740481187.1039414,18.879981994628906,0.0,1740481187.1039433,18.879981994628906,14.757076015567417,1740481187.1039445,18.879981994628906,0.0,1740481187.1039455,18.879981994628906,0.0,1740481187.1039464,18.879981994628906,0.0,1740481187.1039479,18.879981994628906,0.0,1740481187.1039488,18.879981994628906,0.9951619787406595,1740481187.1039495,18.879981994628906,0.0,1740481187.1039505,18.879981994628906,0.029586800381634304,1740481187.1039515,18.879981994628906,0.0,1740481187.1039524,18.879981994628906,0.9655751783590252,, +1740481187.1235642,18.89998197555542,10.932133228619435,1740481187.1235673,18.89998197555542,0.0,1740481187.123571,18.89998197555542,0.017259714697890706,1740481187.1235733,18.89998197555542,14.772129655461775,1740481187.1235745,18.89998197555542,0.0,1740481187.1235754,18.89998197555542,0.0,1740481187.1235769,18.89998197555542,0.0,1740481187.1235778,18.89998197555542,0.0,1740481187.123591,18.89998197555542,0.9951619787406595,1740481187.1235933,18.89998197555542,0.048380212593366334,1740481187.1235943,18.89998197555542,0.07957143149208776,1740481187.1235952,18.89998197555542,0.0,1740481187.123596,18.89998197555542,0.9644721409572589,, +1740481187.1436777,18.919981956481934,10.932133228619435,1740481187.1436803,18.919981956481934,0.0,1740481187.1436825,18.919981956481934,0.017259714697890706,1740481187.1436846,18.919981956481934,14.772129655461775,1740481187.1436856,18.919981956481934,0.0,1740481187.143687,18.919981956481934,0.0,1740481187.1436882,18.919981956481934,0.0,1740481187.1436892,18.919981956481934,0.0,1740481187.1436903,18.919981956481934,0.9951619787406595,1740481187.1436913,18.919981956481934,0.048380212593366334,1740481187.143692,18.919981956481934,0.07907005037676695,1740481187.143693,18.919981956481934,0.0,1740481187.143694,18.919981956481934,0.9644721409572589,, +1740481187.1667068,18.939981937408447,10.932133228619435,1740481187.1667085,18.939981937408447,0.0,1740481187.1667109,18.939981937408447,0.0,1740481187.1667128,18.939981937408447,14.861077510533953,1740481187.166714,18.939981937408447,0.0,1740481187.166715,18.939981937408447,0.0,1740481187.1667159,18.939981937408447,0.0,1740481187.1667168,18.939981937408447,0.0,1740481187.166718,18.939981937408447,0.9948469726322369,1740481187.1667187,18.939981937408447,0.0,1740481187.166732,18.939981937408447,0.03037483167497801,1740481187.1667335,18.939981937408447,0.0,1740481187.1667342,18.939981937408447,0.9644721409572589,, +1740481187.1842113,18.95998191833496,10.932133228619435,1740481187.1842127,18.95998191833496,0.0,1740481187.184215,18.95998191833496,0.0,1740481187.184217,18.95998191833496,14.861077510533953,1740481187.1842182,18.95998191833496,0.0,1740481187.1842194,18.95998191833496,0.0,1740481187.1842208,18.95998191833496,0.0,1740481187.1842217,18.95998191833496,0.0,1740481187.1842225,18.95998191833496,0.9948469726322369,1740481187.1842234,18.95998191833496,0.0,1740481187.1842246,18.95998191833496,0.03037483167497801,1740481187.1842256,18.95998191833496,0.0,1740481187.1842263,18.95998191833496,0.9644721409572589,, +1740481187.2040532,18.979981899261475,10.932133228619435,1740481187.204055,18.979981899261475,0.0,1740481187.2040575,18.979981899261475,0.0,1740481187.2040594,18.979981899261475,14.861077510533953,1740481187.2040603,18.979981899261475,0.0,1740481187.2040617,18.979981899261475,0.0,1740481187.2040627,18.979981899261475,0.0,1740481187.2040637,18.979981899261475,0.0,1740481187.2040648,18.979981899261475,0.9948469726322369,1740481187.2040658,18.979981899261475,0.0,1740481187.2040668,18.979981899261475,0.03037483167497801,1740481187.2040682,18.979981899261475,0.0,1740481187.204069,18.979981899261475,0.9644721409572589,, +1740481187.2253335,18.99998188018799,10.932133228619435,1740481187.2253354,18.99998188018799,0.0,1740481187.2253373,18.99998188018799,0.0,1740481187.2253392,18.99998188018799,14.861077510533953,1740481187.2253401,18.99998188018799,0.0,1740481187.2253418,18.99998188018799,0.0,1740481187.2253428,18.99998188018799,0.0,1740481187.2253437,18.99998188018799,0.0,1740481187.2253447,18.99998188018799,0.9948469726322369,1740481187.2253458,18.99998188018799,0.0,1740481187.2253594,18.99998188018799,0.03037483167497801,1740481187.2253616,18.99998188018799,0.0,1740481187.225363,18.99998188018799,0.9644721409572589,, +1740481187.2437696,19.019981861114502,11.03824222008845,1740481187.2437716,19.019981861114502,0.0,1740481187.2437737,19.019981861114502,0.01723823653363268,1740481187.2437758,19.019981861114502,14.876255870754214,1740481187.2437768,19.019981861114502,0.0,1740481187.243778,19.019981861114502,0.0,1740481187.2437792,19.019981861114502,0.0,1740481187.2437804,19.019981861114502,0.0,1740481187.2437813,19.019981861114502,0.9948469726322369,1740481187.2437823,19.019981861114502,0.05153027367776897,1740481187.2437832,19.019981861114502,0.08340319766348324,1740481187.2437842,19.019981861114502,0.0,1740481187.2437854,19.019981861114502,0.9634422028005735,, +1740481187.2654252,19.039981842041016,11.03824222008845,1740481187.2654295,19.039981842041016,0.0,1740481187.2654328,19.039981842041016,0.0,1740481187.2654357,19.039981842041016,14.965126625689596,1740481187.265437,19.039981842041016,0.0,1740481187.265439,19.039981842041016,0.0,1740481187.2654405,19.039981842041016,0.0,1740481187.26546,19.039981842041016,0.0,1740481187.2654643,19.039981842041016,0.9945438737189592,1740481187.265466,19.039981842041016,0.0,1740481187.2654672,19.039981842041016,0.031101670918385782,1740481187.265469,19.039981842041016,0.0,1740481187.265472,19.039981842041016,0.9634422028005735,, +1740481187.28419,19.05998182296753,11.03824222008845,1740481187.284193,19.05998182296753,0.0,1740481187.2841964,19.05998182296753,0.0,1740481187.2841992,19.05998182296753,14.965126625689596,1740481187.2842004,19.05998182296753,0.0,1740481187.284202,19.05998182296753,0.0,1740481187.2842033,19.05998182296753,0.0,1740481187.2842045,19.05998182296753,0.0,1740481187.284206,19.05998182296753,0.9945438737189592,1740481187.2842073,19.05998182296753,0.0,1740481187.2842083,19.05998182296753,0.031101670918385782,1740481187.2842097,19.05998182296753,0.0,1740481187.284211,19.05998182296753,0.9634422028005735,, +1740481187.3043385,19.079981803894043,11.03824222008845,1740481187.3043408,19.079981803894043,0.0,1740481187.3043432,19.079981803894043,0.0,1740481187.3043458,19.079981803894043,14.965126625689596,1740481187.3043468,19.079981803894043,0.0,1740481187.3043485,19.079981803894043,0.0,1740481187.3043497,19.079981803894043,0.0,1740481187.304351,19.079981803894043,0.0,1740481187.3043523,19.079981803894043,0.9945438737189592,1740481187.3043535,19.079981803894043,0.0,1740481187.3043547,19.079981803894043,0.031101670918385782,1740481187.3043556,19.079981803894043,0.0,1740481187.3043566,19.079981803894043,0.9634422028005735,, +1740481187.323753,19.099981784820557,11.03824222008845,1740481187.3237553,19.099981784820557,0.0,1740481187.3237581,19.099981784820557,0.0,1740481187.32376,19.099981784820557,14.965126625689596,1740481187.3237612,19.099981784820557,0.0,1740481187.3237624,19.099981784820557,0.0,1740481187.3237636,19.099981784820557,0.0,1740481187.3237648,19.099981784820557,0.0,1740481187.3237658,19.099981784820557,0.9945438737189592,1740481187.3237667,19.099981784820557,0.0,1740481187.323768,19.099981784820557,0.031101670918385782,1740481187.3237686,19.099981784820557,0.0,1740481187.3237696,19.099981784820557,0.9634422028005735,, +1740481187.3436203,19.11998176574707,11.144164180106086,1740481187.3436222,19.11998176574707,0.0,1740481187.343625,19.11998176574707,0.017202609112892373,1740481187.343627,19.11998176574707,14.978617027838546,1740481187.343628,19.11998176574707,0.0,1740481187.3436296,19.11998176574707,0.0,1740481187.3436306,19.11998176574707,0.0,1740481187.343632,19.11998176574707,0.0,1740481187.343633,19.11998176574707,0.9945438737189592,1740481187.343634,19.11998176574707,0.05456126281036866,1740481187.3436348,19.11998176574707,0.08836272141622223,1740481187.3436363,19.11998176574707,0.0,1740481187.3436375,19.11998176574707,0.9615860993186018,, +1740481187.3674242,19.139981746673584,11.144164180106086,1740481187.3674269,19.139981746673584,0.0,1740481187.3674297,19.139981746673584,0.0,1740481187.3674316,19.139981746673584,15.06733637874329,1740481187.367433,19.139981746673584,0.0,1740481187.3674345,19.139981746673584,0.0,1740481187.367436,19.139981746673584,0.0,1740481187.3674371,19.139981746673584,0.0,1740481187.367438,19.139981746673584,0.9939757748734914,1740481187.3674388,19.139981746673584,0.0,1740481187.36744,19.139981746673584,0.032389675554889585,1740481187.367441,19.139981746673584,0.0,1740481187.367442,19.139981746673584,0.9615860993186018,, +1740481187.383887,19.159981727600098,11.144164180106086,1740481187.383889,19.159981727600098,0.0,1740481187.383891,19.159981727600098,0.0,1740481187.3838935,19.159981727600098,15.06733637874329,1740481187.3838944,19.159981727600098,0.0,1740481187.3838959,19.159981727600098,0.0,1740481187.3838968,19.159981727600098,0.0,1740481187.3838978,19.159981727600098,0.0,1740481187.383899,19.159981727600098,0.9939757748734914,1740481187.3839,19.159981727600098,0.0,1740481187.383901,19.159981727600098,0.032389675554889585,1740481187.3839018,19.159981727600098,0.0,1740481187.3839028,19.159981727600098,0.9615860993186018,, +1740481187.4039562,19.17998170852661,11.144164180106086,1740481187.403958,19.17998170852661,0.0,1740481187.4039602,19.17998170852661,0.0,1740481187.4039624,19.17998170852661,15.06733637874329,1740481187.4039633,19.17998170852661,0.0,1740481187.4039648,19.17998170852661,0.0,1740481187.403966,19.17998170852661,0.0,1740481187.403967,19.17998170852661,0.0,1740481187.403968,19.17998170852661,0.9939757748734914,1740481187.403969,19.17998170852661,0.0,1740481187.4039698,19.17998170852661,0.032389675554889585,1740481187.4039707,19.17998170852661,0.0,1740481187.403972,19.17998170852661,0.9615860993186018,, +1740481187.423939,19.199981689453125,11.144164180106086,1740481187.423941,19.199981689453125,0.0,1740481187.4239435,19.199981689453125,0.0,1740481187.4239454,19.199981689453125,15.06733637874329,1740481187.4239464,19.199981689453125,0.0,1740481187.423948,19.199981689453125,0.0,1740481187.423949,19.199981689453125,0.0,1740481187.4239502,19.199981689453125,0.0,1740481187.4239511,19.199981689453125,0.9939757748734914,1740481187.4239519,19.199981689453125,0.0,1740481187.4239528,19.199981689453125,0.032389675554889585,1740481187.423954,19.199981689453125,0.0,1740481187.423955,19.199981689453125,0.9615860993186018,, +1740481187.4444535,19.21998167037964,11.144164180106086,1740481187.4444575,19.21998167037964,0.0,1740481187.444461,19.21998167037964,0.0,1740481187.4444633,19.21998167037964,15.06733637874329,1740481187.4444644,19.21998167037964,0.0,1740481187.4444664,19.21998167037964,0.0,1740481187.4444675,19.21998167037964,0.0,1740481187.444469,19.21998167037964,0.0,1740481187.4444706,19.21998167037964,0.9939757748734914,1740481187.4444885,19.21998167037964,0.0,1740481187.4444892,19.21998167037964,0.032389675554889585,1740481187.4444911,19.21998167037964,0.0,1740481187.4444935,19.21998167037964,0.9615860993186018,, +1740481187.4667,19.239981651306152,11.24990782233614,1740481187.466702,19.239981651306152,0.0,1740481187.4667046,19.239981651306152,0.0,1740481187.466707,19.239981651306152,15.169837266746306,1740481187.4667077,19.239981651306152,0.0,1740481187.466709,19.239981651306152,0.0,1740481187.46671,19.239981651306152,0.0,1740481187.466711,19.239981651306152,0.0,1740481187.4667118,19.239981651306152,0.9934565005922579,1740481187.4667127,19.239981651306152,0.06543499407755893,1740481187.4667137,19.239981651306152,0.09942772877534073,1740481187.4667146,19.239981651306152,0.0,1740481187.4667153,19.239981651306152,0.9599647222050824,, +1740481187.4846838,19.259981632232666,11.24990782233614,1740481187.4846866,19.259981632232666,0.0,1740481187.484689,19.259981632232666,0.0,1740481187.4846911,19.259981632232666,15.169837266746306,1740481187.4846923,19.259981632232666,0.0,1740481187.4846935,19.259981632232666,0.0,1740481187.4846945,19.259981632232666,0.0,1740481187.4846954,19.259981632232666,0.0,1740481187.4846966,19.259981632232666,0.9934565005922579,1740481187.4846976,19.259981632232666,0.06543499407755893,1740481187.4846983,19.259981632232666,0.09892677246473436,1740481187.4846995,19.259981632232666,0.0,1740481187.4847004,19.259981632232666,0.9599647222050824,, +1740481187.5047328,19.27998161315918,11.24990782233614,1740481187.504735,19.27998161315918,0.0,1740481187.5047376,19.27998161315918,0.0,1740481187.5047395,19.27998161315918,15.169837266746306,1740481187.5047407,19.27998161315918,0.0,1740481187.504742,19.27998161315918,0.0,1740481187.5047429,19.27998161315918,0.0,1740481187.504744,19.27998161315918,0.0,1740481187.504745,19.27998161315918,0.9934565005922579,1740481187.504746,19.27998161315918,0.06543499407755893,1740481187.504747,19.27998161315918,0.09892677246473436,1740481187.504748,19.27998161315918,0.0,1740481187.504749,19.27998161315918,0.9599647222050824,, +1740481187.5245132,19.299981594085693,11.24990782233614,1740481187.5245152,19.299981594085693,0.0,1740481187.5245173,19.299981594085693,0.0,1740481187.5245194,19.299981594085693,15.169837266746306,1740481187.5245204,19.299981594085693,0.0,1740481187.5245218,19.299981594085693,0.0,1740481187.5245225,19.299981594085693,0.0,1740481187.5245235,19.299981594085693,0.0,1740481187.5245245,19.299981594085693,0.9934565005922579,1740481187.5245256,19.299981594085693,0.06543499407755893,1740481187.5245266,19.299981594085693,0.09892677246473436,1740481187.5245273,19.299981594085693,0.0,1740481187.5245283,19.299981594085693,0.9599647222050824,, +1740481187.5447516,19.319981575012207,11.24990782233614,1740481187.5447552,19.319981575012207,0.0,1740481187.5447598,19.319981575012207,0.0,1740481187.5447628,19.319981575012207,15.169837266746306,1740481187.5447638,19.319981575012207,0.0,1740481187.5447657,19.319981575012207,0.0,1740481187.5447671,19.319981575012207,0.0,1740481187.544769,19.319981575012207,0.0,1740481187.544772,19.319981575012207,0.9934565005922579,1740481187.5447738,19.319981575012207,0.06543499407755893,1740481187.5447757,19.319981575012207,0.09892677246473436,1740481187.5447779,19.319981575012207,0.0,1740481187.5447795,19.319981575012207,0.9599647222050824,, +1740481187.5660923,19.33998155593872,11.355667407889465,1740481187.5660942,19.33998155593872,0.0,1740481187.5660963,19.33998155593872,0.0,1740481187.5660985,19.33998155593872,15.28344042393136,1740481187.5660992,19.33998155593872,0.0,1740481187.5661006,19.33998155593872,0.0,1740481187.5661016,19.33998155593872,0.0,1740481187.5661025,19.33998155593872,0.0,1740481187.5661035,19.33998155593872,0.9946756898788307,1740481187.5661044,19.33998155593872,0.0532431012116541,1740481187.5661054,19.33998155593872,0.08280382893013229,1740481187.566106,19.33998155593872,0.0,1740481187.566107,19.33998155593872,0.9638865080209473,, +1740481187.5836558,19.359981536865234,11.355667407889465,1740481187.5836577,19.359981536865234,0.0,1740481187.5836601,19.359981536865234,0.0,1740481187.583662,19.359981536865234,15.28344042393136,1740481187.583663,19.359981536865234,0.0,1740481187.5836644,19.359981536865234,0.0,1740481187.5836654,19.359981536865234,0.0,1740481187.5836668,19.359981536865234,0.0,1740481187.5836682,19.359981536865234,0.9946756898788307,1740481187.5836692,19.359981536865234,0.0532431012116541,1740481187.5836704,19.359981536865234,0.08403228306953747,1740481187.5836713,19.359981536865234,0.0,1740481187.583672,19.359981536865234,0.9638865080209473,, +1740481187.603855,19.379981517791748,11.355667407889465,1740481187.6038568,19.379981517791748,0.0,1740481187.6038592,19.379981517791748,0.0,1740481187.6038613,19.379981517791748,15.28344042393136,1740481187.6038623,19.379981517791748,0.0,1740481187.6038635,19.379981517791748,0.0,1740481187.6038647,19.379981517791748,0.0,1740481187.6038656,19.379981517791748,0.0,1740481187.6038666,19.379981517791748,0.9946756898788307,1740481187.6038675,19.379981517791748,0.0532431012116541,1740481187.6038685,19.379981517791748,0.08403228306953747,1740481187.6038694,19.379981517791748,0.0,1740481187.6038706,19.379981517791748,0.9638865080209473,, +1740481187.625284,19.39998149871826,11.355667407889465,1740481187.6252859,19.39998149871826,0.0,1740481187.6252887,19.39998149871826,0.0,1740481187.6252909,19.39998149871826,15.28344042393136,1740481187.6252918,19.39998149871826,0.0,1740481187.625293,19.39998149871826,0.0,1740481187.625294,19.39998149871826,0.0,1740481187.6252952,19.39998149871826,0.0,1740481187.6252964,19.39998149871826,0.9946756898788307,1740481187.625297,19.39998149871826,0.0532431012116541,1740481187.6252983,19.39998149871826,0.08403228306953747,1740481187.6252992,19.39998149871826,0.0,1740481187.6253002,19.39998149871826,0.9638865080209473,, +1740481187.6450174,19.419981479644775,11.355667407889465,1740481187.6450222,19.419981479644775,0.0,1740481187.6450272,19.419981479644775,0.0,1740481187.6450293,19.419981479644775,15.28344042393136,1740481187.6450307,19.419981479644775,0.0,1740481187.645032,19.419981479644775,0.0,1740481187.645033,19.419981479644775,0.0,1740481187.645034,19.419981479644775,0.0,1740481187.645035,19.419981479644775,0.9946756898788307,1740481187.645036,19.419981479644775,0.0532431012116541,1740481187.6450372,19.419981479644775,0.08403228306953747,1740481187.6450381,19.419981479644775,0.0,1740481187.6450393,19.419981479644775,0.9638865080209473,, +1740481187.6678586,19.43998146057129,11.355667407889465,1740481187.667861,19.43998146057129,0.0,1740481187.6678634,19.43998146057129,0.0,1740481187.667865,19.43998146057129,15.28344042393136,1740481187.6678662,19.43998146057129,0.0,1740481187.6678677,19.43998146057129,0.0,1740481187.6678686,19.43998146057129,0.0,1740481187.6678698,19.43998146057129,0.0,1740481187.6678708,19.43998146057129,0.9946756898788307,1740481187.6678717,19.43998146057129,0.0532431012116541,1740481187.6678724,19.43998146057129,0.08403228306953747,1740481187.6678736,19.43998146057129,0.0,1740481187.6678743,19.43998146057129,0.9638865080209473,, +1740481187.6842358,19.459981441497803,11.46183830301949,1740481187.6842375,19.459981441497803,0.0,1740481187.6842396,19.459981441497803,0.017245323630303403,1740481187.6842418,19.459981441497803,15.306457119004076,1740481187.6842427,19.459981441497803,0.0,1740481187.684244,19.459981441497803,0.0,1740481187.684245,19.459981441497803,0.0,1740481187.684246,19.459981441497803,0.0,1740481187.684247,19.459981441497803,0.9999999999999961,1740481187.684248,19.459981441497803,5.551115123125783e-15,1740481187.6842492,19.459981441497803,0.034336272951309,1740481187.68425,19.459981441497803,0.0,1740481187.684251,19.459981441497803,0.9667721937421538,, +1740481187.7041419,19.479981422424316,11.46183830301949,1740481187.7041435,19.479981422424316,0.0,1740481187.704146,19.479981422424316,0.017245323630303403,1740481187.704148,19.479981422424316,15.306457119004076,1740481187.704149,19.479981422424316,0.0,1740481187.7041502,19.479981422424316,0.0,1740481187.7041514,19.479981422424316,0.0,1740481187.7041523,19.479981422424316,0.0,1740481187.704153,19.479981422424316,0.9999999999999961,1740481187.7041543,19.479981422424316,5.551115123125783e-15,1740481187.7041552,19.479981422424316,0.033227806257847825,1740481187.7041562,19.479981422424316,0.0,1740481187.7041569,19.479981422424316,0.9667721937421538,, +1740481187.7237208,19.49998140335083,11.46183830301949,1740481187.7237225,19.49998140335083,0.0,1740481187.7237248,19.49998140335083,0.017245323630303403,1740481187.7237265,19.49998140335083,15.306457119004076,1740481187.7237277,19.49998140335083,0.0,1740481187.723729,19.49998140335083,0.0,1740481187.7237298,19.49998140335083,0.0,1740481187.723731,19.49998140335083,0.0,1740481187.723732,19.49998140335083,0.9999999999999961,1740481187.723733,19.49998140335083,5.551115123125783e-15,1740481187.723734,19.49998140335083,0.033227806257847825,1740481187.723735,19.49998140335083,0.0,1740481187.7237358,19.49998140335083,0.9667721937421538,, +1740481187.744664,19.519981384277344,11.46183830301949,1740481187.7448947,19.519981384277344,0.0,1740481187.7449064,19.519981384277344,0.017245323630303403,1740481187.744933,19.519981384277344,15.306457119004076,1740481187.7449343,19.519981384277344,0.0,1740481187.7449365,19.519981384277344,0.0,1740481187.7449381,19.519981384277344,0.0,1740481187.7449393,19.519981384277344,0.0,1740481187.7449408,19.519981384277344,0.9999999999999961,1740481187.7449424,19.519981384277344,5.551115123125783e-15,1740481187.7449436,19.519981384277344,0.033227806257847825,1740481187.7449448,19.519981384277344,0.0,1740481187.7449465,19.519981384277344,0.9667721937421538,, +1740481187.7680128,19.539981365203857,11.46183830301949,1740481187.7680151,19.539981365203857,0.0,1740481187.7680178,19.539981365203857,0.0,1740481187.76802,19.539981365203857,15.395382690503798,1740481187.7680213,19.539981365203857,0.0,1740481187.7680228,19.539981365203857,0.0,1740481187.7680237,19.539981365203857,0.0,1740481187.7680252,19.539981365203857,0.0,1740481187.768026,19.539981365203857,0.9954925832534646,1740481187.768027,19.539981365203857,0.0,1740481187.7680283,19.539981365203857,0.02872038951131073,1740481187.7680295,19.539981365203857,0.0,1740481187.7680304,19.539981365203857,0.9667721937421538,, +1740481187.783701,19.55998134613037,11.56810108363452,1740481187.7837029,19.55998134613037,0.0,1740481187.7837048,19.55998134613037,0.017274423832933872,1740481187.783707,19.55998134613037,15.408168033429225,1740481187.7837076,19.55998134613037,0.0,1740481187.7837088,19.55998134613037,0.0,1740481187.78371,19.55998134613037,0.0,1740481187.7837114,19.55998134613037,0.0,1740481187.7837126,19.55998134613037,0.9954925832534646,1740481187.7837136,19.55998134613037,0.04507416746531545,1740481187.7837143,19.55998134613037,0.077059344064159,1740481187.7837152,19.55998134613037,0.0,1740481187.7837162,19.55998134613037,0.9645276532884008,, +1740481187.803967,19.579981327056885,11.56810108363452,1740481187.8039696,19.579981327056885,0.0,1740481187.8039715,19.579981327056885,0.017274423832933872,1740481187.8039737,19.579981327056885,15.408168033429225,1740481187.8039749,19.579981327056885,0.0,1740481187.8039763,19.579981327056885,0.0,1740481187.8039773,19.579981327056885,0.0,1740481187.8039782,19.579981327056885,0.0,1740481187.8039792,19.579981327056885,0.9954925832534646,1740481187.8039804,19.579981327056885,0.04507416746531545,1740481187.803981,19.579981327056885,0.07603909743037918,1740481187.803982,19.579981327056885,0.0,1740481187.8039832,19.579981327056885,0.9645276532884008,, +1740481187.8240774,19.5999813079834,11.56810108363452,1740481187.8240793,19.5999813079834,0.0,1740481187.8240814,19.5999813079834,0.017274423832933872,1740481187.8240836,19.5999813079834,15.408168033429225,1740481187.8240845,19.5999813079834,0.0,1740481187.8240855,19.5999813079834,0.0,1740481187.8240864,19.5999813079834,0.0,1740481187.8240879,19.5999813079834,0.0,1740481187.8240888,19.5999813079834,0.9954925832534646,1740481187.8240898,19.5999813079834,0.04507416746531545,1740481187.8240907,19.5999813079834,0.07603909743037918,1740481187.8240917,19.5999813079834,0.0,1740481187.8240924,19.5999813079834,0.9645276532884008,, +1740481187.843658,19.619981288909912,11.56810108363452,1740481187.8436599,19.619981288909912,0.0,1740481187.843662,19.619981288909912,0.017274423832933872,1740481187.8436642,19.619981288909912,15.408168033429225,1740481187.8436654,19.619981288909912,0.0,1740481187.8436668,19.619981288909912,0.0,1740481187.8436677,19.619981288909912,0.0,1740481187.843669,19.619981288909912,0.0,1740481187.8436701,19.619981288909912,0.9954925832534646,1740481187.843671,19.619981288909912,0.04507416746531545,1740481187.8436718,19.619981288909912,0.07603909743037918,1740481187.8436728,19.619981288909912,0.0,1740481187.843674,19.619981288909912,0.9645276532884008,, +1740481187.864542,19.639981269836426,11.56810108363452,1740481187.864544,19.639981269836426,0.0,1740481187.8645463,19.639981269836426,0.0,1740481187.8645482,19.639981269836426,15.497156390211321,1740481187.8645494,19.639981269836426,0.0,1740481187.8645506,19.639981269836426,0.0,1740481187.8645518,19.639981269836426,0.0,1740481187.8645527,19.639981269836426,0.0,1740481187.8645535,19.639981269836426,0.9948630632770161,1740481187.8645544,19.639981269836426,0.0,1740481187.8645556,19.639981269836426,0.03033540998861528,1740481187.8645563,19.639981269836426,0.0,1740481187.8645573,19.639981269836426,0.9645276532884008,, +1740481187.8841548,19.65998125076294,11.56810108363452,1740481187.8841565,19.65998125076294,0.0,1740481187.884159,19.65998125076294,0.0,1740481187.8841612,19.65998125076294,15.497156390211321,1740481187.884162,19.65998125076294,0.0,1740481187.8841636,19.65998125076294,0.0,1740481187.8841646,19.65998125076294,0.0,1740481187.8841655,19.65998125076294,0.0,1740481187.8841667,19.65998125076294,0.9948630632770161,1740481187.8841677,19.65998125076294,0.0,1740481187.8841686,19.65998125076294,0.03033540998861528,1740481187.8841698,19.65998125076294,0.0,1740481187.8841705,19.65998125076294,0.9645276532884008,, +1740481187.9045138,19.679981231689453,11.674288941638826,1740481187.9045157,19.679981231689453,0.0,1740481187.904518,19.679981231689453,0.017251328038133357,1740481187.90452,19.679981231689453,15.515765965462034,1740481187.904521,19.679981231689453,0.0,1740481187.904522,19.679981231689453,0.0,1740481187.904523,19.679981231689453,0.0,1740481187.9045243,19.679981231689453,0.0,1740481187.904525,19.679981231689453,0.9948630632770161,1740481187.904526,19.679981231689453,0.0513693672297999,1740481187.9045272,19.679981231689453,0.08071696076941996,1740481187.9045281,19.679981231689453,0.0,1740481187.9045289,19.679981231689453,0.9652067768946903,, +1740481187.9237146,19.699981212615967,11.674288941638826,1740481187.9237163,19.699981212615967,0.0,1740481187.9237185,19.699981212615967,0.017251328038133357,1740481187.9237204,19.699981212615967,15.515765965462034,1740481187.9237218,19.699981212615967,0.0,1740481187.9237227,19.699981212615967,0.0,1740481187.923724,19.699981212615967,0.0,1740481187.9237254,19.699981212615967,0.0,1740481187.9237266,19.699981212615967,0.9948630632770161,1740481187.9237275,19.699981212615967,0.0513693672297999,1740481187.9237285,19.699981212615967,0.08102565361212577,1740481187.9237294,19.699981212615967,0.0,1740481187.9237304,19.699981212615967,0.9652067768946903,, +1740481187.9438865,19.71998119354248,11.674288941638826,1740481187.943889,19.71998119354248,0.0,1740481187.9438913,19.71998119354248,0.017251328038133357,1740481187.9438932,19.71998119354248,15.515765965462034,1740481187.9438944,19.71998119354248,0.0,1740481187.9438953,19.71998119354248,0.0,1740481187.9438965,19.71998119354248,0.0,1740481187.9438972,19.71998119354248,0.0,1740481187.9438984,19.71998119354248,0.9948630632770161,1740481187.9438996,19.71998119354248,0.0513693672297999,1740481187.9439003,19.71998119354248,0.08102565361212577,1740481187.9439015,19.71998119354248,0.0,1740481187.9439023,19.71998119354248,0.9652067768946903,, +1740481187.9650648,19.739981174468994,11.674288941638826,1740481187.9650667,19.739981174468994,0.0,1740481187.9650688,19.739981174468994,0.0,1740481187.965071,19.739981174468994,15.604702495428207,1740481187.965072,19.739981174468994,0.0,1740481187.9650729,19.739981174468994,0.0,1740481187.9650738,19.739981174468994,0.0,1740481187.965075,19.739981174468994,0.0,1740481187.965076,19.739981174468994,0.9950578753080236,1740481187.9650767,19.739981174468994,0.0,1740481187.9650774,19.739981174468994,0.029851098413333332,1740481187.9650784,19.739981174468994,0.0,1740481187.965079,19.739981174468994,0.9652067768946903,, +1740481187.9841545,19.759981155395508,11.674288941638826,1740481187.9841561,19.759981155395508,0.0,1740481187.9841585,19.759981155395508,0.0,1740481187.9841604,19.759981155395508,15.604702495428207,1740481187.9841616,19.759981155395508,0.0,1740481187.9841628,19.759981155395508,0.0,1740481187.9841638,19.759981155395508,0.0,1740481187.984165,19.759981155395508,0.0,1740481187.984166,19.759981155395508,0.9950578753080236,1740481187.9841669,19.759981155395508,0.0,1740481187.9841676,19.759981155395508,0.029851098413333332,1740481187.984169,19.759981155395508,0.0,1740481187.9841697,19.759981155395508,0.9652067768946903,, +1740481188.0045369,19.77998113632202,11.780508642807344,1740481188.0045385,19.77998113632202,0.0,1740481188.004541,19.77998113632202,0.017259880425627847,1740481188.0045428,19.77998113632202,15.621994545796284,1740481188.0045438,19.77998113632202,0.0,1740481188.004545,19.77998113632202,0.0,1740481188.0045462,19.77998113632202,0.0,1740481188.004547,19.77998113632202,0.0,1740481188.0045478,19.77998113632202,0.9950578753080236,1740481188.0045488,19.77998113632202,0.04942124691972527,1740481188.0045497,19.77998113632202,0.07924894900430532,1740481188.0045507,19.77998113632202,0.0,1740481188.0045516,19.77998113632202,0.9652228618659144,, +1740481188.0236309,19.799981117248535,11.780508642807344,1740481188.0236335,19.799981117248535,0.0,1740481188.0236359,19.799981117248535,0.017259880425627847,1740481188.0236385,19.799981117248535,15.621994545796284,1740481188.0236402,19.799981117248535,0.0,1740481188.0236416,19.799981117248535,0.0,1740481188.0236437,19.799981117248535,0.0,1740481188.023645,19.799981117248535,0.0,1740481188.0236468,19.799981117248535,0.9950578753080236,1740481188.023649,19.799981117248535,0.04942124691972527,1740481188.0236506,19.799981117248535,0.07925626036183442,1740481188.0236523,19.799981117248535,0.0,1740481188.023654,19.799981117248535,0.9652228618659144,, +1740481188.0458302,19.81998109817505,11.780508642807344,1740481188.0458636,19.81998109817505,0.0,1740481188.045867,19.81998109817505,0.017259880425627847,1740481188.045869,19.81998109817505,15.621994545796284,1740481188.04587,19.81998109817505,0.0,1740481188.045872,19.81998109817505,0.0,1740481188.0458732,19.81998109817505,0.0,1740481188.0458739,19.81998109817505,0.0,1740481188.0458753,19.81998109817505,0.9950578753080236,1740481188.0458763,19.81998109817505,0.04942124691972527,1740481188.045877,19.81998109817505,0.07925626036183442,1740481188.0458777,19.81998109817505,0.0,1740481188.0459034,19.81998109817505,0.9652228618659144,, +1740481188.0666685,19.839981079101562,11.780508642807344,1740481188.0666704,19.839981079101562,0.0,1740481188.0666726,19.839981079101562,0.0,1740481188.0666745,19.839981079101562,15.710954366539173,1740481188.0666754,19.839981079101562,0.0,1740481188.0666764,19.839981079101562,0.0,1740481188.0666776,19.839981079101562,0.0,1740481188.0666783,19.839981079101562,0.0,1740481188.0666792,19.839981079101562,0.9950624437584972,1740481188.06668,19.839981079101562,0.0,1740481188.0666811,19.839981079101562,0.029839581892582734,1740481188.0666819,19.839981079101562,0.0,1740481188.0666826,19.839981079101562,0.9652228618659144,, +1740481188.0844657,19.859981060028076,11.780508642807344,1740481188.0844684,19.859981060028076,0.0,1740481188.0844717,19.859981060028076,0.0,1740481188.084474,19.859981060028076,15.710954366539173,1740481188.084475,19.859981060028076,0.0,1740481188.0844767,19.859981060028076,0.0,1740481188.0844777,19.859981060028076,0.0,1740481188.0844793,19.859981060028076,0.0,1740481188.0844808,19.859981060028076,0.9950624437584972,1740481188.084482,19.859981060028076,0.0,1740481188.0844834,19.859981060028076,0.029839581892582734,1740481188.084485,19.859981060028076,0.0,1740481188.0844865,19.859981060028076,0.9652228618659144,, +1740481188.1034663,19.87998104095459,11.780508642807344,1740481188.103468,19.87998104095459,0.0,1740481188.10347,19.87998104095459,0.0,1740481188.1034722,19.87998104095459,15.710954366539173,1740481188.1034732,19.87998104095459,0.0,1740481188.1034741,19.87998104095459,0.0,1740481188.103475,19.87998104095459,0.0,1740481188.1034763,19.87998104095459,0.0,1740481188.1034772,19.87998104095459,0.9950624437584972,1740481188.103478,19.87998104095459,0.0,1740481188.1034787,19.87998104095459,0.029839581892582734,1740481188.1034799,19.87998104095459,0.0,1740481188.1034806,19.87998104095459,0.9652228618659144,, +1740481188.1258748,19.899981021881104,11.886752745847467,1740481188.1258764,19.899981021881104,0.0,1740481188.1258786,19.899981021881104,0.017263924801891574,1740481188.1258805,19.899981021881104,15.728035968687472,1740481188.1258817,19.899981021881104,0.0,1740481188.1258826,19.899981021881104,0.0,1740481188.1258836,19.899981021881104,0.0,1740481188.1258848,19.899981021881104,0.0,1740481188.1258855,19.899981021881104,0.9950624437584972,1740481188.1258864,19.899981021881104,0.049375562414989416,1740481188.1258872,19.899981021881104,0.07934774264061115,1740481188.125888,19.899981021881104,0.0,1740481188.125889,19.899981021881104,0.9651317005391183,, +1740481188.1447883,19.919981002807617,11.886752745847467,1740481188.14479,19.919981002807617,0.0,1740481188.1447923,19.919981002807617,0.017263924801891574,1740481188.1447942,19.919981002807617,15.728035968687472,1740481188.1447952,19.919981002807617,0.0,1740481188.1447964,19.919981002807617,0.0,1740481188.1447973,19.919981002807617,0.0,1740481188.1447985,19.919981002807617,0.0,1740481188.1447992,19.919981002807617,0.9950624437584972,1740481188.1448002,19.919981002807617,0.049375562414989416,1740481188.1448011,19.919981002807617,0.07930630563436825,1740481188.144802,19.919981002807617,0.0,1740481188.144803,19.919981002807617,0.9651317005391183,, +1740481188.1688526,19.93998098373413,11.886752745847467,1740481188.1688542,19.93998098373413,0.0,1740481188.1688569,19.93998098373413,0.0,1740481188.1688588,19.93998098373413,15.817016146925702,1740481188.16886,19.93998098373413,0.0,1740481188.1688612,19.93998098373413,0.0,1740481188.168862,19.93998098373413,0.0,1740481188.1688633,19.93998098373413,0.0,1740481188.168865,19.93998098373413,0.9950365241949851,1740481188.1688662,19.93998098373413,0.0,1740481188.1688669,19.93998098373413,0.029904823655866775,1740481188.1688678,19.93998098373413,0.0,1740481188.1688688,19.93998098373413,0.9651317005391183,, +1740481188.1845353,19.959980964660645,11.886752745847467,1740481188.1845372,19.959980964660645,0.0,1740481188.184539,19.959980964660645,0.0,1740481188.1845412,19.959980964660645,15.817016146925702,1740481188.1845422,19.959980964660645,0.0,1740481188.1845431,19.959980964660645,0.0,1740481188.1845446,19.959980964660645,0.0,1740481188.1845455,19.959980964660645,0.0,1740481188.1845465,19.959980964660645,0.9950365241949851,1740481188.1845474,19.959980964660645,0.0,1740481188.1845484,19.959980964660645,0.029904823655866775,1740481188.1845493,19.959980964660645,0.0,1740481188.18455,19.959980964660645,0.9651317005391183,, +1740481188.2073057,19.979980945587158,11.886752745847467,1740481188.2073078,19.979980945587158,0.0,1740481188.20731,19.979980945587158,0.0,1740481188.207312,19.979980945587158,15.817016146925702,1740481188.207313,19.979980945587158,0.0,1740481188.2073145,19.979980945587158,0.0,1740481188.2073154,19.979980945587158,0.0,1740481188.2073164,19.979980945587158,0.0,1740481188.2073176,19.979980945587158,0.9950365241949851,1740481188.2073185,19.979980945587158,0.0,1740481188.2073193,19.979980945587158,0.029904823655866775,1740481188.207334,19.979980945587158,0.0,1740481188.207336,19.979980945587158,0.9651317005391183,, +1740481188.2252505,19.999980926513672,11.992937917075146,1740481188.2252524,19.999980926513672,0.0,1740481188.2252548,19.999980926513672,0.017253899349566164,1740481188.2252564,19.999980926513672,15.833121038104762,1740481188.2252574,19.999980926513672,0.0,1740481188.2252588,19.999980926513672,0.0,1740481188.2252595,19.999980926513672,0.0,1740481188.2252605,19.999980926513672,0.0,1740481188.2252614,19.999980926513672,0.9950365241949851,1740481188.2252624,19.999980926513672,0.04963475805010997,1740481188.2252634,19.999980926513672,0.0803752242608414,1740481188.225264,19.999980926513672,0.0,1740481188.2252655,19.999980926513672,0.9645571964538646,, +1740481188.2450485,20.019980907440186,11.992937917075146,1740481188.2450502,20.019980907440186,0.0,1740481188.2450638,20.019980907440186,0.017253899349566164,1740481188.2450686,20.019980907440186,15.833121038104762,1740481188.2450697,20.019980907440186,0.0,1740481188.2450712,20.019980907440186,0.0,1740481188.2450721,20.019980907440186,0.0,1740481188.245073,20.019980907440186,0.0,1740481188.245074,20.019980907440186,0.9950365241949851,1740481188.245075,20.019980907440186,0.04963475805010997,1740481188.2450757,20.019980907440186,0.08011408579123047,1740481188.2450767,20.019980907440186,0.0,1740481188.2450778,20.019980907440186,0.9645571964538646,, +1740481188.2681901,20.0399808883667,11.992937917075146,1740481188.2681918,20.0399808883667,0.0,1740481188.2681947,20.0399808883667,0.0,1740481188.2681963,20.0399808883667,15.922052309982876,1740481188.2681973,20.0399808883667,0.0,1740481188.2681987,20.0399808883667,0.0,1740481188.2681997,20.0399808883667,0.0,1740481188.2682006,20.0399808883667,0.0,1740481188.2682016,20.0399808883667,0.9948716163155578,1740481188.2682025,20.0399808883667,0.0,1740481188.2682033,20.0399808883667,0.030314419861693143,1740481188.268204,20.0399808883667,0.0,1740481188.2682052,20.0399808883667,0.9645571964538646,, +1740481188.2840762,20.059980869293213,11.992937917075146,1740481188.2840798,20.059980869293213,0.0,1740481188.2840831,20.059980869293213,0.0,1740481188.2840865,20.059980869293213,15.922052309982876,1740481188.284089,20.059980869293213,0.0,1740481188.2840915,20.059980869293213,0.0,1740481188.284093,20.059980869293213,0.0,1740481188.2840946,20.059980869293213,0.0,1740481188.284096,20.059980869293213,0.9948716163155578,1740481188.2840974,20.059980869293213,0.0,1740481188.284099,20.059980869293213,0.030314419861693143,1740481188.2841005,20.059980869293213,0.0,1740481188.2841024,20.059980869293213,0.9645571964538646,, +1740481188.3067873,20.079980850219727,11.992937917075146,1740481188.306789,20.079980850219727,0.0,1740481188.3067913,20.079980850219727,0.0,1740481188.3067935,20.079980850219727,15.922052309982876,1740481188.3067944,20.079980850219727,0.0,1740481188.3067958,20.079980850219727,0.0,1740481188.3067968,20.079980850219727,0.0,1740481188.3067977,20.079980850219727,0.0,1740481188.306799,20.079980850219727,0.9948716163155578,1740481188.3067997,20.079980850219727,0.0,1740481188.3068006,20.079980850219727,0.030314419861693143,1740481188.3068016,20.079980850219727,0.0,1740481188.3068027,20.079980850219727,0.9645571964538646,, +1740481188.3236504,20.09998083114624,11.992937917075146,1740481188.3236518,20.09998083114624,0.0,1740481188.3236542,20.09998083114624,0.0,1740481188.3236566,20.09998083114624,15.922052309982876,1740481188.3236575,20.09998083114624,0.0,1740481188.3236587,20.09998083114624,0.0,1740481188.3236597,20.09998083114624,0.0,1740481188.3236609,20.09998083114624,0.0,1740481188.3236618,20.09998083114624,0.9948716163155578,1740481188.3236628,20.09998083114624,0.0,1740481188.3236637,20.09998083114624,0.030314419861693143,1740481188.3236647,20.09998083114624,0.0,1740481188.3236656,20.09998083114624,0.9645571964538646,, +1740481188.3474858,20.119980812072754,12.099059190794723,1740481188.3474889,20.119980812072754,0.0,1740481188.3474917,20.119980812072754,0.017240658944895425,1740481188.3474946,20.119980812072754,15.937296845923598,1740481188.3474963,20.119980812072754,0.0,1740481188.347498,20.119980812072754,0.0,1740481188.3474996,20.119980812072754,0.0,1740481188.3475006,20.119980812072754,0.0,1740481188.3475018,20.119980812072754,0.9948716163155578,1740481188.3475032,20.119980812072754,0.051283836844383535,1740481188.3475208,20.119980812072754,0.08304998295994227,1740481188.3475218,20.119980812072754,0.0,1740481188.3475227,20.119980812072754,0.9635591349517778,, +1740481188.3653593,20.139980792999268,12.099059190794723,1740481188.3653615,20.139980792999268,0.0,1740481188.365364,20.139980792999268,0.0,1740481188.3653665,20.139980792999268,16.02617746069828,1740481188.365368,20.139980792999268,0.0,1740481188.365369,20.139980792999268,0.0,1740481188.3653703,20.139980792999268,0.0,1740481188.3653715,20.139980792999268,0.0,1740481188.3653722,20.139980792999268,0.9945787213464519,1740481188.3653736,20.139980792999268,0.0,1740481188.3653748,20.139980792999268,0.03101958639467406,1740481188.3653758,20.139980792999268,0.0,1740481188.365377,20.139980792999268,0.9635591349517778,, +1740481188.3838818,20.15998077392578,12.099059190794723,1740481188.3838835,20.15998077392578,0.0,1740481188.3838859,20.15998077392578,0.0,1740481188.3838878,20.15998077392578,16.02617746069828,1740481188.383889,20.15998077392578,0.0,1740481188.3838902,20.15998077392578,0.0,1740481188.383891,20.15998077392578,0.0,1740481188.3838923,20.15998077392578,0.0,1740481188.383893,20.15998077392578,0.9945787213464519,1740481188.3838942,20.15998077392578,0.0,1740481188.3838954,20.15998077392578,0.03101958639467406,1740481188.383896,20.15998077392578,0.0,1740481188.3838968,20.15998077392578,0.9635591349517778,, +1740481188.4050536,20.179980754852295,12.099059190794723,1740481188.4050555,20.179980754852295,0.0,1740481188.4050581,20.179980754852295,0.0,1740481188.405061,20.179980754852295,16.02617746069828,1740481188.4050624,20.179980754852295,0.0,1740481188.4050648,20.179980754852295,0.0,1740481188.405067,20.179980754852295,0.0,1740481188.4050686,20.179980754852295,0.0,1740481188.40507,20.179980754852295,0.9945787213464519,1740481188.4050722,20.179980754852295,0.0,1740481188.4050736,20.179980754852295,0.03101958639467406,1740481188.4050746,20.179980754852295,0.0,1740481188.4050763,20.179980754852295,0.9635591349517778,, +1740481188.4234297,20.19998073577881,12.099059190794723,1740481188.4234316,20.19998073577881,0.0,1740481188.4234347,20.19998073577881,0.0,1740481188.4234374,20.19998073577881,16.02617746069828,1740481188.4234385,20.19998073577881,0.0,1740481188.423441,20.19998073577881,0.0,1740481188.4234421,20.19998073577881,0.0,1740481188.4234436,20.19998073577881,0.0,1740481188.4234455,20.19998073577881,0.9945787213464519,1740481188.4234471,20.19998073577881,0.0,1740481188.4234483,20.19998073577881,0.03101958639467406,1740481188.4234495,20.19998073577881,0.0,1740481188.4234512,20.19998073577881,0.9635591349517778,, +1740481188.4442017,20.219980716705322,12.204993080250453,1740481188.4442043,20.219980716705322,0.0,1740481188.4442065,20.219980716705322,0.01720514937979279,1740481188.4442084,20.219980716705322,16.039640280300514,1740481188.4442093,20.219980716705322,0.0,1740481188.4442108,20.219980716705322,0.0,1740481188.4442117,20.219980716705322,0.0,1740481188.444213,20.219980716705322,0.0,1740481188.4442139,20.219980716705322,0.9945787213464519,1740481188.444215,20.219980716705322,0.054212786535619006,1740481188.444216,20.219980716705322,0.08795406812509911,1740481188.4442167,20.219980716705322,0.0,1740481188.444218,20.219980716705322,0.9616879700629998,, +1740481188.4649096,20.239980697631836,12.204993080250453,1740481188.4649115,20.239980697631836,0.0,1740481188.4649136,20.239980697631836,0.0,1740481188.4649158,20.239980697631836,16.128369020376454,1740481188.4649165,20.239980697631836,0.0,1740481188.4649177,20.239980697631836,0.0,1740481188.4649189,20.239980697631836,0.0,1740481188.4649198,20.239980697631836,0.0,1740481188.4649205,20.239980697631836,0.9940076840810647,1740481188.464922,20.239980697631836,0.0,1740481188.4649227,20.239980697631836,0.03231971401806488,1740481188.4649236,20.239980697631836,0.0,1740481188.4649246,20.239980697631836,0.9616879700629998,, +1740481188.4837606,20.25998067855835,12.204993080250453,1740481188.4837625,20.25998067855835,0.0,1740481188.4837644,20.25998067855835,0.0,1740481188.4837668,20.25998067855835,16.128369020376454,1740481188.4837675,20.25998067855835,0.0,1740481188.483769,20.25998067855835,0.0,1740481188.48377,20.25998067855835,0.0,1740481188.4837708,20.25998067855835,0.0,1740481188.4837716,20.25998067855835,0.9940076840810647,1740481188.4837852,20.25998067855835,0.0,1740481188.4837887,20.25998067855835,0.03231971401806488,1740481188.4837897,20.25998067855835,0.0,1740481188.4837906,20.25998067855835,0.9616879700629998,, +1740481188.5041797,20.279980659484863,12.204993080250453,1740481188.5041811,20.279980659484863,0.0,1740481188.5041835,20.279980659484863,0.0,1740481188.5041857,20.279980659484863,16.128369020376454,1740481188.5041869,20.279980659484863,0.0,1740481188.5041888,20.279980659484863,0.0,1740481188.5041897,20.279980659484863,0.0,1740481188.5041904,20.279980659484863,0.0,1740481188.5041914,20.279980659484863,0.9940076840810647,1740481188.5041924,20.279980659484863,0.0,1740481188.5041933,20.279980659484863,0.03231971401806488,1740481188.504194,20.279980659484863,0.0,1740481188.5041947,20.279980659484863,0.9616879700629998,, +1740481188.5242913,20.299980640411377,12.204993080250453,1740481188.524293,20.299980640411377,0.0,1740481188.5242956,20.299980640411377,0.0,1740481188.5242977,20.299980640411377,16.128369020376454,1740481188.5242987,20.299980640411377,0.0,1740481188.5243,20.299980640411377,0.0,1740481188.5243013,20.299980640411377,0.0,1740481188.524302,20.299980640411377,0.0,1740481188.524303,20.299980640411377,0.9940076840810647,1740481188.5243042,20.299980640411377,0.0,1740481188.5243049,20.299980640411377,0.03231971401806488,1740481188.5243056,20.299980640411377,0.0,1740481188.5243068,20.299980640411377,0.9616879700629998,, +1740481188.5436728,20.31998062133789,12.204993080250453,1740481188.5436745,20.31998062133789,0.0,1740481188.5436769,20.31998062133789,0.0,1740481188.543679,20.31998062133789,16.128369020376454,1740481188.54368,20.31998062133789,0.0,1740481188.5436814,20.31998062133789,0.0,1740481188.5436823,20.31998062133789,0.0,1740481188.5436833,20.31998062133789,0.0,1740481188.543684,20.31998062133789,0.9940076840810647,1740481188.5436852,20.31998062133789,0.0,1740481188.5436862,20.31998062133789,0.03231971401806488,1740481188.543687,20.31998062133789,0.0,1740481188.5436878,20.31998062133789,0.9616879700629998,, +1740481188.564615,20.339980602264404,12.31074686394302,1740481188.5646164,20.339980602264404,0.0,1740481188.5646188,20.339980602264404,0.0,1740481188.5646205,20.339980602264404,16.2308497064993,1740481188.5646217,20.339980602264404,0.0,1740481188.5646229,20.339980602264404,0.0,1740481188.5646238,20.339980602264404,0.0,1740481188.5646248,20.339980602264404,0.0,1740481188.564626,20.339980602264404,0.9934848106770025,1740481188.5646274,20.339980602264404,0.06515189322993664,1740481188.5646281,20.339980602264404,0.09909149919374743,1740481188.5646293,20.339980602264404,0.0,1740481188.56463,20.339980602264404,0.9600514212781387,, +1740481188.5844414,20.359980583190918,12.31074686394302,1740481188.584443,20.359980583190918,0.0,1740481188.5844457,20.359980583190918,0.0,1740481188.5844474,20.359980583190918,16.2308497064993,1740481188.5844486,20.359980583190918,0.0,1740481188.5844498,20.359980583190918,0.0,1740481188.584451,20.359980583190918,0.0,1740481188.5844522,20.359980583190918,0.0,1740481188.584453,20.359980583190918,0.9934848106770025,1740481188.5844538,20.359980583190918,0.06515189322993664,1740481188.5844553,20.359980583190918,0.0985852826288004,1740481188.584456,20.359980583190918,0.0,1740481188.584457,20.359980583190918,0.9600514212781387,, +1740481188.6073682,20.37998056411743,12.31074686394302,1740481188.6073701,20.37998056411743,0.0,1740481188.6073725,20.37998056411743,0.0,1740481188.6073747,20.37998056411743,16.2308497064993,1740481188.6073756,20.37998056411743,0.0,1740481188.6073768,20.37998056411743,0.0,1740481188.607378,20.37998056411743,0.0,1740481188.607379,20.37998056411743,0.0,1740481188.60738,20.37998056411743,0.9934848106770025,1740481188.607381,20.37998056411743,0.06515189322993664,1740481188.607382,20.37998056411743,0.0985852826288004,1740481188.6073828,20.37998056411743,0.0,1740481188.6073837,20.37998056411743,0.9600514212781387,, +1740481188.623789,20.399980545043945,12.31074686394302,1740481188.6237905,20.399980545043945,0.0,1740481188.6237931,20.399980545043945,0.0,1740481188.6237953,20.399980545043945,16.2308497064993,1740481188.6237962,20.399980545043945,0.0,1740481188.6237974,20.399980545043945,0.0,1740481188.6237986,20.399980545043945,0.0,1740481188.6237996,20.399980545043945,0.0,1740481188.6238003,20.399980545043945,0.9934848106770025,1740481188.6238017,20.399980545043945,0.06515189322993664,1740481188.6238027,20.399980545043945,0.0985852826288004,1740481188.6238034,20.399980545043945,0.0,1740481188.6238043,20.399980545043945,0.9600514212781387,, +1740481188.6439867,20.41998052597046,12.31074686394302,1740481188.643991,20.41998052597046,0.0,1740481188.643998,20.41998052597046,0.0,1740481188.6440005,20.41998052597046,16.2308497064993,1740481188.644002,20.41998052597046,0.0,1740481188.6440039,20.41998052597046,0.0,1740481188.6440063,20.41998052597046,0.0,1740481188.644008,20.41998052597046,0.0,1740481188.6440105,20.41998052597046,0.9934848106770025,1740481188.6440122,20.41998052597046,0.06515189322993664,1740481188.6440141,20.41998052597046,0.0985852826288004,1740481188.6440156,20.41998052597046,0.0,1740481188.644018,20.41998052597046,0.9600514212781387,, +1740481188.6654434,20.439980506896973,12.41651435876285,1740481188.665445,20.439980506896973,0.0,1740481188.6654472,20.439980506896973,0.0,1740481188.6654491,20.439980506896973,16.344390191107255,1740481188.6654503,20.439980506896973,0.0,1740481188.6654515,20.439980506896973,0.0,1740481188.6654525,20.439980506896973,0.0,1740481188.665454,20.439980506896973,0.0,1740481188.6654546,20.439980506896973,0.9946908375761386,1740481188.6654556,20.439980506896973,0.05309162423857483,1740481188.6654563,20.439980506896973,0.08262614993740922,1740481188.6654575,20.439980506896973,0.0,1740481188.6654582,20.439980506896973,0.9639379161722026,, +1740481188.6846502,20.459980487823486,12.41651435876285,1740481188.684652,20.459980487823486,0.0,1740481188.6846542,20.459980487823486,0.0,1740481188.6846564,20.459980487823486,16.344390191107255,1740481188.6846573,20.459980487823486,0.0,1740481188.684659,20.459980487823486,0.0,1740481188.68466,20.459980487823486,0.0,1740481188.684661,20.459980487823486,0.0,1740481188.6846619,20.459980487823486,0.9946908375761386,1740481188.6846628,20.459980487823486,0.05309162423857483,1740481188.6846635,20.459980487823486,0.08384454564251087,1740481188.6846647,20.459980487823486,0.0,1740481188.6846662,20.459980487823486,0.9639379161722026,, +1740481188.7056332,20.47998046875,12.41651435876285,1740481188.7056513,20.47998046875,0.0,1740481188.705657,20.47998046875,0.0,1740481188.7056606,20.47998046875,16.344390191107255,1740481188.7056623,20.47998046875,0.0,1740481188.705664,20.47998046875,0.0,1740481188.7056658,20.47998046875,0.0,1740481188.7056668,20.47998046875,0.0,1740481188.7056684,20.47998046875,0.9946908375761386,1740481188.7056706,20.47998046875,0.05309162423857483,1740481188.7056723,20.47998046875,0.08384454564251087,1740481188.7056751,20.47998046875,0.0,1740481188.705677,20.47998046875,0.9639379161722026,, +1740481188.723929,20.499980449676514,12.41651435876285,1740481188.7239325,20.499980449676514,0.0,1740481188.7239358,20.499980449676514,0.0,1740481188.7239377,20.499980449676514,16.344390191107255,1740481188.7239387,20.499980449676514,0.0,1740481188.7239404,20.499980449676514,0.0,1740481188.7239413,20.499980449676514,0.0,1740481188.7239425,20.499980449676514,0.0,1740481188.7239435,20.499980449676514,0.9946908375761386,1740481188.7239444,20.499980449676514,0.05309162423857483,1740481188.7239451,20.499980449676514,0.08384454564251087,1740481188.723946,20.499980449676514,0.0,1740481188.723947,20.499980449676514,0.9639379161722026,, +1740481188.7451599,20.519980430603027,12.41651435876285,1740481188.7451625,20.519980430603027,0.0,1740481188.7451842,20.519980430603027,0.0,1740481188.7451866,20.519980430603027,16.344390191107255,1740481188.7451875,20.519980430603027,0.0,1740481188.7451892,20.519980430603027,0.0,1740481188.7451906,20.519980430603027,0.0,1740481188.7451916,20.519980430603027,0.0,1740481188.7451928,20.519980430603027,0.9946908375761386,1740481188.7453573,20.519980430603027,0.05309162423857483,1740481188.7453628,20.519980430603027,0.08384454564251087,1740481188.7453642,20.519980430603027,0.0,1740481188.7453656,20.519980430603027,0.9639379161722026,, +1740481188.765618,20.53998041152954,12.41651435876285,1740481188.76562,20.53998041152954,0.0,1740481188.765622,20.53998041152954,0.0,1740481188.765624,20.53998041152954,16.344390191107255,1740481188.765625,20.53998041152954,0.0,1740481188.7656264,20.53998041152954,0.0,1740481188.7656274,20.53998041152954,0.0,1740481188.7656283,20.53998041152954,0.0,1740481188.7656293,20.53998041152954,0.9946908375761386,1740481188.7656307,20.53998041152954,0.05309162423857483,1740481188.7656317,20.53998041152954,0.08384454564251087,1740481188.7656326,20.53998041152954,0.0,1740481188.7656336,20.53998041152954,0.9639379161722026,, +1740481188.7837327,20.559980392456055,12.522689877880403,1740481188.7837343,20.559980392456055,0.0,1740481188.7837365,20.559980392456055,0.017246337340628484,1740481188.7837384,20.559980392456055,16.367366359091882,1740481188.7837393,20.559980392456055,0.0,1740481188.7837408,20.559980392456055,0.0,1740481188.7837417,20.559980392456055,0.0,1740481188.7837424,20.559980392456055,0.0,1740481188.7837431,20.559980392456055,0.9999999999999961,1740481188.7837443,20.559980392456055,5.551115123125783e-15,1740481188.7837453,20.559980392456055,0.03430819097528861,1740481188.783746,20.559980392456055,0.0,1740481188.783747,20.559980392456055,0.9668028314942021,, +1740481188.8036923,20.57998037338257,12.522689877880403,1740481188.8036938,20.57998037338257,0.0,1740481188.803696,20.57998037338257,0.017246337340628484,1740481188.8036978,20.57998037338257,16.367366359091882,1740481188.803699,20.57998037338257,0.0,1740481188.8037002,20.57998037338257,0.0,1740481188.8037014,20.57998037338257,0.0,1740481188.8037024,20.57998037338257,0.0,1740481188.8037033,20.57998037338257,0.9999999999999961,1740481188.8037043,20.57998037338257,5.551115123125783e-15,1740481188.8037055,20.57998037338257,0.03319716850579957,1740481188.8037062,20.57998037338257,0.0,1740481188.8037071,20.57998037338257,0.9668028314942021,, +1740481188.8237102,20.599980354309082,12.522689877880403,1740481188.8237116,20.599980354309082,0.0,1740481188.8237138,20.599980354309082,0.017246337340628484,1740481188.823716,20.599980354309082,16.367366359091882,1740481188.8237169,20.599980354309082,0.0,1740481188.823718,20.599980354309082,0.0,1740481188.8237193,20.599980354309082,0.0,1740481188.8237202,20.599980354309082,0.0,1740481188.823721,20.599980354309082,0.9999999999999961,1740481188.823722,20.599980354309082,5.551115123125783e-15,1740481188.823723,20.599980354309082,0.03319716850579957,1740481188.8237238,20.599980354309082,0.0,1740481188.8237247,20.599980354309082,0.9668028314942021,, +1740481188.8437989,20.619980335235596,12.522689877880403,1740481188.8438008,20.619980335235596,0.0,1740481188.843803,20.619980335235596,0.017246337340628484,1740481188.8438046,20.619980335235596,16.367366359091882,1740481188.843806,20.619980335235596,0.0,1740481188.8438072,20.619980335235596,0.0,1740481188.8438082,20.619980335235596,0.0,1740481188.8438091,20.619980335235596,0.0,1740481188.8438098,20.619980335235596,0.9999999999999961,1740481188.8438108,20.619980335235596,5.551115123125783e-15,1740481188.843812,20.619980335235596,0.03319716850579957,1740481188.843813,20.619980335235596,0.0,1740481188.8438144,20.619980335235596,0.9668028314942021,, +1740481188.8661432,20.63998031616211,12.522689877880403,1740481188.8661451,20.63998031616211,0.0,1740481188.8661478,20.63998031616211,0.0,1740481188.8661501,20.63998031616211,16.45629554086881,1740481188.8661513,20.63998031616211,0.0,1740481188.866153,20.63998031616211,0.0,1740481188.8661542,20.63998031616211,0.0,1740481188.8661551,20.63998031616211,0.0,1740481188.8661563,20.63998031616211,0.9955008915630285,1740481188.8661575,20.63998031616211,0.0,1740481188.8661585,20.63998031616211,0.02869806006882636,1740481188.8661597,20.63998031616211,0.0,1740481188.8661606,20.63998031616211,0.9668028314942021,, +1740481188.8836489,20.659980297088623,12.62895569738603,1740481188.8836505,20.659980297088623,0.0,1740481188.8836527,20.659980297088623,0.01727506202011332,1740481188.8836546,20.659980297088623,16.46907165292579,1740481188.8836558,20.659980297088623,0.0,1740481188.883657,20.659980297088623,0.0,1740481188.8836582,20.659980297088623,0.0,1740481188.8836591,20.659980297088623,0.0,1740481188.88366,20.659980297088623,0.9955008915630285,1740481188.883661,20.659980297088623,0.04499108436985311,1740481188.883662,20.659980297088623,0.0769611090233513,1740481188.883663,20.659980297088623,0.0,1740481188.8836637,20.659980297088623,0.9645533565126366,, +1740481188.903431,20.679980278015137,12.62895569738603,1740481188.9034328,20.679980278015137,0.0,1740481188.9034352,20.679980278015137,0.01727506202011332,1740481188.9034374,20.679980278015137,16.46907165292579,1740481188.9034383,20.679980278015137,0.0,1740481188.9034395,20.679980278015137,0.0,1740481188.9034407,20.679980278015137,0.0,1740481188.9034417,20.679980278015137,0.0,1740481188.9034424,20.679980278015137,0.9955008915630285,1740481188.903444,20.679980278015137,0.04499108436985311,1740481188.9034448,20.679980278015137,0.07593861942024493,1740481188.9034457,20.679980278015137,0.0,1740481188.9034464,20.679980278015137,0.9645533565126366,, +1740481188.9236023,20.69998025894165,12.62895569738603,1740481188.923604,20.69998025894165,0.0,1740481188.9236062,20.69998025894165,0.01727506202011332,1740481188.923608,20.69998025894165,16.46907165292579,1740481188.923609,20.69998025894165,0.0,1740481188.9236104,20.69998025894165,0.0,1740481188.9236114,20.69998025894165,0.0,1740481188.923612,20.69998025894165,0.0,1740481188.923613,20.69998025894165,0.9955008915630285,1740481188.923614,20.69998025894165,0.04499108436985311,1740481188.923615,20.69998025894165,0.07593861942024493,1740481188.9236157,20.69998025894165,0.0,1740481188.923617,20.69998025894165,0.9645533565126366,, +1740481188.9438674,20.719980239868164,12.62895569738603,1740481188.943869,20.719980239868164,0.0,1740481188.9438715,20.719980239868164,0.01727506202011332,1740481188.9438732,20.719980239868164,16.46907165292579,1740481188.9438744,20.719980239868164,0.0,1740481188.9438756,20.719980239868164,0.0,1740481188.9438765,20.719980239868164,0.0,1740481188.9438777,20.719980239868164,0.0,1740481188.9438787,20.719980239868164,0.9955008915630285,1740481188.9438796,20.719980239868164,0.04499108436985311,1740481188.9438806,20.719980239868164,0.07593861942024493,1740481188.9438815,20.719980239868164,0.0,1740481188.9438825,20.719980239868164,0.9645533565126366,, +1740481188.9649084,20.739980220794678,12.62895569738603,1740481188.96491,20.739980220794678,0.0,1740481188.9649124,20.739980220794678,0.0,1740481188.9649143,20.739980220794678,16.558062410411303,1740481188.9649155,20.739980220794678,0.0,1740481188.964917,20.739980220794678,0.0,1740481188.9649184,20.739980220794678,0.0,1740481188.964919,20.739980220794678,0.0,1740481188.96492,20.739980220794678,0.9948705050175403,1740481188.964921,20.739980220794678,0.0,1740481188.9649222,20.739980220794678,0.030317148504903635,1740481188.9649231,20.739980220794678,0.0,1740481188.9649239,20.739980220794678,0.9645533565126366,, +1740481188.985889,20.75998020172119,12.62895569738603,1740481188.9858909,20.75998020172119,0.0,1740481188.9858944,20.75998020172119,0.0,1740481188.9858963,20.75998020172119,16.558062410411303,1740481188.9858975,20.75998020172119,0.0,1740481188.9858987,20.75998020172119,0.0,1740481188.9858997,20.75998020172119,0.0,1740481188.9859009,20.75998020172119,0.0,1740481188.9859016,20.75998020172119,0.9948705050175403,1740481188.9859025,20.75998020172119,0.0,1740481188.9859035,20.75998020172119,0.030317148504903635,1740481188.9859045,20.75998020172119,0.0,1740481188.9859054,20.75998020172119,0.9645533565126366,, +1740481189.0053704,20.779980182647705,12.735145850395028,1740481189.0053725,20.779980182647705,0.0,1740481189.0053744,20.779980182647705,0.017251829931227303,1740481189.0053766,20.779980182647705,16.576655086988502,1740481189.0053775,20.779980182647705,0.0,1740481189.005379,20.779980182647705,0.0,1740481189.0053802,20.779980182647705,0.0,1740481189.005381,20.779980182647705,0.0,1740481189.005382,20.779980182647705,0.9948705050175403,1740481189.005383,20.779980182647705,0.05129494982455851,1740481189.005384,20.779980182647705,0.08063693684177071,1740481189.005385,20.779980182647705,0.0,1740481189.0053859,20.779980182647705,0.9652237798356226,, +1740481189.025944,20.79998016357422,12.735145850395028,1740481189.025946,20.79998016357422,0.0,1740481189.0259478,20.79998016357422,0.017251829931227303,1740481189.02595,20.79998016357422,16.576655086988502,1740481189.025951,20.79998016357422,0.0,1740481189.0259526,20.79998016357422,0.0,1740481189.0259533,20.79998016357422,0.0,1740481189.0259542,20.79998016357422,0.0,1740481189.025955,20.79998016357422,0.9948705050175403,1740481189.0259562,20.79998016357422,0.05129494982455851,1740481189.025957,20.79998016357422,0.0809416750064762,1740481189.0259578,20.79998016357422,0.0,1740481189.025959,20.79998016357422,0.9652237798356226,, +1740481189.045534,20.819980144500732,12.735145850395028,1740481189.045536,20.819980144500732,0.0,1740481189.045539,20.819980144500732,0.017251829931227303,1740481189.0455408,20.819980144500732,16.576655086988502,1740481189.045542,20.819980144500732,0.0,1740481189.0455432,20.819980144500732,0.0,1740481189.0455441,20.819980144500732,0.0,1740481189.045545,20.819980144500732,0.0,1740481189.045546,20.819980144500732,0.9948705050175403,1740481189.045547,20.819980144500732,0.05129494982455851,1740481189.0455477,20.819980144500732,0.0809416750064762,1740481189.0455484,20.819980144500732,0.0,1740481189.0455496,20.819980144500732,0.9652237798356226,, +1740481189.064307,20.839980125427246,12.735145850395028,1740481189.0643086,20.839980125427246,0.0,1740481189.0643108,20.839980125427246,0.0,1740481189.064313,20.839980125427246,16.665593410066272,1740481189.064314,20.839980125427246,0.0,1740481189.0643148,20.839980125427246,0.0,1740481189.0643158,20.839980125427246,0.0,1740481189.064317,20.839980125427246,0.0,1740481189.0643177,20.839980125427246,0.9950627044163607,1740481189.0643187,20.839980125427246,0.0,1740481189.0643194,20.839980125427246,0.029838924580738113,1740481189.0643206,20.839980125427246,0.0,1740481189.0643213,20.839980125427246,0.9652237798356226,, +1740481189.0839179,20.85998010635376,12.735145850395028,1740481189.0839193,20.85998010635376,0.0,1740481189.0839217,20.85998010635376,0.0,1740481189.0839233,20.85998010635376,16.665593410066272,1740481189.0839245,20.85998010635376,0.0,1740481189.0839257,20.85998010635376,0.0,1740481189.0839267,20.85998010635376,0.0,1740481189.0839279,20.85998010635376,0.0,1740481189.0839286,20.85998010635376,0.9950627044163607,1740481189.0839293,20.85998010635376,0.0,1740481189.0839303,20.85998010635376,0.029838924580738113,1740481189.0839312,20.85998010635376,0.0,1740481189.0839324,20.85998010635376,0.9652237798356226,, +1740481189.11559,20.879980087280273,12.841367069776702,1740481189.1155927,20.879980087280273,0.0,1740481189.1155953,20.879980087280273,0.017260210888531566,1740481189.1155975,20.879980087280273,16.682874322055266,1740481189.115599,20.879980087280273,0.0,1740481189.1156003,20.879980087280273,0.0,1740481189.1156018,20.879980087280273,0.0,1740481189.1156027,20.879980087280273,0.0,1740481189.115604,20.879980087280273,0.9950627044163607,1740481189.1156049,20.879980087280273,0.04937295583635426,1740481189.115606,20.879980087280273,0.07919682506681527,1740481189.115607,20.879980087280273,0.0,1740481189.1156082,20.879980087280273,0.9652341303858534,, +1740481189.1242058,20.899980068206787,12.841367069776702,1740481189.1242085,20.899980068206787,0.0,1740481189.1242115,20.899980068206787,0.017260210888531566,1740481189.1242144,20.899980068206787,16.682874322055266,1740481189.1242158,20.899980068206787,0.0,1740481189.1242177,20.899980068206787,0.0,1740481189.1242194,20.899980068206787,0.0,1740481189.1242206,20.899980068206787,0.0,1740481189.124222,20.899980068206787,0.9950627044163607,1740481189.1242235,20.899980068206787,0.04937295583635426,1740481189.1242251,20.899980068206787,0.07920152986686158,1740481189.1242263,20.899980068206787,0.0,1740481189.1242275,20.899980068206787,0.9652341303858534,, +1740481189.1436598,20.9199800491333,12.841367069776702,1740481189.1436615,20.9199800491333,0.0,1740481189.143664,20.9199800491333,0.017260210888531566,1740481189.143666,20.9199800491333,16.682874322055266,1740481189.1436672,20.9199800491333,0.0,1740481189.1436687,20.9199800491333,0.0,1740481189.14367,20.9199800491333,0.0,1740481189.1436713,20.9199800491333,0.0,1740481189.1436725,20.9199800491333,0.9950627044163607,1740481189.1436749,20.9199800491333,0.04937295583635426,1740481189.1436765,20.9199800491333,0.07920152986686158,1740481189.1436777,20.9199800491333,0.0,1740481189.143679,20.9199800491333,0.9652341303858534,, +1740481189.1670263,20.939980030059814,12.841367069776702,1740481189.167028,20.939980030059814,0.0,1740481189.1670303,20.939980030059814,0.0,1740481189.167032,20.939980030059814,16.77183533054841,1740481189.1670332,20.939980030059814,0.0,1740481189.1670344,20.939980030059814,0.0,1740481189.1670353,20.939980030059814,0.0,1740481189.167036,20.939980030059814,0.0,1740481189.1670372,20.939980030059814,0.9950656429830341,1740481189.167038,20.939980030059814,0.0,1740481189.1670392,20.939980030059814,0.029831512597180754,1740481189.16704,20.939980030059814,0.0,1740481189.167041,20.939980030059814,0.9652341303858534,, +1740481189.184436,20.959980010986328,12.841367069776702,1740481189.1844378,20.959980010986328,0.0,1740481189.1844401,20.959980010986328,0.0,1740481189.184442,20.959980010986328,16.77183533054841,1740481189.184443,20.959980010986328,0.0,1740481189.1844442,20.959980010986328,0.0,1740481189.1844454,20.959980010986328,0.0,1740481189.1844466,20.959980010986328,0.0,1740481189.1844473,20.959980010986328,0.9950656429830341,1740481189.1844487,20.959980010986328,0.0,1740481189.1844494,20.959980010986328,0.029831512597180754,1740481189.1844506,20.959980010986328,0.0,1740481189.1844513,20.959980010986328,0.9652341303858534,, +1740481189.2057219,20.979979991912842,12.841367069776702,1740481189.2057245,20.979979991912842,0.0,1740481189.2057269,20.979979991912842,0.0,1740481189.2057292,20.979979991912842,16.77183533054841,1740481189.2057307,20.979979991912842,0.0,1740481189.2057319,20.979979991912842,0.0,1740481189.2057328,20.979979991912842,0.0,1740481189.2057338,20.979979991912842,0.0,1740481189.205735,20.979979991912842,0.9950656429830341,1740481189.205736,20.979979991912842,0.0,1740481189.205737,20.979979991912842,0.029831512597180754,1740481189.205738,20.979979991912842,0.0,1740481189.2057395,20.979979991912842,0.9652341303858534,, +1740481189.2235277,20.999979972839355,12.9476121592411,1740481189.22353,20.999979972839355,0.0,1740481189.2235324,20.999979972839355,0.017264140594695165,1740481189.2235346,20.999979972839355,16.78890974141172,1740481189.2235355,20.999979972839355,0.0,1740481189.223537,20.999979972839355,0.0,1740481189.223538,20.999979972839355,0.0,1740481189.2235389,20.999979972839355,0.0,1740481189.2235398,20.999979972839355,0.9950656429830341,1740481189.223541,20.999979972839355,0.0493435701697964,1740481189.223542,20.999979972839355,0.07931306806728594,1740481189.2235427,20.999979972839355,0.0,1740481189.223544,20.999979972839355,0.965139265520163,, +1740481189.24408,21.01997995376587,12.9476121592411,1740481189.244082,21.01997995376587,0.0,1740481189.244084,21.01997995376587,0.017264140594695165,1740481189.2440863,21.01997995376587,16.78890974141172,1740481189.2440872,21.01997995376587,0.0,1740481189.2440886,21.01997995376587,0.0,1740481189.2440896,21.01997995376587,0.0,1740481189.2440906,21.01997995376587,0.0,1740481189.2440915,21.01997995376587,0.9950656429830341,1740481189.244093,21.01997995376587,0.0493435701697964,1740481189.244094,21.01997995376587,0.07926994763266748,1740481189.2440946,21.01997995376587,0.0,1740481189.2440958,21.01997995376587,0.965139265520163,, +1740481189.2647705,21.039979934692383,12.9476121592411,1740481189.264773,21.039979934692383,0.0,1740481189.2647753,21.039979934692383,0.0,1740481189.2647774,21.039979934692383,16.877890690281426,1740481189.2647786,21.039979934692383,0.0,1740481189.2647798,21.039979934692383,0.0,1740481189.2647808,21.039979934692383,0.0,1740481189.2647824,21.039979934692383,0.0,1740481189.2647831,21.039979934692383,0.9950386776999025,1740481189.2647843,21.039979934692383,0.0,1740481189.264785,21.039979934692383,0.02989941217973946,1740481189.2647862,21.039979934692383,0.0,1740481189.264787,21.039979934692383,0.965139265520163,, +1740481189.2850077,21.059979915618896,12.9476121592411,1740481189.2850094,21.059979915618896,0.0,1740481189.2850118,21.059979915618896,0.0,1740481189.2850137,21.059979915618896,16.877890690281426,1740481189.2850153,21.059979915618896,0.0,1740481189.2850165,21.059979915618896,0.0,1740481189.2850175,21.059979915618896,0.0,1740481189.2850187,21.059979915618896,0.0,1740481189.2850196,21.059979915618896,0.9950386776999025,1740481189.2850206,21.059979915618896,0.0,1740481189.2850218,21.059979915618896,0.02989941217973946,1740481189.2850227,21.059979915618896,0.0,1740481189.2850237,21.059979915618896,0.965139265520163,, +1740481189.303421,21.07997989654541,12.9476121592411,1740481189.3034225,21.07997989654541,0.0,1740481189.3034246,21.07997989654541,0.0,1740481189.3034265,21.07997989654541,16.877890690281426,1740481189.3034277,21.07997989654541,0.0,1740481189.303429,21.07997989654541,0.0,1740481189.3034298,21.07997989654541,0.0,1740481189.3034308,21.07997989654541,0.0,1740481189.303432,21.07997989654541,0.9950386776999025,1740481189.303433,21.07997989654541,0.0,1740481189.303434,21.07997989654541,0.02989941217973946,1740481189.3034348,21.07997989654541,0.0,1740481189.3034358,21.07997989654541,0.965139265520163,, +1740481189.3236628,21.099979877471924,13.053773371091882,1740481189.3236644,21.099979877471924,0.0,1740481189.3236663,21.099979877471924,0.017250043552825316,1740481189.3236685,21.099979877471924,16.893003364864025,1740481189.3236692,21.099979877471924,0.0,1740481189.3236706,21.099979877471924,0.0,1740481189.3236716,21.099979877471924,0.0,1740481189.3236725,21.099979877471924,0.0,1740481189.3236735,21.099979877471924,0.9950386776999025,1740481189.3236744,21.099979877471924,0.04961322300093607,1740481189.3236756,21.099979877471924,0.0810670858041016,1740481189.3236763,21.099979877471924,0.0,1740481189.3236775,21.099979877471924,0.9640705810350507,, +1740481189.3445604,21.119979858398438,13.053773371091882,1740481189.3445654,21.119979858398438,0.0,1740481189.3445694,21.119979858398438,0.017250043552825316,1740481189.3445716,21.119979858398438,16.893003364864025,1740481189.3445733,21.119979858398438,0.0,1740481189.3445747,21.119979858398438,0.0,1740481189.3445776,21.119979858398438,0.0,1740481189.3445804,21.119979858398438,0.0,1740481189.3445818,21.119979858398438,0.9950386776999025,1740481189.344584,21.119979858398438,0.04961322300093607,1740481189.3445857,21.119979858398438,0.08058131966578785,1740481189.3445873,21.119979858398438,0.0,1740481189.3445888,21.119979858398438,0.9640705810350507,, +1740481189.3660145,21.13997983932495,13.053773371091882,1740481189.3660166,21.13997983932495,0.0,1740481189.3660188,21.13997983932495,0.0,1740481189.3660207,21.13997983932495,16.981914533161984,1740481189.3660216,21.13997983932495,0.0,1740481189.3660228,21.13997983932495,0.0,1740481189.366024,21.13997983932495,0.0,1740481189.366025,21.13997983932495,0.0,1740481189.366026,21.13997983932495,0.9947298283205174,1740481189.366027,21.13997983932495,0.0,1740481189.3660278,21.13997983932495,0.03065924728546665,1740481189.3660288,21.13997983932495,0.0,1740481189.3660297,21.13997983932495,0.9640705810350507,, +1740481189.3839371,21.159979820251465,13.053773371091882,1740481189.3839405,21.159979820251465,0.0,1740481189.3839447,21.159979820251465,0.0,1740481189.3839493,21.159979820251465,16.981914533161984,1740481189.3839514,21.159979820251465,0.0,1740481189.3839543,21.159979820251465,0.0,1740481189.3839562,21.159979820251465,0.0,1740481189.383958,21.159979820251465,0.0,1740481189.38396,21.159979820251465,0.9947298283205174,1740481189.3839622,21.159979820251465,0.0,1740481189.383964,21.159979820251465,0.03065924728546665,1740481189.383966,21.159979820251465,0.0,1740481189.383968,21.159979820251465,0.9640705810350507,, +1740481189.403632,21.17997980117798,13.053773371091882,1740481189.4036336,21.17997980117798,0.0,1740481189.4036362,21.17997980117798,0.0,1740481189.4036384,21.17997980117798,16.981914533161984,1740481189.4036396,21.17997980117798,0.0,1740481189.403641,21.17997980117798,0.0,1740481189.4036422,21.17997980117798,0.0,1740481189.4036431,21.17997980117798,0.0,1740481189.403644,21.17997980117798,0.9947298283205174,1740481189.4036455,21.17997980117798,0.0,1740481189.4036465,21.17997980117798,0.03065924728546665,1740481189.4036472,21.17997980117798,0.0,1740481189.4036481,21.17997980117798,0.9640705810350507,, +1740481189.4237146,21.199979782104492,13.053773371091882,1740481189.4237163,21.199979782104492,0.0,1740481189.4237185,21.199979782104492,0.0,1740481189.4237201,21.199979782104492,16.981914533161984,1740481189.4237216,21.199979782104492,0.0,1740481189.4237225,21.199979782104492,0.0,1740481189.4237237,21.199979782104492,0.0,1740481189.4237247,21.199979782104492,0.0,1740481189.4237256,21.199979782104492,0.9947298283205174,1740481189.4237266,21.199979782104492,0.0,1740481189.4237273,21.199979782104492,0.03065924728546665,1740481189.4237285,21.199979782104492,0.0,1740481189.4237292,21.199979782104492,0.9640705810350507,, +1740481189.443724,21.219979763031006,13.15984403541566,1740481189.4437258,21.219979763031006,0.0,1740481189.443728,21.219979763031006,0.017229980900879197,1740481189.4437304,21.219979763031006,16.99725004419719,1740481189.4437315,21.219979763031006,0.0,1740481189.4437327,21.219979763031006,0.0,1740481189.4437337,21.219979763031006,0.0,1740481189.4437346,21.219979763031006,0.0,1740481189.4437354,21.219979763031006,0.9947298283205174,1740481189.4437368,21.219979763031006,0.05270171679496394,1740481189.4437375,21.219979763031006,0.08473876075698905,1740481189.4437387,21.219979763031006,0.0,1740481189.4437394,21.219979763031006,0.9631233461022151,, +1740481189.464508,21.23997974395752,13.15984403541566,1740481189.4645102,21.23997974395752,0.0,1740481189.4645123,21.23997974395752,0.0,1740481189.4645143,21.23997974395752,17.08609072762009,1740481189.4645152,21.23997974395752,0.0,1740481189.4645166,21.23997974395752,0.0,1740481189.4645176,21.23997974395752,0.0,1740481189.4645185,21.23997974395752,0.0,1740481189.4645197,21.23997974395752,0.9944482821097547,1740481189.4645207,21.23997974395752,0.0,1740481189.4645216,21.23997974395752,0.031324936007539605,1740481189.4645226,21.23997974395752,0.0,1740481189.4645233,21.23997974395752,0.9631233461022151,, +1740481189.4859915,21.259979724884033,13.15984403541566,1740481189.4859934,21.259979724884033,0.0,1740481189.4859958,21.259979724884033,0.0,1740481189.4859982,21.259979724884033,17.08609072762009,1740481189.4859993,21.259979724884033,0.0,1740481189.486001,21.259979724884033,0.0,1740481189.486002,21.259979724884033,0.0,1740481189.486003,21.259979724884033,0.0,1740481189.4860039,21.259979724884033,0.9944482821097547,1740481189.486005,21.259979724884033,0.0,1740481189.4860058,21.259979724884033,0.031324936007539605,1740481189.4860067,21.259979724884033,0.0,1740481189.4860077,21.259979724884033,0.9631233461022151,, +1740481189.5042524,21.279979705810547,13.15984403541566,1740481189.5042548,21.279979705810547,0.0,1740481189.504257,21.279979705810547,0.0,1740481189.504259,21.279979705810547,17.08609072762009,1740481189.50426,21.279979705810547,0.0,1740481189.5042615,21.279979705810547,0.0,1740481189.5042627,21.279979705810547,0.0,1740481189.5042636,21.279979705810547,0.0,1740481189.5042646,21.279979705810547,0.9944482821097547,1740481189.504266,21.279979705810547,0.0,1740481189.5042667,21.279979705810547,0.031324936007539605,1740481189.5042677,21.279979705810547,0.0,1740481189.5042691,21.279979705810547,0.9631233461022151,, +1740481189.5237432,21.29997968673706,13.15984403541566,1740481189.523745,21.29997968673706,0.0,1740481189.5237474,21.29997968673706,0.0,1740481189.5237627,21.29997968673706,17.08609072762009,1740481189.5237641,21.29997968673706,0.0,1740481189.5237665,21.29997968673706,0.0,1740481189.5237675,21.29997968673706,0.0,1740481189.5237687,21.29997968673706,0.0,1740481189.5237694,21.29997968673706,0.9944482821097547,1740481189.5237703,21.29997968673706,0.0,1740481189.5237713,21.29997968673706,0.031324936007539605,1740481189.5237725,21.29997968673706,0.0,1740481189.5237732,21.29997968673706,0.9631233461022151,, +1740481189.5438273,21.319979667663574,13.265734214764212,1740481189.5438292,21.319979667663574,0.0,1740481189.5438323,21.319979667663574,0.01719579471695431,1740481189.5438354,21.319979667663574,17.09967355063116,1740481189.5438366,21.319979667663574,0.0,1740481189.5438385,21.319979667663574,0.0,1740481189.5438397,21.319979667663574,0.0,1740481189.543842,21.319979667663574,0.0,1740481189.5438437,21.319979667663574,0.9944482821097547,1740481189.543846,21.319979667663574,0.055517178902591,1740481189.5438476,21.319979667663574,0.0894697314793209,1740481189.5438492,21.319979667663574,0.0,1740481189.543851,21.319979667663574,0.961316860249272,, +1740481189.5651782,21.339979648590088,13.265734214764212,1740481189.5651796,21.339979648590088,0.0,1740481189.565182,21.339979648590088,0.0,1740481189.565184,21.339979648590088,17.188367935262754,1740481189.5651848,21.339979648590088,0.0,1740481189.565186,21.339979648590088,0.0,1740481189.565187,21.339979648590088,0.0,1740481189.5651882,21.339979648590088,0.0,1740481189.5651891,21.339979648590088,0.9938910325900246,1740481189.56519,21.339979648590088,0.0,1740481189.5651913,21.339979648590088,0.03257417234075266,1740481189.5651922,21.339979648590088,0.0,1740481189.565193,21.339979648590088,0.961316860249272,, +1740481189.586168,21.3599796295166,13.265734214764212,1740481189.5861704,21.3599796295166,0.0,1740481189.5861726,21.3599796295166,0.0,1740481189.5861747,21.3599796295166,17.188367935262754,1740481189.5861757,21.3599796295166,0.0,1740481189.586177,21.3599796295166,0.0,1740481189.586178,21.3599796295166,0.0,1740481189.586179,21.3599796295166,0.0,1740481189.5861802,21.3599796295166,0.9938910325900246,1740481189.5861812,21.3599796295166,0.0,1740481189.586182,21.3599796295166,0.03257417234075266,1740481189.586183,21.3599796295166,0.0,1740481189.5861843,21.3599796295166,0.961316860249272,, +1740481189.6054463,21.379979610443115,13.265734214764212,1740481189.6054487,21.379979610443115,0.0,1740481189.605451,21.379979610443115,0.0,1740481189.6054533,21.379979610443115,17.188367935262754,1740481189.6054544,21.379979610443115,0.0,1740481189.6054559,21.379979610443115,0.0,1740481189.605457,21.379979610443115,0.0,1740481189.6054583,21.379979610443115,0.0,1740481189.6054592,21.379979610443115,0.9938910325900246,1740481189.6054602,21.379979610443115,0.0,1740481189.6054614,21.379979610443115,0.03257417234075266,1740481189.6054623,21.379979610443115,0.0,1740481189.6054633,21.379979610443115,0.961316860249272,, +1740481189.6240041,21.39997959136963,13.265734214764212,1740481189.624006,21.39997959136963,0.0,1740481189.6240084,21.39997959136963,0.0,1740481189.6240106,21.39997959136963,17.188367935262754,1740481189.6240115,21.39997959136963,0.0,1740481189.6240127,21.39997959136963,0.0,1740481189.624014,21.39997959136963,0.0,1740481189.6240149,21.39997959136963,0.0,1740481189.6240156,21.39997959136963,0.9938910325900246,1740481189.6240165,21.39997959136963,0.0,1740481189.6240177,21.39997959136963,0.03257417234075266,1740481189.6240187,21.39997959136963,0.0,1740481189.6240196,21.39997959136963,0.961316860249272,, +1740481189.644828,21.419979572296143,13.265734214764212,1740481189.6448326,21.419979572296143,0.0,1740481189.6448376,21.419979572296143,0.0,1740481189.644843,21.419979572296143,17.188367935262754,1740481189.644845,21.419979572296143,0.0,1740481189.6448486,21.419979572296143,0.0,1740481189.6448507,21.419979572296143,0.0,1740481189.6448526,21.419979572296143,0.0,1740481189.6448548,21.419979572296143,0.9938910325900246,1740481189.644857,21.419979572296143,0.0,1740481189.6448588,21.419979572296143,0.03257417234075266,1740481189.644861,21.419979572296143,0.0,1740481189.644863,21.419979572296143,0.961316860249272,, +1740481189.6661403,21.439979553222656,13.371451103240858,1740481189.6661422,21.439979553222656,0.0,1740481189.6661444,21.439979553222656,0.0,1740481189.6661463,21.439979553222656,17.29092326334286,1740481189.6661472,21.439979553222656,0.0,1740481189.6661487,21.439979553222656,0.0,1740481189.6661496,21.439979553222656,0.0,1740481189.6661503,21.439979553222656,0.0,1740481189.6661515,21.439979553222656,0.9933815470979754,1740481189.6661522,21.439979553222656,0.0661845290203833,1740481189.6661532,21.439979553222656,0.10031694867094126,1740481189.666154,21.439979553222656,0.0,1740481189.666155,21.439979553222656,0.9597360800510026,, +1740481189.6836426,21.45997953414917,13.371451103240858,1740481189.6836455,21.45997953414917,0.0,1740481189.683648,21.45997953414917,0.0,1740481189.6836503,21.45997953414917,17.29092326334286,1740481189.6836512,21.45997953414917,0.0,1740481189.6836529,21.45997953414917,0.0,1740481189.6836538,21.45997953414917,0.0,1740481189.6836553,21.45997953414917,0.0,1740481189.6836565,21.45997953414917,0.9933815470979754,1740481189.6836572,21.45997953414917,0.0661845290203833,1740481189.6836586,21.45997953414917,0.0998299960673561,1740481189.6836596,21.45997953414917,0.0,1740481189.6836603,21.45997953414917,0.9597360800510026,, +1740481189.7035868,21.479979515075684,13.371451103240858,1740481189.70359,21.479979515075684,0.0,1740481189.7035923,21.479979515075684,0.0,1740481189.7035944,21.479979515075684,17.29092326334286,1740481189.7035956,21.479979515075684,0.0,1740481189.7035968,21.479979515075684,0.0,1740481189.7035983,21.479979515075684,0.0,1740481189.7035997,21.479979515075684,0.0,1740481189.7036006,21.479979515075684,0.9933815470979754,1740481189.703602,21.479979515075684,0.0661845290203833,1740481189.7036033,21.479979515075684,0.0998299960673561,1740481189.7036042,21.479979515075684,0.0,1740481189.7036052,21.479979515075684,0.9597360800510026,, +1740481189.7255397,21.499979496002197,13.371451103240858,1740481189.7255445,21.499979496002197,0.0,1740481189.725549,21.499979496002197,0.0,1740481189.7255526,21.499979496002197,17.29092326334286,1740481189.7255547,21.499979496002197,0.0,1740481189.7255569,21.499979496002197,0.0,1740481189.725559,21.499979496002197,0.0,1740481189.7255604,21.499979496002197,0.0,1740481189.7255619,21.499979496002197,0.9933815470979754,1740481189.7255647,21.499979496002197,0.0661845290203833,1740481189.7255657,21.499979496002197,0.0998299960673561,1740481189.7255673,21.499979496002197,0.0,1740481189.7255695,21.499979496002197,0.9597360800510026,, +1740481189.7441168,21.51997947692871,13.371451103240858,1740481189.7441204,21.51997947692871,0.0,1740481189.7441232,21.51997947692871,0.0,1740481189.7441256,21.51997947692871,17.29092326334286,1740481189.7441278,21.51997947692871,0.0,1740481189.7441294,21.51997947692871,0.0,1740481189.744131,21.51997947692871,0.0,1740481189.7441328,21.51997947692871,0.0,1740481189.744134,21.51997947692871,0.9933815470979754,1740481189.7441351,21.51997947692871,0.0661845290203833,1740481189.7441363,21.51997947692871,0.0998299960673561,1740481189.7441373,21.51997947692871,0.0,1740481189.7441382,21.51997947692871,0.9597360800510026,, +1740481189.7660928,21.539979457855225,13.477189842202876,1740481189.766113,21.539979457855225,0.0,1740481189.7661178,21.539979457855225,0.0,1740481189.7661204,21.539979457855225,17.404692234590463,1740481189.766122,21.539979457855225,0.0,1740481189.7661247,21.539979457855225,0.0,1740481189.7661266,21.539979457855225,0.0,1740481189.7661278,21.539979457855225,0.0,1740481189.7661297,21.539979457855225,0.9946357163517343,1740481189.7661319,21.539979457855225,0.05364283648261803,1740481189.766134,21.539979457855225,0.08327237958506878,1740481189.7661352,21.539979457855225,0.0,1740481189.7661366,21.539979457855225,0.9637511961937933,, +1740481189.7846231,21.55997943878174,13.477189842202876,1740481189.784625,21.55997943878174,0.0,1740481189.7846274,21.55997943878174,0.0,1740481189.7846296,21.55997943878174,17.404692234590463,1740481189.7846305,21.55997943878174,0.0,1740481189.784632,21.55997943878174,0.0,1740481189.7846332,21.55997943878174,0.0,1740481189.7846339,21.55997943878174,0.0,1740481189.7846348,21.55997943878174,0.9946357163517343,1740481189.7846482,21.55997943878174,0.05364283648261803,1740481189.7846494,21.55997943878174,0.08452735664055899,1740481189.7846506,21.55997943878174,0.0,1740481189.7846515,21.55997943878174,0.9637511961937933,, +1740481189.8058102,21.579979419708252,13.477189842202876,1740481189.805814,21.579979419708252,0.0,1740481189.8058188,21.579979419708252,0.0,1740481189.8058221,21.579979419708252,17.404692234590463,1740481189.805824,21.579979419708252,0.0,1740481189.8058267,21.579979419708252,0.0,1740481189.8058286,21.579979419708252,0.0,1740481189.8058312,21.579979419708252,0.0,1740481189.8058326,21.579979419708252,0.9946357163517343,1740481189.8058355,21.579979419708252,0.05364283648261803,1740481189.805837,21.579979419708252,0.08452735664055899,1740481189.8058388,21.579979419708252,0.0,1740481189.805841,21.579979419708252,0.9637511961937933,, +1740481189.8239365,21.599979400634766,13.477189842202876,1740481189.8239386,21.599979400634766,0.0,1740481189.8239408,21.599979400634766,0.0,1740481189.823943,21.599979400634766,17.404692234590463,1740481189.8239439,21.599979400634766,0.0,1740481189.823945,21.599979400634766,0.0,1740481189.823946,21.599979400634766,0.0,1740481189.823947,21.599979400634766,0.0,1740481189.8239481,21.599979400634766,0.9946357163517343,1740481189.8239493,21.599979400634766,0.05364283648261803,1740481189.8239505,21.599979400634766,0.08452735664055899,1740481189.8239512,21.599979400634766,0.0,1740481189.8239524,21.599979400634766,0.9637511961937933,, +1740481189.8446226,21.61997938156128,13.477189842202876,1740481189.8446257,21.61997938156128,0.0,1740481189.8446288,21.61997938156128,0.0,1740481189.8446314,21.61997938156128,17.404692234590463,1740481189.844633,21.61997938156128,0.0,1740481189.8446355,21.61997938156128,0.0,1740481189.8446367,21.61997938156128,0.0,1740481189.8446379,21.61997938156128,0.0,1740481189.8446393,21.61997938156128,0.9946357163517343,1740481189.8446412,21.61997938156128,0.05364283648261803,1740481189.844643,21.61997938156128,0.08452735664055899,1740481189.8446445,21.61997938156128,0.0,1740481189.8446467,21.61997938156128,0.9637511961937933,, +1740481189.8651388,21.639979362487793,13.477189842202876,1740481189.8651404,21.639979362487793,0.0,1740481189.8651426,21.639979362487793,0.0,1740481189.8651443,21.639979362487793,17.404692234590463,1740481189.8651454,21.639979362487793,0.0,1740481189.8651464,21.639979362487793,0.0,1740481189.8651474,21.639979362487793,0.0,1740481189.8651488,21.639979362487793,0.0,1740481189.8651495,21.639979362487793,0.9946357163517343,1740481189.8651505,21.639979362487793,0.05364283648261803,1740481189.8651512,21.639979362487793,0.08452735664055899,1740481189.8651524,21.639979362487793,0.0,1740481189.865153,21.639979362487793,0.9637511961937933,, +1740481189.8849804,21.659979343414307,13.583348571499474,1740481189.8849823,21.659979343414307,0.0,1740481189.8849843,21.659979343414307,0.017242654568692173,1740481189.8849864,21.659979343414307,17.42781580206221,1740481189.8849874,21.659979343414307,0.0,1740481189.8849888,21.659979343414307,0.0,1740481189.8849897,21.659979343414307,0.0,1740481189.8849907,21.659979343414307,0.0,1740481189.8849916,21.659979343414307,0.9999999999999961,1740481189.8849928,21.659979343414307,5.551115123125783e-15,1740481189.8849938,21.659979343414307,0.03441008804026101,1740481189.8849945,21.659979343414307,0.0,1740481189.8849957,21.659979343414307,0.9666916526453214,, +1740481189.9075475,21.67997932434082,13.583348571499474,1740481189.9075513,21.67997932434082,0.0,1740481189.9075563,21.67997932434082,0.017242654568692173,1740481189.90756,21.67997932434082,17.42781580206221,1740481189.907562,21.67997932434082,0.0,1740481189.9075649,21.67997932434082,0.0,1740481189.9075665,21.67997932434082,0.0,1740481189.9075685,21.67997932434082,0.0,1740481189.9075882,21.67997932434082,0.9999999999999961,1740481189.9075942,21.67997932434082,5.551115123125783e-15,1740481189.907596,21.67997932434082,0.033308347354680246,1740481189.907598,21.67997932434082,0.0,1740481189.9076002,21.67997932434082,0.9666916526453214,, +1740481189.9240012,21.699979305267334,13.583348571499474,1740481189.9240031,21.699979305267334,0.0,1740481189.924005,21.699979305267334,0.017242654568692173,1740481189.924007,21.699979305267334,17.42781580206221,1740481189.924008,21.699979305267334,0.0,1740481189.9240093,21.699979305267334,0.0,1740481189.9240103,21.699979305267334,0.0,1740481189.924011,21.699979305267334,0.0,1740481189.924012,21.699979305267334,0.9999999999999961,1740481189.9240131,21.699979305267334,5.551115123125783e-15,1740481189.924014,21.699979305267334,0.033308347354680246,1740481189.9240148,21.699979305267334,0.0,1740481189.9240158,21.699979305267334,0.9666916526453214,, +1740481189.9453275,21.719979286193848,13.583348571499474,1740481189.9453301,21.719979286193848,0.0,1740481189.9453335,21.719979286193848,0.017242654568692173,1740481189.9453359,21.719979286193848,17.42781580206221,1740481189.945337,21.719979286193848,0.0,1740481189.945339,21.719979286193848,0.0,1740481189.9453413,21.719979286193848,0.0,1740481189.9453425,21.719979286193848,0.0,1740481189.945344,21.719979286193848,0.9999999999999961,1740481189.9453459,21.719979286193848,5.551115123125783e-15,1740481189.9453468,21.719979286193848,0.033308347354680246,1740481189.9453483,21.719979286193848,0.0,1740481189.9453495,21.719979286193848,0.9666916526453214,, +1740481189.964285,21.73997926712036,13.583348571499474,1740481189.9642868,21.73997926712036,0.0,1740481189.964289,21.73997926712036,0.0,1740481189.964291,21.73997926712036,17.516731876790118,1740481189.964292,21.73997926712036,0.0,1740481189.9642935,21.73997926712036,0.0,1740481189.9642944,21.73997926712036,0.0,1740481189.9642951,21.73997926712036,0.0,1740481189.964296,21.73997926712036,0.9954707056570888,1740481189.9642973,21.73997926712036,0.0,1740481189.964298,21.73997926712036,0.02877905301176742,1740481189.964299,21.73997926712036,0.0,1740481189.9643,21.73997926712036,0.9666916526453214,, +1740481189.984705,21.759979248046875,13.689603364946514,1740481189.984707,21.759979248046875,0.0,1740481189.9847097,21.759979248046875,0.017272745807376158,1740481189.984712,21.759979248046875,17.529541514583364,1740481189.9847133,21.759979248046875,0.0,1740481189.9847147,21.759979248046875,0.0,1740481189.984716,21.759979248046875,0.0,1740481189.9847171,21.759979248046875,0.0,1740481189.984718,21.759979248046875,0.9954707056570888,1740481189.9847193,21.759979248046875,0.04529294342924928,1740481189.9847205,21.759979248046875,0.07731789414591914,1740481189.9847214,21.759979248046875,0.0,1740481189.9847224,21.759979248046875,0.9644600986382565,, +1740481190.0046217,21.77997922897339,13.689603364946514,1740481190.0046244,21.77997922897339,0.0,1740481190.004627,21.77997922897339,0.017272745807376158,1740481190.004629,21.77997922897339,17.529541514583364,1740481190.0046303,21.77997922897339,0.0,1740481190.0046318,21.77997922897339,0.0,1740481190.0046332,21.77997922897339,0.0,1740481190.0046341,21.77997922897339,0.0,1740481190.004635,21.77997922897339,0.9954707056570888,1740481190.004636,21.77997922897339,0.04529294342924928,1740481190.0046372,21.77997922897339,0.07630355044808157,1740481190.0046382,21.77997922897339,0.0,1740481190.0046394,21.77997922897339,0.9644600986382565,, +1740481190.0240774,21.799979209899902,13.689603364946514,1740481190.0240788,21.799979209899902,0.0,1740481190.0240812,21.799979209899902,0.017272745807376158,1740481190.0240831,21.799979209899902,17.529541514583364,1740481190.0240843,21.799979209899902,0.0,1740481190.0240858,21.799979209899902,0.0,1740481190.024087,21.799979209899902,0.0,1740481190.024088,21.799979209899902,0.0,1740481190.0240889,21.799979209899902,0.9954707056570888,1740481190.0240898,21.799979209899902,0.04529294342924928,1740481190.0240905,21.799979209899902,0.07630355044808157,1740481190.0240917,21.799979209899902,0.0,1740481190.0240924,21.799979209899902,0.9644600986382565,, +1740481190.0446575,21.819979190826416,13.689603364946514,1740481190.0446591,21.819979190826416,0.0,1740481190.0446715,21.819979190826416,0.017272745807376158,1740481190.0446742,21.819979190826416,17.529541514583364,1740481190.044675,21.819979190826416,0.0,1740481190.0446765,21.819979190826416,0.0,1740481190.044678,21.819979190826416,0.0,1740481190.0446787,21.819979190826416,0.0,1740481190.0446796,21.819979190826416,0.9954707056570888,1740481190.0446806,21.819979190826416,0.04529294342924928,1740481190.0446818,21.819979190826416,0.07630355044808157,1740481190.0446827,21.819979190826416,0.0,1740481190.0446837,21.819979190826416,0.9644600986382565,, +1740481190.0646343,21.83997917175293,13.689603364946514,1740481190.0646362,21.83997917175293,0.0,1740481190.0646381,21.83997917175293,0.0,1740481190.0646403,21.83997917175293,17.618523562223025,1740481190.0646412,21.83997917175293,0.0,1740481190.0646427,21.83997917175293,0.0,1740481190.0646436,21.83997917175293,0.0,1740481190.0646443,21.83997917175293,0.0,1740481190.0646453,21.83997917175293,0.9948434787591004,1740481190.0646465,21.83997917175293,0.0,1740481190.0646474,21.83997917175293,0.03038338012084385,1740481190.0646484,21.83997917175293,0.0,1740481190.0646496,21.83997917175293,0.9644600986382565,, +1740481190.084358,21.859979152679443,13.689603364946514,1740481190.08436,21.859979152679443,0.0,1740481190.0843623,21.859979152679443,0.0,1740481190.0843642,21.859979152679443,17.618523562223025,1740481190.0843656,21.859979152679443,0.0,1740481190.0843668,21.859979152679443,0.0,1740481190.084368,21.859979152679443,0.0,1740481190.0843692,21.859979152679443,0.0,1740481190.0843701,21.859979152679443,0.9948434787591004,1740481190.0843716,21.859979152679443,0.0,1740481190.0843728,21.859979152679443,0.03038338012084385,1740481190.0843737,21.859979152679443,0.0,1740481190.0843747,21.859979152679443,0.9644600986382565,, +1740481190.104202,21.879979133605957,13.795785192993907,1740481190.1042035,21.879979133605957,0.0,1740481190.1042056,21.879979133605957,0.01725000882439215,1740481190.1042075,21.879979133605957,17.637177608647193,1740481190.1042087,21.879979133605957,0.0,1740481190.10421,21.879979133605957,0.0,1740481190.1042109,21.879979133605957,0.0,1740481190.104212,21.879979133605957,0.0,1740481190.104213,21.879979133605957,0.9948434787591004,1740481190.104214,21.879979133605957,0.05156521240895717,1740481190.1042154,21.879979133605957,0.08092747397110452,1740481190.104216,21.879979133605957,0.0,1740481190.1042168,21.879979133605957,0.9651621174381423,, +1740481190.123631,21.89997911453247,13.795785192993907,1740481190.123633,21.89997911453247,0.0,1740481190.1236353,21.89997911453247,0.01725000882439215,1740481190.1236372,21.89997911453247,17.637177608647193,1740481190.1236382,21.89997911453247,0.0,1740481190.1236396,21.89997911453247,0.0,1740481190.1236405,21.89997911453247,0.0,1740481190.1236415,21.89997911453247,0.0,1740481190.1236424,21.89997911453247,0.9948434787591004,1740481190.1236436,21.89997911453247,0.05156521240895717,1740481190.1236444,21.89997911453247,0.08124657372991528,1740481190.1236455,21.89997911453247,0.0,1740481190.1236463,21.89997911453247,0.9651621174381423,, +1740481190.1464427,21.919979095458984,13.795785192993907,1740481190.1464448,21.919979095458984,0.0,1740481190.146447,21.919979095458984,0.01725000882439215,1740481190.1464489,21.919979095458984,17.637177608647193,1740481190.1464498,21.919979095458984,0.0,1740481190.1464512,21.919979095458984,0.0,1740481190.1464522,21.919979095458984,0.0,1740481190.1464531,21.919979095458984,0.0,1740481190.1464546,21.919979095458984,0.9948434787591004,1740481190.1464553,21.919979095458984,0.05156521240895717,1740481190.1464658,21.919979095458984,0.08124657372991528,1740481190.1464694,21.919979095458984,0.0,1740481190.1464703,21.919979095458984,0.9651621174381423,, +1740481190.1681745,21.939979076385498,13.795785192993907,1740481190.168177,21.939979076385498,0.0,1740481190.16818,21.939979076385498,0.0,1740481190.168183,21.939979076385498,17.726109427870192,1740481190.1681845,21.939979076385498,0.0,1740481190.1681864,21.939979076385498,0.0,1740481190.1681879,21.939979076385498,0.0,1740481190.1681898,21.939979076385498,0.0,1740481190.168191,21.939979076385498,0.9950451800626208,1740481190.1681926,21.939979076385498,0.0,1740481190.1681938,21.939979076385498,0.029883062624478485,1740481190.168195,21.939979076385498,0.0,1740481190.1681964,21.939979076385498,0.9651621174381423,, +1740481190.1834373,21.95997905731201,13.795785192993907,1740481190.1834388,21.95997905731201,0.0,1740481190.1834412,21.95997905731201,0.0,1740481190.1834433,21.95997905731201,17.726109427870192,1740481190.1834445,21.95997905731201,0.0,1740481190.1834457,21.95997905731201,0.0,1740481190.183447,21.95997905731201,0.0,1740481190.1834478,21.95997905731201,0.0,1740481190.1834486,21.95997905731201,0.9950451800626208,1740481190.1834497,21.95997905731201,0.0,1740481190.183451,21.95997905731201,0.029883062624478485,1740481190.183452,21.95997905731201,0.0,1740481190.1834528,21.95997905731201,0.9651621174381423,, +1740481190.2235546,21.99997901916504,13.902000907770052,1740481190.2235563,21.99997901916504,0.0,1740481190.2235587,21.99997901916504,0.01725901246923722,1740481190.2235608,21.99997901916504,17.7434307735628,1740481190.2235618,21.99997901916504,0.0,1740481190.223575,21.99997901916504,0.0,1740481190.223576,21.99997901916504,0.0,1740481190.223577,21.99997901916504,0.0,1740481190.2235782,21.99997901916504,0.9950451800626208,1740481190.2235792,21.99997901916504,0.04954819937392996,1740481190.22358,21.99997901916504,0.07938592873153628,1740481190.2235808,21.99997901916504,0.0,1740481190.2235818,21.99997901916504,0.9651932840498285,, +1740481190.2437959,22.019979000091553,13.902000907770052,1740481190.243798,22.019979000091553,0.0,1740481190.2438,22.019979000091553,0.01725901246923722,1740481190.2438018,22.019979000091553,17.7434307735628,1740481190.2438028,22.019979000091553,0.0,1740481190.2438042,22.019979000091553,0.0,1740481190.2438052,22.019979000091553,0.0,1740481190.2438061,22.019979000091553,0.0,1740481190.2438073,22.019979000091553,0.9950451800626208,1740481190.2438083,22.019979000091553,0.04954819937392996,1740481190.243809,22.019979000091553,0.07940009538672221,1740481190.24381,22.019979000091553,0.0,1740481190.2438111,22.019979000091553,0.9651932840498285,, +1740481190.263778,22.039978981018066,13.902000907770052,1740481190.2637799,22.039978981018066,0.0,1740481190.2637818,22.039978981018066,0.0,1740481190.263784,22.039978981018066,17.83238747586971,1740481190.263785,22.039978981018066,0.0,1740481190.2637863,22.039978981018066,0.0,1740481190.2637873,22.039978981018066,0.0,1740481190.263788,22.039978981018066,0.0,1740481190.263789,22.039978981018066,0.9950540414435072,1740481190.2637904,22.039978981018066,0.0,1740481190.2637913,22.039978981018066,0.02986075739367866,1740481190.263792,22.039978981018066,0.0,1740481190.2638054,22.039978981018066,0.9651932840498285,, +1740481190.2846308,22.05997896194458,13.902000907770052,1740481190.2846332,22.05997896194458,0.0,1740481190.284635,22.05997896194458,0.0,1740481190.2846372,22.05997896194458,17.83238747586971,1740481190.2846382,22.05997896194458,0.0,1740481190.2846396,22.05997896194458,0.0,1740481190.2846408,22.05997896194458,0.0,1740481190.2846417,22.05997896194458,0.0,1740481190.2846425,22.05997896194458,0.9950540414435072,1740481190.284644,22.05997896194458,0.0,1740481190.2846448,22.05997896194458,0.02986075739367866,1740481190.2846456,22.05997896194458,0.0,1740481190.2846467,22.05997896194458,0.9651932840498285,, +1740481190.3062813,22.079978942871094,13.902000907770052,1740481190.3062854,22.079978942871094,0.0,1740481190.3062892,22.079978942871094,0.0,1740481190.306308,22.079978942871094,17.83238747586971,1740481190.306311,22.079978942871094,0.0,1740481190.306314,22.079978942871094,0.0,1740481190.3063157,22.079978942871094,0.0,1740481190.3063173,22.079978942871094,0.0,1740481190.3063185,22.079978942871094,0.9950540414435072,1740481190.3063207,22.079978942871094,0.0,1740481190.306322,22.079978942871094,0.02986075739367866,1740481190.3063235,22.079978942871094,0.0,1740481190.306325,22.079978942871094,0.9651932840498285,, +1740481190.3237355,22.099978923797607,14.008148623171483,1740481190.3237371,22.099978923797607,0.0,1740481190.323739,22.099978923797607,0.01724811683925277,1740481190.3237412,22.099978923797607,17.84750505335072,1740481190.3237422,22.099978923797607,0.0,1740481190.3237438,22.099978923797607,0.0,1740481190.3237445,22.099978923797607,0.0,1740481190.3237457,22.099978923797607,0.0,1740481190.323747,22.099978923797607,0.9950540414435072,1740481190.3237476,22.099978923797607,0.049459585564889386,1740481190.3237486,22.099978923797607,0.08086982658998151,1740481190.3237493,22.099978923797607,0.0,1740481190.3237505,22.099978923797607,0.9641280143707072,, +1740481190.3435235,22.11997890472412,14.008148623171483,1740481190.3435254,22.11997890472412,0.0,1740481190.3435273,22.11997890472412,0.01724811683925277,1740481190.3435295,22.11997890472412,17.84750505335072,1740481190.3435302,22.11997890472412,0.0,1740481190.3435316,22.11997890472412,0.0,1740481190.3435326,22.11997890472412,0.0,1740481190.3435333,22.11997890472412,0.0,1740481190.343534,22.11997890472412,0.9950540414435072,1740481190.3435352,22.11997890472412,0.049459585564889386,1740481190.3435361,22.11997890472412,0.0803856126376894,1740481190.343537,22.11997890472412,0.0,1740481190.3435378,22.11997890472412,0.9641280143707072,, +1740481190.3644657,22.139978885650635,14.008148623171483,1740481190.3644674,22.139978885650635,0.0,1740481190.3644698,22.139978885650635,0.0,1740481190.3644714,22.139978885650635,17.9364046519129,1740481190.3644729,22.139978885650635,0.0,1740481190.3644738,22.139978885650635,0.0,1740481190.3644748,22.139978885650635,0.0,1740481190.364476,22.139978885650635,0.0,1740481190.3644767,22.139978885650635,0.9947466636397301,1740481190.3644776,22.139978885650635,0.0,1740481190.3644783,22.139978885650635,0.030618649269022913,1740481190.3644795,22.139978885650635,0.0,1740481190.3644922,22.139978885650635,0.9641280143707072,, +1740481190.3834224,22.15997886657715,14.008148623171483,1740481190.3834243,22.15997886657715,0.0,1740481190.3834271,22.15997886657715,0.0,1740481190.3834293,22.15997886657715,17.9364046519129,1740481190.3834305,22.15997886657715,0.0,1740481190.3834317,22.15997886657715,0.0,1740481190.3834326,22.15997886657715,0.0,1740481190.3834336,22.15997886657715,0.0,1740481190.3834345,22.15997886657715,0.9947466636397301,1740481190.3834355,22.15997886657715,0.0,1740481190.3834362,22.15997886657715,0.030618649269022913,1740481190.3834372,22.15997886657715,0.0,1740481190.383438,22.15997886657715,0.9641280143707072,, +1740481190.403528,22.169978857040405,14.008148623171483,1740481190.4035296,22.169978857040405,0.0,1740481190.4035323,22.169978857040405,0.0,1740481190.403535,22.169978857040405,17.9364046519129,1740481190.403536,22.169978857040405,0.0,1740481190.4035375,22.169978857040405,0.0,1740481190.4035387,22.169978857040405,0.0,1740481190.4035397,22.169978857040405,0.0,1740481190.4035408,22.169978857040405,0.9947466636397301,1740481190.403542,22.169978857040405,0.0,1740481190.4035428,22.169978857040405,0.030618649269022913,1740481190.4035437,22.169978857040405,0.0,1740481190.403545,22.169978857040405,0.9641280143707072,, +1740481190.4258456,22.199978828430176,14.11420417619556,1740481190.4258473,22.199978828430176,0.0,1740481190.42585,22.199978828430176,0.017227817808503663,1740481190.4258518,22.199978828430176,17.951703533768057,1740481190.4258533,22.199978828430176,0.0,1740481190.4258544,22.199978828430176,0.0,1740481190.4258556,22.199978828430176,0.0,1740481190.4258568,22.199978828430176,0.0,1740481190.4258575,22.199978828430176,0.9947466636397301,1740481190.4258585,22.199978828430176,0.052533363602660366,1740481190.4258597,22.199978828430176,0.08455487580129162,1740481190.4258606,22.199978828430176,0.0,1740481190.4258616,22.199978828430176,0.9631635463940356,, +1740481190.4454231,22.21997880935669,14.11420417619556,1740481190.445425,22.21997880935669,0.0,1740481190.4454274,22.21997880935669,0.017227817808503663,1740481190.4454298,22.21997880935669,17.951703533768057,1740481190.445431,22.21997880935669,0.0,1740481190.4454327,22.21997880935669,0.0,1740481190.4454339,22.21997880935669,0.0,1740481190.4454348,22.21997880935669,0.0,1740481190.4454362,22.21997880935669,0.9947466636397301,1740481190.4454372,22.21997880935669,0.052533363602660366,1740481190.4454381,22.21997880935669,0.08411648084835488,1740481190.4454393,22.21997880935669,0.0,1740481190.4454403,22.21997880935669,0.9631635463940356,, +1740481190.4762583,22.239978790283203,14.11420417619556,1740481190.4762602,22.239978790283203,0.0,1740481190.4762623,22.239978790283203,0.0,1740481190.4762647,22.239978790283203,18.04053126898363,1740481190.4762657,22.239978790283203,0.0,1740481190.476267,22.239978790283203,0.0,1740481190.4762683,22.239978790283203,0.0,1740481190.4762692,22.239978790283203,0.0,1740481190.4762704,22.239978790283203,0.9944603796841252,1740481190.4762714,22.239978790283203,0.0,1740481190.476272,22.239978790283203,0.03129683329008959,1740481190.476273,22.239978790283203,0.0,1740481190.4762743,22.239978790283203,0.9631635463940356,, +1740481190.4841037,22.259978771209717,14.11420417619556,1740481190.484105,22.259978771209717,0.0,1740481190.4841075,22.259978771209717,0.0,1740481190.4841096,22.259978771209717,18.04053126898363,1740481190.4841106,22.259978771209717,0.0,1740481190.4841118,22.259978771209717,0.0,1740481190.484113,22.259978771209717,0.0,1740481190.484114,22.259978771209717,0.0,1740481190.484115,22.259978771209717,0.9944603796841252,1740481190.484116,22.259978771209717,0.0,1740481190.484117,22.259978771209717,0.03129683329008959,1740481190.4841177,22.259978771209717,0.0,1740481190.4841187,22.259978771209717,0.9631635463940356,, +1740481190.5034425,22.27997875213623,14.11420417619556,1740481190.503444,22.27997875213623,0.0,1740481190.503446,22.27997875213623,0.0,1740481190.503448,22.27997875213623,18.04053126898363,1740481190.5034494,22.27997875213623,0.0,1740481190.5034506,22.27997875213623,0.0,1740481190.5034516,22.27997875213623,0.0,1740481190.5034523,22.27997875213623,0.0,1740481190.5034535,22.27997875213623,0.9944603796841252,1740481190.5034542,22.27997875213623,0.0,1740481190.5034552,22.27997875213623,0.03129683329008959,1740481190.503456,22.27997875213623,0.0,1740481190.503457,22.27997875213623,0.9631635463940356,, +1740481190.5255694,22.289978742599487,14.11420417619556,1740481190.5255713,22.289978742599487,0.0,1740481190.5255737,22.289978742599487,0.0,1740481190.5255756,22.289978742599487,18.04053126898363,1740481190.525577,22.289978742599487,0.0,1740481190.5255783,22.289978742599487,0.0,1740481190.5255792,22.289978742599487,0.0,1740481190.5255804,22.289978742599487,0.0,1740481190.5255814,22.289978742599487,0.9944603796841252,1740481190.5255823,22.289978742599487,0.0,1740481190.525583,22.289978742599487,0.03129683329008959,1740481190.5255842,22.289978742599487,0.0,1740481190.525585,22.289978742599487,0.9631635463940356,, +1740481190.5444336,22.319978713989258,14.2202202839661,1740481190.5444357,22.319978713989258,0.0,1740481190.5444381,22.319978713989258,0.017216454014023785,1740481190.5444403,22.319978713989258,18.057287385682663,1740481190.5444415,22.319978713989258,0.0,1740481190.5444427,22.319978713989258,0.0,1740481190.5444436,22.319978713989258,0.0,1740481190.5444446,22.319978713989258,0.0,1740481190.5444458,22.319978713989258,0.9944603796841252,1740481190.5444467,22.319978713989258,0.055396203158709634,1740481190.5444477,22.319978713989258,0.08702782732311411,1740481190.5444489,22.319978713989258,0.0,1740481190.5444498,22.319978713989258,0.9629333777365398,, +1740481190.5656588,22.33997869491577,14.2202202839661,1740481190.5656607,22.33997869491577,0.0,1740481190.5656629,22.33997869491577,0.0,1740481190.5656652,22.33997869491577,18.14608703943918,1740481190.5656662,22.33997869491577,0.0,1740481190.5656679,22.33997869491577,0.0,1740481190.5656688,22.33997869491577,0.0,1740481190.5656698,22.33997869491577,0.0,1740481190.565671,22.33997869491577,0.9943909359487243,1740481190.565672,22.33997869491577,0.0,1740481190.5656729,22.33997869491577,0.031457558212184544,1740481190.565674,22.33997869491577,0.0,1740481190.565675,22.33997869491577,0.9629333777365398,, +1740481190.584715,22.359978675842285,14.2202202839661,1740481190.584717,22.359978675842285,0.0,1740481190.58472,22.359978675842285,0.0,1740481190.5847223,22.359978675842285,18.14608703943918,1740481190.5847235,22.359978675842285,0.0,1740481190.584725,22.359978675842285,0.0,1740481190.5847273,22.359978675842285,0.0,1740481190.5847282,22.359978675842285,0.0,1740481190.5847294,22.359978675842285,0.9943909359487243,1740481190.5847304,22.359978675842285,0.0,1740481190.5847316,22.359978675842285,0.031457558212184544,1740481190.5847328,22.359978675842285,0.0,1740481190.5847342,22.359978675842285,0.9629333777365398,, +1740481190.6036751,22.3799786567688,14.2202202839661,1740481190.6036773,22.3799786567688,0.0,1740481190.60368,22.3799786567688,0.0,1740481190.603682,22.3799786567688,18.14608703943918,1740481190.6036832,22.3799786567688,0.0,1740481190.6036847,22.3799786567688,0.0,1740481190.603686,22.3799786567688,0.0,1740481190.6036873,22.3799786567688,0.0,1740481190.603688,22.3799786567688,0.9943909359487243,1740481190.603689,22.3799786567688,0.0,1740481190.60369,22.3799786567688,0.031457558212184544,1740481190.603691,22.3799786567688,0.0,1740481190.603692,22.3799786567688,0.9629333777365398,, +1740481190.6244793,22.399978637695312,14.2202202839661,1740481190.624481,22.399978637695312,0.0,1740481190.6244833,22.399978637695312,0.0,1740481190.6244855,22.399978637695312,18.14608703943918,1740481190.6244867,22.399978637695312,0.0,1740481190.6244879,22.399978637695312,0.0,1740481190.624489,22.399978637695312,0.0,1740481190.6244898,22.399978637695312,0.0,1740481190.6244905,22.399978637695312,0.9943909359487243,1740481190.6244915,22.399978637695312,0.0,1740481190.6244926,22.399978637695312,0.031457558212184544,1740481190.6244934,22.399978637695312,0.0,1740481190.6244946,22.399978637695312,0.9629333777365398,, +1740481190.6484926,22.419978618621826,14.326094526719686,1740481190.6484942,22.419978618621826,0.0,1740481190.6484966,22.419978618621826,0.017192215261122665,1740481190.6484988,22.419978618621826,18.159794024216378,1740481190.6485,22.419978618621826,0.0,1740481190.6485014,22.419978618621826,0.0,1740481190.6485028,22.419978618621826,0.0,1740481190.648521,22.419978618621826,0.0,1740481190.6485221,22.419978618621826,0.9943909359487243,1740481190.6485233,22.419978618621826,0.05609064051271817,1740481190.648524,22.419978618621826,0.09008291255952451,1740481190.648525,22.419978618621826,0.0,1740481190.6485262,22.419978618621826,0.9611907624945776,, +1740481190.6722696,22.43997859954834,14.326094526719686,1740481190.6722727,22.43997859954834,0.0,1740481190.6722753,22.43997859954834,0.0,1740481190.6722775,22.43997859954834,18.248476051708842,1740481190.672279,22.43997859954834,0.0,1740481190.6722803,22.43997859954834,0.0,1740481190.6722815,22.43997859954834,0.0,1740481190.6722827,22.43997859954834,0.0,1740481190.672284,22.43997859954834,0.99385114013974,1740481190.6722856,22.43997859954834,0.0,1740481190.672287,22.43997859954834,0.032660377645162386,1740481190.6722884,22.43997859954834,0.0,1740481190.6722896,22.43997859954834,0.9611907624945776,, +1740481190.6836197,22.459978580474854,14.326094526719686,1740481190.6836216,22.459978580474854,0.0,1740481190.6836243,22.459978580474854,0.0,1740481190.6836262,22.459978580474854,18.248476051708842,1740481190.6836274,22.459978580474854,0.0,1740481190.6836286,22.459978580474854,0.0,1740481190.6836295,22.459978580474854,0.0,1740481190.6836307,22.459978580474854,0.0,1740481190.6836317,22.459978580474854,0.99385114013974,1740481190.6836329,22.459978580474854,0.0,1740481190.6836338,22.459978580474854,0.032660377645162386,1740481190.683635,22.459978580474854,0.0,1740481190.6836376,22.459978580474854,0.9611907624945776,, +1740481190.7050152,22.479978561401367,14.326094526719686,1740481190.7050242,22.479978561401367,0.0,1740481190.705035,22.479978561401367,0.0,1740481190.7050412,22.479978561401367,18.248476051708842,1740481190.705046,22.479978561401367,0.0,1740481190.705052,22.479978561401367,0.0,1740481190.705099,22.479978561401367,0.0,1740481190.705102,22.479978561401367,0.0,1740481190.7051046,22.479978561401367,0.99385114013974,1740481190.7051086,22.479978561401367,0.0,1740481190.7051132,22.479978561401367,0.032660377645162386,1740481190.7051156,22.479978561401367,0.0,1740481190.7051194,22.479978561401367,0.9611907624945776,, +1740481190.7235749,22.49997854232788,14.326094526719686,1740481190.7235765,22.49997854232788,0.0,1740481190.723579,22.49997854232788,0.0,1740481190.723581,22.49997854232788,18.248476051708842,1740481190.7235823,22.49997854232788,0.0,1740481190.7235835,22.49997854232788,0.0,1740481190.7235844,22.49997854232788,0.0,1740481190.7235856,22.49997854232788,0.0,1740481190.7235866,22.49997854232788,0.99385114013974,1740481190.7235873,22.49997854232788,0.0,1740481190.7235885,22.49997854232788,0.032660377645162386,1740481190.7235892,22.49997854232788,0.0,1740481190.7235901,22.49997854232788,0.9611907624945776,, +1740481190.7436142,22.519978523254395,14.326094526719686,1740481190.7436156,22.519978523254395,0.0,1740481190.7436178,22.519978523254395,0.0,1740481190.74362,22.519978523254395,18.248476051708842,1740481190.7436209,22.519978523254395,0.0,1740481190.743622,22.519978523254395,0.0,1740481190.7436233,22.519978523254395,0.0,1740481190.7436242,22.519978523254395,0.0,1740481190.7436252,22.519978523254395,0.99385114013974,1740481190.7436264,22.519978523254395,0.0,1740481190.743627,22.519978523254395,0.032660377645162386,1740481190.743628,22.519978523254395,0.0,1740481190.743629,22.519978523254395,0.9611907624945776,, +1740481190.763993,22.539978504180908,14.431844890680622,1740481190.763995,22.539978504180908,0.0,1740481190.7639976,22.539978504180908,0.0,1740481190.7639995,22.539978504180908,18.35224871579107,1740481190.7640004,22.539978504180908,0.0,1740481190.7640018,22.539978504180908,0.0,1740481190.7640028,22.539978504180908,0.0,1740481190.7640035,22.539978504180908,0.0,1740481190.7640047,22.539978504180908,0.9935338052795356,1740481190.7640057,22.539978504180908,0.06466194720460505,1740481190.7640064,22.539978504180908,0.09829907434689557,1740481190.7640073,22.539978504180908,0.0,1740481190.7640083,22.539978504180908,0.9602019125552249,, +1740481190.7832685,22.559978485107422,14.431844890680622,1740481190.78327,22.559978485107422,0.0,1740481190.7832723,22.559978485107422,0.0,1740481190.7832744,22.559978485107422,18.35224871579107,1740481190.7832756,22.559978485107422,0.0,1740481190.7832768,22.559978485107422,0.0,1740481190.7832778,22.559978485107422,0.0,1740481190.7832787,22.559978485107422,0.0,1740481190.7832797,22.559978485107422,0.9935338052795356,1740481190.7832808,22.559978485107422,0.06466194720460505,1740481190.7832818,22.559978485107422,0.09799383992891575,1740481190.7832835,22.559978485107422,0.0,1740481190.783285,22.559978485107422,0.9602019125552249,, +1740481190.8041642,22.579978466033936,14.431844890680622,1740481190.804166,22.579978466033936,0.0,1740481190.8041682,22.579978466033936,0.0,1740481190.8041701,22.579978466033936,18.35224871579107,1740481190.8041713,22.579978466033936,0.0,1740481190.8041725,22.579978466033936,0.0,1740481190.8041735,22.579978466033936,0.0,1740481190.8041747,22.579978466033936,0.0,1740481190.8041754,22.579978466033936,0.9935338052795356,1740481190.8041763,22.579978466033936,0.06466194720460505,1740481190.804177,22.579978466033936,0.09799383992891575,1740481190.8041782,22.579978466033936,0.0,1740481190.8041792,22.579978466033936,0.9602019125552249,, +1740481190.8237143,22.59997844696045,14.431844890680622,1740481190.8237162,22.59997844696045,0.0,1740481190.823718,22.59997844696045,0.0,1740481190.8237202,22.59997844696045,18.35224871579107,1740481190.8237212,22.59997844696045,0.0,1740481190.8237226,22.59997844696045,0.0,1740481190.8237236,22.59997844696045,0.0,1740481190.8237245,22.59997844696045,0.0,1740481190.8237252,22.59997844696045,0.9935338052795356,1740481190.8237264,22.59997844696045,0.06466194720460505,1740481190.8237274,22.59997844696045,0.09799383992891575,1740481190.823728,22.59997844696045,0.0,1740481190.8237288,22.59997844696045,0.9602019125552249,, +1740481190.8439116,22.619978427886963,14.431844890680622,1740481190.8439145,22.619978427886963,0.0,1740481190.843917,22.619978427886963,0.0,1740481190.8439193,22.619978427886963,18.35224871579107,1740481190.8439207,22.619978427886963,0.0,1740481190.8439221,22.619978427886963,0.0,1740481190.843923,22.619978427886963,0.0,1740481190.8439245,22.619978427886963,0.0,1740481190.8439252,22.619978427886963,0.9935338052795356,1740481190.8439264,22.619978427886963,0.06466194720460505,1740481190.8439276,22.619978427886963,0.09799383992891575,1740481190.8439288,22.619978427886963,0.0,1740481190.8439298,22.619978427886963,0.9602019125552249,, +1740481190.864678,22.639978408813477,14.537626224608736,1740481190.8646796,22.639978408813477,0.0,1740481190.8646817,22.639978408813477,0.0,1740481190.8646839,22.639978408813477,18.46568160884493,1740481190.8646848,22.639978408813477,0.0,1740481190.864686,22.639978408813477,0.0,1740481190.864687,22.639978408813477,0.0,1740481190.864688,22.639978408813477,0.0,1740481190.8646889,22.639978408813477,0.9947172388120288,1740481190.8646898,22.639978408813477,-0.197801478424926,1740481190.8646913,22.639978408813477,-0.16831299925386486,1740481190.8646922,22.639978408813477,0.0,1740481190.864693,22.639978408813477,0.9640276921180959,, +1740481190.883498,22.65997838973999,14.537626224608736,1740481190.8834999,22.65997838973999,0.0,1740481190.883502,22.65997838973999,0.0,1740481190.883504,22.65997838973999,18.46568160884493,1740481190.883505,22.65997838973999,0.0,1740481190.8835065,22.65997838973999,0.0,1740481190.8835077,22.65997838973999,0.0,1740481190.8835087,22.65997838973999,0.0,1740481190.8835099,22.65997838973999,0.9947172388120288,1740481190.8835108,22.65997838973999,-0.197801478424926,1740481190.8835118,22.65997838973999,-0.16711193173099315,1740481190.8835125,22.65997838973999,0.0,1740481190.8835137,22.65997838973999,0.9640276921180959,, +1740481190.9036531,22.679978370666504,14.537626224608736,1740481190.9036567,22.679978370666504,0.0,1740481190.9036677,22.679978370666504,0.0,1740481190.903673,22.679978370666504,18.46568160884493,1740481190.9036748,22.679978370666504,0.0,1740481190.9036794,22.679978370666504,0.0,1740481190.9036832,22.679978370666504,0.0,1740481190.9036846,22.679978370666504,0.0,1740481190.9036887,22.679978370666504,0.9947172388120288,1740481190.9036908,22.679978370666504,-0.197801478424926,1740481190.9036925,22.679978370666504,-0.16711193173099315,1740481190.9036944,22.679978370666504,0.0,1740481190.9036953,22.679978370666504,0.9640276921180959,, +1740481190.9235902,22.699978351593018,14.537626224608736,1740481190.9235923,22.699978351593018,0.0,1740481190.9235945,22.699978351593018,0.0,1740481190.9236085,22.699978351593018,18.46568160884493,1740481190.9236112,22.699978351593018,0.0,1740481190.9236135,22.699978351593018,0.0,1740481190.9236145,22.699978351593018,0.0,1740481190.9236155,22.699978351593018,0.0,1740481190.9236164,22.699978351593018,0.9947172388120288,1740481190.9236176,22.699978351593018,-0.197801478424926,1740481190.9236186,22.699978351593018,-0.16711193173099315,1740481190.9236193,22.699978351593018,0.0,1740481190.9236205,22.699978351593018,0.9640276921180959,, +1740481190.9448135,22.71997833251953,14.537626224608736,1740481190.9448156,22.71997833251953,0.0,1740481190.944818,22.71997833251953,0.0,1740481190.94482,22.71997833251953,18.46568160884493,1740481190.944821,22.71997833251953,0.0,1740481190.9448223,22.71997833251953,0.0,1740481190.9448233,22.71997833251953,0.0,1740481190.9448242,22.71997833251953,0.0,1740481190.9448254,22.71997833251953,0.9947172388120288,1740481190.9448261,22.71997833251953,-0.197801478424926,1740481190.9448273,22.71997833251953,-0.16711193173099315,1740481190.9448283,22.71997833251953,0.0,1740481190.9448292,22.71997833251953,0.9640276921180959,, +1740481190.9640782,22.739978313446045,14.537626224608736,1740481190.9640799,22.739978313446045,0.0,1740481190.9640822,22.739978313446045,0.0,1740481190.9640841,22.739978313446045,18.46568160884493,1740481190.964085,22.739978313446045,0.0,1740481190.9640863,22.739978313446045,0.0,1740481190.9640872,22.739978313446045,0.0,1740481190.9640882,22.739978313446045,0.0,1740481190.9640894,22.739978313446045,0.9947172388120288,1740481190.9640903,22.739978313446045,-0.197801478424926,1740481190.964091,22.739978313446045,-0.16711193173099315,1740481190.9640923,22.739978313446045,0.0,1740481190.964093,22.739978313446045,0.9640276921180959,, +1740481190.9840267,22.75997829437256,14.642255982888702,1740481190.9840307,22.75997829437256,0.0,1740481190.984035,22.75997829437256,0.016995706891274852,1740481190.9840379,22.75997829437256,18.42622376106883,1740481190.984039,22.75997829437256,0.0,1740481190.984041,22.75997829437256,0.0,1740481190.9841373,22.75997829437256,0.0,1740481190.9841385,22.75997829437256,0.0,1740481190.9841392,22.75997829437256,0.9749370909695362,1740481190.9841406,22.75997829437256,-1.7506282997896205,1740481190.9841413,22.75997829437256,-1.707652742901523,1740481190.9841423,22.75997829437256,0.0,1740481190.984143,22.75997829437256,0.9358009147844093,, +1740481191.0039463,22.779978275299072,14.642255982888702,1740481191.003948,22.779978275299072,0.0,1740481191.00395,22.779978275299072,0.016995706891274852,1740481191.003952,22.779978275299072,18.42622376106883,1740481191.0039532,22.779978275299072,0.0,1740481191.0039542,22.779978275299072,0.0,1740481191.0039551,22.779978275299072,0.0,1740481191.0039563,22.779978275299072,0.0,1740481191.003957,22.779978275299072,0.9749370909695362,1740481191.0039582,22.779978275299072,-1.7506282997896205,1740481191.003959,22.779978275299072,-1.7114921236044935,1740481191.0039601,22.779978275299072,0.0,1740481191.0039608,22.779978275299072,0.9358009147844093,, +1740481191.0237548,22.799978256225586,14.642255982888702,1740481191.0237565,22.799978256225586,0.0,1740481191.0237586,22.799978256225586,0.016995706891274852,1740481191.0237603,22.799978256225586,18.42622376106883,1740481191.0237615,22.799978256225586,0.0,1740481191.0237627,22.799978256225586,0.0,1740481191.0237637,22.799978256225586,0.0,1740481191.0237648,22.799978256225586,0.0,1740481191.0237656,22.799978256225586,0.9749370909695362,1740481191.0237665,22.799978256225586,-1.7506282997896205,1740481191.0237675,22.799978256225586,-1.7114921236044935,1740481191.0237687,22.799978256225586,0.0,1740481191.0237696,22.799978256225586,0.9358009147844093,, +1740481191.0450165,22.8199782371521,14.642255982888702,1740481191.0450213,22.8199782371521,0.0,1740481191.0450249,22.8199782371521,0.016995706891274852,1740481191.0450273,22.8199782371521,18.42622376106883,1740481191.0450287,22.8199782371521,0.0,1740481191.0450306,22.8199782371521,0.0,1740481191.045033,22.8199782371521,0.0,1740481191.0450346,22.8199782371521,0.0,1740481191.0450366,22.8199782371521,0.9749370909695362,1740481191.0450387,22.8199782371521,-1.7506282997896205,1740481191.045041,22.8199782371521,-1.7114921236044935,1740481191.0450428,22.8199782371521,0.0,1740481191.0450444,22.8199782371521,0.9358009147844093,, +1740481191.0646093,22.839978218078613,14.642255982888702,1740481191.0646133,22.839978218078613,0.0,1740481191.0646167,22.839978218078613,0.0,1740481191.064619,22.839978218078613,18.51385781245752,1740481191.0646205,22.839978218078613,0.0,1740481191.0646238,22.839978218078613,0.0,1740481191.0646255,22.839978218078613,0.0,1740481191.0646288,22.839978218078613,0.0,1740481191.06463,22.839978218078613,0.966097064717689,1740481191.0646322,22.839978218078613,0.0,1740481191.0646336,22.839978218078613,0.03029614993327967,1740481191.0646348,22.839978218078613,0.0,1740481191.0646374,22.839978218078613,0.9358009147844093,, +1740481191.086093,22.859978199005127,14.740536571595726,1740481191.0860958,22.859978199005127,0.0,1740481191.0860984,22.859978199005127,0.015505039537042296,1740481191.0861006,22.859978199005127,18.363466313918078,1740481191.0861018,22.859978199005127,0.0,1740481191.0861034,22.859978199005127,0.0,1740481191.0861046,22.859978199005127,0.0,1740481191.0861056,22.859978199005127,0.0,1740481191.0861063,22.859978199005127,0.966097064717689,1740481191.0861077,22.859978199005127,-1.7171229947615785,1740481191.0861087,22.859978199005127,-1.5661747811791686,1740481191.0861096,22.859978199005127,0.0,1740481191.0861108,22.859978199005127,0.8528526457461664,, +1740481191.104126,22.87997817993164,14.740536571595726,1740481191.104128,22.87997817993164,0.0,1740481191.1041303,22.87997817993164,0.015505039537042296,1740481191.1041327,22.87997817993164,18.363466313918078,1740481191.1041338,22.87997817993164,0.0,1740481191.1041353,22.87997817993164,0.0,1740481191.1041362,22.87997817993164,0.0,1740481191.1041372,22.87997817993164,0.0,1740481191.1041381,22.87997817993164,0.966097064717689,1740481191.104139,22.87997817993164,-1.7171229947615785,1740481191.10414,22.87997817993164,-1.603878575790056,1740481191.1041408,22.87997817993164,0.0,1740481191.1041417,22.87997817993164,0.8528526457461664,, +1740481191.124616,22.899978160858154,14.740536571595726,1740481191.124618,22.899978160858154,0.0,1740481191.1246204,22.899978160858154,0.015505039537042296,1740481191.1246228,22.899978160858154,18.363466313918078,1740481191.1246245,22.899978160858154,0.0,1740481191.124626,22.899978160858154,0.0,1740481191.1246269,22.899978160858154,0.0,1740481191.1246283,22.899978160858154,0.0,1740481191.1246302,22.899978160858154,0.966097064717689,1740481191.1246314,22.899978160858154,-1.7171229947615785,1740481191.1246324,22.899978160858154,-1.603878575790056,1740481191.1246333,22.899978160858154,0.0,1740481191.1246347,22.899978160858154,0.8528526457461664,, +1740481191.144209,22.919978141784668,14.740536571595726,1740481191.1442113,22.919978141784668,0.0,1740481191.1442142,22.919978141784668,0.015505039537042296,1740481191.1442165,22.919978141784668,18.363466313918078,1740481191.144218,22.919978141784668,0.0,1740481191.1442192,22.919978141784668,0.0,1740481191.1442204,22.919978141784668,0.0,1740481191.1442218,22.919978141784668,0.0,1740481191.1442227,22.919978141784668,0.966097064717689,1740481191.1442237,22.919978141784668,-1.7171229947615785,1740481191.144225,22.919978141784668,-1.603878575790056,1740481191.1442258,22.919978141784668,0.0,1740481191.1442266,22.919978141784668,0.8528526457461664,, +1740481191.1663098,22.93997812271118,14.740536571595726,1740481191.1663122,22.93997812271118,0.0,1740481191.1663148,22.93997812271118,0.0,1740481191.166317,22.93997812271118,18.44624186308806,1740481191.1663182,22.93997812271118,0.0,1740481191.1663196,22.93997812271118,0.0,1740481191.1663203,22.93997812271118,0.0,1740481191.1663215,22.93997812271118,0.0,1740481191.1663225,22.93997812271118,0.8316855900821778,1740481191.1663232,22.93997812271118,0.0,1740481191.1663241,22.93997812271118,-0.021167055663988577,1740481191.1663253,22.93997812271118,0.0,1740481191.1663265,22.93997812271118,0.8528526457461664,, +1740481191.1836033,22.959978103637695,14.740536571595726,1740481191.183605,22.959978103637695,0.0,1740481191.1836073,22.959978103637695,0.0,1740481191.183609,22.959978103637695,18.44624186308806,1740481191.1836102,22.959978103637695,0.0,1740481191.1836116,22.959978103637695,0.0,1740481191.1836126,22.959978103637695,0.0,1740481191.1836138,22.959978103637695,0.0,1740481191.1836145,22.959978103637695,0.8316855900821778,1740481191.1836154,22.959978103637695,0.0,1740481191.1836164,22.959978103637695,-0.021167055663988577,1740481191.1836174,22.959978103637695,0.0,1740481191.1836183,22.959978103637695,0.8528526457461664,, +1740481191.2037117,22.97997808456421,14.829130632123295,1740481191.2037134,22.97997808456421,0.0,1740481191.2037156,22.97997808456421,0.01203228610770627,1740481191.2037177,22.97997808456421,18.29432976976031,1740481191.2037184,22.97997808456421,0.0,1740481191.2037196,22.97997808456421,0.0,1740481191.203721,22.97997808456421,0.0,1740481191.2037218,22.97997808456421,0.0,1740481191.2037227,22.97997808456421,0.8316855900821778,1740481191.2037237,22.97997808456421,-2.0,1740481191.2037246,22.97997808456421,-1.9019347441769099,1740481191.2037256,22.97997808456421,0.0,1740481191.2037268,22.97997808456421,0.7708804560284394,, +1740481191.223443,22.999978065490723,14.829130632123295,1740481191.223445,22.999978065490723,0.0,1740481191.2234473,22.999978065490723,0.01203228610770627,1740481191.223449,22.999978065490723,18.29432976976031,1740481191.2234502,22.999978065490723,0.0,1740481191.2234514,22.999978065490723,0.0,1740481191.223452,22.999978065490723,0.0,1740481191.2234533,22.999978065490723,0.0,1740481191.2234542,22.999978065490723,0.8316855900821778,1740481191.223455,22.999978065490723,-2.0,1740481191.2234557,22.999978065490723,-1.9391948659462614,1740481191.2234569,22.999978065490723,0.0,1740481191.2234576,22.999978065490723,0.7708804560284394,, +1740481191.24367,23.019978046417236,14.829130632123295,1740481191.243672,23.019978046417236,0.0,1740481191.243674,23.019978046417236,0.01203228610770627,1740481191.2436762,23.019978046417236,18.29432976976031,1740481191.2436771,23.019978046417236,0.0,1740481191.2436786,23.019978046417236,0.0,1740481191.2436795,23.019978046417236,0.0,1740481191.2436805,23.019978046417236,0.0,1740481191.2436812,23.019978046417236,0.8316855900821778,1740481191.2436824,23.019978046417236,-2.0,1740481191.243683,23.019978046417236,-1.9391948659462614,1740481191.243684,23.019978046417236,0.0,1740481191.243685,23.019978046417236,0.7708804560284394,, +1740481191.263793,23.03997802734375,14.829130632123295,1740481191.2637947,23.03997802734375,0.0,1740481191.263797,23.03997802734375,0.0,1740481191.263799,23.03997802734375,18.370891544180175,1740481191.2638001,23.03997802734375,0.0,1740481191.263801,23.03997802734375,0.0,1740481191.263802,23.03997802734375,0.0,1740481191.2638032,23.03997802734375,0.0,1740481191.2638042,23.03997802734375,0.6612157772959436,1740481191.2638052,23.03997802734375,0.0,1740481191.2638059,23.03997802734375,-0.10966467873249575,1740481191.2638073,23.03997802734375,0.0,1740481191.263808,23.03997802734375,0.7708804560284394,, +1740481191.2838497,23.059978008270264,14.829130632123295,1740481191.2838528,23.059978008270264,0.0,1740481191.283856,23.059978008270264,0.0,1740481191.2838578,23.059978008270264,18.370891544180175,1740481191.2838588,23.059978008270264,0.0,1740481191.2838602,23.059978008270264,0.0,1740481191.2838612,23.059978008270264,0.0,1740481191.2838624,23.059978008270264,0.0,1740481191.2838633,23.059978008270264,0.6612157772959436,1740481191.283864,23.059978008270264,0.0,1740481191.283865,23.059978008270264,-0.10966467873249575,1740481191.2838662,23.059978008270264,0.0,1740481191.283867,23.059978008270264,0.7708804560284394,, +1740481191.3051186,23.079977989196777,14.909817557149807,1740481191.3051207,23.079977989196777,0.0,1740481191.305123,23.079977989196777,0.008712258217240861,1740481191.3051248,23.079977989196777,18.239064808966855,1740481191.305126,23.079977989196777,0.0,1740481191.3051271,23.079977989196777,0.0,1740481191.305128,23.079977989196777,0.0,1740481191.3051293,23.079977989196777,0.0,1740481191.3051705,23.079977989196777,0.6612157772959436,1740481191.3051744,23.079977989196777,-2.0,1740481191.3051753,23.079977989196777,-2.0074544712310542,1740481191.3051763,23.079977989196777,0.0,1740481191.305177,23.079977989196777,0.7006109593131602,, +1740481191.3237514,23.09997797012329,14.909817557149807,1740481191.323753,23.09997797012329,0.0,1740481191.3237555,23.09997797012329,0.008712258217240861,1740481191.3237576,23.09997797012329,18.239064808966855,1740481191.3237586,23.09997797012329,0.0,1740481191.3237596,23.09997797012329,0.0,1740481191.3237607,23.09997797012329,0.0,1740481191.3237617,23.09997797012329,0.0,1740481191.3237627,23.09997797012329,0.6612157772959436,1740481191.3237634,23.09997797012329,-2.0,1740481191.3237646,23.09997797012329,-2.0393951820172167,1740481191.3237653,23.09997797012329,0.0,1740481191.3237662,23.09997797012329,0.7006109593131602,, +1740481191.3459969,23.119977951049805,14.909817557149807,1740481191.3459988,23.119977951049805,0.0,1740481191.346001,23.119977951049805,0.008712258217240861,1740481191.346003,23.119977951049805,18.239064808966855,1740481191.346004,23.119977951049805,0.0,1740481191.3460174,23.119977951049805,0.0,1740481191.3460188,23.119977951049805,0.0,1740481191.3460197,23.119977951049805,0.0,1740481191.3460207,23.119977951049805,0.6612157772959436,1740481191.3460217,23.119977951049805,-2.0,1740481191.3460226,23.119977951049805,-2.0393951820172167,1740481191.3460233,23.119977951049805,0.0,1740481191.3460245,23.119977951049805,0.7006109593131602,, +1740481191.3728402,23.13997793197632,14.909817557149807,1740481191.3728428,23.13997793197632,0.0,1740481191.3728456,23.13997793197632,0.0,1740481191.372848,23.13997793197632,18.311039475776127,1740481191.3728492,23.13997793197632,0.0,1740481191.3728511,23.13997793197632,0.0,1740481191.3728526,23.13997793197632,0.0,1740481191.3728535,23.13997793197632,0.0,1740481191.3728552,23.13997793197632,0.5748087301181215,1740481191.3728578,23.13997793197632,0.0,1740481191.3728588,23.13997793197632,-0.1258022291950387,1740481191.3728602,23.13997793197632,0.0,1740481191.3728616,23.13997793197632,0.7006109593131602,, +1740481191.3841162,23.159977912902832,14.909817557149807,1740481191.3841183,23.159977912902832,0.0,1740481191.384121,23.159977912902832,0.0,1740481191.384123,23.159977912902832,18.311039475776127,1740481191.3841243,23.159977912902832,0.0,1740481191.3841255,23.159977912902832,0.0,1740481191.3841267,23.159977912902832,0.0,1740481191.3841279,23.159977912902832,0.0,1740481191.3841288,23.159977912902832,0.5748087301181215,1740481191.3841298,23.159977912902832,0.0,1740481191.3841307,23.159977912902832,-0.1258022291950387,1740481191.384132,23.159977912902832,0.0,1740481191.3841329,23.159977912902832,0.7006109593131602,, +1740481191.4035087,23.179977893829346,14.909817557149807,1740481191.4035106,23.179977893829346,0.0,1740481191.4035127,23.179977893829346,0.0,1740481191.4035149,23.179977893829346,18.311039475776127,1740481191.4035156,23.179977893829346,0.0,1740481191.4035172,23.179977893829346,0.0,1740481191.403518,23.179977893829346,0.0,1740481191.403519,23.179977893829346,0.0,1740481191.4035203,23.179977893829346,0.5748087301181215,1740481191.4035213,23.179977893829346,0.0,1740481191.403522,23.179977893829346,-0.1258022291950387,1740481191.403523,23.179977893829346,0.0,1740481191.4035242,23.179977893829346,0.7006109593131602,, +1740481191.42341,23.19997787475586,14.981843517264423,1740481191.4234116,23.19997787475586,0.0,1740481191.4234145,23.19997787475586,0.004140115066902053,1740481191.4234166,23.19997787475586,18.15635668272273,1740481191.4234173,23.19997787475586,0.0,1740481191.4234185,23.19997787475586,0.0,1740481191.4234197,23.19997787475586,0.0,1740481191.4234207,23.19997787475586,0.0,1740481191.4234216,23.19997787475586,0.3270156983838035,1740481191.4234226,23.19997787475586,0.0,1740481191.4234235,23.19997787475586,-0.37072096062171,1740481191.4234242,23.19997787475586,0.0,1740481191.4234252,23.19997787475586,0.6211995052530103,, +1740481191.4463553,23.219977855682373,14.981843517264423,1740481191.4463575,23.219977855682373,0.0,1740481191.44636,23.219977855682373,0.004140115066902053,1740481191.446362,23.219977855682373,18.15635668272273,1740481191.4463632,23.219977855682373,0.0,1740481191.4463644,23.219977855682373,0.0,1740481191.4463654,23.219977855682373,0.0,1740481191.4463665,23.219977855682373,0.0,1740481191.4463675,23.219977855682373,0.3270156983838035,1740481191.4463687,23.219977855682373,0.0,1740481191.4463696,23.219977855682373,-0.29418380686920675,1740481191.4463706,23.219977855682373,0.0,1740481191.4463716,23.219977855682373,0.6211995052530103,, +1740481191.4635515,23.239977836608887,14.981843517264423,1740481191.4635534,23.239977836608887,0.0,1740481191.4635558,23.239977836608887,0.0,1740481191.4635577,23.239977836608887,18.224242527770443,1740481191.4635587,23.239977836608887,0.0,1740481191.46356,23.239977836608887,0.0,1740481191.463561,23.239977836608887,0.0,1740481191.463562,23.239977836608887,0.0,1740481191.4635627,23.239977836608887,1.0,1740481191.4635637,23.239977836608887,0.0,1740481191.4635649,23.239977836608887,0.37880049474698974,1740481191.4635656,23.239977836608887,0.0,1740481191.4635665,23.239977836608887,0.6211995052530103,, +1740481191.48747,23.2599778175354,14.981843517264423,1740481191.4874716,23.2599778175354,0.0,1740481191.4874737,23.2599778175354,0.0,1740481191.4874756,23.2599778175354,18.224242527770443,1740481191.4874766,23.2599778175354,0.0,1740481191.4874778,23.2599778175354,0.0,1740481191.4874785,23.2599778175354,0.0,1740481191.4874794,23.2599778175354,0.0,1740481191.4874804,23.2599778175354,1.0,1740481191.4874814,23.2599778175354,0.0,1740481191.487482,23.2599778175354,0.37880049474698974,1740481191.4874828,23.2599778175354,0.0,1740481191.4874842,23.2599778175354,0.6211995052530103,, +1740481191.5032043,23.279977798461914,14.981843517264423,1740481191.5032065,23.279977798461914,0.0,1740481191.5032086,23.279977798461914,0.0,1740481191.5032105,23.279977798461914,18.224242527770443,1740481191.5032115,23.279977798461914,0.0,1740481191.5032127,23.279977798461914,0.0,1740481191.503214,23.279977798461914,0.0,1740481191.5032148,23.279977798461914,0.0,1740481191.503216,23.279977798461914,1.0,1740481191.5032175,23.279977798461914,0.0,1740481191.5032182,23.279977798461914,0.37880049474698974,1740481191.5032191,23.279977798461914,0.0,1740481191.5032206,23.279977798461914,0.6211995052530103,, +1740481191.52367,23.299977779388428,15.049341527320987,1740481191.5236719,23.299977779388428,0.0,1740481191.523674,23.299977779388428,0.0012255264542778172,1740481191.5236762,23.299977779388428,18.232749692792765,1740481191.5236924,23.299977779388428,0.0,1740481191.5236948,23.299977779388428,0.0,1740481191.523696,23.299977779388428,0.0,1740481191.523697,23.299977779388428,0.0,1740481191.5236979,23.299977779388428,1.0,1740481191.5236988,23.299977779388428,0.0,1740481191.5236998,23.299977779388428,0.37350475602833905,1740481191.5237005,23.299977779388428,0.0,1740481191.5237014,23.299977779388428,0.6248403245370329,, +1740481191.543626,23.31997776031494,15.049341527320987,1740481191.543628,23.31997776031494,0.0,1740481191.5436304,23.31997776031494,0.0012255264542778172,1740481191.543632,23.31997776031494,18.232749692792765,1740481191.5436332,23.31997776031494,0.0,1740481191.5436347,23.31997776031494,0.0,1740481191.5436363,23.31997776031494,0.0,1740481191.5436375,23.31997776031494,0.0,1740481191.5436385,23.31997776031494,1.0,1740481191.5436401,23.31997776031494,0.0,1740481191.543641,23.31997776031494,0.37515967546296713,1740481191.543642,23.31997776031494,0.0,1740481191.5436432,23.31997776031494,0.6248403245370329,, +1740481191.5649607,23.339977741241455,15.049341527320987,1740481191.5649621,23.339977741241455,0.0,1740481191.5649643,23.339977741241455,0.0,1740481191.5649664,23.339977741241455,18.249680649074065,1740481191.5649674,23.339977741241455,0.0,1740481191.564969,23.339977741241455,0.0,1740481191.56497,23.339977741241455,0.0,1740481191.564971,23.339977741241455,0.0,1740481191.5649724,23.339977741241455,0.0,1740481191.5649734,23.339977741241455,-2.0,1740481191.564974,23.339977741241455,-2.6248403245370326,1740481191.5649753,23.339977741241455,0.0,1740481191.5649765,23.339977741241455,0.6248403245370329,, +1740481191.58766,23.35997772216797,15.049341527320987,1740481191.5876615,23.35997772216797,0.0,1740481191.587664,23.35997772216797,0.0,1740481191.5876656,23.35997772216797,18.249680649074065,1740481191.5876667,23.35997772216797,0.0,1740481191.587668,23.35997772216797,0.0,1740481191.587669,23.35997772216797,0.0,1740481191.58767,23.35997772216797,0.0,1740481191.587671,23.35997772216797,0.0,1740481191.5876718,23.35997772216797,-2.0,1740481191.587673,23.35997772216797,-2.6248403245370326,1740481191.5876737,23.35997772216797,0.0,1740481191.5876744,23.35997772216797,0.6248403245370329,, +1740481191.6033006,23.379977703094482,15.049341527320987,1740481191.6033025,23.379977703094482,0.0,1740481191.6033044,23.379977703094482,0.0,1740481191.6033068,23.379977703094482,18.249680649074065,1740481191.6033075,23.379977703094482,0.0,1740481191.6033092,23.379977703094482,0.0,1740481191.6033103,23.379977703094482,0.0,1740481191.6033113,23.379977703094482,0.0,1740481191.6033125,23.379977703094482,0.0,1740481191.6033137,23.379977703094482,-2.0,1740481191.6033146,23.379977703094482,-2.6248403245370326,1740481191.6033154,23.379977703094482,0.0,1740481191.6033165,23.379977703094482,0.6248403245370329,, +1740481191.6233559,23.399977684020996,15.049341527320987,1740481191.6233575,23.399977684020996,0.0,1740481191.6233594,23.399977684020996,0.0,1740481191.6233616,23.399977684020996,18.249680649074065,1740481191.6233625,23.399977684020996,0.0,1740481191.6233637,23.399977684020996,0.0,1740481191.623365,23.399977684020996,0.0,1740481191.6233659,23.399977684020996,0.0,1740481191.6233668,23.399977684020996,0.0,1740481191.623368,23.399977684020996,-2.0,1740481191.6233687,23.399977684020996,-2.6248403245370326,1740481191.6233695,23.399977684020996,0.0,1740481191.6233704,23.399977684020996,0.6248403245370329,, +1740481191.6451235,23.41997766494751,15.117125889986575,1740481191.6451254,23.41997766494751,0.0,1740481191.6451652,23.41997766494751,0.0,1740481191.6451697,23.41997766494751,18.136790106903078,1740481191.645171,23.41997766494751,0.0,1740481191.6451726,23.41997766494751,0.0,1740481191.6451735,23.41997766494751,0.0,1740481191.6451745,23.41997766494751,0.0,1740481191.6451757,23.41997766494751,0.0,1740481191.645177,23.41997766494751,-2.0,1740481191.6451778,23.41997766494751,-2.5427380875806525,1740481191.6451788,23.41997766494751,0.0,1740481191.64518,23.41997766494751,0.5683950534515387,, +1740481191.6644094,23.439977645874023,15.117125889986575,1740481191.664411,23.439977645874023,0.0,1740481191.6644132,23.439977645874023,0.0,1740481191.6644151,23.439977645874023,18.136790106903078,1740481191.6644166,23.439977645874023,0.0,1740481191.6644177,23.439977645874023,0.0,1740481191.6644187,23.439977645874023,0.0,1740481191.66442,23.439977645874023,0.0,1740481191.6644208,23.439977645874023,0.0,1740481191.6644218,23.439977645874023,-2.0,1740481191.6644228,23.439977645874023,-2.568395053451539,1740481191.6644237,23.439977645874023,0.0,1740481191.6644247,23.439977645874023,0.5683950534515387,, +1740481191.6834497,23.459977626800537,15.117125889986575,1740481191.6834512,23.459977626800537,0.0,1740481191.683453,23.459977626800537,0.0,1740481191.6834552,23.459977626800537,18.136790106903078,1740481191.6834562,23.459977626800537,0.0,1740481191.6834576,23.459977626800537,0.0,1740481191.6834586,23.459977626800537,0.0,1740481191.6834595,23.459977626800537,0.0,1740481191.6834607,23.459977626800537,0.0,1740481191.6834617,23.459977626800537,-2.0,1740481191.6834626,23.459977626800537,-2.568395053451539,1740481191.6834633,23.459977626800537,0.0,1740481191.6834645,23.459977626800537,0.5683950534515387,, +1740481191.7033205,23.47997760772705,15.117125889986575,1740481191.7033224,23.47997760772705,0.0,1740481191.7033246,23.47997760772705,0.0,1740481191.7033267,23.47997760772705,18.136790106903078,1740481191.7033277,23.47997760772705,0.0,1740481191.703329,23.47997760772705,0.0,1740481191.70333,23.47997760772705,0.0,1740481191.7033308,23.47997760772705,0.0,1740481191.7033322,23.47997760772705,0.0,1740481191.7033331,23.47997760772705,-2.0,1740481191.7033339,23.47997760772705,-2.568395053451539,1740481191.7033348,23.47997760772705,0.0,1740481191.703336,23.47997760772705,0.5683950534515387,, +1740481191.7243614,23.499977588653564,15.117125889986575,1740481191.724363,23.499977588653564,0.0,1740481191.724365,23.499977588653564,0.0,1740481191.7243671,23.499977588653564,18.136790106903078,1740481191.724368,23.499977588653564,0.0,1740481191.7243695,23.499977588653564,0.0,1740481191.7243702,23.499977588653564,0.0,1740481191.7243712,23.499977588653564,0.0,1740481191.7243721,23.499977588653564,0.0,1740481191.7243733,23.499977588653564,-2.0,1740481191.724374,23.499977588653564,-2.568395053451539,1740481191.724375,23.499977588653564,0.0,1740481191.7243757,23.499977588653564,0.5683950534515387,, +1740481191.743855,23.519977569580078,15.174149345866248,1740481191.7438574,23.519977569580078,0.0,1740481191.7438605,23.519977569580078,0.0,1740481191.7438629,23.519977569580078,17.91679010690308,1740481191.743865,23.519977569580078,0.0,1740481191.7438667,23.519977569580078,0.0,1740481191.7438679,23.519977569580078,0.0,1740481191.74387,23.519977569580078,0.0,1740481191.7438712,23.519977569580078,0.0,1740481191.7438731,23.519977569580078,-2.0,1740481191.7438748,23.519977569580078,-2.4083950057677774,1740481191.7438765,23.519977569580078,0.0,1740481191.743878,23.519977569580078,0.45839505345153864,, +1740481191.7667143,23.539977550506592,15.174149345866248,1740481191.7667174,23.539977550506592,0.0,1740481191.7667212,23.539977550506592,0.0,1740481191.7667248,23.539977550506592,17.91679010690308,1740481191.7667272,23.539977550506592,0.0,1740481191.7667294,23.539977550506592,0.0,1740481191.7667315,23.539977550506592,0.0,1740481191.7667344,23.539977550506592,0.0,1740481191.7667363,23.539977550506592,0.0,1740481191.7667382,23.539977550506592,-2.0,1740481191.7667406,23.539977550506592,-2.4583950534515386,1740481191.7667422,23.539977550506592,0.0,1740481191.7667446,23.539977550506592,0.45839505345153864,, +1740481191.7835867,23.559977531433105,15.174149345866248,1740481191.7835891,23.559977531433105,0.0,1740481191.783593,23.559977531433105,0.0,1740481191.7835956,23.559977531433105,17.91679010690308,1740481191.7835968,23.559977531433105,0.0,1740481191.783599,23.559977531433105,0.0,1740481191.7836,23.559977531433105,0.0,1740481191.7836015,23.559977531433105,0.0,1740481191.7836032,23.559977531433105,0.0,1740481191.7836056,23.559977531433105,-2.0,1740481191.7836068,23.559977531433105,-2.4583950534515386,1740481191.783608,23.559977531433105,0.0,1740481191.7836092,23.559977531433105,0.45839505345153864,, +1740481191.8037322,23.57997751235962,15.174149345866248,1740481191.8037336,23.57997751235962,0.0,1740481191.8037357,23.57997751235962,0.0,1740481191.8037379,23.57997751235962,17.91679010690308,1740481191.8037388,23.57997751235962,0.0,1740481191.8037403,23.57997751235962,0.0,1740481191.8037412,23.57997751235962,0.0,1740481191.803742,23.57997751235962,0.0,1740481191.803743,23.57997751235962,0.0,1740481191.803744,23.57997751235962,-2.0,1740481191.803745,23.57997751235962,-2.4583950534515386,1740481191.8037457,23.57997751235962,0.0,1740481191.8037465,23.57997751235962,0.45839505345153864,, +1740481191.8237088,23.599977493286133,15.174149345866248,1740481191.8237102,23.599977493286133,0.0,1740481191.8237126,23.599977493286133,0.0,1740481191.8237143,23.599977493286133,17.91679010690308,1740481191.8237152,23.599977493286133,0.0,1740481191.8237166,23.599977493286133,0.0,1740481191.8237176,23.599977493286133,0.0,1740481191.823719,23.599977493286133,0.0,1740481191.82372,23.599977493286133,0.0,1740481191.823721,23.599977493286133,-2.0,1740481191.8237216,23.599977493286133,-2.4583950534515386,1740481191.8237228,23.599977493286133,0.0,1740481191.8237236,23.599977493286133,0.45839505345153864,, +1740481191.844567,23.619977474212646,15.174149345866248,1740481191.8445685,23.619977474212646,0.0,1740481191.844571,23.619977474212646,0.0,1740481191.8445733,23.619977474212646,17.91679010690308,1740481191.8445742,23.619977474212646,0.0,1740481191.8445756,23.619977474212646,0.0,1740481191.8445766,23.619977474212646,0.0,1740481191.8445778,23.619977474212646,0.0,1740481191.844579,23.619977474212646,0.0,1740481191.84458,23.619977474212646,-2.0,1740481191.844581,23.619977474212646,-2.4583950534515386,1740481191.8445818,23.619977474212646,0.0,1740481191.8445826,23.619977474212646,0.45839505345153864,, +1740481191.865459,23.63997745513916,15.219072801745913,1740481191.8654604,23.63997745513916,0.0,1740481191.8654628,23.63997745513916,0.0,1740481191.865465,23.63997745513916,17.696790106903077,1740481191.8654659,23.63997745513916,0.0,1740481191.865467,23.63997745513916,0.0,1740481191.8654683,23.63997745513916,0.0,1740481191.8654692,23.63997745513916,0.0,1740481191.8654702,23.63997745513916,0.0,1740481191.8654711,23.63997745513916,-2.0,1740481191.8654723,23.63997745513916,-2.298395005767777,1740481191.865473,23.63997745513916,0.0,1740481191.865474,23.63997745513916,0.34839505345153854,, +1740481191.884009,23.659977436065674,15.219072801745913,1740481191.8840106,23.659977436065674,0.0,1740481191.8840127,23.659977436065674,0.0,1740481191.8840148,23.659977436065674,17.696790106903077,1740481191.8840158,23.659977436065674,0.0,1740481191.8840172,23.659977436065674,0.0,1740481191.8840182,23.659977436065674,0.0,1740481191.8840191,23.659977436065674,0.0,1740481191.8840203,23.659977436065674,0.0,1740481191.8840213,23.659977436065674,-2.0,1740481191.8840222,23.659977436065674,-2.3483950534515383,1740481191.884023,23.659977436065674,0.0,1740481191.884024,23.659977436065674,0.34839505345153854,, +1740481191.9037619,23.679977416992188,15.219072801745913,1740481191.9037635,23.679977416992188,0.0,1740481191.9037654,23.679977416992188,0.0,1740481191.9037676,23.679977416992188,17.696790106903077,1740481191.9037688,23.679977416992188,0.0,1740481191.9037702,23.679977416992188,0.0,1740481191.9037712,23.679977416992188,0.0,1740481191.903772,23.679977416992188,0.0,1740481191.9037728,23.679977416992188,0.0,1740481191.903774,23.679977416992188,-2.0,1740481191.903775,23.679977416992188,-2.3483950534515383,1740481191.903776,23.679977416992188,0.0,1740481191.903777,23.679977416992188,0.34839505345153854,, +1740481191.924058,23.6999773979187,15.219072801745913,1740481191.9240594,23.6999773979187,0.0,1740481191.9240615,23.6999773979187,0.0,1740481191.9240634,23.6999773979187,17.696790106903077,1740481191.9240642,23.6999773979187,0.0,1740481191.9240656,23.6999773979187,0.0,1740481191.9240665,23.6999773979187,0.0,1740481191.9240673,23.6999773979187,0.0,1740481191.9240685,23.6999773979187,0.0,1740481191.9240694,23.6999773979187,-2.0,1740481191.9240701,23.6999773979187,-2.3483950534515383,1740481191.924071,23.6999773979187,0.0,1740481191.924072,23.6999773979187,0.34839505345153854,, +1740481191.9437916,23.719977378845215,15.219072801745913,1740481191.943793,23.719977378845215,0.0,1740481191.9437954,23.719977378845215,0.0,1740481191.9437978,23.719977378845215,17.696790106903077,1740481191.9437988,23.719977378845215,0.0,1740481191.9438,23.719977378845215,0.0,1740481191.9438012,23.719977378845215,0.0,1740481191.943802,23.719977378845215,0.0,1740481191.943803,23.719977378845215,0.0,1740481191.9438038,23.719977378845215,-2.0,1740481191.943805,23.719977378845215,-2.3483950534515383,1740481191.943806,23.719977378845215,0.0,1740481191.9438066,23.719977378845215,0.34839505345153854,, +1740481191.964399,23.73997735977173,15.251896257625582,1740481191.964401,23.73997735977173,0.0,1740481191.9644027,23.73997735977173,0.0,1740481191.9644048,23.73997735977173,17.476790106903078,1740481191.9644058,23.73997735977173,0.0,1740481191.964407,23.73997735977173,0.0,1740481191.9644082,23.73997735977173,0.0,1740481191.964409,23.73997735977173,0.0,1740481191.96441,23.73997735977173,0.0,1740481191.9644108,23.73997735977173,-2.0,1740481191.964412,23.73997735977173,-2.1883950057677772,1740481191.9644127,23.73997735977173,0.0,1740481191.964414,23.73997735977173,0.23839505345153844,, +1740481191.9853487,23.759977340698242,15.251896257625582,1740481191.9853501,23.759977340698242,0.0,1740481191.9853523,23.759977340698242,0.0,1740481191.985354,23.759977340698242,17.476790106903078,1740481191.985355,23.759977340698242,0.0,1740481191.9853563,23.759977340698242,0.0,1740481191.9853573,23.759977340698242,0.0,1740481191.985358,23.759977340698242,0.0,1740481191.9853592,23.759977340698242,0.0,1740481191.98536,23.759977340698242,-2.0,1740481191.9853837,23.759977340698242,-2.2383950534515384,1740481191.9853857,23.759977340698242,0.0,1740481191.9853866,23.759977340698242,0.23839505345153844,, +1740481192.0035179,23.779977321624756,15.251896257625582,1740481192.0035198,23.779977321624756,0.0,1740481192.0035217,23.779977321624756,0.0,1740481192.0035236,23.779977321624756,17.476790106903078,1740481192.0035245,23.779977321624756,0.0,1740481192.003526,23.779977321624756,0.0,1740481192.0035267,23.779977321624756,0.0,1740481192.0035276,23.779977321624756,0.0,1740481192.0035286,23.779977321624756,0.0,1740481192.0035295,23.779977321624756,-2.0,1740481192.0035305,23.779977321624756,-2.2383950534515384,1740481192.0035312,23.779977321624756,0.0,1740481192.003532,23.779977321624756,0.23839505345153844,, +1740481192.0238469,23.79997730255127,15.251896257625582,1740481192.0238485,23.79997730255127,0.0,1740481192.0238507,23.79997730255127,0.0,1740481192.0238528,23.79997730255127,17.476790106903078,1740481192.0238535,23.79997730255127,0.0,1740481192.0238547,23.79997730255127,0.0,1740481192.023856,23.79997730255127,0.0,1740481192.0238569,23.79997730255127,0.0,1740481192.0238576,23.79997730255127,0.0,1740481192.0238588,23.79997730255127,-2.0,1740481192.0238595,23.79997730255127,-2.2383950534515384,1740481192.0238602,23.79997730255127,0.0,1740481192.0238612,23.79997730255127,0.23839505345153844,, +1740481192.0438921,23.819977283477783,15.251896257625582,1740481192.0438948,23.819977283477783,0.0,1740481192.043898,23.819977283477783,0.0,1740481192.043901,23.819977283477783,17.476790106903078,1740481192.0439034,23.819977283477783,0.0,1740481192.0439053,23.819977283477783,0.0,1740481192.0439079,23.819977283477783,0.0,1740481192.0439093,23.819977283477783,0.0,1740481192.0439107,23.819977283477783,0.0,1740481192.043912,23.819977283477783,-2.0,1740481192.0439134,23.819977283477783,-2.2383950534515384,1740481192.043917,23.819977283477783,0.0,1740481192.0439193,23.819977283477783,0.23839505345153844,, +1740481192.0679157,23.839977264404297,15.251896257625582,1740481192.0679176,23.839977264404297,0.0,1740481192.0679197,23.839977264404297,0.0,1740481192.0679216,23.839977264404297,17.476790106903078,1740481192.0679226,23.839977264404297,0.0,1740481192.067924,23.839977264404297,0.0,1740481192.0679247,23.839977264404297,0.0,1740481192.0679257,23.839977264404297,0.0,1740481192.067927,23.839977264404297,0.0,1740481192.0679278,23.839977264404297,-2.0,1740481192.0679286,23.839977264404297,-2.2383950534515384,1740481192.0679293,23.839977264404297,0.0,1740481192.0679305,23.839977264404297,0.23839505345153844,, +1740481192.0840538,23.85997724533081,15.272619713505254,1740481192.0840552,23.85997724533081,0.0,1740481192.0840573,23.85997724533081,0.0,1740481192.0840592,23.85997724533081,17.256790106903075,1740481192.0840602,23.85997724533081,0.0,1740481192.0840614,23.85997724533081,0.0,1740481192.0840745,23.85997724533081,0.0,1740481192.084076,23.85997724533081,0.0,1740481192.0840771,23.85997724533081,0.0,1740481192.084078,23.85997724533081,-2.0,1740481192.0840788,23.85997724533081,-2.0783950057677774,1740481192.08408,23.85997724533081,0.0,1740481192.0840807,23.85997724533081,0.12839505345153834,, +1740481192.1036847,23.879977226257324,15.272619713505254,1740481192.103686,23.879977226257324,0.0,1740481192.1036882,23.879977226257324,0.0,1740481192.10369,23.879977226257324,17.256790106903075,1740481192.103691,23.879977226257324,0.0,1740481192.1036923,23.879977226257324,0.0,1740481192.103693,23.879977226257324,0.0,1740481192.103694,23.879977226257324,0.0,1740481192.1036952,23.879977226257324,0.0,1740481192.1036959,23.879977226257324,-2.0,1740481192.1036968,23.879977226257324,-2.1283950534515386,1740481192.103698,23.879977226257324,0.0,1740481192.103699,23.879977226257324,0.12839505345153834,, +1740481192.123871,23.899977207183838,15.272619713505254,1740481192.1238725,23.899977207183838,0.0,1740481192.1238747,23.899977207183838,0.0,1740481192.1238763,23.899977207183838,17.256790106903075,1740481192.1238773,23.899977207183838,0.0,1740481192.1238785,23.899977207183838,0.0,1740481192.1238794,23.899977207183838,0.0,1740481192.1238801,23.899977207183838,0.0,1740481192.123881,23.899977207183838,0.0,1740481192.1238823,23.899977207183838,-2.0,1740481192.123883,23.899977207183838,-2.1283950534515386,1740481192.123884,23.899977207183838,0.0,1740481192.123885,23.899977207183838,0.12839505345153834,, +1740481192.1439178,23.91997718811035,15.272619713505254,1740481192.1439195,23.91997718811035,0.0,1740481192.1439216,23.91997718811035,0.0,1740481192.1439235,23.91997718811035,17.256790106903075,1740481192.1439245,23.91997718811035,0.0,1740481192.1439257,23.91997718811035,0.0,1740481192.1439269,23.91997718811035,0.0,1740481192.1439278,23.91997718811035,0.0,1740481192.1439288,23.91997718811035,0.0,1740481192.1439295,23.91997718811035,-2.0,1740481192.1439307,23.91997718811035,-2.1283950534515386,1740481192.1439314,23.91997718811035,0.0,1740481192.1439323,23.91997718811035,0.12839505345153834,, +1740481192.1636214,23.939977169036865,15.272619713505254,1740481192.163623,23.939977169036865,0.0,1740481192.1636379,23.939977169036865,0.0,1740481192.1636403,23.939977169036865,17.256790106903075,1740481192.1636415,23.939977169036865,0.0,1740481192.1636426,23.939977169036865,0.0,1740481192.1636438,23.939977169036865,0.0,1740481192.163645,23.939977169036865,0.0,1740481192.163646,23.939977169036865,0.0,1740481192.163647,23.939977169036865,-2.0,1740481192.1636477,23.939977169036865,-2.1283950534515386,1740481192.1636486,23.939977169036865,0.0,1740481192.1636496,23.939977169036865,0.12839505345153834,, +1740481192.1833954,23.95997714996338,15.281243169384922,1740481192.183397,23.95997714996338,0.0,1740481192.1833992,23.95997714996338,0.0,1740481192.183401,23.95997714996338,17.036790106903076,1740481192.1834023,23.95997714996338,0.0,1740481192.1834035,23.95997714996338,0.0,1740481192.1834044,23.95997714996338,0.0,1740481192.1834056,23.95997714996338,0.0,1740481192.1834066,23.95997714996338,0.0,1740481192.1834075,23.95997714996338,-2.0,1740481192.1834087,23.95997714996338,-1.968395005767777,1740481192.1834097,23.95997714996338,0.0,1740481192.1834104,23.95997714996338,0.018395053451538364,, +1740481192.2042024,23.979977130889893,15.281243169384922,1740481192.204204,23.979977130889893,0.0,1740481192.204206,23.979977130889893,0.0,1740481192.2042081,23.979977130889893,17.036790106903076,1740481192.204209,23.979977130889893,0.0,1740481192.2042103,23.979977130889893,0.0,1740481192.2042112,23.979977130889893,0.0,1740481192.2042122,23.979977130889893,0.0,1740481192.2042131,23.979977130889893,0.0,1740481192.204214,23.979977130889893,-2.0,1740481192.204215,23.979977130889893,-2.0183950534515382,1740481192.2042158,23.979977130889893,0.0,1740481192.2042165,23.979977130889893,0.018395053451538364,, +1740481192.223328,23.999977111816406,15.281243169384922,1740481192.2233298,23.999977111816406,0.0,1740481192.223333,23.999977111816406,0.0,1740481192.223335,23.999977111816406,17.036790106903076,1740481192.2233357,23.999977111816406,0.0,1740481192.223337,23.999977111816406,0.0,1740481192.223338,23.999977111816406,0.0,1740481192.2233388,23.999977111816406,0.0,1740481192.2233398,23.999977111816406,0.0,1740481192.2233407,23.999977111816406,-2.0,1740481192.2233415,23.999977111816406,-2.0183950534515382,1740481192.2233424,23.999977111816406,0.0,1740481192.2233434,23.999977111816406,0.018395053451538364,, +1740481192.2453547,24.01997709274292,15.281243169384922,1740481192.2453563,24.01997709274292,0.0,1740481192.2453582,24.01997709274292,0.0,1740481192.2453604,24.01997709274292,17.036790106903076,1740481192.2453613,24.01997709274292,0.0,1740481192.2453625,24.01997709274292,0.0,1740481192.2453635,24.01997709274292,0.0,1740481192.2453644,24.01997709274292,0.0,1740481192.2453656,24.01997709274292,0.0,1740481192.2453663,24.01997709274292,-2.0,1740481192.2453673,24.01997709274292,-2.0183950534515382,1740481192.245368,24.01997709274292,0.0,1740481192.2453692,24.01997709274292,0.018395053451538364,, +1740481192.2671142,24.039977073669434,15.281243169384922,1740481192.267116,24.039977073669434,0.0,1740481192.2671185,24.039977073669434,0.0,1740481192.2671204,24.039977073669434,17.036790106903076,1740481192.267121,24.039977073669434,0.0,1740481192.2671227,24.039977073669434,0.0,1740481192.2671235,24.039977073669434,0.0,1740481192.2671247,24.039977073669434,0.0,1740481192.2671258,24.039977073669434,0.0,1740481192.2671268,24.039977073669434,-2.0,1740481192.2671275,24.039977073669434,-2.0183950534515382,1740481192.2671282,24.039977073669434,0.0,1740481192.2671294,24.039977073669434,0.018395053451538364,, +1740481192.2861936,24.059977054595947,15.281243169384922,1740481192.2861962,24.059977054595947,0.0,1740481192.2861996,24.059977054595947,0.0,1740481192.286203,24.059977054595947,17.036790106903076,1740481192.2862043,24.059977054595947,0.0,1740481192.2862065,24.059977054595947,0.0,1740481192.286208,24.059977054595947,0.0,1740481192.2862098,24.059977054595947,0.0,1740481192.2862115,24.059977054595947,0.0,1740481192.2862132,24.059977054595947,-2.0,1740481192.2862146,24.059977054595947,-2.0183950534515382,1740481192.2862163,24.059977054595947,0.0,1740481192.2862177,24.059977054595947,0.018395053451538364,, +1740481192.303992,24.069977045059204,15.281511070453956,1740481192.3039954,24.069977045059204,0.0,1740481192.3040006,24.069977045059204,0.0,1740481192.3040051,24.069977045059204,17.0,1740481192.3040075,24.069977045059204,0.0,1740481192.3040109,24.069977045059204,0.0,1740481192.3040133,24.069977045059204,0.0,1740481192.3040159,24.069977045059204,0.0,1740481192.3040185,24.069977045059204,0.0,1740481192.304021,24.069977045059204,-2.0,1740481192.3040235,24.069977045059204,-1.991638604093434,1740481192.304026,24.069977045059204,0.0,1740481192.3040285,24.069977045059204,0.0,, +1740481192.3240838,24.099977016448975,15.281511070453956,1740481192.3240852,24.099977016448975,0.0,1740481192.3240874,24.099977016448975,0.0,1740481192.324089,24.099977016448975,17.0,1740481192.32409,24.099977016448975,0.0,1740481192.3240914,24.099977016448975,0.0,1740481192.3240924,24.099977016448975,0.0,1740481192.324093,24.099977016448975,0.0,1740481192.3240943,24.099977016448975,0.0,1740481192.324095,24.099977016448975,-2.0,1740481192.324096,24.099977016448975,-2.0,1740481192.3240967,24.099977016448975,0.0,1740481192.3240979,24.099977016448975,0.0,, +1740481192.343841,24.11997699737549,15.281511070453956,1740481192.3438432,24.11997699737549,0.0,1740481192.3438468,24.11997699737549,0.0,1740481192.3438494,24.11997699737549,17.0,1740481192.343851,24.11997699737549,0.0,1740481192.3438535,24.11997699737549,0.0,1740481192.3438554,24.11997699737549,0.0,1740481192.3438566,24.11997699737549,0.0,1740481192.343859,24.11997699737549,0.0,1740481192.3438601,24.11997699737549,-2.0,1740481192.3438623,24.11997699737549,-2.0,1740481192.3438635,24.11997699737549,0.0,1740481192.3438652,24.11997699737549,0.0,, +1740481192.3641067,24.139976978302002,15.281511070453956,1740481192.3641086,24.139976978302002,0.0,1740481192.364111,24.139976978302002,0.0,1740481192.3641129,24.139976978302002,17.0,1740481192.3641138,24.139976978302002,0.0,1740481192.3641152,24.139976978302002,0.0,1740481192.3641164,24.139976978302002,0.0,1740481192.3641176,24.139976978302002,0.0,1740481192.3641188,24.139976978302002,0.0,1740481192.3641198,24.139976978302002,-2.0,1740481192.3641207,24.139976978302002,-2.0,1740481192.364122,24.139976978302002,0.0,1740481192.3641229,24.139976978302002,0.0,, +1740481192.3851168,24.159976959228516,15.281511070453956,1740481192.3851185,24.159976959228516,0.0,1740481192.3851209,24.159976959228516,0.0,1740481192.385123,24.159976959228516,17.0,1740481192.3851242,24.159976959228516,0.0,1740481192.3851254,24.159976959228516,0.0,1740481192.3851264,24.159976959228516,0.0,1740481192.385127,24.159976959228516,0.0,1740481192.3851283,24.159976959228516,0.0,1740481192.3851292,24.159976959228516,-2.0,1740481192.38513,24.159976959228516,-2.0,1740481192.3851311,24.159976959228516,0.0,1740481192.3851318,24.159976959228516,0.0,, +1740481192.4032497,24.17997694015503,15.281511070453956,1740481192.4032512,24.17997694015503,0.0,1740481192.4032536,24.17997694015503,0.0,1740481192.4032555,24.17997694015503,17.0,1740481192.403257,24.17997694015503,0.0,1740481192.4032583,24.17997694015503,0.0,1740481192.4032593,24.17997694015503,0.0,1740481192.4032605,24.17997694015503,0.0,1740481192.4032614,24.17997694015503,0.0,1740481192.4032624,24.17997694015503,-2.0,1740481192.403264,24.17997694015503,-2.0,1740481192.403265,24.17997694015503,0.0,1740481192.403266,24.17997694015503,0.0,, +1740481192.4237356,24.199976921081543,15.281511070453956,1740481192.4237373,24.199976921081543,0.0,1740481192.4237394,24.199976921081543,0.0,1740481192.4237416,24.199976921081543,17.0,1740481192.4237428,24.199976921081543,0.0,1740481192.423744,24.199976921081543,0.0,1740481192.423745,24.199976921081543,0.0,1740481192.423746,24.199976921081543,0.0,1740481192.4237473,24.199976921081543,0.0,1740481192.4237483,24.199976921081543,-2.0,1740481192.4237494,24.199976921081543,-2.0,1740481192.4237502,24.199976921081543,0.0,1740481192.423751,24.199976921081543,0.0,, +1740481192.443501,24.219976902008057,15.281511070453956,1740481192.4435031,24.219976902008057,0.0,1740481192.4435062,24.219976902008057,0.0,1740481192.4435084,24.219976902008057,17.0,1740481192.4435096,24.219976902008057,0.0,1740481192.443511,24.219976902008057,0.0,1740481192.443512,24.219976902008057,0.0,1740481192.4435134,24.219976902008057,0.0,1740481192.4435143,24.219976902008057,0.0,1740481192.4435153,24.219976902008057,-2.0,1740481192.4435165,24.219976902008057,-2.0,1740481192.4435172,24.219976902008057,0.0,1740481192.4435182,24.219976902008057,0.0,, +1740481192.4635289,24.23997688293457,15.281511070453956,1740481192.4635305,24.23997688293457,0.0,1740481192.4635327,24.23997688293457,0.0,1740481192.4635346,24.23997688293457,17.0,1740481192.4635355,24.23997688293457,0.0,1740481192.463537,24.23997688293457,0.0,1740481192.4635382,24.23997688293457,0.0,1740481192.463539,24.23997688293457,0.0,1740481192.4635403,24.23997688293457,0.0,1740481192.4635413,24.23997688293457,-2.0,1740481192.4635422,24.23997688293457,-2.0,1740481192.463543,24.23997688293457,0.0,1740481192.4635441,24.23997688293457,0.0,, +1740481192.4834015,24.259976863861084,15.281511070453956,1740481192.483403,24.259976863861084,0.0,1740481192.483405,24.259976863861084,0.0,1740481192.483407,24.259976863861084,17.0,1740481192.4834082,24.259976863861084,0.0,1740481192.4834094,24.259976863861084,0.0,1740481192.4834104,24.259976863861084,0.0,1740481192.4834116,24.259976863861084,0.0,1740481192.4834125,24.259976863861084,0.0,1740481192.4834137,24.259976863861084,-2.0,1740481192.4834144,24.259976863861084,-2.0,1740481192.4834156,24.259976863861084,0.0,1740481192.4834166,24.259976863861084,0.0,, +1740481192.5043275,24.279976844787598,15.281511070453956,1740481192.5043287,24.279976844787598,0.0,1740481192.504331,24.279976844787598,0.0,1740481192.5043328,24.279976844787598,17.0,1740481192.5043337,24.279976844787598,0.0,1740481192.5043352,24.279976844787598,0.0,1740481192.504336,24.279976844787598,0.0,1740481192.504337,24.279976844787598,0.0,1740481192.5043383,24.279976844787598,0.0,1740481192.5043392,24.279976844787598,-2.0,1740481192.5043402,24.279976844787598,-2.0,1740481192.504341,24.279976844787598,0.0,1740481192.504342,24.279976844787598,0.0,, +1740481192.5234709,24.29997682571411,15.281511070453956,1740481192.5234725,24.29997682571411,0.0,1740481192.523475,24.29997682571411,0.0,1740481192.5234768,24.29997682571411,17.0,1740481192.5234778,24.29997682571411,0.0,1740481192.5234792,24.29997682571411,0.0,1740481192.5234804,24.29997682571411,0.0,1740481192.5234816,24.29997682571411,0.0,1740481192.5234826,24.29997682571411,0.0,1740481192.5234838,24.29997682571411,-2.0,1740481192.5234847,24.29997682571411,-2.0,1740481192.5234854,24.29997682571411,0.0,1740481192.5234864,24.29997682571411,0.0,, +1740481192.5448976,24.319976806640625,15.281511070453956,1740481192.544899,24.319976806640625,0.0,1740481192.5449011,24.319976806640625,0.0,1740481192.5449033,24.319976806640625,17.0,1740481192.544904,24.319976806640625,0.0,1740481192.5449052,24.319976806640625,0.0,1740481192.5449061,24.319976806640625,0.0,1740481192.544907,24.319976806640625,0.0,1740481192.544908,24.319976806640625,0.0,1740481192.544909,24.319976806640625,-2.0,1740481192.5449097,24.319976806640625,-2.0,1740481192.544911,24.319976806640625,0.0,1740481192.5449119,24.319976806640625,0.0,, +1740481192.5671194,24.33997678756714,15.281511070453956,1740481192.5671206,24.33997678756714,0.0,1740481192.567123,24.33997678756714,0.0,1740481192.5671248,24.33997678756714,17.0,1740481192.5671258,24.33997678756714,0.0,1740481192.567127,24.33997678756714,0.0,1740481192.5671277,24.33997678756714,0.0,1740481192.567129,24.33997678756714,0.0,1740481192.5671299,24.33997678756714,0.0,1740481192.5671306,24.33997678756714,-2.0,1740481192.5671318,24.33997678756714,-2.0,1740481192.5671325,24.33997678756714,0.0,1740481192.5671334,24.33997678756714,0.0,, +1740481192.5836713,24.359976768493652,15.281511070453956,1740481192.5836728,24.359976768493652,0.0,1740481192.583675,24.359976768493652,0.0,1740481192.5836766,24.359976768493652,17.0,1740481192.5836775,24.359976768493652,0.0,1740481192.5836787,24.359976768493652,0.0,1740481192.5836797,24.359976768493652,0.0,1740481192.5836809,24.359976768493652,0.0,1740481192.5836816,24.359976768493652,0.0,1740481192.5836825,24.359976768493652,-2.0,1740481192.5836973,24.359976768493652,-2.0,1740481192.5836985,24.359976768493652,0.0,1740481192.5836992,24.359976768493652,0.0,, +1740481192.6034124,24.379976749420166,15.281511070453956,1740481192.603414,24.379976749420166,0.0,1740481192.603416,24.379976749420166,0.0,1740481192.6034179,24.379976749420166,17.0,1740481192.6034188,24.379976749420166,0.0,1740481192.6034203,24.379976749420166,0.0,1740481192.6034212,24.379976749420166,0.0,1740481192.6034222,24.379976749420166,0.0,1740481192.6034229,24.379976749420166,0.0,1740481192.603424,24.379976749420166,-2.0,1740481192.6034248,24.379976749420166,-2.0,1740481192.6034255,24.379976749420166,0.0,1740481192.6034265,24.379976749420166,0.0,, +1740481192.627083,24.39997673034668,15.281511070453956,1740481192.6270845,24.39997673034668,0.0,1740481192.6270864,24.39997673034668,0.0,1740481192.6270883,24.39997673034668,17.0,1740481192.6270895,24.39997673034668,0.0,1740481192.6271114,24.39997673034668,0.0,1740481192.6271122,24.39997673034668,0.0,1740481192.627113,24.39997673034668,0.0,1740481192.6271143,24.39997673034668,0.0,1740481192.627115,24.39997673034668,-2.0,1740481192.627116,24.39997673034668,-2.0,1740481192.627117,24.39997673034668,0.0,1740481192.6271179,24.39997673034668,0.0,, +1740481192.646052,24.419976711273193,15.281511070453956,1740481192.6460533,24.419976711273193,0.0,1740481192.6460557,24.419976711273193,0.0,1740481192.6460578,24.419976711273193,17.0,1740481192.6460588,24.419976711273193,0.0,1740481192.64606,24.419976711273193,0.0,1740481192.646061,24.419976711273193,0.0,1740481192.6460621,24.419976711273193,0.0,1740481192.646063,24.419976711273193,0.0,1740481192.6460638,24.419976711273193,-2.0,1740481192.646065,24.419976711273193,-2.0,1740481192.6460657,24.419976711273193,0.0,1740481192.6460667,24.419976711273193,0.0,, +1740481192.665968,24.439976692199707,15.281511070453956,1740481192.6659694,24.439976692199707,0.0,1740481192.6659718,24.439976692199707,0.0,1740481192.6659882,24.439976692199707,17.0,1740481192.6659894,24.439976692199707,0.0,1740481192.6659908,24.439976692199707,0.0,1740481192.665992,24.439976692199707,0.0,1740481192.665993,24.439976692199707,0.0,1740481192.665994,24.439976692199707,0.0,1740481192.6659951,24.439976692199707,-2.0,1740481192.665996,24.439976692199707,-2.0,1740481192.6659968,24.439976692199707,0.0,1740481192.6659977,24.439976692199707,0.0,, +1740481192.6843987,24.45997667312622,15.281511070453956,1740481192.6844,24.45997667312622,0.0,1740481192.6844022,24.45997667312622,0.0,1740481192.6844041,24.45997667312622,17.0,1740481192.6844056,24.45997667312622,0.0,1740481192.6844068,24.45997667312622,0.0,1740481192.6844077,24.45997667312622,0.0,1740481192.684409,24.45997667312622,0.0,1740481192.68441,24.45997667312622,0.0,1740481192.6844108,24.45997667312622,-2.0,1740481192.6844122,24.45997667312622,-2.0,1740481192.6844132,24.45997667312622,0.0,1740481192.684414,24.45997667312622,0.0,, +1740481192.7032652,24.479976654052734,15.281511070453956,1740481192.703267,24.479976654052734,0.0,1740481192.7032695,24.479976654052734,0.0,1740481192.7032974,24.479976654052734,17.0,1740481192.7032986,24.479976654052734,0.0,1740481192.7033,24.479976654052734,0.0,1740481192.7033012,24.479976654052734,0.0,1740481192.7033024,24.479976654052734,0.0,1740481192.7033033,24.479976654052734,0.0,1740481192.7033045,24.479976654052734,-2.0,1740481192.7033055,24.479976654052734,-2.0,1740481192.703329,24.479976654052734,0.0,1740481192.7033303,24.479976654052734,0.0,, +1740481192.7235148,24.499976634979248,15.281511070453956,1740481192.7235165,24.499976634979248,0.0,1740481192.7235186,24.499976634979248,0.0,1740481192.7235208,24.499976634979248,17.0,1740481192.7235215,24.499976634979248,0.0,1740481192.7235231,24.499976634979248,0.0,1740481192.723524,24.499976634979248,0.0,1740481192.723525,24.499976634979248,0.0,1740481192.7235265,24.499976634979248,0.0,1740481192.7235272,24.499976634979248,-2.0,1740481192.7235281,24.499976634979248,-2.0,1740481192.7235289,24.499976634979248,0.0,1740481192.72353,24.499976634979248,0.0,, +1740481192.7458577,24.51997661590576,15.281511070453956,1740481192.7458594,24.51997661590576,0.0,1740481192.7458615,24.51997661590576,0.0,1740481192.745864,24.51997661590576,17.0,1740481192.7458649,24.51997661590576,0.0,1740481192.7458665,24.51997661590576,0.0,1740481192.7458675,24.51997661590576,0.0,1740481192.7458692,24.51997661590576,0.0,1740481192.7458704,24.51997661590576,0.0,1740481192.7458713,24.51997661590576,-2.0,1740481192.7458725,24.51997661590576,-2.0,1740481192.7458735,24.51997661590576,0.0,1740481192.7458744,24.51997661590576,0.0,, +1740481192.7659786,24.539976596832275,15.281511070453956,1740481192.7659802,24.539976596832275,0.0,1740481192.7659822,24.539976596832275,0.0,1740481192.7659843,24.539976596832275,17.0,1740481192.7659853,24.539976596832275,0.0,1740481192.7659864,24.539976596832275,0.0,1740481192.7659874,24.539976596832275,0.0,1740481192.7659883,24.539976596832275,0.0,1740481192.7659893,24.539976596832275,0.0,1740481192.7659905,24.539976596832275,-2.0,1740481192.7659914,24.539976596832275,-2.0,1740481192.7659924,24.539976596832275,0.0,1740481192.7659934,24.539976596832275,0.0,, +1740481192.7833302,24.55997657775879,15.281511070453956,1740481192.783332,24.55997657775879,0.0,1740481192.7833343,24.55997657775879,0.0,1740481192.7833362,24.55997657775879,17.0,1740481192.783337,24.55997657775879,0.0,1740481192.7833385,24.55997657775879,0.0,1740481192.7833393,24.55997657775879,0.0,1740481192.7833402,24.55997657775879,0.0,1740481192.7833416,24.55997657775879,0.0,1740481192.7833426,24.55997657775879,-2.0,1740481192.7833436,24.55997657775879,-2.0,1740481192.7833443,24.55997657775879,0.0,1740481192.7833455,24.55997657775879,0.0,, +1740481192.803522,24.579976558685303,15.281511070453956,1740481192.8035233,24.579976558685303,0.0,1740481192.8035257,24.579976558685303,0.0,1740481192.8035274,24.579976558685303,17.0,1740481192.8035285,24.579976558685303,0.0,1740481192.8035297,24.579976558685303,0.0,1740481192.8035307,24.579976558685303,0.0,1740481192.803532,24.579976558685303,0.0,1740481192.8035328,24.579976558685303,0.0,1740481192.8035338,24.579976558685303,-2.0,1740481192.8035345,24.579976558685303,-2.0,1740481192.8035357,24.579976558685303,0.0,1740481192.8035367,24.579976558685303,0.0,, +1740481192.8234339,24.599976539611816,15.281511070453956,1740481192.8234358,24.599976539611816,0.0,1740481192.8234384,24.599976539611816,0.0,1740481192.8234406,24.599976539611816,17.0,1740481192.823442,24.599976539611816,0.0,1740481192.8234434,24.599976539611816,0.0,1740481192.8234444,24.599976539611816,0.0,1740481192.8234458,24.599976539611816,0.0,1740481192.8234468,24.599976539611816,0.0,1740481192.8234646,24.599976539611816,-2.0,1740481192.8234658,24.599976539611816,-2.0,1740481192.8234665,24.599976539611816,0.0,1740481192.8234675,24.599976539611816,0.0,, +1740481192.8436203,24.61997652053833,15.281511070453956,1740481192.8436217,24.61997652053833,0.0,1740481192.8436239,24.61997652053833,0.0,1740481192.8436258,24.61997652053833,17.0,1740481192.8436267,24.61997652053833,0.0,1740481192.843628,24.61997652053833,0.0,1740481192.8436291,24.61997652053833,0.0,1740481192.84363,24.61997652053833,0.0,1740481192.843631,24.61997652053833,0.0,1740481192.8436322,24.61997652053833,-2.0,1740481192.8436332,24.61997652053833,-2.0,1740481192.8436341,24.61997652053833,0.0,1740481192.8436348,24.61997652053833,0.0,, +1740481192.8649108,24.639976501464844,15.281511070453956,1740481192.8649123,24.639976501464844,0.0,1740481192.864915,24.639976501464844,0.0,1740481192.8649168,24.639976501464844,17.0,1740481192.8649178,24.639976501464844,0.0,1740481192.864919,24.639976501464844,0.0,1740481192.8649201,24.639976501464844,0.0,1740481192.864921,24.639976501464844,0.0,1740481192.8649223,24.639976501464844,0.0,1740481192.8649232,24.639976501464844,-2.0,1740481192.8649242,24.639976501464844,-2.0,1740481192.8649251,24.639976501464844,0.0,1740481192.8649259,24.639976501464844,0.0,, +1740481192.883603,24.659976482391357,15.281511070453956,1740481192.8836048,24.659976482391357,0.0,1740481192.8836071,24.659976482391357,0.0,1740481192.883609,24.659976482391357,17.0,1740481192.8836098,24.659976482391357,0.0,1740481192.8836114,24.659976482391357,0.0,1740481192.8836124,24.659976482391357,0.0,1740481192.8836133,24.659976482391357,0.0,1740481192.8836145,24.659976482391357,0.0,1740481192.8836155,24.659976482391357,-2.0,1740481192.8836164,24.659976482391357,-2.0,1740481192.8836176,24.659976482391357,0.0,1740481192.8836186,24.659976482391357,0.0,, +1740481192.903437,24.67997646331787,15.281511070453956,1740481192.9034383,24.67997646331787,0.0,1740481192.9034405,24.67997646331787,0.0,1740481192.903461,24.67997646331787,17.0,1740481192.9034948,24.67997646331787,0.0,1740481192.9034977,24.67997646331787,0.0,1740481192.9034991,24.67997646331787,0.0,1740481192.903516,24.67997646331787,0.0,1740481192.9035172,24.67997646331787,0.0,1740481192.9035182,24.67997646331787,-2.0,1740481192.9035192,24.67997646331787,-2.0,1740481192.9035203,24.67997646331787,0.0,1740481192.9035218,24.67997646331787,0.0,, +1740481192.9233878,24.699976444244385,15.281511070453956,1740481192.9233897,24.699976444244385,0.0,1740481192.9233918,24.699976444244385,0.0,1740481192.9233935,24.699976444244385,17.0,1740481192.923395,24.699976444244385,0.0,1740481192.923396,24.699976444244385,0.0,1740481192.9233968,24.699976444244385,0.0,1740481192.9233983,24.699976444244385,0.0,1740481192.9233992,24.699976444244385,0.0,1740481192.9234,24.699976444244385,-2.0,1740481192.9234009,24.699976444244385,-2.0,1740481192.9234018,24.699976444244385,0.0,1740481192.9234028,24.699976444244385,0.0,, +1740481192.9437807,24.7199764251709,15.281511070453956,1740481192.943782,24.7199764251709,0.0,1740481192.9437857,24.7199764251709,0.0,1740481192.9437883,24.7199764251709,17.0,1740481192.9437895,24.7199764251709,0.0,1740481192.9437919,24.7199764251709,0.0,1740481192.9437933,24.7199764251709,0.0,1740481192.9437954,24.7199764251709,0.0,1740481192.9437969,24.7199764251709,0.0,1740481192.9437983,24.7199764251709,-2.0,1740481192.9437995,24.7199764251709,-2.0,1740481192.9438007,24.7199764251709,0.0,1740481192.943802,24.7199764251709,0.0,, +1740481192.9660716,24.739976406097412,15.281511070453956,1740481192.9660728,24.739976406097412,0.0,1740481192.9660752,24.739976406097412,0.0,1740481192.9660769,24.739976406097412,17.0,1740481192.966078,24.739976406097412,0.0,1740481192.966079,24.739976406097412,0.0,1740481192.96608,24.739976406097412,0.0,1740481192.9660811,24.739976406097412,0.0,1740481192.9660823,24.739976406097412,0.0,1740481192.966083,24.739976406097412,-2.0,1740481192.966084,24.739976406097412,-2.0,1740481192.9660852,24.739976406097412,0.0,1740481192.966086,24.739976406097412,0.0,, +1740481192.9845502,24.759976387023926,15.281511070453956,1740481192.9845517,24.759976387023926,0.0,1740481192.984554,24.759976387023926,0.0,1740481192.984556,24.759976387023926,17.0,1740481192.9845572,24.759976387023926,0.0,1740481192.9845586,24.759976387023926,0.0,1740481192.9845598,24.759976387023926,0.0,1740481192.984561,24.759976387023926,0.0,1740481192.984562,24.759976387023926,0.0,1740481192.9845629,24.759976387023926,-2.0,1740481192.9845643,24.759976387023926,-2.0,1740481192.9845653,24.759976387023926,0.0,1740481192.9845665,24.759976387023926,0.0,, +1740481193.003372,24.77997636795044,15.281511070453956,1740481193.0033739,24.77997636795044,0.0,1740481193.0033762,24.77997636795044,0.0,1740481193.0033782,24.77997636795044,17.0,1740481193.003379,24.77997636795044,0.0,1740481193.0033805,24.77997636795044,0.0,1740481193.0033817,24.77997636795044,0.0,1740481193.0033827,24.77997636795044,0.0,1740481193.003384,24.77997636795044,0.0,1740481193.003385,24.77997636795044,-2.0,1740481193.0033858,24.77997636795044,-2.0,1740481193.003387,24.77997636795044,0.0,1740481193.003388,24.77997636795044,0.0,, +1740481193.0235133,24.799976348876953,15.281511070453956,1740481193.023515,24.799976348876953,0.0,1740481193.0235171,24.799976348876953,0.0,1740481193.023519,24.799976348876953,17.0,1740481193.02352,24.799976348876953,0.0,1740481193.0235214,24.799976348876953,0.0,1740481193.0235224,24.799976348876953,0.0,1740481193.0235236,24.799976348876953,0.0,1740481193.0235245,24.799976348876953,0.0,1740481193.0235257,24.799976348876953,-2.0,1740481193.0235267,24.799976348876953,-2.0,1740481193.0235276,24.799976348876953,0.0,1740481193.0235283,24.799976348876953,0.0,, +1740481193.0445082,24.819976329803467,15.281511070453956,1740481193.04451,24.819976329803467,0.0,1740481193.0445132,24.819976329803467,0.0,1740481193.0445166,24.819976329803467,17.0,1740481193.0445187,24.819976329803467,0.0,1740481193.0445201,24.819976329803467,0.0,1740481193.044522,24.819976329803467,0.0,1740481193.0445235,24.819976329803467,0.0,1740481193.0445256,24.819976329803467,0.0,1740481193.044527,24.819976329803467,-2.0,1740481193.0445285,24.819976329803467,-2.0,1740481193.0445297,24.819976329803467,0.0,1740481193.0445313,24.819976329803467,0.0,, +1740481193.0643969,24.83997631072998,15.281511070453956,1740481193.0643983,24.83997631072998,0.0,1740481193.0644004,24.83997631072998,0.0,1740481193.0644023,24.83997631072998,17.0,1740481193.0644035,24.83997631072998,0.0,1740481193.0644052,24.83997631072998,0.0,1740481193.064406,24.83997631072998,0.0,1740481193.064407,24.83997631072998,0.0,1740481193.0644083,24.83997631072998,0.0,1740481193.064409,24.83997631072998,-2.0,1740481193.0644102,24.83997631072998,-2.0,1740481193.064411,24.83997631072998,0.0,1740481193.0644119,24.83997631072998,0.0,, +1740481193.0840356,24.859976291656494,15.281511070453956,1740481193.084037,24.859976291656494,0.0,1740481193.0840394,24.859976291656494,0.0,1740481193.084041,24.859976291656494,17.0,1740481193.0840423,24.859976291656494,0.0,1740481193.0840433,24.859976291656494,0.0,1740481193.0840442,24.859976291656494,0.0,1740481193.0840454,24.859976291656494,0.0,1740481193.0840461,24.859976291656494,0.0,1740481193.0840473,24.859976291656494,-2.0,1740481193.0840483,24.859976291656494,-2.0,1740481193.0840497,24.859976291656494,0.0,1740481193.0840504,24.859976291656494,0.0,, +1740481193.1046572,24.879976272583008,15.281511070453956,1740481193.1046586,24.879976272583008,0.0,1740481193.1046607,24.879976272583008,0.0,1740481193.1046624,24.879976272583008,17.0,1740481193.1046636,24.879976272583008,0.0,1740481193.1046648,24.879976272583008,0.0,1740481193.104666,24.879976272583008,0.0,1740481193.1046672,24.879976272583008,0.0,1740481193.1046684,24.879976272583008,0.0,1740481193.1046693,24.879976272583008,-2.0,1740481193.1046705,24.879976272583008,-2.0,1740481193.1046715,24.879976272583008,0.0,1740481193.1046722,24.879976272583008,0.0,, +1740481193.1232307,24.89997625350952,15.281511070453956,1740481193.1232324,24.89997625350952,0.0,1740481193.1232347,24.89997625350952,0.0,1740481193.1232374,24.89997625350952,17.0,1740481193.1232386,24.89997625350952,0.0,1740481193.1232402,24.89997625350952,0.0,1740481193.1232414,24.89997625350952,0.0,1740481193.1232424,24.89997625350952,0.0,1740481193.1232438,24.89997625350952,0.0,1740481193.1232448,24.89997625350952,-2.0,1740481193.1232457,24.89997625350952,-2.0,1740481193.1232467,24.89997625350952,0.0,1740481193.1232479,24.89997625350952,0.0,, +1740481193.1448102,24.919976234436035,15.281511070453956,1740481193.144812,24.919976234436035,0.0,1740481193.1448157,24.919976234436035,0.0,1740481193.1448176,24.919976234436035,17.0,1740481193.1448188,24.919976234436035,0.0,1740481193.14482,24.919976234436035,0.0,1740481193.1448207,24.919976234436035,0.0,1740481193.1448221,24.919976234436035,0.0,1740481193.1448233,24.919976234436035,0.0,1740481193.1448243,24.919976234436035,-2.0,1740481193.1448255,24.919976234436035,-2.0,1740481193.1448262,24.919976234436035,0.0,1740481193.1448271,24.919976234436035,0.0,, +1740481193.165114,24.93997621536255,15.281511070453956,1740481193.1651154,24.93997621536255,0.0,1740481193.1651175,24.93997621536255,0.0,1740481193.1651194,24.93997621536255,17.0,1740481193.1651206,24.93997621536255,0.0,1740481193.1651218,24.93997621536255,0.0,1740481193.1651227,24.93997621536255,0.0,1740481193.1651242,24.93997621536255,0.0,1740481193.1651251,24.93997621536255,0.0,1740481193.165126,24.93997621536255,-2.0,1740481193.1651273,24.93997621536255,-2.0,1740481193.165128,24.93997621536255,0.0,1740481193.165129,24.93997621536255,0.0,, +1740481193.1845424,24.959976196289062,15.281511070453956,1740481193.184544,24.959976196289062,0.0,1740481193.1845465,24.959976196289062,0.0,1740481193.1845486,24.959976196289062,17.0,1740481193.1845496,24.959976196289062,0.0,1740481193.1845512,24.959976196289062,0.0,1740481193.1845522,24.959976196289062,0.0,1740481193.1845531,24.959976196289062,0.0,1740481193.1845546,24.959976196289062,0.0,1740481193.1845553,24.959976196289062,-2.0,1740481193.1845562,24.959976196289062,-2.0,1740481193.1845572,24.959976196289062,0.0,1740481193.1845584,24.959976196289062,0.0,, +1740481193.2037578,24.979976177215576,15.281511070453956,1740481193.2037594,24.979976177215576,0.0,1740481193.2037613,24.979976177215576,0.0,1740481193.2037632,24.979976177215576,17.0,1740481193.2037644,24.979976177215576,0.0,1740481193.2037659,24.979976177215576,0.0,1740481193.2037668,24.979976177215576,0.0,1740481193.2037675,24.979976177215576,0.0,1740481193.2037692,24.979976177215576,0.0,1740481193.2037702,24.979976177215576,-2.0,1740481193.203771,24.979976177215576,-2.0,1740481193.2037718,24.979976177215576,0.0,1740481193.203773,24.979976177215576,0.0,, +1740481193.2235699,24.99997615814209,15.281511070453956,1740481193.2235715,24.99997615814209,0.0,1740481193.2235734,24.99997615814209,0.0,1740481193.2235758,24.99997615814209,17.0,1740481193.2235768,24.99997615814209,0.0,1740481193.2235782,24.99997615814209,0.0,1740481193.223579,24.99997615814209,0.0,1740481193.22358,24.99997615814209,0.0,1740481193.2235808,24.99997615814209,0.0,1740481193.223582,24.99997615814209,-2.0,1740481193.2235827,24.99997615814209,-2.0,1740481193.2235837,24.99997615814209,0.0,1740481193.2235847,24.99997615814209,0.0,, +1740481193.2437491,25.019976139068604,15.281511070453956,1740481193.2437506,25.019976139068604,0.0,1740481193.243753,25.019976139068604,0.0,1740481193.2437549,25.019976139068604,17.0,1740481193.243756,25.019976139068604,0.0,1740481193.2437572,25.019976139068604,0.0,1740481193.2437584,25.019976139068604,0.0,1740481193.2437596,25.019976139068604,0.0,1740481193.2437606,25.019976139068604,0.0,1740481193.243762,25.019976139068604,-2.0,1740481193.243763,25.019976139068604,-2.0,1740481193.2437637,25.019976139068604,0.0,1740481193.2437646,25.019976139068604,0.0,, +1740481193.2646139,25.039976119995117,15.281511070453956,1740481193.2646155,25.039976119995117,0.0,1740481193.2646174,25.039976119995117,0.0,1740481193.2646196,25.039976119995117,17.0,1740481193.2646203,25.039976119995117,0.0,1740481193.2646215,25.039976119995117,0.0,1740481193.264623,25.039976119995117,0.0,1740481193.2646239,25.039976119995117,0.0,1740481193.2646248,25.039976119995117,0.0,1740481193.264626,25.039976119995117,-2.0,1740481193.264627,25.039976119995117,-2.0,1740481193.2646277,25.039976119995117,0.0,1740481193.2646286,25.039976119995117,0.0,, +1740481193.2834897,25.05997610092163,15.281511070453956,1740481193.2834914,25.05997610092163,0.0,1740481193.2834935,25.05997610092163,0.0,1740481193.2834954,25.05997610092163,17.0,1740481193.2834964,25.05997610092163,0.0,1740481193.2834978,25.05997610092163,0.0,1740481193.2834988,25.05997610092163,0.0,1740481193.2834997,25.05997610092163,0.0,1740481193.283501,25.05997610092163,0.0,1740481193.2835019,25.05997610092163,-2.0,1740481193.2835028,25.05997610092163,-2.0,1740481193.2835035,25.05997610092163,0.0,1740481193.2835045,25.05997610092163,0.0,, diff --git a/tuning logs/2025-02-25_02-59-27/behavior.json b/tuning logs/2025-02-25_02-59-27/behavior.json new file mode 100644 index 000000000..5da32160f --- /dev/null +++ b/tuning logs/2025-02-25_02-59-27/behavior.json @@ -0,0 +1,2834 @@ +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.303631, "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": 1740481167.323631} +{"agents": {}, "time": 1740481167.323631} +{"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": 1740481167.323631} +{"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": 1740481167.343631} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.0, 0.0], [0.010000000000000002, 0.0], [0.04000000000000001, 0.0], [0.09000000000000002, 0.0], [0.16000000000000003, 0.0], [0.25, 0.0], [0.36, 0.0], [0.4899999999999999, 0.0], [0.6399999999999999, 0.0], [0.80302717900324, 0.0], [0.9030271790032401, 0.0], [1.0030271790032401, 0.0], [1.1030271790032402, 0.0], [1.2030271790032403, 0.0], [1.3030271790032404, 0.0], [1.4030271790032405, 0.0], [1.5030271790032406, 0.0], [1.6030271790032407, 0.0], [1.7030271790032407, 0.0], [1.8030271790032408, 0.0], [1.903027179003241, 0.0], [2.003027179003241, 0.0], [2.103027179003241, 0.0], [2.203027179003241, 0.0], [2.3030271790032413, 0.0], [2.4030271790032414, 0.0], [2.5030271790032415, 0.0], [2.6030271790032415, 0.0], [2.7030271790032416, 0.0], [2.8030271790032413, 0.0], [2.903027179003242, 0.0], [3.0030271790032415, 0.0], [3.103027179003242, 0.0], [3.2030271790032416, 0.0], [3.303027179003242, 0.0], [3.403027179003242, 0.0], [3.5030271790032415, 0.0], [3.603027179003241, 0.0], [3.7030271790032407, 0.0], [3.8030271790032404, 0.0], [3.90302717900324, 0.0], [4.00302717900324, 0.0], [4.10302717900324, 0.0], [4.203027179003239, 0.0], [4.303027179003239, 0.0], [4.403027179003239, 0.0], [4.503027179003238, 0.0], [4.603027179003238, 0.0], [4.703027179003238, 0.0], [4.803027179003237, 0.0], [4.903027179003237, 0.0], [5.003027179003237, 0.0], [5.103027179003236, 0.0], [5.203027179003236, 0.0], [5.3030271790032355, 0.0], [5.403027179003235, 0.0], [5.503027179003235, 0.0], [5.603027179003234, 0.0], [5.703027179003234, 0.0], [5.803027179003234, 0.0], [5.903027179003233, 0.0], [6.003027179003233, 0.0], [6.103027179003233, 0.0], [6.203027179003232, 0.0], [6.303027179003232, 0.0], [6.403027179003232, 0.0], [6.503027179003231, 0.0], [6.603027179003231, 0.0], [6.7030271790032305, 0.0], [6.80302717900323, 0.0], [6.90302717900323, 0.0], [7.0030271790032295, 0.0], [7.103027179003229, 0.0], [7.203027179003229, 0.0], [7.303027179003228, 0.0], [7.403027179003228, 0.0], [7.503027179003228, 0.0], [7.603027179003227, 0.0], [7.703027179003227, 0.0], [7.803027179003227, 0.0], [7.903027179003226, 0.0], [8.003027179003226, 0.0], [8.103027179003226, 0.0], [8.203027179003225, 0.0], [8.303027179003225, 0.0], [8.403027179003224, 0.0], [8.503027179003224, 0.0], [8.603027179003224, 0.0], [8.703027179003222, 0.0], [8.803027179003221, 0.0], [8.903027179003221, 0.0], [9.00302717900322, 0.0], [9.10302717900322, 0.0], [9.20302717900322, 0.0], [9.30302717900322, 0.0], [9.40302717900322, 0.0], [9.503027179003219, 0.0], [9.603027179003218, 0.0], [9.703027179003218, 0.0], [9.803027179003218, 0.0], [9.903027179003217, 0.0], [10.003027179003217, 0.0], [10.103027179003217, 0.0], [10.203027179003216, 0.0], [10.303027179003216, 0.0], [10.403027179003216, 0.0], [10.503027179003215, 0.0], [10.603027179003215, 0.0], [10.703027179003215, 0.0], [10.803027179003214, 0.0], [10.903027179003214, 0.0], [11.003027179003213, 0.0], [11.103027179003213, 0.0], [11.203027179003213, 0.0], [11.303027179003212, 0.0], [11.403027179003212, 0.0], [11.503027179003212, 0.0], [11.603027179003211, 0.0], [11.703027179003211, 0.0], [11.80302717900321, 0.0], [11.90302717900321, 0.0], [12.00302717900321, 0.0], [12.10302717900321, 0.0], [12.20302717900321, 0.0], [12.303027179003209, 0.0], [12.403027179003209, 0.0], [12.503027179003208, 0.0], [12.603027179003208, 0.0], [12.703027179003207, 0.0], [12.803027179003207, 0.0], [12.903027179003207, 0.0], [13.003027179003206, 0.0], [13.103027179003206, 0.0], [13.203027179003206, 0.0], [13.303027179003205, 0.0], [13.403027179003205, 0.0], [13.503027179003205, 0.0], [13.603027179003204, 0.0], [13.703027179003204, 0.0], [13.803027179003204, 0.0], [13.903027179003203, 0.0], [14.003027179003203, 0.0], [14.103027179003202, 0.0], [14.203027179003202, 0.0], [14.303027179003202, 0.0], [14.403027179003201, 0.0], [14.503027179003201, 0.0], [14.6030271790032, 0.0], [14.7030271790032, 0.0], [14.800215297290162, 0.0], [14.879609861489522, 0.0], [14.939004425688882, 0.0], [14.978398989888243, 0.0], [14.997793554087602, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884, 10.969693845669884, 11.069693845669883, 11.169693845669883, 11.269693845669883, 11.369693845669882, 11.469693845669882, 11.569693845669882, 11.669693845669881, 11.769693845669881, 11.86969384566988, 11.96969384566988, 12.06969384566988, 12.16969384566988, 12.26969384566988, 12.369693845669879, 12.469693845669878, 12.569693845669878, 12.669693845669878, 12.769693845669877, 12.869693845669877, 12.969693845669877, 13.069693845669876, 13.169693845669876, 13.269693845669876, 13.369693845669875, 13.469693845669875, 13.569693845669875, 13.669693845669874, 13.769693845669874, 13.869693845669874, 13.969693845669873, 14.069693845669873, 14.169693845669872, 14.269693845669872, 14.369693845669872, 14.469693845669871, 14.569693845669871, 14.66969384566987, 14.76969384566987, 14.86969384566987, 14.96969384566987, 15.06969384566987, 15.169693845669869, 15.269693845669869, 15.369693845669868, 15.469693845669868, 15.569693845669867, 15.669693845669867, 15.769693845669867, 15.869693845669866], "velocities": null}}, "time": 1740481167.343631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481167.343631} +{"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": 1740481167.363631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0012244386476737384, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.363631} +{"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": 1740481167.383631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0018361987141206945, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.383631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.413631, "x": 4.000091794632344, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.413631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.003669642823243459, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.413631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.423631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02366095407098251, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.423631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.443631} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.179463234421092e-05, 0.0], [0.010691044796025064, 0.0], [0.04129029495970592, 0.0], [0.09188954512338679, 0.0], [0.16248879528706764, 0.0], [0.2530880454507485, 0.0], [0.3636872956144293, 0.0], [0.49428654577811004, 0.0], [0.644885795941791, 0.0], [0.8080028532142753, 0.0], [0.9080028532142754, 0.0], [1.0080028532142755, 0.0], [1.1080028532142756, 0.0], [1.2080028532142757, 0.0], [1.3080028532142758, 0.0], [1.4080028532142757, 0.0], [1.5080028532142757, 0.0], [1.6080028532142758, 0.0], [1.708002853214276, 0.0], [1.808002853214276, 0.0], [1.908002853214276, 0.0], [2.0080028532142764, 0.0], [2.108002853214276, 0.0], [2.2080028532142766, 0.0], [2.3080028532142762, 0.0], [2.4080028532142768, 0.0], [2.5080028532142764, 0.0], [2.608002853214277, 0.0], [2.7080028532142766, 0.0], [2.808002853214277, 0.0], [2.9080028532142768, 0.0], [3.0080028532142773, 0.0], [3.108002853214277, 0.0], [3.2080028532142775, 0.0], [3.308002853214277, 0.0], [3.4080028532142768, 0.0], [3.5080028532142764, 0.0], [3.608002853214276, 0.0], [3.7080028532142757, 0.0], [3.8080028532142753, 0.0], [3.908002853214275, 0.0], [4.008002853214275, 0.0], [4.108002853214274, 0.0], [4.208002853214274, 0.0], [4.308002853214274, 0.0], [4.408002853214273, 0.0], [4.508002853214273, 0.0], [4.6080028532142725, 0.0], [4.708002853214272, 0.0], [4.808002853214272, 0.0], [4.908002853214271, 0.0], [5.008002853214271, 0.0], [5.108002853214271, 0.0], [5.20800285321427, 0.0], [5.30800285321427, 0.0], [5.40800285321427, 0.0], [5.508002853214269, 0.0], [5.608002853214269, 0.0], [5.708002853214269, 0.0], [5.808002853214268, 0.0], [5.908002853214268, 0.0], [6.0080028532142675, 0.0], [6.108002853214267, 0.0], [6.208002853214267, 0.0], [6.3080028532142665, 0.0], [6.408002853214266, 0.0], [6.508002853214266, 0.0], [6.608002853214265, 0.0], [6.708002853214265, 0.0], [6.808002853214265, 0.0], [6.908002853214264, 0.0], [7.008002853214264, 0.0], [7.108002853214264, 0.0], [7.208002853214263, 0.0], [7.308002853214263, 0.0], [7.4080028532142626, 0.0], [7.508002853214262, 0.0], [7.608002853214262, 0.0], [7.7080028532142615, 0.0], [7.808002853214261, 0.0], [7.908002853214261, 0.0], [8.00800285321426, 0.0], [8.10800285321426, 0.0], [8.208002853214259, 0.0], [8.308002853214258, 0.0], [8.408002853214258, 0.0], [8.508002853214258, 0.0], [8.608002853214257, 0.0], [8.708002853214257, 0.0], [8.808002853214257, 0.0], [8.908002853214256, 0.0], [9.008002853214256, 0.0], [9.108002853214256, 0.0], [9.208002853214255, 0.0], [9.308002853214255, 0.0], [9.408002853214255, 0.0], [9.508002853214254, 0.0], [9.608002853214254, 0.0], [9.708002853214253, 0.0], [9.808002853214253, 0.0], [9.908002853214253, 0.0], [10.008002853214252, 0.0], [10.108002853214252, 0.0], [10.208002853214252, 0.0], [10.308002853214251, 0.0], [10.408002853214251, 0.0], [10.50800285321425, 0.0], [10.60800285321425, 0.0], [10.70800285321425, 0.0], [10.80800285321425, 0.0], [10.90800285321425, 0.0], [11.008002853214249, 0.0], [11.108002853214249, 0.0], [11.208002853214248, 0.0], [11.308002853214248, 0.0], [11.408002853214247, 0.0], [11.508002853214247, 0.0], [11.608002853214247, 0.0], [11.708002853214246, 0.0], [11.808002853214246, 0.0], [11.908002853214246, 0.0], [12.008002853214245, 0.0], [12.108002853214245, 0.0], [12.208002853214245, 0.0], [12.308002853214244, 0.0], [12.408002853214244, 0.0], [12.508002853214244, 0.0], [12.608002853214243, 0.0], [12.708002853214243, 0.0], [12.808002853214242, 0.0], [12.908002853214242, 0.0], [13.008002853214242, 0.0], [13.108002853214241, 0.0], [13.208002853214241, 0.0], [13.30800285321424, 0.0], [13.40800285321424, 0.0], [13.50800285321424, 0.0], [13.60800285321424, 0.0], [13.70800285321424, 0.0], [13.808002853214239, 0.0], [13.908002853214239, 0.0], [14.008002853214238, 0.0], [14.108002853214238, 0.0], [14.208002853214238, 0.0], [14.308002853214237, 0.0], [14.408002853214237, 0.0], [14.508002853214236, 0.0], [14.608002853214236, 0.0], [14.708002853214236, 0.0], [14.804638522233244, 0.0], [14.883037951590396, 0.0], [14.94143738094755, 0.0], [14.979836810304702, 0.0], [14.998236239661855, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884, 10.969693845669884, 11.069693845669883, 11.169693845669883, 11.269693845669883, 11.369693845669882, 11.469693845669882, 11.569693845669882, 11.669693845669881, 11.769693845669881, 11.86969384566988, 11.96969384566988, 12.06969384566988, 12.16969384566988, 12.26969384566988, 12.369693845669879, 12.469693845669878, 12.569693845669878, 12.669693845669878, 12.769693845669877, 12.869693845669877, 12.969693845669877, 13.069693845669876, 13.169693845669876, 13.269693845669876, 13.369693845669875, 13.469693845669875, 13.569693845669875, 13.669693845669874, 13.769693845669874, 13.869693845669874, 13.969693845669873, 14.069693845669873, 14.169693845669872, 14.269693845669872, 14.369693845669872, 14.469693845669871, 14.569693845669871, 14.66969384566987, 14.76969384566987, 14.86969384566987, 14.96969384566987, 15.06969384566987, 15.169693845669869, 15.269693845669869, 15.369693845669868, 15.469693845669868, 15.569693845669867, 15.669693845669867, 15.769693845669867, 15.869693845669866], "velocities": null}}, "time": 1740481167.443631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.043632129850092224, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.443631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.473631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04481256146944708, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.473631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.493631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.045991791943005525, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.493631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.5136309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04716982193689877, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5136309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.5236309, "x": 4.004016390192038, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5336308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39153730273173676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04834665211827801, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5336308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5536308} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.004016390192037811, 0.0], [0.021815302125124995, 0.0], [0.059614214058212184, 0.0], [0.11741312599129938, 0.0], [0.19521203792438657, 0.0], [0.2930109498574737, 0.0], [0.4108098617905609, 0.0], [0.5486087737236479, 0.0], [0.7059015266094528, 0.0], [0.8059015266094529, 0.0], [0.905901526609453, 0.0], [1.005901526609453, 0.0], [1.1059015266094532, 0.0], [1.2059015266094533, 0.0], [1.3059015266094534, 0.0], [1.4059015266094532, 0.0], [1.5059015266094533, 0.0], [1.6059015266094534, 0.0], [1.7059015266094535, 0.0], [1.8059015266094536, 0.0], [1.9059015266094537, 0.0], [2.0059015266094535, 0.0], [2.105901526609454, 0.0], [2.2059015266094537, 0.0], [2.3059015266094542, 0.0], [2.405901526609454, 0.0], [2.5059015266094544, 0.0], [2.605901526609454, 0.0], [2.705901526609454, 0.0], [2.8059015266094547, 0.0], [2.9059015266094543, 0.0], [3.005901526609455, 0.0], [3.1059015266094545, 0.0], [3.205901526609455, 0.0], [3.3059015266094547, 0.0], [3.4059015266094543, 0.0], [3.505901526609454, 0.0], [3.6059015266094536, 0.0], [3.7059015266094533, 0.0], [3.805901526609453, 0.0], [3.9059015266094526, 0.0], [4.005901526609452, 0.0], [4.105901526609451, 0.0], [4.205901526609451, 0.0], [4.305901526609451, 0.0], [4.40590152660945, 0.0], [4.50590152660945, 0.0], [4.60590152660945, 0.0], [4.705901526609449, 0.0], [4.805901526609449, 0.0], [4.905901526609449, 0.0], [5.005901526609448, 0.0], [5.105901526609448, 0.0], [5.2059015266094475, 0.0], [5.305901526609447, 0.0], [5.405901526609447, 0.0], [5.505901526609446, 0.0], [5.605901526609446, 0.0], [5.705901526609446, 0.0], [5.805901526609445, 0.0], [5.905901526609445, 0.0], [6.005901526609445, 0.0], [6.105901526609444, 0.0], [6.205901526609444, 0.0], [6.305901526609444, 0.0], [6.405901526609443, 0.0], [6.505901526609443, 0.0], [6.6059015266094425, 0.0], [6.705901526609442, 0.0], [6.805901526609442, 0.0], [6.9059015266094415, 0.0], [7.005901526609441, 0.0], [7.105901526609441, 0.0], [7.20590152660944, 0.0], [7.30590152660944, 0.0], [7.4059015266094415, 0.0], [7.505901526609441, 0.0], [7.605901526609441, 0.0], [7.70590152660944, 0.0], [7.80590152660944, 0.0], [7.90590152660944, 0.0], [8.00590152660944, 0.0], [8.10590152660944, 0.0], [8.20590152660944, 0.0], [8.30590152660944, 0.0], [8.405901526609439, 0.0], [8.505901526609438, 0.0], [8.605901526609438, 0.0], [8.705901526609438, 0.0], [8.805901526609437, 0.0], [8.905901526609437, 0.0], [9.005901526609437, 0.0], [9.105901526609436, 0.0], [9.205901526609436, 0.0], [9.305901526609436, 0.0], [9.405901526609435, 0.0], [9.505901526609435, 0.0], [9.605901526609435, 0.0], [9.705901526609434, 0.0], [9.805901526609434, 0.0], [9.905901526609433, 0.0], [10.005901526609433, 0.0], [10.105901526609433, 0.0], [10.205901526609432, 0.0], [10.305901526609432, 0.0], [10.405901526609432, 0.0], [10.505901526609431, 0.0], [10.605901526609431, 0.0], [10.70590152660943, 0.0], [10.80590152660943, 0.0], [10.90590152660943, 0.0], [11.00590152660943, 0.0], [11.10590152660943, 0.0], [11.205901526609429, 0.0], [11.305901526609428, 0.0], [11.405901526609428, 0.0], [11.505901526609428, 0.0], [11.605901526609427, 0.0], [11.705901526609427, 0.0], [11.805901526609427, 0.0], [11.905901526609426, 0.0], [12.005901526609426, 0.0], [12.105901526609426, 0.0], [12.205901526609425, 0.0], [12.305901526609425, 0.0], [12.405901526609425, 0.0], [12.505901526609424, 0.0], [12.605901526609424, 0.0], [12.705901526609424, 0.0], [12.805901526609423, 0.0], [12.905901526609423, 0.0], [13.005901526609422, 0.0], [13.105901526609422, 0.0], [13.205901526609422, 0.0], [13.305901526609421, 0.0], [13.405901526609421, 0.0], [13.50590152660942, 0.0], [13.60590152660942, 0.0], [13.70590152660942, 0.0], [13.80590152660942, 0.0], [13.90590152660942, 0.0], [14.005901526609419, 0.0], [14.105901526609419, 0.0], [14.205901526609418, 0.0], [14.305901526609418, 0.0], [14.405901526609417, 0.0], [14.505901526609417, 0.0], [14.605901526609417, 0.0], [14.705901526609416, 0.0], [14.802776545932153, 0.0], [14.88159624061027, 0.0], [14.940415935288385, 0.0], [14.979235629966503, 0.0], [14.99805532464462, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323, 15.806394529484322], "velocities": null}}, "time": 1740481167.5536308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0682349214193812, "gear": 1, "accelerator_pedal_position": 0.39153730273173676, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5536308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5736308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06939020335529934, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5736308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5936308} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.3505635, "x": 15.0, "y": 2.1249999999999982, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481167.5936308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07054429838169154, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5936308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.6136308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0716972071853235, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6136308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.6336308, "x": 4.011180782430692, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6336308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07284893045389727, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6336308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6436307} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.011180782430692204, 0.0], [0.03307696295866197, 0.0], [0.07497314348663174, 0.0], [0.13686932401460153, 0.0], [0.2187655045425713, 0.0], [0.32066168507054105, 0.0], [0.4425578655985108, 0.0], [0.5844540461264804, 0.0], [0.744502574741399, 0.0], [0.8445025747413991, 0.0], [0.9445025747413992, 0.0], [1.0445025747413994, 0.0], [1.1445025747413995, 0.0], [1.2445025747413996, 0.0], [1.3445025747413997, 0.0], [1.4445025747413993, 0.0], [1.5445025747413994, 0.0], [1.6445025747413995, 0.0], [1.7445025747413996, 0.0], [1.8445025747413997, 0.0], [1.9445025747413998, 0.0], [2.0445025747414, 0.0], [2.1445025747414, 0.0], [2.2445025747414, 0.0], [2.3445025747414, 0.0], [2.4445025747414, 0.0], [2.5445025747414003, 0.0], [2.6445025747414004, 0.0], [2.744502574741401, 0.0], [2.8445025747414006, 0.0], [2.944502574741401, 0.0], [3.0445025747414007, 0.0], [3.1445025747414013, 0.0], [3.244502574741401, 0.0], [3.3445025747414014, 0.0], [3.444502574741401, 0.0], [3.5445025747414007, 0.0], [3.6445025747414004, 0.0], [3.7445025747414, 0.0], [3.8445025747413997, 0.0], [3.9445025747413993, 0.0], [4.044502574741399, 0.0], [4.144502574741399, 0.0], [4.244502574741398, 0.0], [4.344502574741398, 0.0], [4.4445025747413975, 0.0], [4.544502574741397, 0.0], [4.644502574741397, 0.0], [4.7445025747413965, 0.0], [4.844502574741396, 0.0], [4.944502574741396, 0.0], [5.044502574741395, 0.0], [5.144502574741395, 0.0], [5.244502574741395, 0.0], [5.344502574741394, 0.0], [5.444502574741394, 0.0], [5.544502574741394, 0.0], [5.644502574741393, 0.0], [5.744502574741393, 0.0], [5.844502574741393, 0.0], [5.944502574741392, 0.0], [6.044502574741392, 0.0], [6.1445025747413915, 0.0], [6.244502574741391, 0.0], [6.344502574741391, 0.0], [6.44450257474139, 0.0], [6.54450257474139, 0.0], [6.64450257474139, 0.0], [6.744502574741389, 0.0], [6.844502574741389, 0.0], [6.944502574741389, 0.0], [7.044502574741388, 0.0], [7.144502574741388, 0.0], [7.244502574741388, 0.0], [7.344502574741387, 0.0], [7.444502574741388, 0.0], [7.544502574741387, 0.0], [7.644502574741387, 0.0], [7.744502574741387, 0.0], [7.844502574741386, 0.0], [7.944502574741386, 0.0], [8.044502574741385, 0.0], [8.144502574741384, 0.0], [8.244502574741384, 0.0], [8.344502574741384, 0.0], [8.444502574741383, 0.0], [8.544502574741383, 0.0], [8.644502574741383, 0.0], [8.744502574741382, 0.0], [8.844502574741382, 0.0], [8.944502574741382, 0.0], [9.044502574741381, 0.0], [9.14450257474138, 0.0], [9.24450257474138, 0.0], [9.34450257474138, 0.0], [9.44450257474138, 0.0], [9.54450257474138, 0.0], [9.644502574741379, 0.0], [9.744502574741379, 0.0], [9.844502574741378, 0.0], [9.944502574741378, 0.0], [10.044502574741378, 0.0], [10.144502574741377, 0.0], [10.244502574741377, 0.0], [10.344502574741377, 0.0], [10.444502574741376, 0.0], [10.544502574741376, 0.0], [10.644502574741376, 0.0], [10.744502574741375, 0.0], [10.844502574741375, 0.0], [10.944502574741374, 0.0], [11.044502574741374, 0.0], [11.144502574741374, 0.0], [11.244502574741373, 0.0], [11.344502574741373, 0.0], [11.444502574741373, 0.0], [11.544502574741372, 0.0], [11.644502574741372, 0.0], [11.744502574741372, 0.0], [11.844502574741371, 0.0], [11.944502574741371, 0.0], [12.04450257474137, 0.0], [12.14450257474137, 0.0], [12.24450257474137, 0.0], [12.34450257474137, 0.0], [12.44450257474137, 0.0], [12.544502574741369, 0.0], [12.644502574741368, 0.0], [12.744502574741368, 0.0], [12.844502574741368, 0.0], [12.944502574741367, 0.0], [13.044502574741367, 0.0], [13.144502574741367, 0.0], [13.244502574741366, 0.0], [13.344502574741366, 0.0], [13.444502574741366, 0.0], [13.544502574741365, 0.0], [13.644502574741365, 0.0], [13.744502574741364, 0.0], [13.844502574741364, 0.0], [13.944502574741364, 0.0], [14.044502574741363, 0.0], [14.144502574741363, 0.0], [14.244502574741363, 0.0], [14.344502574741362, 0.0], [14.444502574741362, 0.0], [14.544502574741362, 0.0], [14.644502574741361, 0.0], [14.744502574741361, 0.0], [14.835571838108613, 0.0], [14.906671323160342, 0.0], [14.95777080821207, 0.0], [14.988870293263798, 0.0], [14.999969778315526, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323, 15.806394529484322], "velocities": null}}, "time": 1740481167.6436307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09276988352203232, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6436307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6736307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09389984417892214, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6736307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6836307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0950286328656605, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6836307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.7036307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09559258794081704, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7036307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.7336307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09728269715356862, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7336307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.7436306, "x": 4.021289880601261, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7536306} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.02128988060126069, 0.0], [0.04726798087894486, 0.0], [0.09324608115662905, 0.0], [0.15922418143431324, 0.0], [0.24520228171199743, 0.0], [0.35118038198968154, 0.0], [0.4771584822673657, 0.0], [0.6231365825450498, 0.0], [0.7850958936713571, 0.0], [0.8850958936713572, 0.0], [0.9850958936713573, 0.0], [1.0850958936713573, 0.0], [1.1850958936713574, 0.0], [1.2850958936713575, 0.0], [1.3850958936713575, 0.0], [1.4850958936713576, 0.0], [1.5850958936713577, 0.0], [1.6850958936713578, 0.0], [1.785095893671358, 0.0], [1.885095893671358, 0.0], [1.985095893671358, 0.0], [2.085095893671358, 0.0], [2.1850958936713583, 0.0], [2.2850958936713583, 0.0], [2.3850958936713584, 0.0], [2.4850958936713585, 0.0], [2.5850958936713586, 0.0], [2.6850958936713587, 0.0], [2.7850958936713583, 0.0], [2.885095893671359, 0.0], [2.9850958936713585, 0.0], [3.085095893671359, 0.0], [3.1850958936713587, 0.0], [3.2850958936713592, 0.0], [3.385095893671359, 0.0], [3.4850958936713585, 0.0], [3.585095893671358, 0.0], [3.685095893671358, 0.0], [3.7850958936713575, 0.0], [3.885095893671357, 0.0], [3.9850958936713567, 0.0], [4.085095893671356, 0.0], [4.185095893671356, 0.0], [4.285095893671356, 0.0], [4.385095893671355, 0.0], [4.485095893671355, 0.0], [4.585095893671355, 0.0], [4.685095893671354, 0.0], [4.785095893671354, 0.0], [4.8850958936713536, 0.0], [4.985095893671353, 0.0], [5.085095893671353, 0.0], [5.1850958936713525, 0.0], [5.285095893671352, 0.0], [5.385095893671352, 0.0], [5.485095893671351, 0.0], [5.585095893671351, 0.0], [5.685095893671351, 0.0], [5.78509589367135, 0.0], [5.88509589367135, 0.0], [5.98509589367135, 0.0], [6.085095893671349, 0.0], [6.185095893671349, 0.0], [6.285095893671349, 0.0], [6.385095893671348, 0.0], [6.485095893671348, 0.0], [6.5850958936713475, 0.0], [6.685095893671347, 0.0], [6.785095893671347, 0.0], [6.8850958936713464, 0.0], [6.985095893671346, 0.0], [7.085095893671346, 0.0], [7.185095893671345, 0.0], [7.285095893671345, 0.0], [7.385095893671345, 0.0], [7.485095893671345, 0.0], [7.585095893671345, 0.0], [7.6850958936713445, 0.0], [7.785095893671344, 0.0], [7.885095893671344, 0.0], [7.985095893671343, 0.0], [8.085095893671344, 0.0], [8.185095893671344, 0.0], [8.285095893671343, 0.0], [8.385095893671343, 0.0], [8.485095893671343, 0.0], [8.585095893671342, 0.0], [8.685095893671342, 0.0], [8.785095893671341, 0.0], [8.885095893671341, 0.0], [8.98509589367134, 0.0], [9.08509589367134, 0.0], [9.18509589367134, 0.0], [9.28509589367134, 0.0], [9.38509589367134, 0.0], [9.485095893671339, 0.0], [9.585095893671339, 0.0], [9.685095893671338, 0.0], [9.785095893671338, 0.0], [9.885095893671338, 0.0], [9.985095893671337, 0.0], [10.085095893671337, 0.0], [10.185095893671336, 0.0], [10.285095893671336, 0.0], [10.385095893671336, 0.0], [10.485095893671335, 0.0], [10.585095893671335, 0.0], [10.685095893671335, 0.0], [10.785095893671334, 0.0], [10.885095893671334, 0.0], [10.985095893671334, 0.0], [11.085095893671333, 0.0], [11.185095893671333, 0.0], [11.285095893671333, 0.0], [11.385095893671332, 0.0], [11.485095893671332, 0.0], [11.585095893671332, 0.0], [11.685095893671331, 0.0], [11.78509589367133, 0.0], [11.88509589367133, 0.0], [11.98509589367133, 0.0], [12.08509589367133, 0.0], [12.18509589367133, 0.0], [12.285095893671329, 0.0], [12.385095893671329, 0.0], [12.485095893671328, 0.0], [12.585095893671328, 0.0], [12.685095893671328, 0.0], [12.785095893671327, 0.0], [12.885095893671327, 0.0], [12.985095893671327, 0.0], [13.085095893671326, 0.0], [13.185095893671326, 0.0], [13.285095893671325, 0.0], [13.385095893671325, 0.0], [13.485095893671325, 0.0], [13.585095893671324, 0.0], [13.685095893671324, 0.0], [13.785095893671324, 0.0], [13.885095893671323, 0.0], [13.985095893671323, 0.0], [14.085095893671323, 0.0], [14.185095893671322, 0.0], [14.285095893671322, 0.0], [14.385095893671322, 0.0], [14.485095893671321, 0.0], [14.58509589367132, 0.0], [14.68509589367132, 0.0], [14.783864171918731, 0.0], [14.866844993184467, 0.0], [14.929825814450203, 0.0], [14.972806635715939, 0.0], [14.995787456981676, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323], "velocities": null}}, "time": 1740481167.7536306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09840797416931088, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7536306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7636306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11830244872708315, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7636306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7936306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1381761324083651, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7936306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8136306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15802888899716164, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8136306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8336306} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.5710602, "x": 15.0, "y": 2.234999999999996, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481167.8336306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17786058291891527, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8336306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8436306} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.02128988060126069, 0.0], [0.04726798087894486, 0.0], [0.09324608115662905, 0.0], [0.15922418143431324, 0.0], [0.24520228171199743, 0.0], [0.35118038198968154, 0.0], [0.4771584822673657, 0.0], [0.6231365825450498, 0.0], [0.7850958936713571, 0.0], [0.8850958936713572, 0.0], [0.9850958936713573, 0.0], [1.0850958936713573, 0.0], [1.1850958936713574, 0.0], [1.2850958936713575, 0.0], [1.3850958936713575, 0.0], [1.4850958936713576, 0.0], [1.5850958936713577, 0.0], [1.6850958936713578, 0.0], [1.785095893671358, 0.0], [1.885095893671358, 0.0], [1.985095893671358, 0.0], [2.085095893671358, 0.0], [2.1850958936713583, 0.0], [2.2850958936713583, 0.0], [2.3850958936713584, 0.0], [2.4850958936713585, 0.0], [2.5850958936713586, 0.0], [2.6850958936713587, 0.0], [2.7850958936713583, 0.0], [2.885095893671359, 0.0], [2.9850958936713585, 0.0], [3.085095893671359, 0.0], [3.1850958936713587, 0.0], [3.2850958936713592, 0.0], [3.385095893671359, 0.0], [3.4850958936713585, 0.0], [3.585095893671358, 0.0], [3.685095893671358, 0.0], [3.7850958936713575, 0.0], [3.885095893671357, 0.0], [3.9850958936713567, 0.0], [4.085095893671356, 0.0], [4.185095893671356, 0.0], [4.285095893671356, 0.0], [4.385095893671355, 0.0], [4.485095893671355, 0.0], [4.585095893671355, 0.0], [4.685095893671354, 0.0], [4.785095893671354, 0.0], [4.8850958936713536, 0.0], [4.985095893671353, 0.0], [5.085095893671353, 0.0], [5.1850958936713525, 0.0], [5.285095893671352, 0.0], [5.385095893671352, 0.0], [5.485095893671351, 0.0], [5.585095893671351, 0.0], [5.685095893671351, 0.0], [5.78509589367135, 0.0], [5.88509589367135, 0.0], [5.98509589367135, 0.0], [6.085095893671349, 0.0], [6.185095893671349, 0.0], [6.285095893671349, 0.0], [6.385095893671348, 0.0], [6.485095893671348, 0.0], [6.5850958936713475, 0.0], [6.685095893671347, 0.0], [6.785095893671347, 0.0], [6.8850958936713464, 0.0], [6.985095893671346, 0.0], [7.085095893671346, 0.0], [7.185095893671345, 0.0], [7.285095893671345, 0.0], [7.385095893671345, 0.0], [7.485095893671345, 0.0], [7.585095893671345, 0.0], [7.6850958936713445, 0.0], [7.785095893671344, 0.0], [7.885095893671344, 0.0], [7.985095893671343, 0.0], [8.085095893671344, 0.0], [8.185095893671344, 0.0], [8.285095893671343, 0.0], [8.385095893671343, 0.0], [8.485095893671343, 0.0], [8.585095893671342, 0.0], [8.685095893671342, 0.0], [8.785095893671341, 0.0], [8.885095893671341, 0.0], [8.98509589367134, 0.0], [9.08509589367134, 0.0], [9.18509589367134, 0.0], [9.28509589367134, 0.0], [9.38509589367134, 0.0], [9.485095893671339, 0.0], [9.585095893671339, 0.0], [9.685095893671338, 0.0], [9.785095893671338, 0.0], [9.885095893671338, 0.0], [9.985095893671337, 0.0], [10.085095893671337, 0.0], [10.185095893671336, 0.0], [10.285095893671336, 0.0], [10.385095893671336, 0.0], [10.485095893671335, 0.0], [10.585095893671335, 0.0], [10.685095893671335, 0.0], [10.785095893671334, 0.0], [10.885095893671334, 0.0], [10.985095893671334, 0.0], [11.085095893671333, 0.0], [11.185095893671333, 0.0], [11.285095893671333, 0.0], [11.385095893671332, 0.0], [11.485095893671332, 0.0], [11.585095893671332, 0.0], [11.685095893671331, 0.0], [11.78509589367133, 0.0], [11.88509589367133, 0.0], [11.98509589367133, 0.0], [12.08509589367133, 0.0], [12.18509589367133, 0.0], [12.285095893671329, 0.0], [12.385095893671329, 0.0], [12.485095893671328, 0.0], [12.585095893671328, 0.0], [12.685095893671328, 0.0], [12.785095893671327, 0.0], [12.885095893671327, 0.0], [12.985095893671327, 0.0], [13.085095893671326, 0.0], [13.185095893671326, 0.0], [13.285095893671325, 0.0], [13.385095893671325, 0.0], [13.485095893671325, 0.0], [13.585095893671324, 0.0], [13.685095893671324, 0.0], [13.785095893671324, 0.0], [13.885095893671323, 0.0], [13.985095893671323, 0.0], [14.085095893671323, 0.0], [14.185095893671322, 0.0], [14.285095893671322, 0.0], [14.385095893671322, 0.0], [14.485095893671321, 0.0], [14.58509589367132, 0.0], [14.68509589367132, 0.0], [14.783864171918731, 0.0], [14.866844993184467, 0.0], [14.929825814450203, 0.0], [14.972806635715939, 0.0], [14.995787456981676, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323], "velocities": null}}, "time": 1740481167.8436306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19767107924361257, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8436306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.8536305, "x": 4.036580302704266, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.8736305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24706897488242152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2207709501419795, "gear": 1, "accelerator_pedal_position": 0.24706897488242152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8736305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.03658030270426593, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.9136305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24542178133015952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.22149455201880083, "gear": 1, "accelerator_pedal_position": 0.24542178133015952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.9136305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.03658030270426593, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.9536304} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.03658030270426593, 0.0], [0.07885985477440659, 0.0], [0.14113940684454723, 0.0], [0.22341895891468794, 0.0], [0.3256985109848286, 0.0], [0.44797806305496923, 0.0], [0.5902576151251098, 0.0], [0.750521051281676, 0.0], [0.8505210512816761, 0.0], [0.9505210512816762, 0.0], [1.0505210512816763, 0.0], [1.1505210512816764, 0.0], [1.2505210512816765, 0.0], [1.3505210512816765, 0.0], [1.4505210512816766, 0.0], [1.5505210512816767, 0.0], [1.6505210512816766, 0.0], [1.7505210512816767, 0.0], [1.8505210512816768, 0.0], [1.9505210512816769, 0.0], [2.050521051281677, 0.0], [2.150521051281677, 0.0], [2.250521051281677, 0.0], [2.350521051281677, 0.0], [2.4505210512816773, 0.0], [2.5505210512816774, 0.0], [2.6505210512816775, 0.0], [2.7505210512816776, 0.0], [2.850521051281678, 0.0], [2.9505210512816777, 0.0], [3.0505210512816783, 0.0], [3.150521051281678, 0.0], [3.2505210512816785, 0.0], [3.350521051281678, 0.0], [3.4505210512816786, 0.0], [3.5505210512816783, 0.0], [3.650521051281679, 0.0], [3.7505210512816785, 0.0], [3.850521051281678, 0.0], [3.9505210512816777, 0.0], [4.050521051281677, 0.0], [4.150521051281677, 0.0], [4.250521051281677, 0.0], [4.350521051281676, 0.0], [4.450521051281676, 0.0], [4.550521051281676, 0.0], [4.650521051281675, 0.0], [4.750521051281675, 0.0], [4.8505210512816745, 0.0], [4.950521051281674, 0.0], [5.050521051281674, 0.0], [5.1505210512816735, 0.0], [5.250521051281673, 0.0], [5.350521051281673, 0.0], [5.450521051281672, 0.0], [5.550521051281672, 0.0], [5.650521051281672, 0.0], [5.750521051281671, 0.0], [5.850521051281671, 0.0], [5.950521051281671, 0.0], [6.05052105128167, 0.0], [6.15052105128167, 0.0], [6.25052105128167, 0.0], [6.350521051281669, 0.0], [6.450521051281669, 0.0], [6.5505210512816685, 0.0], [6.650521051281668, 0.0], [6.750521051281668, 0.0], [6.850521051281667, 0.0], [6.950521051281667, 0.0], [7.050521051281667, 0.0], [7.150521051281666, 0.0], [7.250521051281666, 0.0], [7.350521051281666, 0.0], [7.450521051281665, 0.0], [7.550521051281665, 0.0], [7.6505210512816655, 0.0], [7.750521051281665, 0.0], [7.850521051281665, 0.0], [7.950521051281664, 0.0], [8.050521051281663, 0.0], [8.150521051281663, 0.0], [8.250521051281662, 0.0], [8.350521051281662, 0.0], [8.450521051281662, 0.0], [8.550521051281661, 0.0], [8.650521051281661, 0.0], [8.75052105128166, 0.0], [8.85052105128166, 0.0], [8.95052105128166, 0.0], [9.05052105128166, 0.0], [9.15052105128166, 0.0], [9.250521051281659, 0.0], [9.350521051281659, 0.0], [9.450521051281658, 0.0], [9.550521051281658, 0.0], [9.650521051281657, 0.0], [9.750521051281657, 0.0], [9.850521051281657, 0.0], [9.950521051281656, 0.0], [10.050521051281656, 0.0], [10.150521051281656, 0.0], [10.250521051281655, 0.0], [10.350521051281655, 0.0], [10.450521051281655, 0.0], [10.550521051281654, 0.0], [10.650521051281654, 0.0], [10.750521051281654, 0.0], [10.850521051281653, 0.0], [10.950521051281653, 0.0], [11.050521051281653, 0.0], [11.150521051281652, 0.0], [11.250521051281652, 0.0], [11.350521051281651, 0.0], [11.450521051281651, 0.0], [11.55052105128165, 0.0], [11.65052105128165, 0.0], [11.75052105128165, 0.0], [11.85052105128165, 0.0], [11.95052105128165, 0.0], [12.050521051281649, 0.0], [12.150521051281649, 0.0], [12.250521051281648, 0.0], [12.350521051281648, 0.0], [12.450521051281648, 0.0], [12.550521051281647, 0.0], [12.650521051281647, 0.0], [12.750521051281646, 0.0], [12.850521051281646, 0.0], [12.950521051281646, 0.0], [13.050521051281645, 0.0], [13.150521051281645, 0.0], [13.250521051281645, 0.0], [13.350521051281644, 0.0], [13.450521051281644, 0.0], [13.550521051281644, 0.0], [13.650521051281643, 0.0], [13.750521051281643, 0.0], [13.850521051281643, 0.0], [13.950521051281642, 0.0], [14.050521051281642, 0.0], [14.150521051281642, 0.0], [14.250521051281641, 0.0], [14.35052105128164, 0.0], [14.45052105128164, 0.0], [14.55052105128164, 0.0], [14.65052105128164, 0.0], [14.750520779787202, 0.0], [14.840416569530873, 0.0], [14.910312359274545, 0.0], [14.960208149018218, 0.0], [14.990103938761889, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779, 15.543095213298779], "velocities": null}}, "time": 1740481167.9536304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23401274097597255, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.9536304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.0736303, "x": 4.085421049444235, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.229591660542647, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.049230537236539695, "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": 1740481168.1636302} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.9500866, "x": 15.0, "y": 2.3999999999999924, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.1636302} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.08542104944423468, 0.0], [0.13291321061275274, 0.0], [0.20040537178127082, 0.0], [0.2878975329497889, 0.0], [0.39538969411830704, 0.0], [0.5228818552868251, 0.0], [0.6703740164553431, 0.0], [0.8328302564060938, 0.0], [0.9328302564060938, 0.0], [1.0328302564060938, 0.0], [1.132830256406094, 0.0], [1.232830256406094, 0.0], [1.332830256406094, 0.0], [1.4328302564060942, 0.0], [1.5328302564060943, 0.0], [1.6328302564060944, 0.0], [1.7328302564060944, 0.0], [1.8328302564060945, 0.0], [1.9328302564060946, 0.0], [2.0328302564060947, 0.0], [2.132830256406095, 0.0], [2.232830256406095, 0.0], [2.332830256406095, 0.0], [2.432830256406095, 0.0], [2.532830256406095, 0.0], [2.6328302564060952, 0.0], [2.732830256406095, 0.0], [2.8328302564060954, 0.0], [2.932830256406095, 0.0], [3.0328302564060956, 0.0], [3.1328302564060952, 0.0], [3.232830256406096, 0.0], [3.3328302564060954, 0.0], [3.432830256406096, 0.0], [3.5328302564060956, 0.0], [3.632830256406096, 0.0], [3.732830256406096, 0.0], [3.8328302564060954, 0.0], [3.932830256406095, 0.0], [4.032830256406095, 0.0], [4.132830256406095, 0.0], [4.2328302564060944, 0.0], [4.332830256406094, 0.0], [4.432830256406094, 0.0], [4.532830256406093, 0.0], [4.632830256406093, 0.0], [4.732830256406093, 0.0], [4.832830256406092, 0.0], [4.932830256406092, 0.0], [5.032830256406092, 0.0], [5.132830256406091, 0.0], [5.232830256406091, 0.0], [5.3328302564060905, 0.0], [5.43283025640609, 0.0], [5.53283025640609, 0.0], [5.6328302564060895, 0.0], [5.732830256406089, 0.0], [5.832830256406089, 0.0], [5.932830256406088, 0.0], [6.032830256406088, 0.0], [6.132830256406088, 0.0], [6.232830256406087, 0.0], [6.332830256406087, 0.0], [6.432830256406087, 0.0], [6.532830256406086, 0.0], [6.632830256406086, 0.0], [6.732830256406086, 0.0], [6.832830256406085, 0.0], [6.932830256406085, 0.0], [7.0328302564060845, 0.0], [7.132830256406084, 0.0], [7.232830256406084, 0.0], [7.332830256406083, 0.0], [7.432830256406083, 0.0], [7.532830256406083, 0.0], [7.632830256406082, 0.0], [7.732830256406083, 0.0], [7.8328302564060825, 0.0], [7.932830256406082, 0.0], [8.032830256406083, 0.0], [8.132830256406082, 0.0], [8.232830256406082, 0.0], [8.332830256406082, 0.0], [8.432830256406081, 0.0], [8.532830256406081, 0.0], [8.63283025640608, 0.0], [8.73283025640608, 0.0], [8.83283025640608, 0.0], [8.93283025640608, 0.0], [9.03283025640608, 0.0], [9.132830256406079, 0.0], [9.232830256406078, 0.0], [9.332830256406078, 0.0], [9.432830256406078, 0.0], [9.532830256406077, 0.0], [9.632830256406077, 0.0], [9.732830256406077, 0.0], [9.832830256406076, 0.0], [9.932830256406076, 0.0], [10.032830256406076, 0.0], [10.132830256406075, 0.0], [10.232830256406075, 0.0], [10.332830256406075, 0.0], [10.432830256406074, 0.0], [10.532830256406074, 0.0], [10.632830256406073, 0.0], [10.732830256406073, 0.0], [10.832830256406073, 0.0], [10.932830256406072, 0.0], [11.032830256406072, 0.0], [11.132830256406072, 0.0], [11.232830256406071, 0.0], [11.332830256406071, 0.0], [11.43283025640607, 0.0], [11.53283025640607, 0.0], [11.63283025640607, 0.0], [11.73283025640607, 0.0], [11.83283025640607, 0.0], [11.932830256406069, 0.0], [12.032830256406069, 0.0], [12.132830256406068, 0.0], [12.232830256406068, 0.0], [12.332830256406067, 0.0], [12.432830256406067, 0.0], [12.532830256406067, 0.0], [12.632830256406066, 0.0], [12.732830256406066, 0.0], [12.832830256406066, 0.0], [12.932830256406065, 0.0], [13.032830256406065, 0.0], [13.132830256406065, 0.0], [13.232830256406064, 0.0], [13.332830256406064, 0.0], [13.432830256406064, 0.0], [13.532830256406063, 0.0], [13.632830256406063, 0.0], [13.732830256406062, 0.0], [13.832830256406062, 0.0], [13.932830256406062, 0.0], [14.032830256406061, 0.0], [14.132830256406061, 0.0], [14.23283025640606, 0.0], [14.33283025640606, 0.0], [14.43283025640606, 0.0], [14.53283025640606, 0.0], [14.63283025640606, 0.0], [14.732830256406059, 0.0], [14.825969405029765, 0.0], [14.899403353748554, 0.0], [14.95283730246734, 0.0], [14.98627125118613, 0.0], [14.999705199904918, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779, 15.543095213298779], "velocities": null}}, "time": 1740481168.1636302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26584749887485426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23450263084488646, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.1636302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.1836302, "x": 4.110946456891718, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.1836302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28829036169917055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2364953490607551, "gear": 1, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.1836302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2036302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2432821040609096, "gear": 1, "accelerator_pedal_position": 0.28829036169917055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2036302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2236302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2490110624396571, "gear": 1, "accelerator_pedal_position": 0.2798852046927663, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2236302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2436302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2547337262433775, "gear": 1, "accelerator_pedal_position": 0.2798852046927663, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2436302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2636302} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.11094645689171756, 0.0], [0.1595659856744007, 0.0], [0.22818551445708382, 0.0], [0.316805043239767, 0.0], [0.4254245720224501, 0.0], [0.5540441008051332, 0.0], [0.7026636295878164, 0.0], [0.8654154355199618, 0.0], [0.9654154355199619, 0.0], [1.065415435519962, 0.0], [1.1654154355199622, 0.0], [1.2654154355199623, 0.0], [1.3654154355199624, 0.0], [1.4654154355199625, 0.0], [1.5654154355199625, 0.0], [1.6654154355199626, 0.0], [1.7654154355199623, 0.0], [1.8654154355199624, 0.0], [1.9654154355199625, 0.0], [2.0654154355199625, 0.0], [2.1654154355199626, 0.0], [2.2654154355199627, 0.0], [2.365415435519963, 0.0], [2.465415435519963, 0.0], [2.565415435519963, 0.0], [2.665415435519963, 0.0], [2.765415435519963, 0.0], [2.8654154355199632, 0.0], [2.9654154355199633, 0.0], [3.0654154355199634, 0.0], [3.1654154355199635, 0.0], [3.2654154355199636, 0.0], [3.3654154355199637, 0.0], [3.465415435519964, 0.0], [3.565415435519964, 0.0], [3.665415435519964, 0.0], [3.765415435519964, 0.0], [3.8654154355199637, 0.0], [3.9654154355199633, 0.0], [4.065415435519963, 0.0], [4.165415435519963, 0.0], [4.265415435519962, 0.0], [4.365415435519962, 0.0], [4.465415435519962, 0.0], [4.565415435519961, 0.0], [4.665415435519961, 0.0], [4.7654154355199605, 0.0], [4.86541543551996, 0.0], [4.96541543551996, 0.0], [5.065415435519959, 0.0], [5.165415435519959, 0.0], [5.265415435519959, 0.0], [5.365415435519958, 0.0], [5.465415435519958, 0.0], [5.565415435519958, 0.0], [5.665415435519957, 0.0], [5.765415435519957, 0.0], [5.865415435519957, 0.0], [5.965415435519956, 0.0], [6.065415435519956, 0.0], [6.1654154355199555, 0.0], [6.265415435519955, 0.0], [6.365415435519955, 0.0], [6.4654154355199545, 0.0], [6.565415435519954, 0.0], [6.665415435519954, 0.0], [6.765415435519953, 0.0], [6.865415435519953, 0.0], [6.965415435519953, 0.0], [7.065415435519952, 0.0], [7.165415435519952, 0.0], [7.265415435519952, 0.0], [7.365415435519951, 0.0], [7.465415435519951, 0.0], [7.5654154355199505, 0.0], [7.66541543551995, 0.0], [7.765415435519951, 0.0], [7.86541543551995, 0.0], [7.96541543551995, 0.0], [8.065415435519949, 0.0], [8.16541543551995, 0.0], [8.26541543551995, 0.0], [8.36541543551995, 0.0], [8.46541543551995, 0.0], [8.565415435519949, 0.0], [8.665415435519948, 0.0], [8.765415435519948, 0.0], [8.865415435519948, 0.0], [8.965415435519947, 0.0], [9.065415435519947, 0.0], [9.165415435519947, 0.0], [9.265415435519946, 0.0], [9.365415435519946, 0.0], [9.465415435519946, 0.0], [9.565415435519945, 0.0], [9.665415435519945, 0.0], [9.765415435519945, 0.0], [9.865415435519944, 0.0], [9.965415435519944, 0.0], [10.065415435519943, 0.0], [10.165415435519943, 0.0], [10.265415435519943, 0.0], [10.365415435519942, 0.0], [10.465415435519942, 0.0], [10.565415435519942, 0.0], [10.665415435519941, 0.0], [10.765415435519941, 0.0], [10.86541543551994, 0.0], [10.96541543551994, 0.0], [11.06541543551994, 0.0], [11.16541543551994, 0.0], [11.26541543551994, 0.0], [11.365415435519939, 0.0], [11.465415435519938, 0.0], [11.565415435519938, 0.0], [11.665415435519938, 0.0], [11.765415435519937, 0.0], [11.865415435519937, 0.0], [11.965415435519937, 0.0], [12.065415435519936, 0.0], [12.165415435519936, 0.0], [12.265415435519936, 0.0], [12.365415435519935, 0.0], [12.465415435519935, 0.0], [12.565415435519935, 0.0], [12.665415435519934, 0.0], [12.765415435519934, 0.0], [12.865415435519933, 0.0], [12.965415435519933, 0.0], [13.065415435519933, 0.0], [13.165415435519932, 0.0], [13.265415435519932, 0.0], [13.365415435519932, 0.0], [13.465415435519931, 0.0], [13.565415435519931, 0.0], [13.66541543551993, 0.0], [13.76541543551993, 0.0], [13.86541543551993, 0.0], [13.96541543551993, 0.0], [14.06541543551993, 0.0], [14.165415435519929, 0.0], [14.265415435519929, 0.0], [14.365415435519928, 0.0], [14.465415435519928, 0.0], [14.565415435519927, 0.0], [14.665415435519927, 0.0], [14.765177799867658, 0.0], [14.852094712763671, 0.0], [14.919011625659687, 0.0], [14.965928538555701, 0.0], [14.992845451451716, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779], "velocities": null}}, "time": 1740481168.2636302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26377969259852846, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2636302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2836301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26377969259852846, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2836301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.2936301, "x": 4.138612065219516, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.30363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26472648006610955, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.30363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.32363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2844422754527114, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.32363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.34363} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.1744242, "x": 15.0, "y": 2.50999999999999, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.34363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30413615681640904, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.34363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.36363} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.1386120652195162, 0.0], [0.1917644348906054, 0.0], [0.26491680456169464, 0.0], [0.35806917423278384, 0.0], [0.47122154390387305, 0.0], [0.6043739135749622, 0.0], [0.7575262832460514, 0.0], [0.9208250595996438, 0.0], [1.0208250595996438, 0.0], [1.1208250595996438, 0.0], [1.220825059599644, 0.0], [1.320825059599644, 0.0], [1.4208250595996441, 0.0], [1.5208250595996442, 0.0], [1.6208250595996443, 0.0], [1.7208250595996444, 0.0], [1.8208250595996445, 0.0], [1.9208250595996446, 0.0], [2.0208250595996446, 0.0], [2.1208250595996447, 0.0], [2.220825059599645, 0.0], [2.320825059599645, 0.0], [2.420825059599645, 0.0], [2.520825059599645, 0.0], [2.620825059599645, 0.0], [2.7208250595996453, 0.0], [2.8208250595996454, 0.0], [2.9208250595996454, 0.0], [3.0208250595996455, 0.0], [3.1208250595996456, 0.0], [3.2208250595996457, 0.0], [3.320825059599646, 0.0], [3.420825059599646, 0.0], [3.520825059599646, 0.0], [3.620825059599646, 0.0], [3.720825059599646, 0.0], [3.8208250595996462, 0.0], [3.920825059599646, 0.0], [4.0208250595996455, 0.0], [4.120825059599645, 0.0], [4.220825059599645, 0.0], [4.3208250595996445, 0.0], [4.420825059599644, 0.0], [4.520825059599644, 0.0], [4.620825059599643, 0.0], [4.720825059599643, 0.0], [4.820825059599643, 0.0], [4.920825059599642, 0.0], [5.020825059599642, 0.0], [5.120825059599642, 0.0], [5.220825059599641, 0.0], [5.320825059599641, 0.0], [5.420825059599641, 0.0], [5.52082505959964, 0.0], [5.62082505959964, 0.0], [5.7208250595996395, 0.0], [5.820825059599639, 0.0], [5.920825059599639, 0.0], [6.020825059599638, 0.0], [6.120825059599638, 0.0], [6.220825059599638, 0.0], [6.320825059599637, 0.0], [6.420825059599637, 0.0], [6.520825059599637, 0.0], [6.620825059599636, 0.0], [6.720825059599636, 0.0], [6.820825059599636, 0.0], [6.920825059599635, 0.0], [7.020825059599635, 0.0], [7.1208250595996345, 0.0], [7.220825059599634, 0.0], [7.320825059599634, 0.0], [7.4208250595996335, 0.0], [7.520825059599633, 0.0], [7.620825059599633, 0.0], [7.720825059599632, 0.0], [7.820825059599633, 0.0], [7.920825059599633, 0.0], [8.020825059599632, 0.0], [8.120825059599632, 0.0], [8.22082505959963, 0.0], [8.32082505959963, 0.0], [8.420825059599629, 0.0], [8.520825059599629, 0.0], [8.620825059599628, 0.0], [8.720825059599628, 0.0], [8.820825059599628, 0.0], [8.920825059599627, 0.0], [9.020825059599627, 0.0], [9.120825059599627, 0.0], [9.220825059599626, 0.0], [9.320825059599626, 0.0], [9.420825059599625, 0.0], [9.520825059599625, 0.0], [9.620825059599625, 0.0], [9.720825059599624, 0.0], [9.820825059599624, 0.0], [9.920825059599624, 0.0], [10.020825059599623, 0.0], [10.120825059599623, 0.0], [10.220825059599623, 0.0], [10.320825059599622, 0.0], [10.420825059599622, 0.0], [10.520825059599622, 0.0], [10.620825059599621, 0.0], [10.72082505959962, 0.0], [10.82082505959962, 0.0], [10.92082505959962, 0.0], [11.02082505959962, 0.0], [11.12082505959962, 0.0], [11.220825059599619, 0.0], [11.320825059599619, 0.0], [11.420825059599618, 0.0], [11.520825059599618, 0.0], [11.620825059599618, 0.0], [11.720825059599617, 0.0], [11.820825059599617, 0.0], [11.920825059599617, 0.0], [12.020825059599616, 0.0], [12.120825059599616, 0.0], [12.220825059599616, 0.0], [12.320825059599615, 0.0], [12.420825059599615, 0.0], [12.520825059599614, 0.0], [12.620825059599614, 0.0], [12.720825059599614, 0.0], [12.820825059599613, 0.0], [12.920825059599613, 0.0], [13.020825059599613, 0.0], [13.120825059599612, 0.0], [13.220825059599612, 0.0], [13.320825059599612, 0.0], [13.420825059599611, 0.0], [13.520825059599611, 0.0], [13.62082505959961, 0.0], [13.72082505959961, 0.0], [13.82082505959961, 0.0], [13.92082505959961, 0.0], [14.02082505959961, 0.0], [14.120825059599609, 0.0], [14.220825059599608, 0.0], [14.320825059599608, 0.0], [14.420825059599608, 0.0], [14.520825059599607, 0.0], [14.620825059599607, 0.0], [14.720825059599607, 0.0], [14.815808870532319, 0.0], [14.891643858612397, 0.0], [14.947478846692476, 0.0], [14.983313834772554, 0.0], [14.999148822852634, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779], "velocities": null}}, "time": 1740481168.36363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3336356042600706, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.36363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.38363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3340700276219934, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.38363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.40363, "x": 4.1718763639281535, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.40363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38534764574512076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3349381357925551, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.40363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.42363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3904883719987723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3537438749924682, "gear": 1, "accelerator_pedal_position": 0.38534764574512076, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.42363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.44363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3904883719987723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37317059575740025, "gear": 1, "accelerator_pedal_position": 0.3904883719987723, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.44363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.46363} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.17187636392815353, 0.0], [0.23657153246753906, 0.0], [0.3212667010069246, 0.0], [0.42596186954631016, 0.0], [0.5506570380856957, 0.0], [0.6953522066250812, 0.0], [0.8568007388927036, 0.0], [0.9568007388927037, 0.0], [1.0568007388927039, 0.0], [1.156800738892704, 0.0], [1.256800738892704, 0.0], [1.3568007388927041, 0.0], [1.4568007388927042, 0.0], [1.5568007388927043, 0.0], [1.6568007388927044, 0.0], [1.7568007388927045, 0.0], [1.8568007388927046, 0.0], [1.9568007388927042, 0.0], [2.0568007388927043, 0.0], [2.1568007388927044, 0.0], [2.2568007388927045, 0.0], [2.3568007388927046, 0.0], [2.4568007388927047, 0.0], [2.5568007388927048, 0.0], [2.656800738892705, 0.0], [2.756800738892705, 0.0], [2.856800738892705, 0.0], [2.956800738892705, 0.0], [3.056800738892705, 0.0], [3.1568007388927053, 0.0], [3.2568007388927054, 0.0], [3.3568007388927055, 0.0], [3.4568007388927056, 0.0], [3.5568007388927056, 0.0], [3.6568007388927057, 0.0], [3.756800738892706, 0.0], [3.856800738892706, 0.0], [3.9568007388927056, 0.0], [4.056800738892705, 0.0], [4.156800738892705, 0.0], [4.2568007388927045, 0.0], [4.356800738892704, 0.0], [4.456800738892704, 0.0], [4.556800738892703, 0.0], [4.656800738892703, 0.0], [4.756800738892703, 0.0], [4.856800738892702, 0.0], [4.956800738892702, 0.0], [5.056800738892702, 0.0], [5.156800738892701, 0.0], [5.256800738892701, 0.0], [5.356800738892701, 0.0], [5.4568007388927, 0.0], [5.5568007388927, 0.0], [5.6568007388926995, 0.0], [5.756800738892699, 0.0], [5.856800738892699, 0.0], [5.9568007388926985, 0.0], [6.056800738892698, 0.0], [6.156800738892698, 0.0], [6.256800738892697, 0.0], [6.356800738892697, 0.0], [6.456800738892697, 0.0], [6.556800738892696, 0.0], [6.656800738892696, 0.0], [6.756800738892696, 0.0], [6.856800738892695, 0.0], [6.956800738892695, 0.0], [7.0568007388926945, 0.0], [7.156800738892694, 0.0], [7.256800738892694, 0.0], [7.3568007388926935, 0.0], [7.456800738892693, 0.0], [7.556800738892693, 0.0], [7.656800738892692, 0.0], [7.756800738892692, 0.0], [7.856800738892692, 0.0], [7.956800738892691, 0.0], [8.05680073889269, 0.0], [8.15680073889269, 0.0], [8.25680073889269, 0.0], [8.356800738892689, 0.0], [8.456800738892689, 0.0], [8.556800738892688, 0.0], [8.656800738892688, 0.0], [8.756800738892688, 0.0], [8.856800738892687, 0.0], [8.956800738892687, 0.0], [9.056800738892687, 0.0], [9.156800738892686, 0.0], [9.256800738892686, 0.0], [9.356800738892685, 0.0], [9.456800738892685, 0.0], [9.556800738892685, 0.0], [9.656800738892684, 0.0], [9.756800738892684, 0.0], [9.856800738892684, 0.0], [9.956800738892683, 0.0], [10.056800738892683, 0.0], [10.156800738892683, 0.0], [10.256800738892682, 0.0], [10.356800738892682, 0.0], [10.456800738892682, 0.0], [10.556800738892681, 0.0], [10.65680073889268, 0.0], [10.75680073889268, 0.0], [10.85680073889268, 0.0], [10.95680073889268, 0.0], [11.05680073889268, 0.0], [11.156800738892679, 0.0], [11.256800738892679, 0.0], [11.356800738892678, 0.0], [11.456800738892678, 0.0], [11.556800738892678, 0.0], [11.656800738892677, 0.0], [11.756800738892677, 0.0], [11.856800738892677, 0.0], [11.956800738892676, 0.0], [12.056800738892676, 0.0], [12.156800738892676, 0.0], [12.256800738892675, 0.0], [12.356800738892675, 0.0], [12.456800738892674, 0.0], [12.556800738892674, 0.0], [12.656800738892674, 0.0], [12.756800738892673, 0.0], [12.856800738892673, 0.0], [12.956800738892673, 0.0], [13.056800738892672, 0.0], [13.156800738892672, 0.0], [13.256800738892672, 0.0], [13.356800738892671, 0.0], [13.456800738892671, 0.0], [13.55680073889267, 0.0], [13.65680073889267, 0.0], [13.75680073889267, 0.0], [13.85680073889267, 0.0], [13.95680073889267, 0.0], [14.056800738892669, 0.0], [14.156800738892668, 0.0], [14.256800738892668, 0.0], [14.356800738892668, 0.0], [14.456800738892667, 0.0], [14.556800738892667, 0.0], [14.656800738892667, 0.0], [14.75675448884318, 0.0], [14.845394341064647, 0.0], [14.914034193286113, 0.0], [14.96267404550758, 0.0], [14.991313897729047, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251, 10.47979589711325, 10.57979589711325, 10.67979589711325, 10.77979589711325, 10.87979589711325, 10.979795897113249, 11.079795897113248, 11.179795897113248, 11.279795897113248, 11.379795897113247, 11.479795897113247, 11.579795897113247, 11.679795897113246, 11.779795897113246, 11.879795897113246, 11.979795897113245, 12.079795897113245, 12.179795897113245, 12.279795897113244, 12.379795897113244, 12.479795897113243, 12.579795897113243, 12.679795897113243, 12.779795897113242, 12.879795897113242, 12.979795897113242, 13.079795897113241, 13.179795897113241, 13.27979589711324, 13.37979589711324, 13.47979589711324, 13.57979589711324, 13.67979589711324, 13.779795897113239, 13.879795897113238, 13.979795897113238, 14.079795897113238, 14.179795897113237, 14.279795897113237, 14.379795897113237, 14.479795897113236, 14.579795897113236, 14.679795897113236, 14.779795897113235, 14.879795897113235, 14.979795897113235, 15.079795897113234, 15.179795897113234, 15.279795897113233], "velocities": null}}, "time": 1740481168.46363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40226885836995085, "gear": 1, "accelerator_pedal_position": 0.3904883719987723, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.46363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.48363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40266391435302024, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.48363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.50363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4034533384390684, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.50363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.51363, "x": 4.213441881828219, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.52363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38576081767890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41363343506612116, "gear": 1, "accelerator_pedal_position": 0.38576081767890713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.52363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.54363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3907724276185952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4230195601916593, "gear": 1, "accelerator_pedal_position": 0.38576081767890713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.54363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.5636299} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.21344188182821888, 0.0], [0.2893899361829274, 0.0], [0.38533799053763584, 0.0], [0.5012860448923444, 0.0], [0.6372340992470529, 0.0], [0.7930067582545417, 0.0], [0.8930067582545417, 0.0], [0.9930067582545417, 0.0], [1.0930067582545417, 0.0], [1.1930067582545418, 0.0], [1.293006758254542, 0.0], [1.393006758254542, 0.0], [1.493006758254542, 0.0], [1.5930067582545422, 0.0], [1.6930067582545423, 0.0], [1.7930067582545424, 0.0], [1.8930067582545425, 0.0], [1.9930067582545425, 0.0], [2.0930067582545426, 0.0], [2.1930067582545427, 0.0], [2.293006758254543, 0.0], [2.393006758254543, 0.0], [2.493006758254543, 0.0], [2.593006758254543, 0.0], [2.693006758254543, 0.0], [2.7930067582545433, 0.0], [2.8930067582545433, 0.0], [2.9930067582545434, 0.0], [3.0930067582545435, 0.0], [3.1930067582545436, 0.0], [3.2930067582545437, 0.0], [3.393006758254544, 0.0], [3.493006758254544, 0.0], [3.593006758254544, 0.0], [3.693006758254544, 0.0], [3.793006758254544, 0.0], [3.8930067582545442, 0.0], [3.993006758254544, 0.0], [4.0930067582545435, 0.0], [4.193006758254543, 0.0], [4.293006758254543, 0.0], [4.3930067582545425, 0.0], [4.493006758254542, 0.0], [4.593006758254542, 0.0], [4.693006758254541, 0.0], [4.793006758254541, 0.0], [4.893006758254541, 0.0], [4.99300675825454, 0.0], [5.09300675825454, 0.0], [5.19300675825454, 0.0], [5.293006758254539, 0.0], [5.393006758254539, 0.0], [5.4930067582545385, 0.0], [5.593006758254538, 0.0], [5.693006758254538, 0.0], [5.7930067582545375, 0.0], [5.893006758254537, 0.0], [5.993006758254537, 0.0], [6.093006758254536, 0.0], [6.193006758254536, 0.0], [6.293006758254536, 0.0], [6.393006758254535, 0.0], [6.493006758254535, 0.0], [6.593006758254535, 0.0], [6.693006758254534, 0.0], [6.793006758254534, 0.0], [6.893006758254534, 0.0], [6.993006758254533, 0.0], [7.093006758254533, 0.0], [7.1930067582545325, 0.0], [7.293006758254532, 0.0], [7.393006758254532, 0.0], [7.493006758254531, 0.0], [7.593006758254531, 0.0], [7.693006758254531, 0.0], [7.79300675825453, 0.0], [7.89300675825453, 0.0], [7.9930067582545306, 0.0], [8.09300675825453, 0.0], [8.19300675825453, 0.0], [8.29300675825453, 0.0], [8.39300675825453, 0.0], [8.493006758254529, 0.0], [8.593006758254528, 0.0], [8.693006758254528, 0.0], [8.793006758254528, 0.0], [8.893006758254527, 0.0], [8.993006758254527, 0.0], [9.093006758254527, 0.0], [9.193006758254526, 0.0], [9.293006758254526, 0.0], [9.393006758254526, 0.0], [9.493006758254525, 0.0], [9.593006758254525, 0.0], [9.693006758254525, 0.0], [9.793006758254524, 0.0], [9.893006758254524, 0.0], [9.993006758254523, 0.0], [10.093006758254523, 0.0], [10.193006758254523, 0.0], [10.293006758254522, 0.0], [10.393006758254522, 0.0], [10.493006758254522, 0.0], [10.593006758254521, 0.0], [10.693006758254521, 0.0], [10.79300675825452, 0.0], [10.89300675825452, 0.0], [10.99300675825452, 0.0], [11.09300675825452, 0.0], [11.19300675825452, 0.0], [11.293006758254519, 0.0], [11.393006758254518, 0.0], [11.493006758254518, 0.0], [11.593006758254518, 0.0], [11.693006758254517, 0.0], [11.793006758254517, 0.0], [11.893006758254517, 0.0], [11.993006758254516, 0.0], [12.093006758254516, 0.0], [12.193006758254516, 0.0], [12.293006758254515, 0.0], [12.393006758254515, 0.0], [12.493006758254515, 0.0], [12.593006758254514, 0.0], [12.693006758254514, 0.0], [12.793006758254513, 0.0], [12.893006758254513, 0.0], [12.993006758254513, 0.0], [13.093006758254512, 0.0], [13.193006758254512, 0.0], [13.293006758254512, 0.0], [13.393006758254511, 0.0], [13.493006758254511, 0.0], [13.59300675825451, 0.0], [13.69300675825451, 0.0], [13.79300675825451, 0.0], [13.89300675825451, 0.0], [13.99300675825451, 0.0], [14.093006758254509, 0.0], [14.193006758254509, 0.0], [14.293006758254508, 0.0], [14.393006758254508, 0.0], [14.493006758254507, 0.0], [14.593006758254507, 0.0], [14.693006758254507, 0.0], [14.791157176998945, 0.0], [14.872555825348043, 0.0], [14.933954473697142, 0.0], [14.97535312204624, 0.0], [14.99675177039534, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769, 15.11649658092769, 15.21649658092769], "velocities": null}}, "time": 1740481168.5636299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45245002485627767, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.5636299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.5836298} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.3927798, "x": 15.0, "y": 2.6199999999999877, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.5836298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45245002485627767, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.5836298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.6036298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45318116155623006, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6036298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.6236298, "x": 4.26128123218118, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6236298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39014676058456527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45391143489302915, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6236298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6436298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47317895898620943, "gear": 1, "accelerator_pedal_position": 0.39014676058456527, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6436298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6636298} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.2612812321811804, 0.0], [0.34540465910801166, 0.0], [0.44952808603484296, 0.0], [0.5736515129616743, 0.0], [0.7177749398885056, 0.0], [0.878969332481846, 0.0], [0.978969332481846, 0.0], [1.078969332481846, 0.0], [1.178969332481846, 0.0], [1.278969332481846, 0.0], [1.3789693324818462, 0.0], [1.4789693324818463, 0.0], [1.5789693324818463, 0.0], [1.6789693324818464, 0.0], [1.7789693324818465, 0.0], [1.8789693324818466, 0.0], [1.9789693324818467, 0.0], [2.078969332481847, 0.0], [2.178969332481847, 0.0], [2.278969332481847, 0.0], [2.378969332481847, 0.0], [2.478969332481847, 0.0], [2.5789693324818472, 0.0], [2.6789693324818473, 0.0], [2.7789693324818474, 0.0], [2.8789693324818475, 0.0], [2.9789693324818476, 0.0], [3.0789693324818477, 0.0], [3.1789693324818478, 0.0], [3.278969332481848, 0.0], [3.378969332481848, 0.0], [3.478969332481848, 0.0], [3.578969332481848, 0.0], [3.678969332481848, 0.0], [3.7789693324818483, 0.0], [3.8789693324818484, 0.0], [3.9789693324818485, 0.0], [4.078969332481848, 0.0], [4.178969332481848, 0.0], [4.278969332481847, 0.0], [4.378969332481847, 0.0], [4.478969332481847, 0.0], [4.578969332481846, 0.0], [4.678969332481846, 0.0], [4.778969332481846, 0.0], [4.878969332481845, 0.0], [4.978969332481845, 0.0], [5.078969332481845, 0.0], [5.178969332481844, 0.0], [5.278969332481844, 0.0], [5.3789693324818435, 0.0], [5.478969332481843, 0.0], [5.578969332481843, 0.0], [5.678969332481842, 0.0], [5.778969332481842, 0.0], [5.878969332481842, 0.0], [5.978969332481841, 0.0], [6.078969332481841, 0.0], [6.178969332481841, 0.0], [6.27896933248184, 0.0], [6.37896933248184, 0.0], [6.47896933248184, 0.0], [6.578969332481839, 0.0], [6.678969332481839, 0.0], [6.7789693324818385, 0.0], [6.878969332481838, 0.0], [6.978969332481838, 0.0], [7.0789693324818375, 0.0], [7.178969332481837, 0.0], [7.278969332481837, 0.0], [7.378969332481836, 0.0], [7.478969332481836, 0.0], [7.578969332481836, 0.0], [7.678969332481835, 0.0], [7.778969332481835, 0.0], [7.878969332481835, 0.0], [7.978969332481834, 0.0], [8.078969332481835, 0.0], [8.178969332481834, 0.0], [8.278969332481834, 0.0], [8.378969332481834, 0.0], [8.478969332481833, 0.0], [8.578969332481833, 0.0], [8.678969332481833, 0.0], [8.778969332481832, 0.0], [8.878969332481832, 0.0], [8.978969332481832, 0.0], [9.078969332481831, 0.0], [9.178969332481831, 0.0], [9.27896933248183, 0.0], [9.37896933248183, 0.0], [9.47896933248183, 0.0], [9.57896933248183, 0.0], [9.67896933248183, 0.0], [9.778969332481829, 0.0], [9.878969332481828, 0.0], [9.978969332481828, 0.0], [10.078969332481828, 0.0], [10.178969332481827, 0.0], [10.278969332481827, 0.0], [10.378969332481827, 0.0], [10.478969332481826, 0.0], [10.578969332481826, 0.0], [10.678969332481826, 0.0], [10.778969332481825, 0.0], [10.878969332481825, 0.0], [10.978969332481824, 0.0], [11.078969332481824, 0.0], [11.178969332481824, 0.0], [11.278969332481823, 0.0], [11.378969332481823, 0.0], [11.478969332481823, 0.0], [11.578969332481822, 0.0], [11.678969332481822, 0.0], [11.778969332481822, 0.0], [11.878969332481821, 0.0], [11.978969332481821, 0.0], [12.07896933248182, 0.0], [12.17896933248182, 0.0], [12.27896933248182, 0.0], [12.37896933248182, 0.0], [12.47896933248182, 0.0], [12.578969332481819, 0.0], [12.678969332481818, 0.0], [12.778969332481818, 0.0], [12.878969332481818, 0.0], [12.978969332481817, 0.0], [13.078969332481817, 0.0], [13.178969332481817, 0.0], [13.278969332481816, 0.0], [13.378969332481816, 0.0], [13.478969332481816, 0.0], [13.578969332481815, 0.0], [13.678969332481815, 0.0], [13.778969332481815, 0.0], [13.878969332481814, 0.0], [13.978969332481814, 0.0], [14.078969332481813, 0.0], [14.178969332481813, 0.0], [14.278969332481813, 0.0], [14.378969332481812, 0.0], [14.478969332481812, 0.0], [14.578969332481812, 0.0], [14.678969332481811, 0.0], [14.778130110257369, 0.0], [14.862336243761007, 0.0], [14.926542377264644, 0.0], [14.970748510768283, 0.0], [14.994954644271921, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769, 15.11649658092769], "velocities": null}}, "time": 1740481168.6636298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5027205411068251, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6636298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6836298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5027205411068251, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6836298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.7036297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5033918182110465, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7036297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.7236297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5043972225712381, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7236297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.7336297, "x": 4.315136795216979, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7436297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39004853579169174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5047319547398345, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7436297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7636297} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.31513679521697924, 0.0], [0.4075045167487507, 0.0], [0.5198722382805221, 0.0], [0.6522399598122935, 0.0], [0.804607681344065, 0.0], [0.9678853008146366, 0.0], [1.0678853008146367, 0.0], [1.1678853008146366, 0.0], [1.2678853008146367, 0.0], [1.3678853008146368, 0.0], [1.4678853008146369, 0.0], [1.567885300814637, 0.0], [1.667885300814637, 0.0], [1.7678853008146371, 0.0], [1.8678853008146372, 0.0], [1.9678853008146373, 0.0], [2.0678853008146376, 0.0], [2.1678853008146373, 0.0], [2.267885300814638, 0.0], [2.3678853008146374, 0.0], [2.4678853008146375, 0.0], [2.5678853008146376, 0.0], [2.6678853008146377, 0.0], [2.767885300814638, 0.0], [2.867885300814638, 0.0], [2.967885300814638, 0.0], [3.067885300814638, 0.0], [3.167885300814638, 0.0], [3.2678853008146382, 0.0], [3.3678853008146383, 0.0], [3.4678853008146384, 0.0], [3.5678853008146385, 0.0], [3.6678853008146386, 0.0], [3.7678853008146387, 0.0], [3.8678853008146388, 0.0], [3.967885300814639, 0.0], [4.067885300814639, 0.0], [4.167885300814639, 0.0], [4.267885300814639, 0.0], [4.367885300814638, 0.0], [4.467885300814638, 0.0], [4.567885300814638, 0.0], [4.667885300814637, 0.0], [4.767885300814637, 0.0], [4.8678853008146366, 0.0], [4.967885300814636, 0.0], [5.067885300814636, 0.0], [5.1678853008146355, 0.0], [5.267885300814635, 0.0], [5.367885300814635, 0.0], [5.467885300814634, 0.0], [5.567885300814634, 0.0], [5.667885300814634, 0.0], [5.767885300814633, 0.0], [5.867885300814633, 0.0], [5.967885300814633, 0.0], [6.067885300814632, 0.0], [6.167885300814632, 0.0], [6.267885300814632, 0.0], [6.367885300814631, 0.0], [6.467885300814631, 0.0], [6.5678853008146305, 0.0], [6.66788530081463, 0.0], [6.76788530081463, 0.0], [6.8678853008146294, 0.0], [6.967885300814629, 0.0], [7.067885300814629, 0.0], [7.167885300814628, 0.0], [7.267885300814628, 0.0], [7.367885300814628, 0.0], [7.467885300814627, 0.0], [7.567885300814627, 0.0], [7.667885300814627, 0.0], [7.767885300814626, 0.0], [7.867885300814626, 0.0], [7.9678853008146255, 0.0], [8.067885300814625, 0.0], [8.167885300814625, 0.0], [8.267885300814626, 0.0], [8.367885300814626, 0.0], [8.467885300814626, 0.0], [8.567885300814625, 0.0], [8.667885300814625, 0.0], [8.767885300814624, 0.0], [8.867885300814624, 0.0], [8.967885300814624, 0.0], [9.067885300814623, 0.0], [9.167885300814623, 0.0], [9.267885300814623, 0.0], [9.367885300814622, 0.0], [9.467885300814622, 0.0], [9.567885300814622, 0.0], [9.667885300814621, 0.0], [9.767885300814621, 0.0], [9.86788530081462, 0.0], [9.96788530081462, 0.0], [10.06788530081462, 0.0], [10.16788530081462, 0.0], [10.26788530081462, 0.0], [10.367885300814619, 0.0], [10.467885300814618, 0.0], [10.567885300814618, 0.0], [10.667885300814618, 0.0], [10.767885300814617, 0.0], [10.867885300814617, 0.0], [10.967885300814617, 0.0], [11.067885300814616, 0.0], [11.167885300814616, 0.0], [11.267885300814616, 0.0], [11.367885300814615, 0.0], [11.467885300814615, 0.0], [11.567885300814615, 0.0], [11.667885300814614, 0.0], [11.767885300814614, 0.0], [11.867885300814613, 0.0], [11.967885300814613, 0.0], [12.067885300814613, 0.0], [12.167885300814612, 0.0], [12.267885300814612, 0.0], [12.367885300814612, 0.0], [12.467885300814611, 0.0], [12.567885300814611, 0.0], [12.66788530081461, 0.0], [12.76788530081461, 0.0], [12.86788530081461, 0.0], [12.96788530081461, 0.0], [13.06788530081461, 0.0], [13.167885300814609, 0.0], [13.267885300814608, 0.0], [13.367885300814608, 0.0], [13.467885300814608, 0.0], [13.567885300814607, 0.0], [13.667885300814607, 0.0], [13.767885300814607, 0.0], [13.867885300814606, 0.0], [13.967885300814606, 0.0], [14.067885300814606, 0.0], [14.167885300814605, 0.0], [14.267885300814605, 0.0], [14.367885300814605, 0.0], [14.467885300814604, 0.0], [14.567885300814604, 0.0], [14.667885300814604, 0.0], [14.767565416829374, 0.0], [14.853988356666454, 0.0], [14.920411296503532, 0.0], [14.966834236340611, 0.0], [14.993257176177691, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769], "velocities": null}}, "time": 1740481168.7636297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5430979928271291, "gear": 1, "accelerator_pedal_position": 0.39004853579169174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7636297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7836297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5430979928271291, "gear": 1, "accelerator_pedal_position": 0.39004853579169174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7836297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.8036296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5437204591297793, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8036296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.8236296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5443421678564628, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8236296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.8436296, "x": 4.373578366741195, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8436296} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.6127732, "x": 15.0, "y": 2.7299999999999853, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.8436296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5449631197746299, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8436296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8636296} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.37357836674119493, 0.0], [0.4725704715467334, 0.0], [0.5915625763522718, 0.0], [0.7305546811578103, 0.0], [0.8887365899065505, 0.0], [0.9887365899065506, 0.0], [1.0887365899065504, 0.0], [1.1887365899065505, 0.0], [1.2887365899065504, 0.0], [1.3887365899065505, 0.0], [1.4887365899065506, 0.0], [1.5887365899065506, 0.0], [1.6887365899065507, 0.0], [1.7887365899065508, 0.0], [1.888736589906551, 0.0], [1.988736589906551, 0.0], [2.088736589906551, 0.0], [2.188736589906551, 0.0], [2.2887365899065513, 0.0], [2.3887365899065514, 0.0], [2.4887365899065514, 0.0], [2.5887365899065515, 0.0], [2.6887365899065516, 0.0], [2.7887365899065517, 0.0], [2.888736589906552, 0.0], [2.988736589906552, 0.0], [3.088736589906552, 0.0], [3.188736589906552, 0.0], [3.288736589906552, 0.0], [3.3887365899065522, 0.0], [3.4887365899065523, 0.0], [3.5887365899065524, 0.0], [3.6887365899065525, 0.0], [3.7887365899065526, 0.0], [3.8887365899065527, 0.0], [3.9887365899065528, 0.0], [4.088736589906553, 0.0], [4.1887365899065525, 0.0], [4.288736589906552, 0.0], [4.388736589906552, 0.0], [4.488736589906551, 0.0], [4.588736589906551, 0.0], [4.688736589906551, 0.0], [4.78873658990655, 0.0], [4.88873658990655, 0.0], [4.98873658990655, 0.0], [5.088736589906549, 0.0], [5.188736589906549, 0.0], [5.288736589906549, 0.0], [5.388736589906548, 0.0], [5.488736589906548, 0.0], [5.5887365899065475, 0.0], [5.688736589906547, 0.0], [5.788736589906547, 0.0], [5.8887365899065465, 0.0], [5.988736589906546, 0.0], [6.088736589906546, 0.0], [6.188736589906545, 0.0], [6.288736589906545, 0.0], [6.388736589906545, 0.0], [6.488736589906544, 0.0], [6.588736589906544, 0.0], [6.688736589906544, 0.0], [6.788736589906543, 0.0], [6.888736589906543, 0.0], [6.988736589906543, 0.0], [7.088736589906542, 0.0], [7.188736589906542, 0.0], [7.2887365899065415, 0.0], [7.388736589906541, 0.0], [7.488736589906541, 0.0], [7.58873658990654, 0.0], [7.68873658990654, 0.0], [7.78873658990654, 0.0], [7.888736589906539, 0.0], [7.988736589906539, 0.0], [8.088736589906539, 0.0], [8.188736589906538, 0.0], [8.288736589906538, 0.0], [8.38873658990654, 0.0], [8.488736589906539, 0.0], [8.588736589906539, 0.0], [8.688736589906538, 0.0], [8.788736589906538, 0.0], [8.888736589906538, 0.0], [8.988736589906537, 0.0], [9.088736589906537, 0.0], [9.188736589906537, 0.0], [9.288736589906536, 0.0], [9.388736589906536, 0.0], [9.488736589906535, 0.0], [9.588736589906535, 0.0], [9.688736589906535, 0.0], [9.788736589906534, 0.0], [9.888736589906534, 0.0], [9.988736589906534, 0.0], [10.088736589906533, 0.0], [10.188736589906533, 0.0], [10.288736589906533, 0.0], [10.388736589906532, 0.0], [10.488736589906532, 0.0], [10.588736589906532, 0.0], [10.688736589906531, 0.0], [10.78873658990653, 0.0], [10.88873658990653, 0.0], [10.98873658990653, 0.0], [11.08873658990653, 0.0], [11.18873658990653, 0.0], [11.288736589906529, 0.0], [11.388736589906529, 0.0], [11.488736589906528, 0.0], [11.588736589906528, 0.0], [11.688736589906528, 0.0], [11.788736589906527, 0.0], [11.888736589906527, 0.0], [11.988736589906527, 0.0], [12.088736589906526, 0.0], [12.188736589906526, 0.0], [12.288736589906526, 0.0], [12.388736589906525, 0.0], [12.488736589906525, 0.0], [12.588736589906524, 0.0], [12.688736589906524, 0.0], [12.788736589906524, 0.0], [12.888736589906523, 0.0], [12.988736589906523, 0.0], [13.088736589906523, 0.0], [13.188736589906522, 0.0], [13.288736589906522, 0.0], [13.388736589906522, 0.0], [13.488736589906521, 0.0], [13.588736589906521, 0.0], [13.68873658990652, 0.0], [13.78873658990652, 0.0], [13.88873658990652, 0.0], [13.98873658990652, 0.0], [14.08873658990652, 0.0], [14.188736589906519, 0.0], [14.288736589906518, 0.0], [14.388736589906518, 0.0], [14.488736589906518, 0.0], [14.588736589906517, 0.0], [14.688736589906517, 0.0], [14.787236066508932, 0.0], [14.869488748527628, 0.0], [14.931741430546325, 0.0], [14.97399411256502, 0.0], [14.996246794583717, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161, 10.153197264742161, 10.25319726474216, 10.35319726474216, 10.45319726474216, 10.55319726474216, 10.65319726474216, 10.753197264742159, 10.853197264742159, 10.953197264742158, 11.053197264742158, 11.153197264742158, 11.253197264742157, 11.353197264742157, 11.453197264742156, 11.553197264742156, 11.653197264742156, 11.753197264742155, 11.853197264742155, 11.953197264742155, 12.053197264742154, 12.153197264742154, 12.253197264742154, 12.353197264742153, 12.453197264742153, 12.553197264742153, 12.653197264742152, 12.753197264742152, 12.853197264742152, 12.953197264742151, 13.05319726474215, 13.15319726474215, 13.25319726474215, 13.35319726474215, 13.45319726474215, 13.553197264742149, 13.653197264742149, 13.753197264742148, 13.853197264742148, 13.953197264742148, 14.053197264742147, 14.153197264742147, 14.253197264742147, 14.353197264742146, 14.453197264742146, 14.553197264742145, 14.653197264742145, 14.753197264742145, 14.853197264742144, 14.953197264742144], "velocities": null}}, "time": 1740481168.8636296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5740388185533857, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8636296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8836296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5743312195232841, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8836296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9036295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5749154822197232, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9036295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9236295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5754990265478943, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9236295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9436295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5760818532548847, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9436295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.9536295, "x": 4.436223012925216, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481168.9636295} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.4362230129252156, 0.0], [0.540344329322956, 0.0], [0.6644656457206964, 0.0], [0.8085869621184367, 0.0], [0.9697803863013584, 0.0], [1.0697803863013584, 0.0], [1.1697803863013583, 0.0], [1.2697803863013584, 0.0], [1.3697803863013585, 0.0], [1.4697803863013585, 0.0], [1.5697803863013586, 0.0], [1.6697803863013587, 0.0], [1.7697803863013588, 0.0], [1.869780386301359, 0.0], [1.969780386301359, 0.0], [2.069780386301359, 0.0], [2.169780386301359, 0.0], [2.2697803863013593, 0.0], [2.369780386301359, 0.0], [2.469780386301359, 0.0], [2.569780386301359, 0.0], [2.669780386301359, 0.0], [2.7697803863013593, 0.0], [2.8697803863013593, 0.0], [2.9697803863013594, 0.0], [3.0697803863013595, 0.0], [3.1697803863013596, 0.0], [3.2697803863013597, 0.0], [3.36978038630136, 0.0], [3.46978038630136, 0.0], [3.56978038630136, 0.0], [3.66978038630136, 0.0], [3.76978038630136, 0.0], [3.8697803863013602, 0.0], [3.9697803863013603, 0.0], [4.06978038630136, 0.0], [4.16978038630136, 0.0], [4.269780386301361, 0.0], [4.36978038630136, 0.0], [4.46978038630136, 0.0], [4.5697803863013595, 0.0], [4.669780386301359, 0.0], [4.769780386301359, 0.0], [4.8697803863013585, 0.0], [4.969780386301358, 0.0], [5.069780386301358, 0.0], [5.169780386301357, 0.0], [5.269780386301357, 0.0], [5.369780386301357, 0.0], [5.469780386301356, 0.0], [5.569780386301356, 0.0], [5.669780386301356, 0.0], [5.769780386301355, 0.0], [5.869780386301355, 0.0], [5.9697803863013545, 0.0], [6.069780386301354, 0.0], [6.169780386301354, 0.0], [6.2697803863013535, 0.0], [6.369780386301353, 0.0], [6.469780386301353, 0.0], [6.569780386301352, 0.0], [6.669780386301352, 0.0], [6.769780386301352, 0.0], [6.869780386301351, 0.0], [6.969780386301351, 0.0], [7.069780386301351, 0.0], [7.16978038630135, 0.0], [7.26978038630135, 0.0], [7.36978038630135, 0.0], [7.469780386301349, 0.0], [7.569780386301349, 0.0], [7.6697803863013485, 0.0], [7.769780386301348, 0.0], [7.869780386301348, 0.0], [7.969780386301347, 0.0], [8.069780386301346, 0.0], [8.169780386301346, 0.0], [8.269780386301345, 0.0], [8.369780386301345, 0.0], [8.469780386301345, 0.0], [8.569780386301344, 0.0], [8.669780386301344, 0.0], [8.769780386301344, 0.0], [8.869780386301343, 0.0], [8.969780386301343, 0.0], [9.069780386301343, 0.0], [9.169780386301342, 0.0], [9.269780386301342, 0.0], [9.369780386301342, 0.0], [9.469780386301341, 0.0], [9.56978038630134, 0.0], [9.66978038630134, 0.0], [9.76978038630134, 0.0], [9.86978038630134, 0.0], [9.96978038630134, 0.0], [10.069780386301339, 0.0], [10.169780386301339, 0.0], [10.269780386301338, 0.0], [10.369780386301338, 0.0], [10.469780386301338, 0.0], [10.569780386301337, 0.0], [10.669780386301337, 0.0], [10.769780386301337, 0.0], [10.869780386301336, 0.0], [10.969780386301336, 0.0], [11.069780386301336, 0.0], [11.169780386301335, 0.0], [11.269780386301335, 0.0], [11.369780386301334, 0.0], [11.469780386301334, 0.0], [11.569780386301334, 0.0], [11.669780386301333, 0.0], [11.769780386301333, 0.0], [11.869780386301333, 0.0], [11.969780386301332, 0.0], [12.069780386301332, 0.0], [12.169780386301332, 0.0], [12.269780386301331, 0.0], [12.369780386301331, 0.0], [12.46978038630133, 0.0], [12.56978038630133, 0.0], [12.66978038630133, 0.0], [12.76978038630133, 0.0], [12.86978038630133, 0.0], [12.969780386301329, 0.0], [13.069780386301328, 0.0], [13.169780386301328, 0.0], [13.269780386301328, 0.0], [13.369780386301327, 0.0], [13.469780386301327, 0.0], [13.569780386301327, 0.0], [13.669780386301326, 0.0], [13.769780386301326, 0.0], [13.869780386301326, 0.0], [13.969780386301325, 0.0], [14.069780386301325, 0.0], [14.169780386301325, 0.0], [14.269780386301324, 0.0], [14.369780386301324, 0.0], [14.469780386301323, 0.0], [14.569780386301323, 0.0], [14.669780386301323, 0.0], [14.769389122619092, 0.0], [14.855433045358827, 0.0], [14.921476968098563, 0.0], [14.9675208908383, 0.0], [14.993564813578034, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161, 10.153197264742161, 10.25319726474216, 10.35319726474216, 10.45319726474216, 10.55319726474216, 10.65319726474216, 10.753197264742159, 10.853197264742159, 10.953197264742158, 11.053197264742158, 11.153197264742158, 11.253197264742157, 11.353197264742157, 11.453197264742156, 11.553197264742156, 11.653197264742156, 11.753197264742155, 11.853197264742155, 11.953197264742155, 12.053197264742154, 12.153197264742154, 12.253197264742154, 12.353197264742153, 12.453197264742153, 12.553197264742153, 12.653197264742152, 12.753197264742152, 12.853197264742152, 12.953197264742151, 13.05319726474215, 13.15319726474215, 13.25319726474215, 13.35319726474215, 13.45319726474215, 13.553197264742149, 13.653197264742149, 13.753197264742148, 13.853197264742148, 13.953197264742148, 14.053197264742147, 14.153197264742147, 14.253197264742147, 14.353197264742146, 14.453197264742146, 14.553197264742145, 14.653197264742145, 14.753197264742145, 14.853197264742144], "velocities": null}}, "time": 1740481168.9636295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5769547494088851, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9636295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481168.9836295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5866329843558942, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9836295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0036294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6059715434152646, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0036294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0236294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6252861213177344, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0236294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0436294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6445765986270439, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0436294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.0636294, "x": 4.503158444844102, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.0636294} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.503158444844102, 0.0], [0.6215635293837478, 0.0], [0.7599686139233935, 0.0], [0.917721976700896, 0.0], [1.017721976700896, 0.0], [1.117721976700896, 0.0], [1.2177219767008958, 0.0], [1.3177219767008959, 0.0], [1.4177219767008957, 0.0], [1.5177219767008958, 0.0], [1.617721976700896, 0.0], [1.717721976700896, 0.0], [1.817721976700896, 0.0], [1.9177219767008962, 0.0], [2.017721976700896, 0.0], [2.1177219767008966, 0.0], [2.217721976700896, 0.0], [2.3177219767008967, 0.0], [2.4177219767008964, 0.0], [2.517721976700897, 0.0], [2.617721976700897, 0.0], [2.717721976700897, 0.0], [2.817721976700897, 0.0], [2.917721976700897, 0.0], [3.017721976700897, 0.0], [3.117721976700897, 0.0], [3.217721976700897, 0.0], [3.317721976700897, 0.0], [3.4177219767008973, 0.0], [3.5177219767008974, 0.0], [3.6177219767008975, 0.0], [3.7177219767008975, 0.0], [3.8177219767008976, 0.0], [3.9177219767008977, 0.0], [4.017721976700898, 0.0], [4.1177219767008975, 0.0], [4.217721976700898, 0.0], [4.3177219767008985, 0.0], [4.417721976700898, 0.0], [4.517721976700899, 0.0], [4.617721976700898, 0.0], [4.717721976700898, 0.0], [4.817721976700898, 0.0], [4.917721976700897, 0.0], [5.017721976700897, 0.0], [5.117721976700897, 0.0], [5.217721976700896, 0.0], [5.317721976700896, 0.0], [5.4177219767008955, 0.0], [5.517721976700895, 0.0], [5.617721976700895, 0.0], [5.717721976700894, 0.0], [5.817721976700894, 0.0], [5.917721976700894, 0.0], [6.017721976700893, 0.0], [6.117721976700893, 0.0], [6.217721976700893, 0.0], [6.317721976700892, 0.0], [6.417721976700892, 0.0], [6.517721976700892, 0.0], [6.617721976700891, 0.0], [6.717721976700891, 0.0], [6.8177219767008905, 0.0], [6.91772197670089, 0.0], [7.01772197670089, 0.0], [7.1177219767008895, 0.0], [7.217721976700889, 0.0], [7.317721976700889, 0.0], [7.417721976700888, 0.0], [7.517721976700888, 0.0], [7.617721976700888, 0.0], [7.717721976700887, 0.0], [7.817721976700887, 0.0], [7.917721976700887, 0.0], [8.017721976700887, 0.0], [8.117721976700885, 0.0], [8.217721976700886, 0.0], [8.317721976700884, 0.0], [8.417721976700886, 0.0], [8.517721976700884, 0.0], [8.617721976700883, 0.0], [8.717721976700883, 0.0], [8.817721976700883, 0.0], [8.917721976700882, 0.0], [9.017721976700882, 0.0], [9.117721976700881, 0.0], [9.217721976700881, 0.0], [9.31772197670088, 0.0], [9.41772197670088, 0.0], [9.51772197670088, 0.0], [9.61772197670088, 0.0], [9.71772197670088, 0.0], [9.817721976700879, 0.0], [9.917721976700879, 0.0], [10.017721976700878, 0.0], [10.117721976700878, 0.0], [10.217721976700878, 0.0], [10.317721976700877, 0.0], [10.417721976700877, 0.0], [10.517721976700876, 0.0], [10.617721976700876, 0.0], [10.717721976700876, 0.0], [10.817721976700875, 0.0], [10.917721976700875, 0.0], [11.017721976700875, 0.0], [11.117721976700874, 0.0], [11.217721976700874, 0.0], [11.317721976700874, 0.0], [11.417721976700873, 0.0], [11.517721976700873, 0.0], [11.617721976700873, 0.0], [11.717721976700872, 0.0], [11.817721976700872, 0.0], [11.917721976700872, 0.0], [12.017721976700871, 0.0], [12.11772197670087, 0.0], [12.21772197670087, 0.0], [12.31772197670087, 0.0], [12.41772197670087, 0.0], [12.51772197670087, 0.0], [12.617721976700869, 0.0], [12.717721976700869, 0.0], [12.817721976700868, 0.0], [12.917721976700868, 0.0], [13.017721976700868, 0.0], [13.117721976700867, 0.0], [13.217721976700867, 0.0], [13.317721976700867, 0.0], [13.417721976700866, 0.0], [13.517721976700866, 0.0], [13.617721976700865, 0.0], [13.717721976700865, 0.0], [13.817721976700865, 0.0], [13.917721976700864, 0.0], [14.017721976700864, 0.0], [14.117721976700864, 0.0], [14.217721976700863, 0.0], [14.317721976700863, 0.0], [14.417721976700863, 0.0], [14.517721976700862, 0.0], [14.617721976700862, 0.0], [14.717721976700862, 0.0], [14.81313571057259, 0.0], [14.889591315232417, 0.0], [14.946046919892245, 0.0], [14.982502524552073, 0.0], [14.9989581292119, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618, 9.989897948556617, 10.089897948556617, 10.189897948556617, 10.289897948556616, 10.389897948556616, 10.489897948556616, 10.589897948556615, 10.689897948556615, 10.789897948556614, 10.889897948556614, 10.989897948556614, 11.089897948556613, 11.189897948556613, 11.289897948556613, 11.389897948556612, 11.489897948556612, 11.589897948556612, 11.689897948556611, 11.78989794855661, 11.88989794855661, 11.98989794855661, 12.08989794855661, 12.18989794855661, 12.289897948556609, 12.389897948556609, 12.489897948556608, 12.589897948556608, 12.689897948556608, 12.789897948556607, 12.889897948556607, 12.989897948556607, 13.089897948556606, 13.189897948556606, 13.289897948556606, 13.389897948556605, 13.489897948556605, 13.589897948556604, 13.689897948556604, 13.789897948556604, 13.889897948556603, 13.989897948556603, 14.089897948556603, 14.189897948556602, 14.289897948556602, 14.389897948556602, 14.489897948556601, 14.589897948556601, 14.6898979485566, 14.7898979485566], "velocities": null}}, "time": 1740481169.0636294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6734668664513794, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0636294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.0836294} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.8314939, "x": 15.0, "y": 2.839999999999983, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.0836294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6830847772561329, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0836294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1036294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7023022432446031, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1036294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1236293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7214951379813445, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1236293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1436293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7406633455834576, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1436293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1636293} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.503158444844102, 0.0], [0.6215635293837478, 0.0], [0.7599686139233935, 0.0], [0.917721976700896, 0.0], [1.017721976700896, 0.0], [1.117721976700896, 0.0], [1.2177219767008958, 0.0], [1.3177219767008959, 0.0], [1.4177219767008957, 0.0], [1.5177219767008958, 0.0], [1.617721976700896, 0.0], [1.717721976700896, 0.0], [1.817721976700896, 0.0], [1.9177219767008962, 0.0], [2.017721976700896, 0.0], [2.1177219767008966, 0.0], [2.217721976700896, 0.0], [2.3177219767008967, 0.0], [2.4177219767008964, 0.0], [2.517721976700897, 0.0], [2.617721976700897, 0.0], [2.717721976700897, 0.0], [2.817721976700897, 0.0], [2.917721976700897, 0.0], [3.017721976700897, 0.0], [3.117721976700897, 0.0], [3.217721976700897, 0.0], [3.317721976700897, 0.0], [3.4177219767008973, 0.0], [3.5177219767008974, 0.0], [3.6177219767008975, 0.0], [3.7177219767008975, 0.0], [3.8177219767008976, 0.0], [3.9177219767008977, 0.0], [4.017721976700898, 0.0], [4.1177219767008975, 0.0], [4.217721976700898, 0.0], [4.3177219767008985, 0.0], [4.417721976700898, 0.0], [4.517721976700899, 0.0], [4.617721976700898, 0.0], [4.717721976700898, 0.0], [4.817721976700898, 0.0], [4.917721976700897, 0.0], [5.017721976700897, 0.0], [5.117721976700897, 0.0], [5.217721976700896, 0.0], [5.317721976700896, 0.0], [5.4177219767008955, 0.0], [5.517721976700895, 0.0], [5.617721976700895, 0.0], [5.717721976700894, 0.0], [5.817721976700894, 0.0], [5.917721976700894, 0.0], [6.017721976700893, 0.0], [6.117721976700893, 0.0], [6.217721976700893, 0.0], [6.317721976700892, 0.0], [6.417721976700892, 0.0], [6.517721976700892, 0.0], [6.617721976700891, 0.0], [6.717721976700891, 0.0], [6.8177219767008905, 0.0], [6.91772197670089, 0.0], [7.01772197670089, 0.0], [7.1177219767008895, 0.0], [7.217721976700889, 0.0], [7.317721976700889, 0.0], [7.417721976700888, 0.0], [7.517721976700888, 0.0], [7.617721976700888, 0.0], [7.717721976700887, 0.0], [7.817721976700887, 0.0], [7.917721976700887, 0.0], [8.017721976700887, 0.0], [8.117721976700885, 0.0], [8.217721976700886, 0.0], [8.317721976700884, 0.0], [8.417721976700886, 0.0], [8.517721976700884, 0.0], [8.617721976700883, 0.0], [8.717721976700883, 0.0], [8.817721976700883, 0.0], [8.917721976700882, 0.0], [9.017721976700882, 0.0], [9.117721976700881, 0.0], [9.217721976700881, 0.0], [9.31772197670088, 0.0], [9.41772197670088, 0.0], [9.51772197670088, 0.0], [9.61772197670088, 0.0], [9.71772197670088, 0.0], [9.817721976700879, 0.0], [9.917721976700879, 0.0], [10.017721976700878, 0.0], [10.117721976700878, 0.0], [10.217721976700878, 0.0], [10.317721976700877, 0.0], [10.417721976700877, 0.0], [10.517721976700876, 0.0], [10.617721976700876, 0.0], [10.717721976700876, 0.0], [10.817721976700875, 0.0], [10.917721976700875, 0.0], [11.017721976700875, 0.0], [11.117721976700874, 0.0], [11.217721976700874, 0.0], [11.317721976700874, 0.0], [11.417721976700873, 0.0], [11.517721976700873, 0.0], [11.617721976700873, 0.0], [11.717721976700872, 0.0], [11.817721976700872, 0.0], [11.917721976700872, 0.0], [12.017721976700871, 0.0], [12.11772197670087, 0.0], [12.21772197670087, 0.0], [12.31772197670087, 0.0], [12.41772197670087, 0.0], [12.51772197670087, 0.0], [12.617721976700869, 0.0], [12.717721976700869, 0.0], [12.817721976700868, 0.0], [12.917721976700868, 0.0], [13.017721976700868, 0.0], [13.117721976700867, 0.0], [13.217721976700867, 0.0], [13.317721976700867, 0.0], [13.417721976700866, 0.0], [13.517721976700866, 0.0], [13.617721976700865, 0.0], [13.717721976700865, 0.0], [13.817721976700865, 0.0], [13.917721976700864, 0.0], [14.017721976700864, 0.0], [14.117721976700864, 0.0], [14.217721976700863, 0.0], [14.317721976700863, 0.0], [14.417721976700863, 0.0], [14.517721976700862, 0.0], [14.617721976700862, 0.0], [14.717721976700862, 0.0], [14.81313571057259, 0.0], [14.889591315232417, 0.0], [14.946046919892245, 0.0], [14.982502524552073, 0.0], [14.9989581292119, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618, 9.989897948556617, 10.089897948556617, 10.189897948556617, 10.289897948556616, 10.389897948556616, 10.489897948556616, 10.589897948556615, 10.689897948556615, 10.789897948556614, 10.889897948556614, 10.989897948556614, 11.089897948556613, 11.189897948556613, 11.289897948556613, 11.389897948556612, 11.489897948556612, 11.589897948556612, 11.689897948556611, 11.78989794855661, 11.88989794855661, 11.98989794855661, 12.08989794855661, 12.18989794855661, 12.289897948556609, 12.389897948556609, 12.489897948556608, 12.589897948556608, 12.689897948556608, 12.789897948556607, 12.889897948556607, 12.989897948556607, 13.089897948556606, 13.189897948556606, 13.289897948556606, 13.389897948556605, 13.489897948556605, 13.589897948556604, 13.689897948556604, 13.789897948556604, 13.889897948556603, 13.989897948556603, 14.089897948556603, 14.189897948556602, 14.289897948556602, 14.389897948556602, 14.489897948556601, 14.589897948556601, 14.6898979485566, 14.7898979485566], "velocities": null}}, "time": 1740481169.1636293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7693691168793342, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1636293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.1736293, "x": 4.5814642529667085, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.1836293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457422747644263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7789252394370938, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1836293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2036293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7797424855639807, "gear": 1, "accelerator_pedal_position": 0.2457422747644263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2036293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2236292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.780735384815269, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2236292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2436292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7810659170531803, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2436292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2636292} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.5814642529667085, 0.0], [0.7171017036473806, 0.0], [0.8726024825051201, 0.0], [0.97260248250512, 0.0], [1.0726024825051201, 0.0], [1.17260248250512, 0.0], [1.2726024825051199, 0.0], [1.37260248250512, 0.0], [1.47260248250512, 0.0], [1.57260248250512, 0.0], [1.67260248250512, 0.0], [1.77260248250512, 0.0], [1.8726024825051202, 0.0], [1.9726024825051203, 0.0], [2.07260248250512, 0.0], [2.1726024825051207, 0.0], [2.2726024825051203, 0.0], [2.372602482505121, 0.0], [2.4726024825051205, 0.0], [2.5726024825051206, 0.0], [2.6726024825051207, 0.0], [2.7726024825051208, 0.0], [2.872602482505121, 0.0], [2.972602482505121, 0.0], [3.072602482505121, 0.0], [3.172602482505121, 0.0], [3.272602482505121, 0.0], [3.3726024825051213, 0.0], [3.4726024825051214, 0.0], [3.5726024825051215, 0.0], [3.6726024825051216, 0.0], [3.7726024825051216, 0.0], [3.8726024825051217, 0.0], [3.972602482505122, 0.0], [4.072602482505122, 0.0], [4.172602482505122, 0.0], [4.272602482505122, 0.0], [4.372602482505123, 0.0], [4.472602482505122, 0.0], [4.572602482505122, 0.0], [4.672602482505122, 0.0], [4.772602482505121, 0.0], [4.872602482505121, 0.0], [4.9726024825051205, 0.0], [5.07260248250512, 0.0], [5.17260248250512, 0.0], [5.272602482505119, 0.0], [5.372602482505119, 0.0], [5.472602482505119, 0.0], [5.572602482505118, 0.0], [5.672602482505118, 0.0], [5.772602482505118, 0.0], [5.872602482505117, 0.0], [5.972602482505117, 0.0], [6.072602482505117, 0.0], [6.172602482505116, 0.0], [6.272602482505116, 0.0], [6.3726024825051155, 0.0], [6.472602482505115, 0.0], [6.572602482505115, 0.0], [6.6726024825051145, 0.0], [6.772602482505114, 0.0], [6.872602482505114, 0.0], [6.972602482505113, 0.0], [7.072602482505113, 0.0], [7.172602482505113, 0.0], [7.272602482505112, 0.0], [7.372602482505112, 0.0], [7.472602482505112, 0.0], [7.572602482505111, 0.0], [7.672602482505111, 0.0], [7.7726024825051105, 0.0], [7.87260248250511, 0.0], [7.97260248250511, 0.0], [8.07260248250511, 0.0], [8.17260248250511, 0.0], [8.272602482505109, 0.0], [8.372602482505108, 0.0], [8.472602482505108, 0.0], [8.572602482505108, 0.0], [8.672602482505106, 0.0], [8.772602482505105, 0.0], [8.872602482505105, 0.0], [8.972602482505105, 0.0], [9.072602482505104, 0.0], [9.172602482505104, 0.0], [9.272602482505103, 0.0], [9.372602482505103, 0.0], [9.472602482505103, 0.0], [9.572602482505102, 0.0], [9.672602482505102, 0.0], [9.772602482505102, 0.0], [9.872602482505101, 0.0], [9.972602482505101, 0.0], [10.0726024825051, 0.0], [10.1726024825051, 0.0], [10.2726024825051, 0.0], [10.3726024825051, 0.0], [10.4726024825051, 0.0], [10.572602482505099, 0.0], [10.672602482505098, 0.0], [10.772602482505098, 0.0], [10.872602482505098, 0.0], [10.972602482505097, 0.0], [11.072602482505097, 0.0], [11.172602482505097, 0.0], [11.272602482505096, 0.0], [11.372602482505096, 0.0], [11.472602482505096, 0.0], [11.572602482505095, 0.0], [11.672602482505095, 0.0], [11.772602482505095, 0.0], [11.872602482505094, 0.0], [11.972602482505094, 0.0], [12.072602482505093, 0.0], [12.172602482505093, 0.0], [12.272602482505093, 0.0], [12.372602482505092, 0.0], [12.472602482505092, 0.0], [12.572602482505092, 0.0], [12.672602482505091, 0.0], [12.772602482505091, 0.0], [12.87260248250509, 0.0], [12.97260248250509, 0.0], [13.07260248250509, 0.0], [13.17260248250509, 0.0], [13.27260248250509, 0.0], [13.372602482505089, 0.0], [13.472602482505089, 0.0], [13.572602482505088, 0.0], [13.672602482505088, 0.0], [13.772602482505087, 0.0], [13.872602482505087, 0.0], [13.972602482505087, 0.0], [14.072602482505086, 0.0], [14.172602482505086, 0.0], [14.272602482505086, 0.0], [14.372602482505085, 0.0], [14.472602482505085, 0.0], [14.572602482505085, 0.0], [14.672602482505084, 0.0], [14.77209161028969, 0.0], [14.857571113788675, 0.0], [14.923050617287657, 0.0], [14.96853012078664, 0.0], [14.994009624285624, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055, 14.526598632371055, 14.626598632371055], "velocities": null}}, "time": 1740481169.2636292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7817263309834314, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2636292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.2836292, "x": 4.667210850357501, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.2836292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7820470250323956, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2836292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3036292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8011363821047098, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3036292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3236291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8202005772979156, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3236291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3436291} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.1610777, "x": 15.0, "y": 3.0049999999999795, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.3436291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8392394984489674, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3436291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.363629} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.6672108503575007, 0.0], [0.8049185947702309, 0.0], [0.962140483197105, 0.0], [1.0621404831971049, 0.0], [1.162140483197105, 0.0], [1.262140483197105, 0.0], [1.362140483197105, 0.0], [1.4621404831971048, 0.0], [1.5621404831971049, 0.0], [1.6621404831971047, 0.0], [1.7621404831971048, 0.0], [1.862140483197105, 0.0], [1.962140483197105, 0.0], [2.062140483197105, 0.0], [2.1621404831971054, 0.0], [2.262140483197105, 0.0], [2.3621404831971056, 0.0], [2.462140483197105, 0.0], [2.5621404831971057, 0.0], [2.6621404831971054, 0.0], [2.7621404831971055, 0.0], [2.8621404831971056, 0.0], [2.962140483197106, 0.0], [3.062140483197106, 0.0], [3.1621404831971063, 0.0], [3.2621404831971064, 0.0], [3.3621404831971065, 0.0], [3.4621404831971065, 0.0], [3.5621404831971066, 0.0], [3.6621404831971067, 0.0], [3.762140483197107, 0.0], [3.862140483197107, 0.0], [3.962140483197107, 0.0], [4.062140483197107, 0.0], [4.162140483197107, 0.0], [4.262140483197108, 0.0], [4.362140483197107, 0.0], [4.462140483197107, 0.0], [4.5621404831971075, 0.0], [4.662140483197107, 0.0], [4.762140483197107, 0.0], [4.8621404831971065, 0.0], [4.962140483197105, 0.0], [5.062140483197105, 0.0], [5.1621404831971045, 0.0], [5.262140483197104, 0.0], [5.362140483197104, 0.0], [5.462140483197103, 0.0], [5.562140483197103, 0.0], [5.662140483197103, 0.0], [5.762140483197102, 0.0], [5.862140483197102, 0.0], [5.962140483197102, 0.0], [6.062140483197101, 0.0], [6.162140483197101, 0.0], [6.262140483197101, 0.0], [6.3621404831971, 0.0], [6.4621404831971, 0.0], [6.5621404831970995, 0.0], [6.662140483197099, 0.0], [6.762140483197099, 0.0], [6.8621404831970985, 0.0], [6.962140483197098, 0.0], [7.062140483197098, 0.0], [7.162140483197097, 0.0], [7.262140483197097, 0.0], [7.362140483197097, 0.0], [7.462140483197096, 0.0], [7.562140483197096, 0.0], [7.662140483197096, 0.0], [7.762140483197095, 0.0], [7.862140483197095, 0.0], [7.9621404831970946, 0.0], [8.062140483197094, 0.0], [8.162140483197094, 0.0], [8.262140483197093, 0.0], [8.362140483197093, 0.0], [8.462140483197093, 0.0], [8.562140483197092, 0.0], [8.662140483197092, 0.0], [8.762140483197092, 0.0], [8.862140483197091, 0.0], [8.962140483197093, 0.0], [9.062140483197092, 0.0], [9.162140483197092, 0.0], [9.262140483197092, 0.0], [9.362140483197091, 0.0], [9.462140483197091, 0.0], [9.56214048319709, 0.0], [9.66214048319709, 0.0], [9.76214048319709, 0.0], [9.86214048319709, 0.0], [9.96214048319709, 0.0], [10.062140483197089, 0.0], [10.162140483197089, 0.0], [10.262140483197088, 0.0], [10.362140483197088, 0.0], [10.462140483197087, 0.0], [10.562140483197087, 0.0], [10.662140483197087, 0.0], [10.762140483197086, 0.0], [10.862140483197086, 0.0], [10.962140483197086, 0.0], [11.062140483197085, 0.0], [11.162140483197085, 0.0], [11.262140483197085, 0.0], [11.362140483197084, 0.0], [11.462140483197084, 0.0], [11.562140483197084, 0.0], [11.662140483197083, 0.0], [11.762140483197083, 0.0], [11.862140483197082, 0.0], [11.962140483197082, 0.0], [12.062140483197082, 0.0], [12.162140483197081, 0.0], [12.262140483197081, 0.0], [12.36214048319708, 0.0], [12.46214048319708, 0.0], [12.56214048319708, 0.0], [12.66214048319708, 0.0], [12.76214048319708, 0.0], [12.862140483197079, 0.0], [12.962140483197079, 0.0], [13.062140483197078, 0.0], [13.162140483197078, 0.0], [13.262140483197078, 0.0], [13.362140483197077, 0.0], [13.462140483197077, 0.0], [13.562140483197076, 0.0], [13.662140483197076, 0.0], [13.762140483197076, 0.0], [13.862140483197075, 0.0], [13.962140483197075, 0.0], [14.062140483197075, 0.0], [14.162140483197074, 0.0], [14.262140483197074, 0.0], [14.362140483197074, 0.0], [14.462140483197073, 0.0], [14.562140483197073, 0.0], [14.662140483197073, 0.0], [14.761993091864813, 0.0], [14.8495649952254, 0.0], [14.917136898585985, 0.0], [14.96470880194657, 0.0], [14.992280705307156, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055, 14.526598632371055], "velocities": null}}, "time": 1740481169.363629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8677502477765686, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.363629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.383629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8678534460391245, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.383629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.393629, "x": 4.758383043708155, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.403629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38180445779595534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8680596340781482, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.403629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.423629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3880524310096888, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8949923941240038, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.423629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.443629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3880524310096888, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9042180737264933, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.443629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.463629} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.7583830437081547, 0.0], [0.9101197588503417, 0.0], [1.0733580319853693, 0.0], [1.1733580319853694, 0.0], [1.2733580319853692, 0.0], [1.373358031985369, 0.0], [1.4733580319853692, 0.0], [1.5733580319853693, 0.0], [1.6733580319853691, 0.0], [1.7733580319853692, 0.0], [1.8733580319853693, 0.0], [1.9733580319853694, 0.0], [2.0733580319853697, 0.0], [2.1733580319853694, 0.0], [2.27335803198537, 0.0], [2.3733580319853695, 0.0], [2.47335803198537, 0.0], [2.5733580319853697, 0.0], [2.6733580319853703, 0.0], [2.77335803198537, 0.0], [2.87335803198537, 0.0], [2.97335803198537, 0.0], [3.07335803198537, 0.0], [3.1733580319853703, 0.0], [3.2733580319853703, 0.0], [3.3733580319853704, 0.0], [3.4733580319853705, 0.0], [3.5733580319853706, 0.0], [3.6733580319853707, 0.0], [3.773358031985371, 0.0], [3.873358031985371, 0.0], [3.973358031985371, 0.0], [4.0733580319853715, 0.0], [4.173358031985371, 0.0], [4.273358031985371, 0.0], [4.373358031985371, 0.0], [4.473358031985372, 0.0], [4.5733580319853715, 0.0], [4.673358031985371, 0.0], [4.773358031985371, 0.0], [4.87335803198537, 0.0], [4.97335803198537, 0.0], [5.07335803198537, 0.0], [5.173358031985369, 0.0], [5.273358031985369, 0.0], [5.373358031985369, 0.0], [5.473358031985368, 0.0], [5.573358031985368, 0.0], [5.673358031985368, 0.0], [5.773358031985367, 0.0], [5.873358031985367, 0.0], [5.9733580319853665, 0.0], [6.073358031985366, 0.0], [6.173358031985366, 0.0], [6.2733580319853655, 0.0], [6.373358031985365, 0.0], [6.473358031985365, 0.0], [6.573358031985364, 0.0], [6.673358031985364, 0.0], [6.773358031985364, 0.0], [6.873358031985363, 0.0], [6.973358031985363, 0.0], [7.073358031985363, 0.0], [7.173358031985362, 0.0], [7.273358031985362, 0.0], [7.3733580319853615, 0.0], [7.473358031985361, 0.0], [7.573358031985361, 0.0], [7.6733580319853605, 0.0], [7.77335803198536, 0.0], [7.87335803198536, 0.0], [7.973358031985359, 0.0], [8.073358031985359, 0.0], [8.173358031985359, 0.0], [8.273358031985358, 0.0], [8.373358031985358, 0.0], [8.473358031985358, 0.0], [8.573358031985357, 0.0], [8.673358031985357, 0.0], [8.773358031985355, 0.0], [8.873358031985354, 0.0], [8.973358031985354, 0.0], [9.073358031985354, 0.0], [9.173358031985353, 0.0], [9.273358031985353, 0.0], [9.373358031985353, 0.0], [9.473358031985352, 0.0], [9.573358031985352, 0.0], [9.673358031985352, 0.0], [9.773358031985351, 0.0], [9.873358031985351, 0.0], [9.97335803198535, 0.0], [10.07335803198535, 0.0], [10.17335803198535, 0.0], [10.27335803198535, 0.0], [10.37335803198535, 0.0], [10.473358031985349, 0.0], [10.573358031985348, 0.0], [10.673358031985348, 0.0], [10.773358031985348, 0.0], [10.873358031985347, 0.0], [10.973358031985347, 0.0], [11.073358031985347, 0.0], [11.173358031985346, 0.0], [11.273358031985346, 0.0], [11.373358031985346, 0.0], [11.473358031985345, 0.0], [11.573358031985345, 0.0], [11.673358031985344, 0.0], [11.773358031985344, 0.0], [11.873358031985344, 0.0], [11.973358031985343, 0.0], [12.073358031985343, 0.0], [12.173358031985343, 0.0], [12.273358031985342, 0.0], [12.373358031985342, 0.0], [12.473358031985342, 0.0], [12.573358031985341, 0.0], [12.673358031985341, 0.0], [12.77335803198534, 0.0], [12.87335803198534, 0.0], [12.97335803198534, 0.0], [13.07335803198534, 0.0], [13.17335803198534, 0.0], [13.273358031985339, 0.0], [13.373358031985338, 0.0], [13.473358031985338, 0.0], [13.573358031985338, 0.0], [13.673358031985337, 0.0], [13.773358031985337, 0.0], [13.873358031985337, 0.0], [13.973358031985336, 0.0], [14.073358031985336, 0.0], [14.173358031985336, 0.0], [14.273358031985335, 0.0], [14.373358031985335, 0.0], [14.473358031985335, 0.0], [14.573358031985334, 0.0], [14.673358031985334, 0.0], [14.772812434327106, 0.0], [14.858140827930038, 0.0], [14.923469221532972, 0.0], [14.968797615135905, 0.0], [14.994126008738839, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055], "velocities": null}}, "time": 1740481169.463629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9318574252137378, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.463629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.483629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319170331107341, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.483629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.503629, "x": 4.857680436732315, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.503629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3395766886097067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9320361261915507, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.503629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.523629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34423702406506745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505353708480782, "gear": 1, "accelerator_pedal_position": 0.3395766886097067, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.523629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.543629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34423702406506745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569845654175975, "gear": 1, "accelerator_pedal_position": 0.34423702406506745, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.543629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.563629} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.8576804367323154, 0.0], [1.0179003608224935, 0.0], [1.1179003608224936, 0.0], [1.2179003608224934, 0.0], [1.3179003608224935, 0.0], [1.4179003608224934, 0.0], [1.5179003608224932, 0.0], [1.6179003608224933, 0.0], [1.7179003608224934, 0.0], [1.8179003608224933, 0.0], [1.9179003608224934, 0.0], [2.0179003608224937, 0.0], [2.1179003608224933, 0.0], [2.217900360822494, 0.0], [2.3179003608224935, 0.0], [2.417900360822494, 0.0], [2.5179003608224937, 0.0], [2.617900360822494, 0.0], [2.717900360822494, 0.0], [2.8179003608224944, 0.0], [2.917900360822494, 0.0], [3.017900360822494, 0.0], [3.117900360822494, 0.0], [3.2179003608224943, 0.0], [3.3179003608224944, 0.0], [3.4179003608224945, 0.0], [3.5179003608224946, 0.0], [3.6179003608224947, 0.0], [3.7179003608224948, 0.0], [3.817900360822495, 0.0], [3.917900360822495, 0.0], [4.017900360822495, 0.0], [4.117900360822495, 0.0], [4.217900360822496, 0.0], [4.317900360822495, 0.0], [4.417900360822495, 0.0], [4.5179003608224955, 0.0], [4.617900360822496, 0.0], [4.717900360822496, 0.0], [4.817900360822495, 0.0], [4.917900360822496, 0.0], [5.017900360822496, 0.0], [5.117900360822496, 0.0], [5.217900360822496, 0.0], [5.317900360822495, 0.0], [5.417900360822495, 0.0], [5.517900360822495, 0.0], [5.617900360822494, 0.0], [5.717900360822494, 0.0], [5.8179003608224935, 0.0], [5.917900360822493, 0.0], [6.017900360822493, 0.0], [6.1179003608224924, 0.0], [6.217900360822492, 0.0], [6.317900360822492, 0.0], [6.417900360822491, 0.0], [6.517900360822491, 0.0], [6.617900360822491, 0.0], [6.71790036082249, 0.0], [6.81790036082249, 0.0], [6.91790036082249, 0.0], [7.017900360822489, 0.0], [7.117900360822489, 0.0], [7.2179003608224885, 0.0], [7.317900360822488, 0.0], [7.417900360822488, 0.0], [7.5179003608224875, 0.0], [7.617900360822487, 0.0], [7.717900360822487, 0.0], [7.817900360822486, 0.0], [7.917900360822486, 0.0], [8.017900360822486, 0.0], [8.117900360822485, 0.0], [8.217900360822485, 0.0], [8.317900360822485, 0.0], [8.417900360822484, 0.0], [8.517900360822484, 0.0], [8.617900360822484, 0.0], [8.717900360822483, 0.0], [8.817900360822483, 0.0], [8.917900360822482, 0.0], [9.017900360822482, 0.0], [9.117900360822482, 0.0], [9.217900360822481, 0.0], [9.317900360822481, 0.0], [9.41790036082248, 0.0], [9.51790036082248, 0.0], [9.61790036082248, 0.0], [9.71790036082248, 0.0], [9.81790036082248, 0.0], [9.917900360822479, 0.0], [10.017900360822479, 0.0], [10.117900360822478, 0.0], [10.217900360822478, 0.0], [10.317900360822478, 0.0], [10.417900360822477, 0.0], [10.517900360822477, 0.0], [10.617900360822476, 0.0], [10.717900360822476, 0.0], [10.817900360822476, 0.0], [10.917900360822475, 0.0], [11.017900360822475, 0.0], [11.117900360822475, 0.0], [11.217900360822474, 0.0], [11.317900360822474, 0.0], [11.417900360822474, 0.0], [11.517900360822473, 0.0], [11.617900360822473, 0.0], [11.717900360822473, 0.0], [11.817900360822472, 0.0], [11.917900360822472, 0.0], [12.017900360822471, 0.0], [12.117900360822471, 0.0], [12.21790036082247, 0.0], [12.31790036082247, 0.0], [12.41790036082247, 0.0], [12.51790036082247, 0.0], [12.61790036082247, 0.0], [12.717900360822469, 0.0], [12.817900360822469, 0.0], [12.917900360822468, 0.0], [13.017900360822468, 0.0], [13.117900360822468, 0.0], [13.217900360822467, 0.0], [13.317900360822467, 0.0], [13.417900360822467, 0.0], [13.517900360822466, 0.0], [13.617900360822466, 0.0], [13.717900360822465, 0.0], [13.817900360822465, 0.0], [13.917900360822465, 0.0], [14.017900360822464, 0.0], [14.117900360822464, 0.0], [14.217900360822464, 0.0], [14.317900360822463, 0.0], [14.417900360822463, 0.0], [14.517900360822463, 0.0], [14.617900360822462, 0.0], [14.717900360822462, 0.0], [14.81328990182264, 0.0], [14.889709829658148, 0.0], [14.946129757493656, 0.0], [14.982549685329165, 0.0], [14.998969613164672, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512, 14.263299316185512, 14.363299316185511], "velocities": null}}, "time": 1740481169.563629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969781650702614, "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": 1740481169.563629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.583629} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.3812554, "x": 15.0, "y": 3.114999999999977, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.583629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969693777486553, "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": 1740481169.583629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.6036289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9695182139487789, "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": 1740481169.6036289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.6136289, "x": 4.963020782137273, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6236289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26132610277149815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693428939779085, "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": 1740481169.6236289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6436288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26404569789949384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9718505183609643, "gear": 1, "accelerator_pedal_position": 0.26132610277149815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.6436288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6636288} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.9630207821372734, 0.0], [1.125697103062101, 0.0], [1.2256971030621011, 0.0], [1.325697103062101, 0.0], [1.425697103062101, 0.0], [1.5256971030621012, 0.0], [1.625697103062101, 0.0], [1.725697103062101, 0.0], [1.825697103062101, 0.0], [1.925697103062101, 0.0], [2.0256971030621007, 0.0], [2.125697103062101, 0.0], [2.225697103062101, 0.0], [2.325697103062101, 0.0], [2.425697103062101, 0.0], [2.525697103062101, 0.0], [2.6256971030621012, 0.0], [2.7256971030621013, 0.0], [2.8256971030621014, 0.0], [2.9256971030621015, 0.0], [3.025697103062102, 0.0], [3.125697103062102, 0.0], [3.2256971030621022, 0.0], [3.3256971030621023, 0.0], [3.4256971030621024, 0.0], [3.5256971030621025, 0.0], [3.6256971030621026, 0.0], [3.7256971030621027, 0.0], [3.8256971030621028, 0.0], [3.925697103062103, 0.0], [4.025697103062103, 0.0], [4.1256971030621035, 0.0], [4.225697103062103, 0.0], [4.325697103062103, 0.0], [4.425697103062103, 0.0], [4.525697103062104, 0.0], [4.6256971030621035, 0.0], [4.725697103062103, 0.0], [4.825697103062104, 0.0], [4.925697103062104, 0.0], [5.025697103062103, 0.0], [5.125697103062103, 0.0], [5.225697103062102, 0.0], [5.325697103062102, 0.0], [5.4256971030621015, 0.0], [5.525697103062101, 0.0], [5.625697103062101, 0.0], [5.7256971030621004, 0.0], [5.8256971030621, 0.0], [5.9256971030621, 0.0], [6.025697103062099, 0.0], [6.125697103062099, 0.0], [6.225697103062099, 0.0], [6.325697103062098, 0.0], [6.425697103062098, 0.0], [6.525697103062098, 0.0], [6.625697103062097, 0.0], [6.725697103062097, 0.0], [6.8256971030620965, 0.0], [6.925697103062096, 0.0], [7.025697103062096, 0.0], [7.1256971030620955, 0.0], [7.225697103062095, 0.0], [7.325697103062095, 0.0], [7.425697103062094, 0.0], [7.525697103062094, 0.0], [7.625697103062094, 0.0], [7.725697103062093, 0.0], [7.825697103062093, 0.0], [7.925697103062093, 0.0], [8.025697103062093, 0.0], [8.125697103062093, 0.0], [8.225697103062092, 0.0], [8.325697103062092, 0.0], [8.425697103062092, 0.0], [8.525697103062091, 0.0], [8.625697103062091, 0.0], [8.72569710306209, 0.0], [8.82569710306209, 0.0], [8.92569710306209, 0.0], [9.02569710306209, 0.0], [9.12569710306209, 0.0], [9.225697103062089, 0.0], [9.325697103062089, 0.0], [9.425697103062088, 0.0], [9.525697103062088, 0.0], [9.625697103062087, 0.0], [9.725697103062087, 0.0], [9.825697103062087, 0.0], [9.925697103062086, 0.0], [10.025697103062086, 0.0], [10.125697103062086, 0.0], [10.225697103062085, 0.0], [10.325697103062085, 0.0], [10.425697103062085, 0.0], [10.525697103062084, 0.0], [10.625697103062084, 0.0], [10.725697103062084, 0.0], [10.825697103062083, 0.0], [10.925697103062083, 0.0], [11.025697103062083, 0.0], [11.125697103062082, 0.0], [11.225697103062082, 0.0], [11.325697103062081, 0.0], [11.425697103062081, 0.0], [11.52569710306208, 0.0], [11.62569710306208, 0.0], [11.72569710306208, 0.0], [11.82569710306208, 0.0], [11.92569710306208, 0.0], [12.025697103062079, 0.0], [12.125697103062079, 0.0], [12.225697103062078, 0.0], [12.325697103062078, 0.0], [12.425697103062078, 0.0], [12.525697103062077, 0.0], [12.625697103062077, 0.0], [12.725697103062076, 0.0], [12.825697103062076, 0.0], [12.925697103062076, 0.0], [13.025697103062075, 0.0], [13.125697103062075, 0.0], [13.225697103062075, 0.0], [13.325697103062074, 0.0], [13.425697103062074, 0.0], [13.525697103062074, 0.0], [13.625697103062073, 0.0], [13.725697103062073, 0.0], [13.825697103062073, 0.0], [13.925697103062072, 0.0], [14.025697103062072, 0.0], [14.125697103062071, 0.0], [14.225697103062071, 0.0], [14.32569710306207, 0.0], [14.42569710306207, 0.0], [14.52569710306207, 0.0], [14.62569710306207, 0.0], [14.72569710306207, 0.0], [14.81996705165008, 0.0], [14.894827631037666, 0.0], [14.949688210425252, 0.0], [14.984548789812838, 0.0], [14.999409369200425, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512, 14.263299316185512], "velocities": null}}, "time": 1740481169.6636288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.976114999399477, "gear": 1, "accelerator_pedal_position": 0.26404569789949384, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.6636288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6836288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9757992061026549, "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": 1740481169.6836288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.7036288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9751682779468382, "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": 1740481169.7036288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.7236288, "x": 5.070086860428703, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7236288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411960878892153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745382265586362, "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": 1740481169.7236288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7436287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24156755755396767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745232595693641, "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": 1740481169.7436287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7636287} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.0700868604287033, 0.0], [1.2329539753430623, 0.0], [1.3329539753430624, 0.0], [1.4329539753430622, 0.0], [1.5329539753430623, 0.0], [1.6329539753430624, 0.0], [1.7329539753430623, 0.0], [1.8329539753430621, 0.0], [1.9329539753430622, 0.0], [2.0329539753430623, 0.0], [2.132953975343062, 0.0], [2.232953975343062, 0.0], [2.332953975343062, 0.0], [2.4329539753430622, 0.0], [2.5329539753430623, 0.0], [2.6329539753430624, 0.0], [2.7329539753430625, 0.0], [2.8329539753430626, 0.0], [2.9329539753430627, 0.0], [3.0329539753430628, 0.0], [3.1329539753430633, 0.0], [3.2329539753430634, 0.0], [3.3329539753430635, 0.0], [3.4329539753430636, 0.0], [3.5329539753430637, 0.0], [3.6329539753430637, 0.0], [3.732953975343064, 0.0], [3.832953975343064, 0.0], [3.932953975343064, 0.0], [4.032953975343064, 0.0], [4.132953975343064, 0.0], [4.232953975343064, 0.0], [4.332953975343065, 0.0], [4.4329539753430645, 0.0], [4.532953975343064, 0.0], [4.632953975343065, 0.0], [4.732953975343065, 0.0], [4.832953975343065, 0.0], [4.9329539753430645, 0.0], [5.032953975343065, 0.0], [5.132953975343065, 0.0], [5.232953975343064, 0.0], [5.332953975343064, 0.0], [5.432953975343064, 0.0], [5.532953975343063, 0.0], [5.632953975343063, 0.0], [5.7329539753430625, 0.0], [5.832953975343062, 0.0], [5.932953975343062, 0.0], [6.032953975343061, 0.0], [6.132953975343061, 0.0], [6.232953975343061, 0.0], [6.33295397534306, 0.0], [6.43295397534306, 0.0], [6.53295397534306, 0.0], [6.632953975343059, 0.0], [6.732953975343059, 0.0], [6.832953975343059, 0.0], [6.932953975343058, 0.0], [7.032953975343058, 0.0], [7.1329539753430575, 0.0], [7.232953975343057, 0.0], [7.332953975343057, 0.0], [7.4329539753430565, 0.0], [7.532953975343056, 0.0], [7.632953975343056, 0.0], [7.732953975343055, 0.0], [7.832953975343055, 0.0], [7.932953975343055, 0.0], [8.032953975343055, 0.0], [8.132953975343053, 0.0], [8.232953975343055, 0.0], [8.332953975343052, 0.0], [8.432953975343054, 0.0], [8.532953975343052, 0.0], [8.632953975343053, 0.0], [8.732953975343051, 0.0], [8.832953975343052, 0.0], [8.93295397534305, 0.0], [9.03295397534305, 0.0], [9.13295397534305, 0.0], [9.23295397534305, 0.0], [9.332953975343049, 0.0], [9.432953975343048, 0.0], [9.532953975343048, 0.0], [9.632953975343048, 0.0], [9.732953975343047, 0.0], [9.832953975343047, 0.0], [9.932953975343047, 0.0], [10.032953975343046, 0.0], [10.132953975343046, 0.0], [10.232953975343046, 0.0], [10.332953975343045, 0.0], [10.432953975343045, 0.0], [10.532953975343045, 0.0], [10.632953975343044, 0.0], [10.732953975343044, 0.0], [10.832953975343043, 0.0], [10.932953975343043, 0.0], [11.032953975343043, 0.0], [11.132953975343042, 0.0], [11.232953975343042, 0.0], [11.332953975343042, 0.0], [11.432953975343041, 0.0], [11.532953975343041, 0.0], [11.63295397534304, 0.0], [11.73295397534304, 0.0], [11.83295397534304, 0.0], [11.93295397534304, 0.0], [12.03295397534304, 0.0], [12.132953975343039, 0.0], [12.232953975343039, 0.0], [12.332953975343038, 0.0], [12.432953975343038, 0.0], [12.532953975343037, 0.0], [12.632953975343037, 0.0], [12.732953975343037, 0.0], [12.832953975343036, 0.0], [12.932953975343036, 0.0], [13.032953975343036, 0.0], [13.132953975343035, 0.0], [13.232953975343035, 0.0], [13.332953975343035, 0.0], [13.432953975343034, 0.0], [13.532953975343034, 0.0], [13.632953975343034, 0.0], [13.732953975343033, 0.0], [13.832953975343033, 0.0], [13.932953975343032, 0.0], [14.032953975343032, 0.0], [14.132953975343032, 0.0], [14.232953975343031, 0.0], [14.332953975343031, 0.0], [14.43295397534303, 0.0], [14.53295397534303, 0.0], [14.63295397534303, 0.0], [14.73295397534303, 0.0], [14.826072613317818, 0.0], [14.899481818249212, 0.0], [14.952891023180605, 0.0], [14.986300228112, 0.0], [14.999709433043394, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512], "velocities": null}}, "time": 1740481169.7636287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745704502380101, "gear": 1, "accelerator_pedal_position": 0.24156755755396767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.7636287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7836287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742163371765423, "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": 1740481169.7836287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.8036287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9735088490544168, "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": 1740481169.8036287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.8236287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9724494589354963, "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": 1740481169.8236287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.8336287, "x": 5.177234879250172, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8436286} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.601939, "x": 15.0, "y": 3.2249999999999748, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.8436286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24037121837790482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9720968193309091, "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": 1740481169.8436286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8636286} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.1772348792501717, 0.0], [1.3400281738937523, 0.0], [1.4400281738937522, 0.0], [1.5400281738937522, 0.0], [1.6400281738937523, 0.0], [1.7400281738937522, 0.0], [1.840028173893752, 0.0], [1.9400281738937522, 0.0], [2.0400281738937522, 0.0], [2.140028173893752, 0.0], [2.2400281738937524, 0.0], [2.340028173893752, 0.0], [2.4400281738937526, 0.0], [2.5400281738937522, 0.0], [2.6400281738937528, 0.0], [2.7400281738937524, 0.0], [2.840028173893753, 0.0], [2.9400281738937526, 0.0], [3.040028173893753, 0.0], [3.1400281738937528, 0.0], [3.240028173893753, 0.0], [3.340028173893753, 0.0], [3.440028173893753, 0.0], [3.540028173893753, 0.0], [3.640028173893753, 0.0], [3.7400281738937533, 0.0], [3.8400281738937534, 0.0], [3.9400281738937535, 0.0], [4.040028173893754, 0.0], [4.140028173893754, 0.0], [4.240028173893753, 0.0], [4.340028173893754, 0.0], [4.440028173893754, 0.0], [4.540028173893754, 0.0], [4.640028173893754, 0.0], [4.740028173893754, 0.0], [4.840028173893755, 0.0], [4.940028173893754, 0.0], [5.040028173893754, 0.0], [5.1400281738937545, 0.0], [5.240028173893755, 0.0], [5.340028173893755, 0.0], [5.440028173893754, 0.0], [5.540028173893754, 0.0], [5.640028173893754, 0.0], [5.740028173893753, 0.0], [5.840028173893753, 0.0], [5.940028173893753, 0.0], [6.040028173893752, 0.0], [6.140028173893752, 0.0], [6.2400281738937515, 0.0], [6.340028173893751, 0.0], [6.440028173893751, 0.0], [6.5400281738937505, 0.0], [6.64002817389375, 0.0], [6.74002817389375, 0.0], [6.840028173893749, 0.0], [6.940028173893749, 0.0], [7.040028173893749, 0.0], [7.140028173893748, 0.0], [7.240028173893748, 0.0], [7.340028173893748, 0.0], [7.440028173893747, 0.0], [7.540028173893747, 0.0], [7.6400281738937466, 0.0], [7.740028173893746, 0.0], [7.840028173893746, 0.0], [7.9400281738937455, 0.0], [8.040028173893745, 0.0], [8.140028173893745, 0.0], [8.240028173893744, 0.0], [8.340028173893744, 0.0], [8.440028173893744, 0.0], [8.540028173893743, 0.0], [8.640028173893743, 0.0], [8.740028173893743, 0.0], [8.840028173893742, 0.0], [8.940028173893742, 0.0], [9.040028173893742, 0.0], [9.140028173893741, 0.0], [9.24002817389374, 0.0], [9.34002817389374, 0.0], [9.44002817389374, 0.0], [9.54002817389374, 0.0], [9.64002817389374, 0.0], [9.740028173893739, 0.0], [9.840028173893739, 0.0], [9.940028173893738, 0.0], [10.040028173893738, 0.0], [10.140028173893738, 0.0], [10.240028173893737, 0.0], [10.340028173893737, 0.0], [10.440028173893737, 0.0], [10.540028173893736, 0.0], [10.640028173893736, 0.0], [10.740028173893736, 0.0], [10.840028173893735, 0.0], [10.940028173893735, 0.0], [11.040028173893734, 0.0], [11.140028173893734, 0.0], [11.240028173893734, 0.0], [11.340028173893733, 0.0], [11.440028173893733, 0.0], [11.540028173893733, 0.0], [11.640028173893732, 0.0], [11.740028173893732, 0.0], [11.840028173893732, 0.0], [11.940028173893731, 0.0], [12.040028173893731, 0.0], [12.14002817389373, 0.0], [12.24002817389373, 0.0], [12.34002817389373, 0.0], [12.44002817389373, 0.0], [12.54002817389373, 0.0], [12.640028173893729, 0.0], [12.740028173893728, 0.0], [12.840028173893728, 0.0], [12.940028173893728, 0.0], [13.040028173893727, 0.0], [13.140028173893727, 0.0], [13.240028173893727, 0.0], [13.340028173893726, 0.0], [13.440028173893726, 0.0], [13.540028173893726, 0.0], [13.640028173893725, 0.0], [13.740028173893725, 0.0], [13.840028173893725, 0.0], [13.940028173893724, 0.0], [14.040028173893724, 0.0], [14.140028173893723, 0.0], [14.240028173893723, 0.0], [14.340028173893723, 0.0], [14.440028173893722, 0.0], [14.540028173893722, 0.0], [14.640028173893722, 0.0], [14.740028173893721, 0.0], [14.831923101799083, 0.0], [14.903917467020339, 0.0], [14.955911832241593, 0.0], [14.98790619746285, 0.0], [14.999900562684106, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512], "velocities": null}}, "time": 1740481169.8636286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9719249053139879, "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": 1740481169.8636286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8836286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715889971054023, "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": 1740481169.8836286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.9036286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9709178802187332, "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": 1740481169.9036286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.9236286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9702476948103237, "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": 1740481169.9236286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.9436285, "x": 5.284084842700208, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9436285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24153843179010118, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9695784394077295, "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": 1740481169.9436285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9636285} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.2840848427002083, 0.0], [1.4467671779865074, 0.0], [1.5467671779865073, 0.0], [1.6467671779865074, 0.0], [1.7467671779865073, 0.0], [1.8467671779865074, 0.0], [1.9467671779865072, 0.0], [2.0467671779865073, 0.0], [2.1467671779865074, 0.0], [2.2467671779865075, 0.0], [2.346767177986507, 0.0], [2.4467671779865072, 0.0], [2.5467671779865073, 0.0], [2.6467671779865074, 0.0], [2.7467671779865075, 0.0], [2.8467671779865076, 0.0], [2.9467671779865077, 0.0], [3.0467671779865078, 0.0], [3.146767177986508, 0.0], [3.246767177986508, 0.0], [3.346767177986508, 0.0], [3.446767177986508, 0.0], [3.546767177986508, 0.0], [3.6467671779865083, 0.0], [3.7467671779865084, 0.0], [3.8467671779865085, 0.0], [3.9467671779865086, 0.0], [4.046767177986508, 0.0], [4.146767177986509, 0.0], [4.246767177986509, 0.0], [4.346767177986509, 0.0], [4.446767177986509, 0.0], [4.546767177986509, 0.0], [4.64676717798651, 0.0], [4.746767177986509, 0.0], [4.846767177986509, 0.0], [4.9467671779865094, 0.0], [5.04676717798651, 0.0], [5.14676717798651, 0.0], [5.246767177986509, 0.0], [5.34676717798651, 0.0], [5.4467671779865094, 0.0], [5.546767177986509, 0.0], [5.646767177986509, 0.0], [5.746767177986508, 0.0], [5.846767177986508, 0.0], [5.946767177986508, 0.0], [6.046767177986507, 0.0], [6.146767177986507, 0.0], [6.246767177986507, 0.0], [6.346767177986506, 0.0], [6.446767177986506, 0.0], [6.5467671779865055, 0.0], [6.646767177986505, 0.0], [6.746767177986505, 0.0], [6.8467671779865045, 0.0], [6.946767177986504, 0.0], [7.046767177986504, 0.0], [7.146767177986503, 0.0], [7.246767177986503, 0.0], [7.346767177986503, 0.0], [7.446767177986502, 0.0], [7.546767177986502, 0.0], [7.646767177986502, 0.0], [7.746767177986501, 0.0], [7.846767177986501, 0.0], [7.946767177986501, 0.0], [8.0467671779865, 0.0], [8.1467671779865, 0.0], [8.246767177986499, 0.0], [8.3467671779865, 0.0], [8.446767177986498, 0.0], [8.5467671779865, 0.0], [8.646767177986497, 0.0], [8.746767177986499, 0.0], [8.846767177986496, 0.0], [8.946767177986498, 0.0], [9.046767177986496, 0.0], [9.146767177986497, 0.0], [9.246767177986495, 0.0], [9.346767177986495, 0.0], [9.446767177986494, 0.0], [9.546767177986494, 0.0], [9.646767177986494, 0.0], [9.746767177986493, 0.0], [9.846767177986493, 0.0], [9.946767177986493, 0.0], [10.046767177986492, 0.0], [10.146767177986492, 0.0], [10.246767177986492, 0.0], [10.346767177986491, 0.0], [10.44676717798649, 0.0], [10.54676717798649, 0.0], [10.64676717798649, 0.0], [10.74676717798649, 0.0], [10.84676717798649, 0.0], [10.946767177986489, 0.0], [11.046767177986489, 0.0], [11.146767177986488, 0.0], [11.246767177986488, 0.0], [11.346767177986488, 0.0], [11.446767177986487, 0.0], [11.546767177986487, 0.0], [11.646767177986487, 0.0], [11.746767177986486, 0.0], [11.846767177986486, 0.0], [11.946767177986485, 0.0], [12.046767177986485, 0.0], [12.146767177986485, 0.0], [12.246767177986484, 0.0], [12.346767177986484, 0.0], [12.446767177986484, 0.0], [12.546767177986483, 0.0], [12.646767177986483, 0.0], [12.746767177986483, 0.0], [12.846767177986482, 0.0], [12.946767177986482, 0.0], [13.046767177986482, 0.0], [13.146767177986481, 0.0], [13.24676717798648, 0.0], [13.34676717798648, 0.0], [13.44676717798648, 0.0], [13.54676717798648, 0.0], [13.64676717798648, 0.0], [13.746767177986479, 0.0], [13.846767177986479, 0.0], [13.946767177986478, 0.0], [14.046767177986478, 0.0], [14.146767177986478, 0.0], [14.246767177986477, 0.0], [14.346767177986477, 0.0], [14.446767177986477, 0.0], [14.546767177986476, 0.0], [14.646767177986476, 0.0], [14.746767177986476, 0.0], [14.83740329125101, 0.0], [14.908049855653713, 0.0], [14.958696420056418, 0.0], [14.989342984459123, 0.0], [14.999989548861828, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513], "velocities": null}}, "time": 1740481169.9636285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9696304668846722, "gear": 1, "accelerator_pedal_position": 0.24153843179010118, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.9636285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9836285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693180667233167, "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": 1740481169.9836285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0036285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9686939165492818, "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": 1740481170.0036285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0236285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9680706321081676, "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": 1740481170.0236285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0436285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9674482120438118, "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": 1740481170.0436285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.0536284, "x": 5.390655802977525, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.0636284} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.3906558029775251, 0.0], [1.5532351489229446, 0.0], [1.6532351489229447, 0.0], [1.7532351489229445, 0.0], [1.8532351489229446, 0.0], [1.9532351489229445, 0.0], [2.0532351489229446, 0.0], [2.1532351489229447, 0.0], [2.2532351489229443, 0.0], [2.3532351489229444, 0.0], [2.4532351489229445, 0.0], [2.5532351489229446, 0.0], [2.6532351489229447, 0.0], [2.7532351489229447, 0.0], [2.853235148922945, 0.0], [2.953235148922945, 0.0], [3.053235148922945, 0.0], [3.153235148922945, 0.0], [3.253235148922945, 0.0], [3.3532351489229453, 0.0], [3.4532351489229454, 0.0], [3.553235148922945, 0.0], [3.6532351489229455, 0.0], [3.753235148922945, 0.0], [3.8532351489229457, 0.0], [3.9532351489229454, 0.0], [4.053235148922946, 0.0], [4.1532351489229455, 0.0], [4.253235148922946, 0.0], [4.353235148922946, 0.0], [4.453235148922946, 0.0], [4.553235148922946, 0.0], [4.653235148922946, 0.0], [4.753235148922946, 0.0], [4.853235148922947, 0.0], [4.953235148922946, 0.0], [5.053235148922947, 0.0], [5.153235148922946, 0.0], [5.253235148922947, 0.0], [5.353235148922947, 0.0], [5.453235148922947, 0.0], [5.553235148922947, 0.0], [5.653235148922946, 0.0], [5.753235148922946, 0.0], [5.853235148922946, 0.0], [5.953235148922945, 0.0], [6.053235148922945, 0.0], [6.153235148922945, 0.0], [6.253235148922944, 0.0], [6.353235148922944, 0.0], [6.453235148922944, 0.0], [6.553235148922943, 0.0], [6.653235148922943, 0.0], [6.7532351489229425, 0.0], [6.853235148922942, 0.0], [6.953235148922942, 0.0], [7.0532351489229415, 0.0], [7.153235148922941, 0.0], [7.253235148922941, 0.0], [7.35323514892294, 0.0], [7.45323514892294, 0.0], [7.55323514892294, 0.0], [7.653235148922939, 0.0], [7.753235148922939, 0.0], [7.853235148922939, 0.0], [7.953235148922938, 0.0], [8.053235148922937, 0.0], [8.153235148922938, 0.0], [8.253235148922936, 0.0], [8.353235148922938, 0.0], [8.453235148922936, 0.0], [8.553235148922937, 0.0], [8.653235148922935, 0.0], [8.753235148922936, 0.0], [8.853235148922934, 0.0], [8.953235148922936, 0.0], [9.053235148922933, 0.0], [9.153235148922935, 0.0], [9.253235148922933, 0.0], [9.353235148922934, 0.0], [9.453235148922932, 0.0], [9.553235148922932, 0.0], [9.653235148922931, 0.0], [9.753235148922931, 0.0], [9.85323514892293, 0.0], [9.95323514892293, 0.0], [10.05323514892293, 0.0], [10.15323514892293, 0.0], [10.25323514892293, 0.0], [10.353235148922929, 0.0], [10.453235148922928, 0.0], [10.553235148922928, 0.0], [10.653235148922928, 0.0], [10.753235148922927, 0.0], [10.853235148922927, 0.0], [10.953235148922927, 0.0], [11.053235148922926, 0.0], [11.153235148922926, 0.0], [11.253235148922926, 0.0], [11.353235148922925, 0.0], [11.453235148922925, 0.0], [11.553235148922925, 0.0], [11.653235148922924, 0.0], [11.753235148922924, 0.0], [11.853235148922924, 0.0], [11.953235148922923, 0.0], [12.053235148922923, 0.0], [12.153235148922922, 0.0], [12.253235148922922, 0.0], [12.353235148922922, 0.0], [12.453235148922921, 0.0], [12.553235148922921, 0.0], [12.65323514892292, 0.0], [12.75323514892292, 0.0], [12.85323514892292, 0.0], [12.95323514892292, 0.0], [13.05323514892292, 0.0], [13.153235148922919, 0.0], [13.253235148922919, 0.0], [13.353235148922918, 0.0], [13.453235148922918, 0.0], [13.553235148922917, 0.0], [13.653235148922917, 0.0], [13.753235148922917, 0.0], [13.853235148922916, 0.0], [13.953235148922916, 0.0], [14.053235148922916, 0.0], [14.153235148922915, 0.0], [14.253235148922915, 0.0], [14.353235148922915, 0.0], [14.453235148922914, 0.0], [14.553235148922914, 0.0], [14.653235148922914, 0.0], [14.75322468273436, 0.0], [14.842577652949776, 0.0], [14.911930623165194, 0.0], [14.961283593380612, 0.0], [14.990636563596029, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513], "velocities": null}}, "time": 1740481170.0636284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243738511019591, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966516199693314, "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": 1740481170.0636284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.0836284} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.9325814, "x": 15.0, "y": 3.3899999999999713, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.0836284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666731831757649, "gear": 1, "accelerator_pedal_position": 0.243738511019591, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.0836284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1136284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671188102034733, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1136284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1236284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672671465983855, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1236284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1436284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675635108685982, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1436284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.1636283, "x": 5.4970360224747195, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.1636283} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.4970360224747195, 0.0], [1.6596466626336772, 0.0], [1.7596466626336773, 0.0], [1.8596466626336774, 0.0], [1.9596466626336775, 0.0], [2.059646662633677, 0.0], [2.159646662633677, 0.0], [2.2596466626336773, 0.0], [2.3596466626336774, 0.0], [2.459646662633677, 0.0], [2.5596466626336776, 0.0], [2.659646662633677, 0.0], [2.7596466626336777, 0.0], [2.8596466626336774, 0.0], [2.959646662633678, 0.0], [3.0596466626336776, 0.0], [3.159646662633678, 0.0], [3.2596466626336777, 0.0], [3.3596466626336783, 0.0], [3.459646662633678, 0.0], [3.559646662633678, 0.0], [3.659646662633678, 0.0], [3.759646662633678, 0.0], [3.8596466626336783, 0.0], [3.9596466626336784, 0.0], [4.0596466626336785, 0.0], [4.159646662633678, 0.0], [4.259646662633679, 0.0], [4.359646662633679, 0.0], [4.459646662633679, 0.0], [4.5596466626336785, 0.0], [4.659646662633679, 0.0], [4.7596466626336795, 0.0], [4.859646662633679, 0.0], [4.959646662633679, 0.0], [5.059646662633679, 0.0], [5.15964666263368, 0.0], [5.2596466626336795, 0.0], [5.359646662633679, 0.0], [5.45964666263368, 0.0], [5.55964666263368, 0.0], [5.65964666263368, 0.0], [5.7596466626336795, 0.0], [5.859646662633679, 0.0], [5.959646662633679, 0.0], [6.0596466626336785, 0.0], [6.159646662633678, 0.0], [6.259646662633678, 0.0], [6.359646662633677, 0.0], [6.459646662633677, 0.0], [6.559646662633677, 0.0], [6.659646662633676, 0.0], [6.759646662633676, 0.0], [6.859646662633676, 0.0], [6.959646662633675, 0.0], [7.059646662633675, 0.0], [7.1596466626336746, 0.0], [7.259646662633674, 0.0], [7.359646662633674, 0.0], [7.4596466626336735, 0.0], [7.559646662633673, 0.0], [7.659646662633673, 0.0], [7.759646662633672, 0.0], [7.859646662633672, 0.0], [7.959646662633672, 0.0], [8.059646662633671, 0.0], [8.159646662633671, 0.0], [8.25964666263367, 0.0], [8.35964666263367, 0.0], [8.45964666263367, 0.0], [8.55964666263367, 0.0], [8.65964666263367, 0.0], [8.759646662633669, 0.0], [8.859646662633669, 0.0], [8.959646662633668, 0.0], [9.059646662633668, 0.0], [9.159646662633667, 0.0], [9.259646662633667, 0.0], [9.359646662633667, 0.0], [9.459646662633666, 0.0], [9.559646662633666, 0.0], [9.659646662633666, 0.0], [9.759646662633665, 0.0], [9.859646662633665, 0.0], [9.959646662633665, 0.0], [10.059646662633664, 0.0], [10.159646662633664, 0.0], [10.259646662633664, 0.0], [10.359646662633663, 0.0], [10.459646662633663, 0.0], [10.559646662633662, 0.0], [10.659646662633662, 0.0], [10.759646662633662, 0.0], [10.859646662633661, 0.0], [10.959646662633661, 0.0], [11.05964666263366, 0.0], [11.15964666263366, 0.0], [11.25964666263366, 0.0], [11.35964666263366, 0.0], [11.45964666263366, 0.0], [11.559646662633659, 0.0], [11.659646662633659, 0.0], [11.759646662633658, 0.0], [11.859646662633658, 0.0], [11.959646662633657, 0.0], [12.059646662633657, 0.0], [12.159646662633657, 0.0], [12.259646662633656, 0.0], [12.359646662633656, 0.0], [12.459646662633656, 0.0], [12.559646662633655, 0.0], [12.659646662633655, 0.0], [12.759646662633655, 0.0], [12.859646662633654, 0.0], [12.959646662633654, 0.0], [13.059646662633654, 0.0], [13.159646662633653, 0.0], [13.259646662633653, 0.0], [13.359646662633653, 0.0], [13.459646662633652, 0.0], [13.559646662633652, 0.0], [13.659646662633651, 0.0], [13.759646662633651, 0.0], [13.85964666263365, 0.0], [13.95964666263365, 0.0], [14.05964666263365, 0.0], [14.15964666263365, 0.0], [14.25964666263365, 0.0], [14.359646662633649, 0.0], [14.459646662633649, 0.0], [14.559646662633648, 0.0], [14.659646662633648, 0.0], [14.75955360453368, 0.0], [14.84762427200695, 0.0], [14.91569493948022, 0.0], [14.96376560695349, 0.0], [14.991836274426761, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514], "velocities": null}}, "time": 1740481170.1636283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431767612778283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9679804068788609, "gear": 1, "accelerator_pedal_position": 0.2431767612778283, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1636283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.1836283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9681012656484755, "gear": 1, "accelerator_pedal_position": 0.2431767612778283, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1836283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2036283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9683475528286227, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2036283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2236283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687163433157499, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2236283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2436283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9688391029606838, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2436283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2636282} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.4970360224747195, 0.0], [1.6596466626336772, 0.0], [1.7596466626336773, 0.0], [1.8596466626336774, 0.0], [1.9596466626336775, 0.0], [2.059646662633677, 0.0], [2.159646662633677, 0.0], [2.2596466626336773, 0.0], [2.3596466626336774, 0.0], [2.459646662633677, 0.0], [2.5596466626336776, 0.0], [2.659646662633677, 0.0], [2.7596466626336777, 0.0], [2.8596466626336774, 0.0], [2.959646662633678, 0.0], [3.0596466626336776, 0.0], [3.159646662633678, 0.0], [3.2596466626336777, 0.0], [3.3596466626336783, 0.0], [3.459646662633678, 0.0], [3.559646662633678, 0.0], [3.659646662633678, 0.0], [3.759646662633678, 0.0], [3.8596466626336783, 0.0], [3.9596466626336784, 0.0], [4.0596466626336785, 0.0], [4.159646662633678, 0.0], [4.259646662633679, 0.0], [4.359646662633679, 0.0], [4.459646662633679, 0.0], [4.5596466626336785, 0.0], [4.659646662633679, 0.0], [4.7596466626336795, 0.0], [4.859646662633679, 0.0], [4.959646662633679, 0.0], [5.059646662633679, 0.0], [5.15964666263368, 0.0], [5.2596466626336795, 0.0], [5.359646662633679, 0.0], [5.45964666263368, 0.0], [5.55964666263368, 0.0], [5.65964666263368, 0.0], [5.7596466626336795, 0.0], [5.859646662633679, 0.0], [5.959646662633679, 0.0], [6.0596466626336785, 0.0], [6.159646662633678, 0.0], [6.259646662633678, 0.0], [6.359646662633677, 0.0], [6.459646662633677, 0.0], [6.559646662633677, 0.0], [6.659646662633676, 0.0], [6.759646662633676, 0.0], [6.859646662633676, 0.0], [6.959646662633675, 0.0], [7.059646662633675, 0.0], [7.1596466626336746, 0.0], [7.259646662633674, 0.0], [7.359646662633674, 0.0], [7.4596466626336735, 0.0], [7.559646662633673, 0.0], [7.659646662633673, 0.0], [7.759646662633672, 0.0], [7.859646662633672, 0.0], [7.959646662633672, 0.0], [8.059646662633671, 0.0], [8.159646662633671, 0.0], [8.25964666263367, 0.0], [8.35964666263367, 0.0], [8.45964666263367, 0.0], [8.55964666263367, 0.0], [8.65964666263367, 0.0], [8.759646662633669, 0.0], [8.859646662633669, 0.0], [8.959646662633668, 0.0], [9.059646662633668, 0.0], [9.159646662633667, 0.0], [9.259646662633667, 0.0], [9.359646662633667, 0.0], [9.459646662633666, 0.0], [9.559646662633666, 0.0], [9.659646662633666, 0.0], [9.759646662633665, 0.0], [9.859646662633665, 0.0], [9.959646662633665, 0.0], [10.059646662633664, 0.0], [10.159646662633664, 0.0], [10.259646662633664, 0.0], [10.359646662633663, 0.0], [10.459646662633663, 0.0], [10.559646662633662, 0.0], [10.659646662633662, 0.0], [10.759646662633662, 0.0], [10.859646662633661, 0.0], [10.959646662633661, 0.0], [11.05964666263366, 0.0], [11.15964666263366, 0.0], [11.25964666263366, 0.0], [11.35964666263366, 0.0], [11.45964666263366, 0.0], [11.559646662633659, 0.0], [11.659646662633659, 0.0], [11.759646662633658, 0.0], [11.859646662633658, 0.0], [11.959646662633657, 0.0], [12.059646662633657, 0.0], [12.159646662633657, 0.0], [12.259646662633656, 0.0], [12.359646662633656, 0.0], [12.459646662633656, 0.0], [12.559646662633655, 0.0], [12.659646662633655, 0.0], [12.759646662633655, 0.0], [12.859646662633654, 0.0], [12.959646662633654, 0.0], [13.059646662633654, 0.0], [13.159646662633653, 0.0], [13.259646662633653, 0.0], [13.359646662633653, 0.0], [13.459646662633652, 0.0], [13.559646662633652, 0.0], [13.659646662633651, 0.0], [13.759646662633651, 0.0], [13.85964666263365, 0.0], [13.95964666263365, 0.0], [14.05964666263365, 0.0], [14.15964666263365, 0.0], [14.25964666263365, 0.0], [14.359646662633649, 0.0], [14.459646662633649, 0.0], [14.559646662633648, 0.0], [14.659646662633648, 0.0], [14.75955360453368, 0.0], [14.84762427200695, 0.0], [14.91569493948022, 0.0], [14.96376560695349, 0.0], [14.991836274426761, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514], "velocities": null}}, "time": 1740481170.2636282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9692068711286386, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2636282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.2736282, "x": 5.60356781046298, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.2836282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23713561756426965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693292904491424, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2836282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3036282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9688141722664042, "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": 1740481170.3036282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3236282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9682736880331717, "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": 1740481170.3236282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3436282} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.1513095, "x": 15.0, "y": 3.499999999999969, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.3436282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677339533879816, "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": 1740481170.3436282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3636281} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.6035678104629802, 0.0], [1.7662349821247334, 0.0], [1.8662349821247333, 0.0], [1.9662349821247334, 0.0], [2.066234982124733, 0.0], [2.1662349821247333, 0.0], [2.2662349821247334, 0.0], [2.366234982124733, 0.0], [2.466234982124733, 0.0], [2.566234982124733, 0.0], [2.6662349821247333, 0.0], [2.7662349821247334, 0.0], [2.8662349821247335, 0.0], [2.9662349821247336, 0.0], [3.0662349821247337, 0.0], [3.1662349821247338, 0.0], [3.266234982124734, 0.0], [3.366234982124734, 0.0], [3.466234982124734, 0.0], [3.566234982124734, 0.0], [3.6662349821247338, 0.0], [3.766234982124734, 0.0], [3.866234982124734, 0.0], [3.966234982124734, 0.0], [4.066234982124734, 0.0], [4.166234982124735, 0.0], [4.266234982124734, 0.0], [4.366234982124734, 0.0], [4.4662349821247345, 0.0], [4.566234982124735, 0.0], [4.666234982124735, 0.0], [4.766234982124734, 0.0], [4.866234982124735, 0.0], [4.966234982124735, 0.0], [5.066234982124735, 0.0], [5.166234982124735, 0.0], [5.266234982124735, 0.0], [5.366234982124736, 0.0], [5.466234982124735, 0.0], [5.566234982124735, 0.0], [5.666234982124736, 0.0], [5.766234982124736, 0.0], [5.866234982124736, 0.0], [5.966234982124735, 0.0], [6.066234982124735, 0.0], [6.166234982124735, 0.0], [6.266234982124734, 0.0], [6.366234982124734, 0.0], [6.466234982124734, 0.0], [6.566234982124733, 0.0], [6.666234982124733, 0.0], [6.7662349821247325, 0.0], [6.866234982124732, 0.0], [6.966234982124732, 0.0], [7.0662349821247314, 0.0], [7.166234982124731, 0.0], [7.266234982124731, 0.0], [7.36623498212473, 0.0], [7.46623498212473, 0.0], [7.56623498212473, 0.0], [7.666234982124729, 0.0], [7.766234982124729, 0.0], [7.866234982124729, 0.0], [7.966234982124728, 0.0], [8.066234982124728, 0.0], [8.166234982124728, 0.0], [8.266234982124727, 0.0], [8.366234982124727, 0.0], [8.466234982124726, 0.0], [8.566234982124726, 0.0], [8.666234982124726, 0.0], [8.766234982124725, 0.0], [8.866234982124725, 0.0], [8.966234982124725, 0.0], [9.066234982124724, 0.0], [9.166234982124724, 0.0], [9.266234982124724, 0.0], [9.366234982124723, 0.0], [9.466234982124723, 0.0], [9.566234982124723, 0.0], [9.666234982124722, 0.0], [9.766234982124722, 0.0], [9.866234982124721, 0.0], [9.966234982124721, 0.0], [10.06623498212472, 0.0], [10.16623498212472, 0.0], [10.26623498212472, 0.0], [10.36623498212472, 0.0], [10.46623498212472, 0.0], [10.566234982124719, 0.0], [10.666234982124719, 0.0], [10.766234982124718, 0.0], [10.866234982124718, 0.0], [10.966234982124718, 0.0], [11.066234982124717, 0.0], [11.166234982124717, 0.0], [11.266234982124717, 0.0], [11.366234982124716, 0.0], [11.466234982124716, 0.0], [11.566234982124715, 0.0], [11.666234982124715, 0.0], [11.766234982124715, 0.0], [11.866234982124714, 0.0], [11.966234982124714, 0.0], [12.066234982124714, 0.0], [12.166234982124713, 0.0], [12.266234982124713, 0.0], [12.366234982124713, 0.0], [12.466234982124712, 0.0], [12.566234982124712, 0.0], [12.666234982124712, 0.0], [12.766234982124711, 0.0], [12.86623498212471, 0.0], [12.96623498212471, 0.0], [13.06623498212471, 0.0], [13.16623498212471, 0.0], [13.26623498212471, 0.0], [13.366234982124709, 0.0], [13.466234982124709, 0.0], [13.566234982124708, 0.0], [13.666234982124708, 0.0], [13.766234982124708, 0.0], [13.866234982124707, 0.0], [13.966234982124707, 0.0], [14.066234982124707, 0.0], [14.166234982124706, 0.0], [14.266234982124706, 0.0], [14.366234982124706, 0.0], [14.466234982124705, 0.0], [14.566234982124705, 0.0], [14.666234982124704, 0.0], [14.765971407480114, 0.0], [14.852724411055174, 0.0], [14.919477414630233, 0.0], [14.966230418205292, 0.0], [14.992983421780352, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514], "velocities": null}}, "time": 1740481170.3636281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23630752800862376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966925754369432, "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": 1740481170.3636281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.3836281, "x": 5.7100734331534495, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.3836281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24310375115192775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666180174513399, "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": 1740481170.3836281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.403628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668524169626367, "gear": 1, "accelerator_pedal_position": 0.24310375115192775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.403628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.423628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967062964644355, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.423628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.443628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672732204389127, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.443628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.463628} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.7100734331534495, 0.0], [1.8726298448330754, 0.0], [1.9726298448330755, 0.0], [2.0726298448330756, 0.0], [2.172629844833075, 0.0], [2.2726298448330753, 0.0], [2.3726298448330754, 0.0], [2.472629844833075, 0.0], [2.572629844833075, 0.0], [2.672629844833075, 0.0], [2.7726298448330753, 0.0], [2.8726298448330754, 0.0], [2.9726298448330755, 0.0], [3.0726298448330756, 0.0], [3.1726298448330756, 0.0], [3.2726298448330757, 0.0], [3.372629844833076, 0.0], [3.472629844833076, 0.0], [3.572629844833076, 0.0], [3.672629844833076, 0.0], [3.772629844833076, 0.0], [3.8726298448330763, 0.0], [3.9726298448330764, 0.0], [4.072629844833076, 0.0], [4.172629844833077, 0.0], [4.272629844833077, 0.0], [4.372629844833076, 0.0], [4.472629844833077, 0.0], [4.572629844833077, 0.0], [4.672629844833077, 0.0], [4.772629844833077, 0.0], [4.872629844833077, 0.0], [4.972629844833078, 0.0], [5.072629844833077, 0.0], [5.172629844833077, 0.0], [5.2726298448330775, 0.0], [5.372629844833078, 0.0], [5.472629844833078, 0.0], [5.572629844833077, 0.0], [5.672629844833078, 0.0], [5.7726298448330775, 0.0], [5.872629844833077, 0.0], [5.972629844833077, 0.0], [6.072629844833076, 0.0], [6.172629844833076, 0.0], [6.272629844833076, 0.0], [6.372629844833075, 0.0], [6.472629844833075, 0.0], [6.572629844833075, 0.0], [6.672629844833074, 0.0], [6.772629844833074, 0.0], [6.872629844833074, 0.0], [6.972629844833073, 0.0], [7.072629844833073, 0.0], [7.1726298448330725, 0.0], [7.272629844833072, 0.0], [7.372629844833072, 0.0], [7.4726298448330715, 0.0], [7.572629844833071, 0.0], [7.672629844833071, 0.0], [7.77262984483307, 0.0], [7.87262984483307, 0.0], [7.97262984483307, 0.0], [8.07262984483307, 0.0], [8.172629844833068, 0.0], [8.27262984483307, 0.0], [8.372629844833067, 0.0], [8.472629844833069, 0.0], [8.572629844833067, 0.0], [8.672629844833068, 0.0], [8.772629844833066, 0.0], [8.872629844833067, 0.0], [8.972629844833065, 0.0], [9.072629844833067, 0.0], [9.172629844833066, 0.0], [9.272629844833066, 0.0], [9.372629844833066, 0.0], [9.472629844833065, 0.0], [9.572629844833065, 0.0], [9.672629844833065, 0.0], [9.772629844833064, 0.0], [9.872629844833064, 0.0], [9.972629844833063, 0.0], [10.072629844833063, 0.0], [10.172629844833063, 0.0], [10.272629844833062, 0.0], [10.372629844833062, 0.0], [10.472629844833062, 0.0], [10.572629844833061, 0.0], [10.672629844833061, 0.0], [10.77262984483306, 0.0], [10.87262984483306, 0.0], [10.97262984483306, 0.0], [11.07262984483306, 0.0], [11.17262984483306, 0.0], [11.272629844833059, 0.0], [11.372629844833058, 0.0], [11.472629844833058, 0.0], [11.572629844833058, 0.0], [11.672629844833057, 0.0], [11.772629844833057, 0.0], [11.872629844833057, 0.0], [11.972629844833056, 0.0], [12.072629844833056, 0.0], [12.172629844833056, 0.0], [12.272629844833055, 0.0], [12.372629844833055, 0.0], [12.472629844833055, 0.0], [12.572629844833054, 0.0], [12.672629844833054, 0.0], [12.772629844833054, 0.0], [12.872629844833053, 0.0], [12.972629844833053, 0.0], [13.072629844833052, 0.0], [13.172629844833052, 0.0], [13.272629844833052, 0.0], [13.372629844833051, 0.0], [13.472629844833051, 0.0], [13.57262984483305, 0.0], [13.67262984483305, 0.0], [13.77262984483305, 0.0], [13.87262984483305, 0.0], [13.97262984483305, 0.0], [14.072629844833049, 0.0], [14.172629844833049, 0.0], [14.272629844833048, 0.0], [14.372629844833048, 0.0], [14.472629844833047, 0.0], [14.572629844833047, 0.0], [14.672629844833047, 0.0], [14.772117734955879, 0.0], [14.85759176598927, 0.0], [14.92306579702266, 0.0], [14.96853982805605, 0.0], [14.994013859089442, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514], "velocities": null}}, "time": 1740481170.463628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366132224209389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9674831847332829, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.463628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.483628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366132224209389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966905350032973, "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": 1740481170.483628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.493628, "x": 5.816449719899462, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.503628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24389246917826207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663283164075166, "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": 1740481170.503628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.523628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2438923757754336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666616730601639, "gear": 1, "accelerator_pedal_position": 0.24389246917826207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.523628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.543628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2438923757754336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669945559589695, "gear": 1, "accelerator_pedal_position": 0.2438923757754336, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.543628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.563628} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.8164497198994622, 0.0], [1.9790060744152305, 0.0], [2.0790060744152306, 0.0], [2.1790060744152306, 0.0], [2.2790060744152303, 0.0], [2.3790060744152304, 0.0], [2.4790060744152305, 0.0], [2.5790060744152306, 0.0], [2.6790060744152306, 0.0], [2.7790060744152303, 0.0], [2.8790060744152304, 0.0], [2.9790060744152305, 0.0], [3.0790060744152306, 0.0], [3.1790060744152306, 0.0], [3.2790060744152307, 0.0], [3.379006074415231, 0.0], [3.479006074415231, 0.0], [3.579006074415231, 0.0], [3.679006074415231, 0.0], [3.779006074415231, 0.0], [3.8790060744152313, 0.0], [3.9790060744152314, 0.0], [4.079006074415231, 0.0], [4.1790060744152315, 0.0], [4.279006074415232, 0.0], [4.379006074415232, 0.0], [4.479006074415231, 0.0], [4.579006074415232, 0.0], [4.679006074415232, 0.0], [4.779006074415232, 0.0], [4.879006074415232, 0.0], [4.979006074415232, 0.0], [5.079006074415233, 0.0], [5.179006074415232, 0.0], [5.279006074415232, 0.0], [5.379006074415233, 0.0], [5.479006074415233, 0.0], [5.579006074415233, 0.0], [5.679006074415232, 0.0], [5.779006074415233, 0.0], [5.8790060744152335, 0.0], [5.979006074415233, 0.0], [6.079006074415233, 0.0], [6.179006074415232, 0.0], [6.279006074415232, 0.0], [6.379006074415232, 0.0], [6.479006074415231, 0.0], [6.579006074415231, 0.0], [6.679006074415231, 0.0], [6.77900607441523, 0.0], [6.87900607441523, 0.0], [6.97900607441523, 0.0], [7.079006074415229, 0.0], [7.179006074415229, 0.0], [7.2790060744152285, 0.0], [7.379006074415228, 0.0], [7.479006074415228, 0.0], [7.5790060744152274, 0.0], [7.679006074415227, 0.0], [7.779006074415227, 0.0], [7.879006074415226, 0.0], [7.979006074415226, 0.0], [8.079006074415226, 0.0], [8.179006074415225, 0.0], [8.279006074415225, 0.0], [8.379006074415225, 0.0], [8.479006074415224, 0.0], [8.579006074415224, 0.0], [8.679006074415224, 0.0], [8.779006074415223, 0.0], [8.879006074415223, 0.0], [8.979006074415222, 0.0], [9.079006074415222, 0.0], [9.179006074415222, 0.0], [9.279006074415221, 0.0], [9.379006074415221, 0.0], [9.47900607441522, 0.0], [9.57900607441522, 0.0], [9.67900607441522, 0.0], [9.77900607441522, 0.0], [9.87900607441522, 0.0], [9.979006074415219, 0.0], [10.079006074415219, 0.0], [10.179006074415218, 0.0], [10.279006074415218, 0.0], [10.379006074415217, 0.0], [10.479006074415217, 0.0], [10.579006074415217, 0.0], [10.679006074415216, 0.0], [10.779006074415216, 0.0], [10.879006074415216, 0.0], [10.979006074415215, 0.0], [11.079006074415215, 0.0], [11.179006074415215, 0.0], [11.279006074415214, 0.0], [11.379006074415214, 0.0], [11.479006074415214, 0.0], [11.579006074415213, 0.0], [11.679006074415213, 0.0], [11.779006074415213, 0.0], [11.879006074415212, 0.0], [11.979006074415212, 0.0], [12.079006074415211, 0.0], [12.179006074415211, 0.0], [12.27900607441521, 0.0], [12.37900607441521, 0.0], [12.47900607441521, 0.0], [12.57900607441521, 0.0], [12.67900607441521, 0.0], [12.779006074415209, 0.0], [12.879006074415209, 0.0], [12.979006074415208, 0.0], [13.079006074415208, 0.0], [13.179006074415208, 0.0], [13.279006074415207, 0.0], [13.379006074415207, 0.0], [13.479006074415206, 0.0], [13.579006074415206, 0.0], [13.679006074415206, 0.0], [13.779006074415205, 0.0], [13.879006074415205, 0.0], [13.979006074415205, 0.0], [14.079006074415204, 0.0], [14.179006074415204, 0.0], [14.279006074415204, 0.0], [14.379006074415203, 0.0], [14.479006074415203, 0.0], [14.579006074415203, 0.0], [14.679006074415202, 0.0], [14.778164722062222, 0.0], [14.86236350717918, 0.0], [14.92656229229614, 0.0], [14.9707610774131, 0.0], [14.99495986253006, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515], "velocities": null}}, "time": 1740481170.563628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23661337189805243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967326977387624, "gear": 1, "accelerator_pedal_position": 0.2438923757754336, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.563628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.583628} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.37304, "x": 15.0, "y": 3.6099999999999666, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.583628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23661337189805243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667493779349889, "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": 1740481170.583628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.603628, "x": 5.922796326289891, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.603628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24399624662824665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661725791950498, "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": 1740481170.603628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.623628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396394449063197, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666901904425138, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.623628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.643628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396394449063197, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668611428855273, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.643628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.6636279} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.922796326289891, 0.0], [2.085332779543226, 0.0], [2.1853327795432262, 0.0], [2.2853327795432263, 0.0], [2.385332779543226, 0.0], [2.485332779543226, 0.0], [2.585332779543226, 0.0], [2.6853327795432262, 0.0], [2.785332779543226, 0.0], [2.885332779543226, 0.0], [2.985332779543226, 0.0], [3.085332779543226, 0.0], [3.1853327795432262, 0.0], [3.2853327795432263, 0.0], [3.3853327795432264, 0.0], [3.4853327795432265, 0.0], [3.5853327795432266, 0.0], [3.6853327795432267, 0.0], [3.7853327795432268, 0.0], [3.885332779543227, 0.0], [3.985332779543227, 0.0], [4.085332779543227, 0.0], [4.185332779543227, 0.0], [4.285332779543227, 0.0], [4.385332779543227, 0.0], [4.485332779543227, 0.0], [4.5853327795432275, 0.0], [4.685332779543227, 0.0], [4.785332779543228, 0.0], [4.885332779543227, 0.0], [4.985332779543228, 0.0], [5.0853327795432275, 0.0], [5.185332779543228, 0.0], [5.285332779543228, 0.0], [5.385332779543228, 0.0], [5.485332779543228, 0.0], [5.585332779543228, 0.0], [5.685332779543228, 0.0], [5.7853327795432286, 0.0], [5.885332779543228, 0.0], [5.985332779543229, 0.0], [6.085332779543228, 0.0], [6.185332779543228, 0.0], [6.285332779543228, 0.0], [6.385332779543227, 0.0], [6.485332779543227, 0.0], [6.585332779543227, 0.0], [6.685332779543226, 0.0], [6.785332779543226, 0.0], [6.8853327795432255, 0.0], [6.985332779543225, 0.0], [7.085332779543225, 0.0], [7.1853327795432245, 0.0], [7.285332779543224, 0.0], [7.385332779543224, 0.0], [7.485332779543223, 0.0], [7.585332779543223, 0.0], [7.685332779543223, 0.0], [7.785332779543222, 0.0], [7.885332779543222, 0.0], [7.985332779543222, 0.0], [8.085332779543222, 0.0], [8.18533277954322, 0.0], [8.285332779543221, 0.0], [8.38533277954322, 0.0], [8.48533277954322, 0.0], [8.585332779543219, 0.0], [8.68533277954322, 0.0], [8.785332779543218, 0.0], [8.88533277954322, 0.0], [8.985332779543217, 0.0], [9.085332779543219, 0.0], [9.185332779543216, 0.0], [9.285332779543218, 0.0], [9.385332779543216, 0.0], [9.485332779543217, 0.0], [9.585332779543215, 0.0], [9.685332779543216, 0.0], [9.785332779543214, 0.0], [9.885332779543216, 0.0], [9.985332779543215, 0.0], [10.085332779543215, 0.0], [10.185332779543215, 0.0], [10.285332779543214, 0.0], [10.385332779543214, 0.0], [10.485332779543214, 0.0], [10.585332779543213, 0.0], [10.685332779543213, 0.0], [10.785332779543213, 0.0], [10.885332779543212, 0.0], [10.985332779543212, 0.0], [11.085332779543212, 0.0], [11.185332779543211, 0.0], [11.28533277954321, 0.0], [11.38533277954321, 0.0], [11.48533277954321, 0.0], [11.58533277954321, 0.0], [11.68533277954321, 0.0], [11.785332779543209, 0.0], [11.885332779543209, 0.0], [11.985332779543208, 0.0], [12.085332779543208, 0.0], [12.185332779543208, 0.0], [12.285332779543207, 0.0], [12.385332779543207, 0.0], [12.485332779543207, 0.0], [12.585332779543206, 0.0], [12.685332779543206, 0.0], [12.785332779543205, 0.0], [12.885332779543205, 0.0], [12.985332779543205, 0.0], [13.085332779543204, 0.0], [13.185332779543204, 0.0], [13.285332779543204, 0.0], [13.385332779543203, 0.0], [13.485332779543203, 0.0], [13.585332779543203, 0.0], [13.685332779543202, 0.0], [13.785332779543202, 0.0], [13.885332779543202, 0.0], [13.985332779543201, 0.0], [14.0853327795432, 0.0], [14.1853327795432, 0.0], [14.2853327795432, 0.0], [14.3853327795432, 0.0], [14.4853327795432, 0.0], [14.585332779543199, 0.0], [14.685332779543199, 0.0], [14.78408437423295, 0.0], [14.86701781832431, 0.0], [14.92995126241567, 0.0], [14.972884706507031, 0.0], [14.99581815059839, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515], "velocities": null}}, "time": 1740481170.6636279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673732893353835, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.6636279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.6836278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670875801674834, "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": 1740481170.6836278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.7036278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665167560496994, "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": 1740481170.7036278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.7136278, "x": 6.029142359340086, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7236278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441256918195378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965946723198658, "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": 1740481170.7236278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7436278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24412998721254417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663097514679029, "gear": 1, "accelerator_pedal_position": 0.2441256918195378, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.7436278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7636278} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.029142359340086, 0.0], [2.1916814741365895, 0.0], [2.291681474136589, 0.0], [2.3916814741365893, 0.0], [2.4916814741365894, 0.0], [2.5916814741365894, 0.0], [2.6916814741365895, 0.0], [2.791681474136589, 0.0], [2.8916814741365893, 0.0], [2.9916814741365894, 0.0], [3.091681474136589, 0.0], [3.1916814741365895, 0.0], [3.291681474136589, 0.0], [3.3916814741365897, 0.0], [3.4916814741365894, 0.0], [3.59168147413659, 0.0], [3.6916814741365895, 0.0], [3.79168147413659, 0.0], [3.8916814741365897, 0.0], [3.9916814741365902, 0.0], [4.091681474136591, 0.0], [4.19168147413659, 0.0], [4.29168147413659, 0.0], [4.391681474136591, 0.0], [4.491681474136591, 0.0], [4.591681474136591, 0.0], [4.69168147413659, 0.0], [4.791681474136591, 0.0], [4.8916814741365915, 0.0], [4.991681474136591, 0.0], [5.091681474136591, 0.0], [5.191681474136591, 0.0], [5.291681474136592, 0.0], [5.3916814741365915, 0.0], [5.491681474136591, 0.0], [5.591681474136592, 0.0], [5.691681474136592, 0.0], [5.791681474136592, 0.0], [5.8916814741365915, 0.0], [5.991681474136592, 0.0], [6.091681474136592, 0.0], [6.191681474136591, 0.0], [6.291681474136591, 0.0], [6.391681474136591, 0.0], [6.49168147413659, 0.0], [6.59168147413659, 0.0], [6.6916814741365895, 0.0], [6.791681474136589, 0.0], [6.891681474136589, 0.0], [6.9916814741365885, 0.0], [7.091681474136588, 0.0], [7.191681474136588, 0.0], [7.291681474136587, 0.0], [7.391681474136587, 0.0], [7.491681474136587, 0.0], [7.591681474136586, 0.0], [7.691681474136586, 0.0], [7.791681474136586, 0.0], [7.891681474136585, 0.0], [7.991681474136585, 0.0], [8.091681474136585, 0.0], [8.191681474136583, 0.0], [8.291681474136585, 0.0], [8.391681474136583, 0.0], [8.491681474136584, 0.0], [8.591681474136582, 0.0], [8.691681474136583, 0.0], [8.791681474136581, 0.0], [8.891681474136583, 0.0], [8.99168147413658, 0.0], [9.091681474136582, 0.0], [9.19168147413658, 0.0], [9.291681474136581, 0.0], [9.391681474136579, 0.0], [9.49168147413658, 0.0], [9.591681474136578, 0.0], [9.69168147413658, 0.0], [9.791681474136578, 0.0], [9.891681474136579, 0.0], [9.991681474136577, 0.0], [10.091681474136577, 0.0], [10.191681474136576, 0.0], [10.291681474136576, 0.0], [10.391681474136576, 0.0], [10.491681474136575, 0.0], [10.591681474136575, 0.0], [10.691681474136574, 0.0], [10.791681474136574, 0.0], [10.891681474136574, 0.0], [10.991681474136573, 0.0], [11.091681474136573, 0.0], [11.191681474136573, 0.0], [11.291681474136572, 0.0], [11.391681474136572, 0.0], [11.491681474136572, 0.0], [11.591681474136571, 0.0], [11.69168147413657, 0.0], [11.79168147413657, 0.0], [11.89168147413657, 0.0], [11.99168147413657, 0.0], [12.09168147413657, 0.0], [12.191681474136569, 0.0], [12.291681474136569, 0.0], [12.391681474136568, 0.0], [12.491681474136568, 0.0], [12.591681474136568, 0.0], [12.691681474136567, 0.0], [12.791681474136567, 0.0], [12.891681474136567, 0.0], [12.991681474136566, 0.0], [13.091681474136566, 0.0], [13.191681474136566, 0.0], [13.291681474136565, 0.0], [13.391681474136565, 0.0], [13.491681474136564, 0.0], [13.591681474136564, 0.0], [13.691681474136564, 0.0], [13.791681474136563, 0.0], [13.891681474136563, 0.0], [13.991681474136563, 0.0], [14.091681474136562, 0.0], [14.191681474136562, 0.0], [14.291681474136562, 0.0], [14.391681474136561, 0.0], [14.491681474136561, 0.0], [14.59168147413656, 0.0], [14.69168147413656, 0.0], [14.789944128850363, 0.0], [14.87160783402305, 0.0], [14.933271539195738, 0.0], [14.974935244368426, 0.0], [14.996598949541115, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515], "velocities": null}}, "time": 1740481170.7636278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668541554767535, "gear": 1, "accelerator_pedal_position": 0.24412998721254417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.7636278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7836277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665683786576705, "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": 1740481170.7836277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.8036277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659974192892395, "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": 1740481170.8036277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.8236277, "x": 6.1354343149822705, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8236277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442937207295742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654272512565151, "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": 1740481170.8236277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8436277} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.5911465, "x": 15.0, "y": 3.7199999999999642, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.8436277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24423521961661618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658119957606274, "gear": 1, "accelerator_pedal_position": 0.2442937207295742, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.8436277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8636277} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.1354343149822705, 0.0], [2.2979367811973623, 0.0], [2.3979367811973624, 0.0], [2.497936781197362, 0.0], [2.597936781197362, 0.0], [2.6979367811973622, 0.0], [2.7979367811973623, 0.0], [2.8979367811973624, 0.0], [2.997936781197362, 0.0], [3.097936781197362, 0.0], [3.1979367811973622, 0.0], [3.297936781197362, 0.0], [3.3979367811973624, 0.0], [3.497936781197362, 0.0], [3.5979367811973626, 0.0], [3.6979367811973622, 0.0], [3.7979367811973628, 0.0], [3.8979367811973624, 0.0], [3.997936781197363, 0.0], [4.097936781197363, 0.0], [4.197936781197363, 0.0], [4.297936781197363, 0.0], [4.397936781197363, 0.0], [4.497936781197364, 0.0], [4.5979367811973635, 0.0], [4.697936781197363, 0.0], [4.797936781197364, 0.0], [4.897936781197364, 0.0], [4.997936781197364, 0.0], [5.0979367811973635, 0.0], [5.197936781197364, 0.0], [5.2979367811973646, 0.0], [5.397936781197364, 0.0], [5.497936781197364, 0.0], [5.597936781197364, 0.0], [5.697936781197365, 0.0], [5.7979367811973646, 0.0], [5.897936781197364, 0.0], [5.997936781197365, 0.0], [6.097936781197365, 0.0], [6.197936781197365, 0.0], [6.2979367811973646, 0.0], [6.397936781197364, 0.0], [6.497936781197364, 0.0], [6.5979367811973635, 0.0], [6.697936781197363, 0.0], [6.797936781197363, 0.0], [6.897936781197362, 0.0], [6.997936781197362, 0.0], [7.097936781197362, 0.0], [7.197936781197361, 0.0], [7.297936781197361, 0.0], [7.397936781197361, 0.0], [7.49793678119736, 0.0], [7.59793678119736, 0.0], [7.69793678119736, 0.0], [7.797936781197359, 0.0], [7.897936781197359, 0.0], [7.9979367811973585, 0.0], [8.097936781197358, 0.0], [8.197936781197358, 0.0], [8.297936781197357, 0.0], [8.397936781197357, 0.0], [8.497936781197357, 0.0], [8.597936781197356, 0.0], [8.697936781197356, 0.0], [8.797936781197356, 0.0], [8.897936781197355, 0.0], [8.997936781197355, 0.0], [9.097936781197355, 0.0], [9.197936781197354, 0.0], [9.297936781197354, 0.0], [9.397936781197354, 0.0], [9.497936781197353, 0.0], [9.597936781197353, 0.0], [9.697936781197352, 0.0], [9.797936781197352, 0.0], [9.897936781197352, 0.0], [9.997936781197351, 0.0], [10.097936781197351, 0.0], [10.19793678119735, 0.0], [10.29793678119735, 0.0], [10.39793678119735, 0.0], [10.49793678119735, 0.0], [10.59793678119735, 0.0], [10.697936781197349, 0.0], [10.797936781197349, 0.0], [10.897936781197348, 0.0], [10.997936781197348, 0.0], [11.097936781197347, 0.0], [11.197936781197347, 0.0], [11.297936781197347, 0.0], [11.397936781197346, 0.0], [11.497936781197346, 0.0], [11.597936781197346, 0.0], [11.697936781197345, 0.0], [11.797936781197345, 0.0], [11.897936781197345, 0.0], [11.997936781197344, 0.0], [12.097936781197344, 0.0], [12.197936781197344, 0.0], [12.297936781197343, 0.0], [12.397936781197343, 0.0], [12.497936781197343, 0.0], [12.597936781197342, 0.0], [12.697936781197342, 0.0], [12.797936781197341, 0.0], [12.897936781197341, 0.0], [12.99793678119734, 0.0], [13.09793678119734, 0.0], [13.19793678119734, 0.0], [13.29793678119734, 0.0], [13.39793678119734, 0.0], [13.497936781197339, 0.0], [13.597936781197339, 0.0], [13.697936781197338, 0.0], [13.797936781197338, 0.0], [13.897936781197338, 0.0], [13.997936781197337, 0.0], [14.097936781197337, 0.0], [14.197936781197336, 0.0], [14.297936781197336, 0.0], [14.397936781197336, 0.0], [14.497936781197335, 0.0], [14.597936781197335, 0.0], [14.697936781197335, 0.0], [14.795638846205772, 0.0], [14.876051489966306, 0.0], [14.936464133726838, 0.0], [14.976876777487373, 0.0], [14.997289421247906, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516], "velocities": null}}, "time": 1740481170.8636277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661888969789928, "gear": 1, "accelerator_pedal_position": 0.24423521961661618, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.8636277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8836277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656300588317035, "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": 1740481170.8836277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.9036276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650719951376668, "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": 1740481170.9036276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.9236276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645147046990933, "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": 1740481170.9236276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.9336276, "x": 6.24163750167411, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9436276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24483554828289178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639581863203707, "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": 1740481170.9436276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9636276} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.24163750167411, 0.0], [2.4040841253747556, 0.0], [2.5040841253747557, 0.0], [2.6040841253747553, 0.0], [2.7040841253747554, 0.0], [2.8040841253747555, 0.0], [2.904084125374755, 0.0], [3.004084125374755, 0.0], [3.1040841253747553, 0.0], [3.2040841253747554, 0.0], [3.3040841253747555, 0.0], [3.404084125374755, 0.0], [3.5040841253747557, 0.0], [3.6040841253747553, 0.0], [3.704084125374756, 0.0], [3.8040841253747555, 0.0], [3.904084125374756, 0.0], [4.004084125374756, 0.0], [4.104084125374756, 0.0], [4.204084125374756, 0.0], [4.3040841253747555, 0.0], [4.404084125374756, 0.0], [4.5040841253747566, 0.0], [4.604084125374756, 0.0], [4.704084125374756, 0.0], [4.804084125374756, 0.0], [4.904084125374757, 0.0], [5.0040841253747566, 0.0], [5.104084125374756, 0.0], [5.204084125374757, 0.0], [5.304084125374757, 0.0], [5.404084125374757, 0.0], [5.5040841253747566, 0.0], [5.604084125374757, 0.0], [5.704084125374758, 0.0], [5.804084125374757, 0.0], [5.904084125374757, 0.0], [6.004084125374757, 0.0], [6.104084125374758, 0.0], [6.204084125374758, 0.0], [6.304084125374758, 0.0], [6.404084125374758, 0.0], [6.504084125374757, 0.0], [6.604084125374757, 0.0], [6.704084125374757, 0.0], [6.804084125374756, 0.0], [6.904084125374756, 0.0], [7.004084125374756, 0.0], [7.104084125374755, 0.0], [7.204084125374755, 0.0], [7.304084125374755, 0.0], [7.404084125374754, 0.0], [7.504084125374754, 0.0], [7.6040841253747535, 0.0], [7.704084125374753, 0.0], [7.804084125374753, 0.0], [7.9040841253747525, 0.0], [8.004084125374753, 0.0], [8.10408412537475, 0.0], [8.204084125374752, 0.0], [8.30408412537475, 0.0], [8.404084125374752, 0.0], [8.50408412537475, 0.0], [8.60408412537475, 0.0], [8.704084125374749, 0.0], [8.80408412537475, 0.0], [8.904084125374748, 0.0], [9.00408412537475, 0.0], [9.104084125374747, 0.0], [9.204084125374749, 0.0], [9.304084125374747, 0.0], [9.404084125374748, 0.0], [9.504084125374746, 0.0], [9.604084125374747, 0.0], [9.704084125374745, 0.0], [9.804084125374747, 0.0], [9.904084125374744, 0.0], [10.004084125374744, 0.0], [10.104084125374744, 0.0], [10.204084125374743, 0.0], [10.304084125374743, 0.0], [10.404084125374743, 0.0], [10.504084125374742, 0.0], [10.604084125374742, 0.0], [10.704084125374742, 0.0], [10.804084125374741, 0.0], [10.904084125374741, 0.0], [11.00408412537474, 0.0], [11.10408412537474, 0.0], [11.20408412537474, 0.0], [11.30408412537474, 0.0], [11.40408412537474, 0.0], [11.504084125374739, 0.0], [11.604084125374738, 0.0], [11.704084125374738, 0.0], [11.804084125374738, 0.0], [11.904084125374737, 0.0], [12.004084125374737, 0.0], [12.104084125374737, 0.0], [12.204084125374736, 0.0], [12.304084125374736, 0.0], [12.404084125374736, 0.0], [12.504084125374735, 0.0], [12.604084125374735, 0.0], [12.704084125374735, 0.0], [12.804084125374734, 0.0], [12.904084125374734, 0.0], [13.004084125374733, 0.0], [13.104084125374733, 0.0], [13.204084125374733, 0.0], [13.304084125374732, 0.0], [13.404084125374732, 0.0], [13.504084125374732, 0.0], [13.604084125374731, 0.0], [13.704084125374731, 0.0], [13.80408412537473, 0.0], [13.90408412537473, 0.0], [14.00408412537473, 0.0], [14.10408412537473, 0.0], [14.20408412537473, 0.0], [14.304084125374729, 0.0], [14.404084125374728, 0.0], [14.504084125374728, 0.0], [14.604084125374728, 0.0], [14.704084125374727, 0.0], [14.801159032757178, 0.0], [14.880342207682233, 0.0], [14.939525382607286, 0.0], [14.978708557532341, 0.0], [14.997891732457395, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516], "velocities": null}}, "time": 1740481170.9636276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644126711010675, "gear": 1, "accelerator_pedal_position": 0.24483554828289178, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.9636276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9836276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638732669429582, "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": 1740481170.9836276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481171.0036275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633346099261119, "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": 1740481171.0036275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481171.0236275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627966988996255, "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": 1740481171.0236275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.0436275, "x": 6.347638877618153, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0436275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570142474930556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622595327146718, "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": 1740481171.0436275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0636275} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.347638877618153, 0.0], [2.509988631889755, 0.0], [2.609988631889755, 0.0], [2.7099886318897553, 0.0], [2.809988631889755, 0.0], [2.909988631889755, 0.0], [3.009988631889755, 0.0], [3.109988631889755, 0.0], [3.209988631889755, 0.0], [3.309988631889755, 0.0], [3.409988631889755, 0.0], [3.509988631889755, 0.0], [3.609988631889755, 0.0], [3.7099886318897553, 0.0], [3.8099886318897553, 0.0], [3.9099886318897554, 0.0], [4.0099886318897555, 0.0], [4.109988631889756, 0.0], [4.209988631889756, 0.0], [4.309988631889755, 0.0], [4.409988631889756, 0.0], [4.509988631889756, 0.0], [4.609988631889756, 0.0], [4.709988631889756, 0.0], [4.809988631889756, 0.0], [4.909988631889757, 0.0], [5.009988631889756, 0.0], [5.109988631889756, 0.0], [5.209988631889757, 0.0], [5.309988631889757, 0.0], [5.409988631889757, 0.0], [5.509988631889756, 0.0], [5.609988631889757, 0.0], [5.7099886318897575, 0.0], [5.809988631889757, 0.0], [5.909988631889757, 0.0], [6.009988631889757, 0.0], [6.109988631889758, 0.0], [6.2099886318897575, 0.0], [6.309988631889757, 0.0], [6.409988631889757, 0.0], [6.509988631889756, 0.0], [6.609988631889756, 0.0], [6.709988631889756, 0.0], [6.809988631889755, 0.0], [6.909988631889755, 0.0], [7.009988631889755, 0.0], [7.109988631889754, 0.0], [7.209988631889754, 0.0], [7.309988631889754, 0.0], [7.409988631889753, 0.0], [7.509988631889753, 0.0], [7.6099886318897525, 0.0], [7.709988631889752, 0.0], [7.809988631889752, 0.0], [7.909988631889751, 0.0], [8.009988631889751, 0.0], [8.10998863188975, 0.0], [8.20998863188975, 0.0], [8.30998863188975, 0.0], [8.40998863188975, 0.0], [8.50998863188975, 0.0], [8.609988631889749, 0.0], [8.709988631889749, 0.0], [8.809988631889748, 0.0], [8.909988631889748, 0.0], [9.009988631889748, 0.0], [9.109988631889747, 0.0], [9.209988631889747, 0.0], [9.309988631889746, 0.0], [9.409988631889746, 0.0], [9.509988631889746, 0.0], [9.609988631889745, 0.0], [9.709988631889745, 0.0], [9.809988631889745, 0.0], [9.909988631889744, 0.0], [10.009988631889744, 0.0], [10.109988631889744, 0.0], [10.209988631889743, 0.0], [10.309988631889743, 0.0], [10.409988631889743, 0.0], [10.509988631889742, 0.0], [10.609988631889742, 0.0], [10.709988631889741, 0.0], [10.809988631889741, 0.0], [10.90998863188974, 0.0], [11.00998863188974, 0.0], [11.10998863188974, 0.0], [11.20998863188974, 0.0], [11.30998863188974, 0.0], [11.409988631889739, 0.0], [11.509988631889739, 0.0], [11.609988631889738, 0.0], [11.709988631889738, 0.0], [11.809988631889738, 0.0], [11.909988631889737, 0.0], [12.009988631889737, 0.0], [12.109988631889737, 0.0], [12.209988631889736, 0.0], [12.309988631889736, 0.0], [12.409988631889735, 0.0], [12.509988631889735, 0.0], [12.609988631889735, 0.0], [12.709988631889734, 0.0], [12.809988631889734, 0.0], [12.909988631889734, 0.0], [13.009988631889733, 0.0], [13.109988631889733, 0.0], [13.209988631889733, 0.0], [13.309988631889732, 0.0], [13.409988631889732, 0.0], [13.509988631889732, 0.0], [13.609988631889731, 0.0], [13.70998863188973, 0.0], [13.80998863188973, 0.0], [13.90998863188973, 0.0], [14.00998863188973, 0.0], [14.10998863188973, 0.0], [14.209988631889729, 0.0], [14.309988631889729, 0.0], [14.409988631889728, 0.0], [14.509988631889728, 0.0], [14.609988631889728, 0.0], [14.709988631889727, 0.0], [14.806389995933726, 0.0], [14.88439226955578, 0.0], [14.942394543177835, 0.0], [14.980396816799889, 0.0], [14.998399090421945, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516], "velocities": null}}, "time": 1740481171.0636275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628245668887193, "gear": 1, "accelerator_pedal_position": 0.24570142474930556, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.0636275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0836275} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.9255316, "x": 15.0, "y": 3.8849999999999607, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.0836275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623150248298986, "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": 1740481171.0836275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1036274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618061882307547, "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": 1740481171.1036274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1236274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612980560110505, "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": 1740481171.1236274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1436274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960790627092474, "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": 1740481171.1436274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.1536274, "x": 6.453449504191092, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.1636274} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.4534495041910924, 0.0], [2.615710610726425, 0.0], [2.7157106107264246, 0.0], [2.8157106107264247, 0.0], [2.915710610726425, 0.0], [3.015710610726425, 0.0], [3.115710610726425, 0.0], [3.2157106107264246, 0.0], [3.3157106107264247, 0.0], [3.415710610726425, 0.0], [3.5157106107264244, 0.0], [3.615710610726425, 0.0], [3.7157106107264246, 0.0], [3.815710610726425, 0.0], [3.915710610726425, 0.0], [4.015710610726425, 0.0], [4.115710610726425, 0.0], [4.2157106107264255, 0.0], [4.315710610726425, 0.0], [4.415710610726426, 0.0], [4.515710610726426, 0.0], [4.615710610726426, 0.0], [4.7157106107264255, 0.0], [4.815710610726426, 0.0], [4.915710610726427, 0.0], [5.015710610726426, 0.0], [5.115710610726426, 0.0], [5.215710610726426, 0.0], [5.315710610726427, 0.0], [5.415710610726427, 0.0], [5.515710610726426, 0.0], [5.615710610726427, 0.0], [5.715710610726427, 0.0], [5.815710610726427, 0.0], [5.915710610726427, 0.0], [6.015710610726427, 0.0], [6.115710610726428, 0.0], [6.215710610726427, 0.0], [6.315710610726427, 0.0], [6.4157106107264275, 0.0], [6.515710610726427, 0.0], [6.615710610726427, 0.0], [6.715710610726426, 0.0], [6.815710610726426, 0.0], [6.915710610726426, 0.0], [7.015710610726425, 0.0], [7.115710610726425, 0.0], [7.215710610726425, 0.0], [7.315710610726424, 0.0], [7.415710610726424, 0.0], [7.5157106107264235, 0.0], [7.615710610726423, 0.0], [7.715710610726423, 0.0], [7.8157106107264225, 0.0], [7.915710610726422, 0.0], [8.015710610726423, 0.0], [8.11571061072642, 0.0], [8.215710610726422, 0.0], [8.31571061072642, 0.0], [8.415710610726421, 0.0], [8.515710610726419, 0.0], [8.61571061072642, 0.0], [8.715710610726418, 0.0], [8.81571061072642, 0.0], [8.915710610726418, 0.0], [9.015710610726419, 0.0], [9.115710610726417, 0.0], [9.215710610726418, 0.0], [9.315710610726416, 0.0], [9.415710610726418, 0.0], [9.515710610726416, 0.0], [9.615710610726417, 0.0], [9.715710610726415, 0.0], [9.815710610726416, 0.0], [9.915710610726414, 0.0], [10.015710610726414, 0.0], [10.115710610726413, 0.0], [10.215710610726413, 0.0], [10.315710610726413, 0.0], [10.415710610726412, 0.0], [10.515710610726412, 0.0], [10.615710610726412, 0.0], [10.715710610726411, 0.0], [10.815710610726411, 0.0], [10.91571061072641, 0.0], [11.01571061072641, 0.0], [11.11571061072641, 0.0], [11.21571061072641, 0.0], [11.31571061072641, 0.0], [11.415710610726409, 0.0], [11.515710610726408, 0.0], [11.615710610726408, 0.0], [11.715710610726408, 0.0], [11.815710610726407, 0.0], [11.915710610726407, 0.0], [12.015710610726407, 0.0], [12.115710610726406, 0.0], [12.215710610726406, 0.0], [12.315710610726406, 0.0], [12.415710610726405, 0.0], [12.515710610726405, 0.0], [12.615710610726405, 0.0], [12.715710610726404, 0.0], [12.815710610726404, 0.0], [12.915710610726403, 0.0], [13.015710610726403, 0.0], [13.115710610726403, 0.0], [13.215710610726402, 0.0], [13.315710610726402, 0.0], [13.415710610726402, 0.0], [13.515710610726401, 0.0], [13.615710610726401, 0.0], [13.7157106107264, 0.0], [13.8157106107264, 0.0], [13.9157106107264, 0.0], [14.0157106107264, 0.0], [14.1157106107264, 0.0], [14.215710610726399, 0.0], [14.315710610726398, 0.0], [14.415710610726398, 0.0], [14.515710610726398, 0.0], [14.615710610726397, 0.0], [14.715710610726397, 0.0], [14.81139272636436, 0.0], [14.888250604219081, 0.0], [14.945108482073802, 0.0], [14.981966359928522, 0.0], [14.998824237783243, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517], "velocities": null}}, "time": 1740481171.1636274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24755493590799588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600308000501435, "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": 1740481171.1636274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.1836274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604308022306637, "gear": 1, "accelerator_pedal_position": 0.24755493590799588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.1836274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2036273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612192572432331, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2036273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2236273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620066210895067, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2236273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2436273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627928950316912, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2436273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.2636273, "x": 6.559202756307854, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.2636273} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.5592027563078537, 0.0], [2.721617701671829, 0.0], [2.821617701671829, 0.0], [2.921617701671829, 0.0], [3.021617701671829, 0.0], [3.1216177016718287, 0.0], [3.221617701671829, 0.0], [3.321617701671829, 0.0], [3.4216177016718285, 0.0], [3.5216177016718286, 0.0], [3.6216177016718287, 0.0], [3.721617701671829, 0.0], [3.821617701671829, 0.0], [3.921617701671829, 0.0], [4.021617701671829, 0.0], [4.121617701671829, 0.0], [4.221617701671829, 0.0], [4.32161770167183, 0.0], [4.421617701671829, 0.0], [4.521617701671829, 0.0], [4.62161770167183, 0.0], [4.72161770167183, 0.0], [4.82161770167183, 0.0], [4.921617701671829, 0.0], [5.02161770167183, 0.0], [5.1216177016718305, 0.0], [5.22161770167183, 0.0], [5.32161770167183, 0.0], [5.42161770167183, 0.0], [5.521617701671831, 0.0], [5.6216177016718305, 0.0], [5.72161770167183, 0.0], [5.821617701671831, 0.0], [5.921617701671831, 0.0], [6.021617701671831, 0.0], [6.1216177016718305, 0.0], [6.221617701671831, 0.0], [6.321617701671832, 0.0], [6.421617701671831, 0.0], [6.521617701671831, 0.0], [6.621617701671831, 0.0], [6.721617701671831, 0.0], [6.821617701671831, 0.0], [6.92161770167183, 0.0], [7.02161770167183, 0.0], [7.12161770167183, 0.0], [7.221617701671829, 0.0], [7.321617701671829, 0.0], [7.4216177016718285, 0.0], [7.521617701671828, 0.0], [7.621617701671828, 0.0], [7.7216177016718275, 0.0], [7.821617701671827, 0.0], [7.921617701671827, 0.0], [8.021617701671826, 0.0], [8.121617701671827, 0.0], [8.221617701671825, 0.0], [8.321617701671826, 0.0], [8.421617701671824, 0.0], [8.521617701671826, 0.0], [8.621617701671823, 0.0], [8.721617701671825, 0.0], [8.821617701671823, 0.0], [8.921617701671824, 0.0], [9.021617701671822, 0.0], [9.121617701671823, 0.0], [9.221617701671821, 0.0], [9.321617701671823, 0.0], [9.42161770167182, 0.0], [9.521617701671822, 0.0], [9.62161770167182, 0.0], [9.721617701671821, 0.0], [9.82161770167182, 0.0], [9.92161770167182, 0.0], [10.02161770167182, 0.0], [10.12161770167182, 0.0], [10.22161770167182, 0.0], [10.32161770167182, 0.0], [10.421617701671819, 0.0], [10.521617701671818, 0.0], [10.621617701671818, 0.0], [10.721617701671818, 0.0], [10.821617701671817, 0.0], [10.921617701671817, 0.0], [11.021617701671817, 0.0], [11.121617701671816, 0.0], [11.221617701671816, 0.0], [11.321617701671816, 0.0], [11.421617701671815, 0.0], [11.521617701671815, 0.0], [11.621617701671815, 0.0], [11.721617701671814, 0.0], [11.821617701671814, 0.0], [11.921617701671813, 0.0], [12.021617701671813, 0.0], [12.121617701671813, 0.0], [12.221617701671812, 0.0], [12.321617701671812, 0.0], [12.421617701671812, 0.0], [12.521617701671811, 0.0], [12.621617701671811, 0.0], [12.72161770167181, 0.0], [12.82161770167181, 0.0], [12.92161770167181, 0.0], [13.02161770167181, 0.0], [13.12161770167181, 0.0], [13.221617701671809, 0.0], [13.321617701671808, 0.0], [13.421617701671808, 0.0], [13.521617701671808, 0.0], [13.621617701671807, 0.0], [13.721617701671807, 0.0], [13.821617701671807, 0.0], [13.921617701671806, 0.0], [14.021617701671806, 0.0], [14.121617701671806, 0.0], [14.221617701671805, 0.0], [14.321617701671805, 0.0], [14.421617701671805, 0.0], [14.521617701671804, 0.0], [14.621617701671804, 0.0], [14.721617701671804, 0.0], [14.816488606479052, 0.0], [14.89216506614469, 0.0], [14.94784152581033, 0.0], [14.98351798547597, 0.0], [14.99919444514161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517], "velocities": null}}, "time": 1740481171.2636273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24547339038105365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639702651341101, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2636273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.2836273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642374430331526, "gear": 1, "accelerator_pedal_position": 0.24547339038105365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2836273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3036273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647903173766753, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3036273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3236272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653424257787706, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3236272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3436272} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.141229, "x": 15.0, "y": 3.9949999999999584, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.3436272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658937691786719, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3436272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3636272} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.5592027563078537, 0.0], [2.721617701671829, 0.0], [2.821617701671829, 0.0], [2.921617701671829, 0.0], [3.021617701671829, 0.0], [3.1216177016718287, 0.0], [3.221617701671829, 0.0], [3.321617701671829, 0.0], [3.4216177016718285, 0.0], [3.5216177016718286, 0.0], [3.6216177016718287, 0.0], [3.721617701671829, 0.0], [3.821617701671829, 0.0], [3.921617701671829, 0.0], [4.021617701671829, 0.0], [4.121617701671829, 0.0], [4.221617701671829, 0.0], [4.32161770167183, 0.0], [4.421617701671829, 0.0], [4.521617701671829, 0.0], [4.62161770167183, 0.0], [4.72161770167183, 0.0], [4.82161770167183, 0.0], [4.921617701671829, 0.0], [5.02161770167183, 0.0], [5.1216177016718305, 0.0], [5.22161770167183, 0.0], [5.32161770167183, 0.0], [5.42161770167183, 0.0], [5.521617701671831, 0.0], [5.6216177016718305, 0.0], [5.72161770167183, 0.0], [5.821617701671831, 0.0], [5.921617701671831, 0.0], [6.021617701671831, 0.0], [6.1216177016718305, 0.0], [6.221617701671831, 0.0], [6.321617701671832, 0.0], [6.421617701671831, 0.0], [6.521617701671831, 0.0], [6.621617701671831, 0.0], [6.721617701671831, 0.0], [6.821617701671831, 0.0], [6.92161770167183, 0.0], [7.02161770167183, 0.0], [7.12161770167183, 0.0], [7.221617701671829, 0.0], [7.321617701671829, 0.0], [7.4216177016718285, 0.0], [7.521617701671828, 0.0], [7.621617701671828, 0.0], [7.7216177016718275, 0.0], [7.821617701671827, 0.0], [7.921617701671827, 0.0], [8.021617701671826, 0.0], [8.121617701671827, 0.0], [8.221617701671825, 0.0], [8.321617701671826, 0.0], [8.421617701671824, 0.0], [8.521617701671826, 0.0], [8.621617701671823, 0.0], [8.721617701671825, 0.0], [8.821617701671823, 0.0], [8.921617701671824, 0.0], [9.021617701671822, 0.0], [9.121617701671823, 0.0], [9.221617701671821, 0.0], [9.321617701671823, 0.0], [9.42161770167182, 0.0], [9.521617701671822, 0.0], [9.62161770167182, 0.0], [9.721617701671821, 0.0], [9.82161770167182, 0.0], [9.92161770167182, 0.0], [10.02161770167182, 0.0], [10.12161770167182, 0.0], [10.22161770167182, 0.0], [10.32161770167182, 0.0], [10.421617701671819, 0.0], [10.521617701671818, 0.0], [10.621617701671818, 0.0], [10.721617701671818, 0.0], [10.821617701671817, 0.0], [10.921617701671817, 0.0], [11.021617701671817, 0.0], [11.121617701671816, 0.0], [11.221617701671816, 0.0], [11.321617701671816, 0.0], [11.421617701671815, 0.0], [11.521617701671815, 0.0], [11.621617701671815, 0.0], [11.721617701671814, 0.0], [11.821617701671814, 0.0], [11.921617701671813, 0.0], [12.021617701671813, 0.0], [12.121617701671813, 0.0], [12.221617701671812, 0.0], [12.321617701671812, 0.0], [12.421617701671812, 0.0], [12.521617701671811, 0.0], [12.621617701671811, 0.0], [12.72161770167181, 0.0], [12.82161770167181, 0.0], [12.92161770167181, 0.0], [13.02161770167181, 0.0], [13.12161770167181, 0.0], [13.221617701671809, 0.0], [13.321617701671808, 0.0], [13.421617701671808, 0.0], [13.521617701671808, 0.0], [13.621617701671807, 0.0], [13.721617701671807, 0.0], [13.821617701671807, 0.0], [13.921617701671806, 0.0], [14.021617701671806, 0.0], [14.121617701671806, 0.0], [14.221617701671805, 0.0], [14.321617701671805, 0.0], [14.421617701671805, 0.0], [14.521617701671804, 0.0], [14.621617701671804, 0.0], [14.721617701671804, 0.0], [14.816488606479052, 0.0], [14.89216506614469, 0.0], [14.94784152581033, 0.0], [14.98351798547597, 0.0], [14.99919444514161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517], "velocities": null}}, "time": 1740481171.3636272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667193519520267, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3636272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.3736272, "x": 6.665359000707424, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.3836272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23749031268323265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966994164724851, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3836272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.4036272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665266062556056, "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": 1740481171.4036272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.4236271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657954907743637, "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": 1740481171.4236271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.443627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655521234164562, "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": 1740481171.443627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.463627} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.665359000707424, 0.0], [2.8279199158699737, 0.0], [2.927919915869974, 0.0], [3.027919915869974, 0.0], [3.127919915869974, 0.0], [3.2279199158699736, 0.0], [3.3279199158699737, 0.0], [3.427919915869974, 0.0], [3.5279199158699734, 0.0], [3.6279199158699735, 0.0], [3.7279199158699736, 0.0], [3.8279199158699737, 0.0], [3.927919915869974, 0.0], [4.027919915869974, 0.0], [4.127919915869974, 0.0], [4.227919915869974, 0.0], [4.327919915869974, 0.0], [4.427919915869975, 0.0], [4.527919915869974, 0.0], [4.627919915869974, 0.0], [4.7279199158699745, 0.0], [4.827919915869975, 0.0], [4.927919915869975, 0.0], [5.027919915869974, 0.0], [5.127919915869975, 0.0], [5.227919915869975, 0.0], [5.327919915869975, 0.0], [5.427919915869975, 0.0], [5.527919915869975, 0.0], [5.627919915869976, 0.0], [5.727919915869975, 0.0], [5.827919915869975, 0.0], [5.927919915869976, 0.0], [6.027919915869976, 0.0], [6.127919915869976, 0.0], [6.227919915869975, 0.0], [6.327919915869976, 0.0], [6.4279199158699765, 0.0], [6.527919915869976, 0.0], [6.627919915869976, 0.0], [6.727919915869976, 0.0], [6.827919915869976, 0.0], [6.927919915869976, 0.0], [7.027919915869975, 0.0], [7.127919915869975, 0.0], [7.2279199158699745, 0.0], [7.327919915869974, 0.0], [7.427919915869974, 0.0], [7.527919915869973, 0.0], [7.627919915869973, 0.0], [7.727919915869973, 0.0], [7.827919915869972, 0.0], [7.927919915869972, 0.0], [8.027919915869973, 0.0], [8.12791991586997, 0.0], [8.227919915869972, 0.0], [8.32791991586997, 0.0], [8.427919915869971, 0.0], [8.527919915869969, 0.0], [8.62791991586997, 0.0], [8.727919915869968, 0.0], [8.82791991586997, 0.0], [8.927919915869968, 0.0], [9.027919915869969, 0.0], [9.127919915869967, 0.0], [9.227919915869968, 0.0], [9.327919915869966, 0.0], [9.427919915869968, 0.0], [9.527919915869965, 0.0], [9.627919915869967, 0.0], [9.727919915869965, 0.0], [9.827919915869966, 0.0], [9.927919915869964, 0.0], [10.027919915869965, 0.0], [10.127919915869963, 0.0], [10.227919915869965, 0.0], [10.327919915869963, 0.0], [10.427919915869964, 0.0], [10.527919915869962, 0.0], [10.627919915869963, 0.0], [10.727919915869961, 0.0], [10.82791991586996, 0.0], [10.92791991586996, 0.0], [11.02791991586996, 0.0], [11.12791991586996, 0.0], [11.22791991586996, 0.0], [11.327919915869959, 0.0], [11.427919915869959, 0.0], [11.527919915869958, 0.0], [11.627919915869958, 0.0], [11.727919915869958, 0.0], [11.827919915869957, 0.0], [11.927919915869957, 0.0], [12.027919915869957, 0.0], [12.127919915869956, 0.0], [12.227919915869956, 0.0], [12.327919915869956, 0.0], [12.427919915869955, 0.0], [12.527919915869955, 0.0], [12.627919915869954, 0.0], [12.727919915869954, 0.0], [12.827919915869954, 0.0], [12.927919915869953, 0.0], [13.027919915869953, 0.0], [13.127919915869953, 0.0], [13.227919915869952, 0.0], [13.327919915869952, 0.0], [13.427919915869952, 0.0], [13.527919915869951, 0.0], [13.62791991586995, 0.0], [13.72791991586995, 0.0], [13.82791991586995, 0.0], [13.92791991586995, 0.0], [14.02791991586995, 0.0], [14.127919915869949, 0.0], [14.227919915869949, 0.0], [14.327919915869948, 0.0], [14.427919915869948, 0.0], [14.527919915869948, 0.0], [14.627919915869947, 0.0], [14.727919915869947, 0.0], [14.821848402580766, 0.0], [14.896264419406778, 0.0], [14.950680436232789, 0.0], [14.985096453058798, 0.0], [14.99951246988481, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518], "velocities": null}}, "time": 1740481171.463627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23660142139492057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648230329460789, "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": 1740481171.463627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.483627, "x": 6.771617677236139, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.483627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443445743727258, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964535121918298, "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": 1740481171.483627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.503627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649274570158547, "gear": 1, "accelerator_pedal_position": 0.2443445743727258, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.503627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.523627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652993987771079, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.523627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.543627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656708251750213, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.543627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.563627} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.771617677236139, 0.0], [2.9340784883701176, 0.0], [3.0340784883701177, 0.0], [3.134078488370118, 0.0], [3.234078488370118, 0.0], [3.3340784883701176, 0.0], [3.4340784883701176, 0.0], [3.5340784883701177, 0.0], [3.6340784883701174, 0.0], [3.7340784883701175, 0.0], [3.8340784883701176, 0.0], [3.9340784883701176, 0.0], [4.034078488370118, 0.0], [4.134078488370118, 0.0], [4.234078488370118, 0.0], [4.3340784883701176, 0.0], [4.434078488370118, 0.0], [4.534078488370119, 0.0], [4.634078488370118, 0.0], [4.734078488370118, 0.0], [4.834078488370118, 0.0], [4.934078488370119, 0.0], [5.034078488370119, 0.0], [5.134078488370118, 0.0], [5.234078488370119, 0.0], [5.334078488370119, 0.0], [5.434078488370119, 0.0], [5.534078488370119, 0.0], [5.634078488370119, 0.0], [5.73407848837012, 0.0], [5.834078488370119, 0.0], [5.934078488370119, 0.0], [6.0340784883701195, 0.0], [6.13407848837012, 0.0], [6.23407848837012, 0.0], [6.334078488370119, 0.0], [6.43407848837012, 0.0], [6.53407848837012, 0.0], [6.63407848837012, 0.0], [6.73407848837012, 0.0], [6.83407848837012, 0.0], [6.93407848837012, 0.0], [7.0340784883701195, 0.0], [7.134078488370119, 0.0], [7.234078488370119, 0.0], [7.334078488370118, 0.0], [7.434078488370118, 0.0], [7.534078488370118, 0.0], [7.634078488370117, 0.0], [7.734078488370117, 0.0], [7.834078488370117, 0.0], [7.934078488370116, 0.0], [8.034078488370117, 0.0], [8.134078488370115, 0.0], [8.234078488370116, 0.0], [8.334078488370114, 0.0], [8.434078488370115, 0.0], [8.534078488370113, 0.0], [8.634078488370115, 0.0], [8.734078488370113, 0.0], [8.834078488370114, 0.0], [8.934078488370112, 0.0], [9.034078488370113, 0.0], [9.134078488370111, 0.0], [9.234078488370113, 0.0], [9.33407848837011, 0.0], [9.434078488370112, 0.0], [9.53407848837011, 0.0], [9.634078488370111, 0.0], [9.734078488370109, 0.0], [9.83407848837011, 0.0], [9.934078488370108, 0.0], [10.03407848837011, 0.0], [10.13407848837011, 0.0], [10.234078488370109, 0.0], [10.334078488370109, 0.0], [10.434078488370108, 0.0], [10.534078488370108, 0.0], [10.634078488370108, 0.0], [10.734078488370107, 0.0], [10.834078488370107, 0.0], [10.934078488370107, 0.0], [11.034078488370106, 0.0], [11.134078488370106, 0.0], [11.234078488370105, 0.0], [11.334078488370105, 0.0], [11.434078488370105, 0.0], [11.534078488370104, 0.0], [11.634078488370104, 0.0], [11.734078488370104, 0.0], [11.834078488370103, 0.0], [11.934078488370103, 0.0], [12.034078488370103, 0.0], [12.134078488370102, 0.0], [12.234078488370102, 0.0], [12.334078488370102, 0.0], [12.434078488370101, 0.0], [12.5340784883701, 0.0], [12.6340784883701, 0.0], [12.7340784883701, 0.0], [12.8340784883701, 0.0], [12.9340784883701, 0.0], [13.034078488370099, 0.0], [13.134078488370099, 0.0], [13.234078488370098, 0.0], [13.334078488370098, 0.0], [13.434078488370098, 0.0], [13.534078488370097, 0.0], [13.634078488370097, 0.0], [13.734078488370097, 0.0], [13.834078488370096, 0.0], [13.934078488370096, 0.0], [14.034078488370096, 0.0], [14.134078488370095, 0.0], [14.234078488370095, 0.0], [14.334078488370094, 0.0], [14.434078488370094, 0.0], [14.534078488370094, 0.0], [14.634078488370093, 0.0], [14.734078488370093, 0.0], [14.827009296163492, 0.0], [14.900193598489475, 0.0], [14.953377900815456, 0.0], [14.986562203141437, 0.0], [14.999746505467419, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518], "velocities": null}}, "time": 1740481171.563627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368528166838385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662269999068399, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.563627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.583627} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.3612564, "x": 15.0, "y": 4.104999999999956, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.583627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368528166838385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659538279880915, "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": 1740481171.583627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.593627, "x": 6.877816094627512, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.603627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24480181358689196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654080521075539, "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": 1740481171.603627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.623627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448851390131761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965856312812888, "gear": 1, "accelerator_pedal_position": 0.24480181358689196, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.623627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.643627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448851390131761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663143643789391, "gear": 1, "accelerator_pedal_position": 0.2448851390131761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.643627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.663627} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.877816094627512, 0.0], [3.0403302078997805, 0.0], [3.1403302078997806, 0.0], [3.2403302078997807, 0.0], [3.3403302078997807, 0.0], [3.4403302078997804, 0.0], [3.5403302078997805, 0.0], [3.6403302078997806, 0.0], [3.7403302078997807, 0.0], [3.8403302078997807, 0.0], [3.9403302078997804, 0.0], [4.04033020789978, 0.0], [4.140330207899781, 0.0], [4.240330207899781, 0.0], [4.340330207899781, 0.0], [4.44033020789978, 0.0], [4.540330207899781, 0.0], [4.6403302078997815, 0.0], [4.740330207899781, 0.0], [4.840330207899781, 0.0], [4.940330207899781, 0.0], [5.040330207899782, 0.0], [5.1403302078997815, 0.0], [5.240330207899782, 0.0], [5.340330207899782, 0.0], [5.440330207899782, 0.0], [5.540330207899782, 0.0], [5.640330207899782, 0.0], [5.740330207899782, 0.0], [5.8403302078997825, 0.0], [5.940330207899782, 0.0], [6.040330207899783, 0.0], [6.140330207899782, 0.0], [6.240330207899783, 0.0], [6.3403302078997825, 0.0], [6.440330207899783, 0.0], [6.540330207899783, 0.0], [6.640330207899783, 0.0], [6.740330207899783, 0.0], [6.840330207899783, 0.0], [6.940330207899783, 0.0], [7.040330207899783, 0.0], [7.140330207899782, 0.0], [7.240330207899782, 0.0], [7.340330207899782, 0.0], [7.440330207899781, 0.0], [7.540330207899781, 0.0], [7.640330207899781, 0.0], [7.74033020789978, 0.0], [7.84033020789978, 0.0], [7.9403302078997795, 0.0], [8.040330207899778, 0.0], [8.14033020789978, 0.0], [8.240330207899778, 0.0], [8.340330207899779, 0.0], [8.440330207899777, 0.0], [8.540330207899778, 0.0], [8.640330207899776, 0.0], [8.740330207899778, 0.0], [8.840330207899775, 0.0], [8.940330207899777, 0.0], [9.040330207899775, 0.0], [9.140330207899776, 0.0], [9.240330207899774, 0.0], [9.340330207899775, 0.0], [9.440330207899773, 0.0], [9.540330207899775, 0.0], [9.640330207899773, 0.0], [9.740330207899774, 0.0], [9.840330207899772, 0.0], [9.940330207899773, 0.0], [10.040330207899771, 0.0], [10.140330207899773, 0.0], [10.24033020789977, 0.0], [10.340330207899772, 0.0], [10.44033020789977, 0.0], [10.540330207899771, 0.0], [10.640330207899769, 0.0], [10.74033020789977, 0.0], [10.840330207899768, 0.0], [10.940330207899768, 0.0], [11.040330207899768, 0.0], [11.140330207899767, 0.0], [11.240330207899767, 0.0], [11.340330207899767, 0.0], [11.440330207899766, 0.0], [11.540330207899766, 0.0], [11.640330207899765, 0.0], [11.740330207899765, 0.0], [11.840330207899765, 0.0], [11.940330207899764, 0.0], [12.040330207899764, 0.0], [12.140330207899764, 0.0], [12.240330207899763, 0.0], [12.340330207899763, 0.0], [12.440330207899763, 0.0], [12.540330207899762, 0.0], [12.640330207899762, 0.0], [12.740330207899762, 0.0], [12.840330207899761, 0.0], [12.94033020789976, 0.0], [13.04033020789976, 0.0], [13.14033020789976, 0.0], [13.24033020789976, 0.0], [13.34033020789976, 0.0], [13.440330207899759, 0.0], [13.540330207899759, 0.0], [13.640330207899758, 0.0], [13.740330207899758, 0.0], [13.840330207899758, 0.0], [13.940330207899757, 0.0], [14.040330207899757, 0.0], [14.140330207899757, 0.0], [14.240330207899756, 0.0], [14.340330207899756, 0.0], [14.440330207899756, 0.0], [14.540330207899755, 0.0], [14.640330207899755, 0.0], [14.740330207899754, 0.0], [14.832170661440541, 0.0], [14.90410461986059, 0.0], [14.956038578280639, 0.0], [14.987972536700688, 0.0], [14.999906495120738, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518], "velocities": null}}, "time": 1740481171.663627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367217261372408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670002516159308, "gear": 1, "accelerator_pedal_position": 0.2448851390131761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.663627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.683627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367217261372408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667183504250378, "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": 1740481171.683627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.7036269, "x": 6.98410056895514, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7036269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24430473208399844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661551342789061, "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": 1740481171.7036269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7236269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24433922585084694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665402459707456, "gear": 1, "accelerator_pedal_position": 0.24430473208399844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7236269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7436268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24433922585084694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669291340865508, "gear": 1, "accelerator_pedal_position": 0.24433922585084694, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7436268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7636268} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.9841005689551396, 0.0], [3.1466362351835655, 0.0], [3.2466362351835656, 0.0], [3.3466362351835657, 0.0], [3.4466362351835658, 0.0], [3.5466362351835654, 0.0], [3.6466362351835655, 0.0], [3.7466362351835656, 0.0], [3.8466362351835657, 0.0], [3.9466362351835658, 0.0], [4.046636235183565, 0.0], [4.146636235183566, 0.0], [4.246636235183566, 0.0], [4.346636235183565, 0.0], [4.446636235183566, 0.0], [4.546636235183566, 0.0], [4.646636235183566, 0.0], [4.746636235183566, 0.0], [4.846636235183566, 0.0], [4.946636235183567, 0.0], [5.046636235183566, 0.0], [5.146636235183566, 0.0], [5.2466362351835665, 0.0], [5.346636235183567, 0.0], [5.446636235183567, 0.0], [5.546636235183566, 0.0], [5.646636235183567, 0.0], [5.746636235183567, 0.0], [5.846636235183567, 0.0], [5.946636235183567, 0.0], [6.046636235183567, 0.0], [6.146636235183568, 0.0], [6.246636235183567, 0.0], [6.346636235183567, 0.0], [6.4466362351835675, 0.0], [6.546636235183568, 0.0], [6.646636235183568, 0.0], [6.746636235183567, 0.0], [6.846636235183568, 0.0], [6.946636235183568, 0.0], [7.046636235183568, 0.0], [7.146636235183568, 0.0], [7.246636235183567, 0.0], [7.346636235183567, 0.0], [7.446636235183567, 0.0], [7.546636235183566, 0.0], [7.646636235183566, 0.0], [7.746636235183566, 0.0], [7.846636235183565, 0.0], [7.946636235183565, 0.0], [8.046636235183565, 0.0], [8.146636235183564, 0.0], [8.246636235183564, 0.0], [8.346636235183563, 0.0], [8.446636235183563, 0.0], [8.546636235183563, 0.0], [8.646636235183562, 0.0], [8.746636235183562, 0.0], [8.846636235183562, 0.0], [8.946636235183561, 0.0], [9.046636235183561, 0.0], [9.14663623518356, 0.0], [9.24663623518356, 0.0], [9.34663623518356, 0.0], [9.44663623518356, 0.0], [9.54663623518356, 0.0], [9.646636235183559, 0.0], [9.746636235183558, 0.0], [9.846636235183558, 0.0], [9.946636235183558, 0.0], [10.046636235183557, 0.0], [10.146636235183557, 0.0], [10.246636235183557, 0.0], [10.346636235183556, 0.0], [10.446636235183556, 0.0], [10.546636235183556, 0.0], [10.646636235183555, 0.0], [10.746636235183555, 0.0], [10.846636235183555, 0.0], [10.946636235183554, 0.0], [11.046636235183552, 0.0], [11.146636235183554, 0.0], [11.246636235183551, 0.0], [11.346636235183553, 0.0], [11.44663623518355, 0.0], [11.546636235183552, 0.0], [11.64663623518355, 0.0], [11.746636235183551, 0.0], [11.84663623518355, 0.0], [11.94663623518355, 0.0], [12.046636235183549, 0.0], [12.14663623518355, 0.0], [12.246636235183548, 0.0], [12.34663623518355, 0.0], [12.446636235183547, 0.0], [12.546636235183549, 0.0], [12.646636235183546, 0.0], [12.746636235183548, 0.0], [12.846636235183546, 0.0], [12.946636235183547, 0.0], [13.046636235183545, 0.0], [13.146636235183546, 0.0], [13.246636235183544, 0.0], [13.346636235183546, 0.0], [13.446636235183544, 0.0], [13.546636235183545, 0.0], [13.646636235183543, 0.0], [13.746636235183544, 0.0], [13.846636235183542, 0.0], [13.946636235183544, 0.0], [14.046636235183541, 0.0], [14.146636235183543, 0.0], [14.24663623518354, 0.0], [14.346636235183542, 0.0], [14.44663623518354, 0.0], [14.546636235183541, 0.0], [14.64663623518354, 0.0], [14.74663623518354, 0.0], [14.837297673233092, 0.0], [14.907970426196384, 0.0], [14.958643179159676, 0.0], [14.989315932122967, 0.0], [14.99998868508626, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519], "velocities": null}}, "time": 1740481171.7636268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675114556682429, "gear": 1, "accelerator_pedal_position": 0.24433922585084694, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7636268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7836268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672257769375088, "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": 1740481171.7836268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.8036268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666550136544296, "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": 1740481171.8036268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.8136268, "x": 7.090455373258246, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8236268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24409917981193316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660850415853046, "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": 1740481171.8236268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8436267} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.6929522, "x": 15.0, "y": 4.2699999999999525, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.8436267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24411480124617194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664445652982776, "gear": 1, "accelerator_pedal_position": 0.24409917981193316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.8436267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8636267} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.090455373258246, 0.0], [3.2530007016509486, 0.0], [3.3530007016509487, 0.0], [3.4530007016509487, 0.0], [3.553000701650949, 0.0], [3.6530007016509485, 0.0], [3.7530007016509486, 0.0], [3.8530007016509487, 0.0], [3.9530007016509487, 0.0], [4.053000701650949, 0.0], [4.1530007016509485, 0.0], [4.253000701650949, 0.0], [4.353000701650949, 0.0], [4.453000701650948, 0.0], [4.553000701650949, 0.0], [4.653000701650949, 0.0], [4.753000701650949, 0.0], [4.853000701650949, 0.0], [4.953000701650949, 0.0], [5.05300070165095, 0.0], [5.153000701650949, 0.0], [5.25300070165095, 0.0], [5.3530007016509495, 0.0], [5.45300070165095, 0.0], [5.55300070165095, 0.0], [5.65300070165095, 0.0], [5.75300070165095, 0.0], [5.85300070165095, 0.0], [5.95300070165095, 0.0], [6.053000701650951, 0.0], [6.15300070165095, 0.0], [6.253000701650951, 0.0], [6.35300070165095, 0.0], [6.453000701650951, 0.0], [6.553000701650951, 0.0], [6.653000701650951, 0.0], [6.753000701650951, 0.0], [6.853000701650951, 0.0], [6.953000701650951, 0.0], [7.0530007016509515, 0.0], [7.153000701650951, 0.0], [7.253000701650951, 0.0], [7.35300070165095, 0.0], [7.45300070165095, 0.0], [7.55300070165095, 0.0], [7.653000701650949, 0.0], [7.753000701650949, 0.0], [7.853000701650949, 0.0], [7.953000701650948, 0.0], [8.053000701650948, 0.0], [8.153000701650948, 0.0], [8.253000701650947, 0.0], [8.353000701650947, 0.0], [8.453000701650947, 0.0], [8.553000701650946, 0.0], [8.653000701650946, 0.0], [8.753000701650945, 0.0], [8.853000701650945, 0.0], [8.953000701650945, 0.0], [9.053000701650944, 0.0], [9.153000701650944, 0.0], [9.253000701650944, 0.0], [9.353000701650943, 0.0], [9.453000701650943, 0.0], [9.553000701650943, 0.0], [9.653000701650942, 0.0], [9.753000701650942, 0.0], [9.853000701650942, 0.0], [9.953000701650941, 0.0], [10.05300070165094, 0.0], [10.15300070165094, 0.0], [10.25300070165094, 0.0], [10.35300070165094, 0.0], [10.45300070165094, 0.0], [10.553000701650939, 0.0], [10.653000701650939, 0.0], [10.753000701650938, 0.0], [10.853000701650938, 0.0], [10.953000701650938, 0.0], [11.053000701650937, 0.0], [11.153000701650937, 0.0], [11.253000701650937, 0.0], [11.353000701650936, 0.0], [11.453000701650936, 0.0], [11.553000701650936, 0.0], [11.653000701650935, 0.0], [11.753000701650935, 0.0], [11.853000701650934, 0.0], [11.953000701650934, 0.0], [12.053000701650934, 0.0], [12.153000701650933, 0.0], [12.253000701650933, 0.0], [12.353000701650933, 0.0], [12.453000701650932, 0.0], [12.553000701650932, 0.0], [12.653000701650932, 0.0], [12.753000701650931, 0.0], [12.853000701650931, 0.0], [12.95300070165093, 0.0], [13.05300070165093, 0.0], [13.15300070165093, 0.0], [13.25300070165093, 0.0], [13.35300070165093, 0.0], [13.453000701650929, 0.0], [13.553000701650928, 0.0], [13.653000701650928, 0.0], [13.753000701650928, 0.0], [13.853000701650927, 0.0], [13.953000701650927, 0.0], [14.053000701650927, 0.0], [14.153000701650926, 0.0], [14.253000701650926, 0.0], [14.353000701650926, 0.0], [14.453000701650925, 0.0], [14.553000701650925, 0.0], [14.653000701650924, 0.0], [14.752991697440526, 0.0], [14.842391557110341, 0.0], [14.911791416780156, 0.0], [14.961191276449972, 0.0], [14.990591136119786, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552], "velocities": null}}, "time": 1740481171.8636267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669858437025295, "gear": 1, "accelerator_pedal_position": 0.24411480124617194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.8636267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8836267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666989731964188, "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": 1740481171.8836267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.9036267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661258287507418, "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": 1740481171.9036267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.9236267, "x": 7.196761948882999, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9236267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24421960896673525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655534786987786, "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": 1740481171.9236267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9436266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416023072130294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659287875229806, "gear": 1, "accelerator_pedal_position": 0.24421960896673525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.9436266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9636266} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.1967619488829992, 0.0], [3.359270223182041, 0.0], [3.459270223182041, 0.0], [3.559270223182041, 0.0], [3.6592702231820406, 0.0], [3.7592702231820407, 0.0], [3.859270223182041, 0.0], [3.959270223182041, 0.0], [4.059270223182041, 0.0], [4.159270223182041, 0.0], [4.259270223182041, 0.0], [4.35927022318204, 0.0], [4.459270223182041, 0.0], [4.5592702231820414, 0.0], [4.659270223182041, 0.0], [4.759270223182041, 0.0], [4.859270223182041, 0.0], [4.959270223182042, 0.0], [5.0592702231820414, 0.0], [5.159270223182041, 0.0], [5.259270223182042, 0.0], [5.359270223182041, 0.0], [5.459270223182042, 0.0], [5.5592702231820414, 0.0], [5.659270223182042, 0.0], [5.759270223182042, 0.0], [5.859270223182042, 0.0], [5.959270223182042, 0.0], [6.059270223182042, 0.0], [6.159270223182042, 0.0], [6.2592702231820425, 0.0], [6.359270223182042, 0.0], [6.459270223182043, 0.0], [6.559270223182042, 0.0], [6.659270223182043, 0.0], [6.7592702231820425, 0.0], [6.859270223182043, 0.0], [6.959270223182043, 0.0], [7.059270223182043, 0.0], [7.159270223182043, 0.0], [7.259270223182043, 0.0], [7.359270223182043, 0.0], [7.459270223182043, 0.0], [7.559270223182042, 0.0], [7.659270223182042, 0.0], [7.759270223182042, 0.0], [7.859270223182041, 0.0], [7.959270223182041, 0.0], [8.05927022318204, 0.0], [8.159270223182041, 0.0], [8.259270223182039, 0.0], [8.35927022318204, 0.0], [8.459270223182038, 0.0], [8.55927022318204, 0.0], [8.659270223182038, 0.0], [8.759270223182039, 0.0], [8.859270223182037, 0.0], [8.959270223182038, 0.0], [9.059270223182036, 0.0], [9.159270223182038, 0.0], [9.259270223182035, 0.0], [9.359270223182037, 0.0], [9.459270223182035, 0.0], [9.559270223182036, 0.0], [9.659270223182034, 0.0], [9.759270223182035, 0.0], [9.859270223182033, 0.0], [9.959270223182035, 0.0], [10.059270223182033, 0.0], [10.159270223182034, 0.0], [10.259270223182032, 0.0], [10.359270223182033, 0.0], [10.459270223182031, 0.0], [10.559270223182033, 0.0], [10.65927022318203, 0.0], [10.759270223182032, 0.0], [10.85927022318203, 0.0], [10.959270223182031, 0.0], [11.059270223182029, 0.0], [11.15927022318203, 0.0], [11.25927022318203, 0.0], [11.35927022318203, 0.0], [11.45927022318203, 0.0], [11.559270223182029, 0.0], [11.659270223182029, 0.0], [11.759270223182028, 0.0], [11.859270223182028, 0.0], [11.959270223182028, 0.0], [12.059270223182027, 0.0], [12.159270223182027, 0.0], [12.259270223182027, 0.0], [12.359270223182026, 0.0], [12.459270223182026, 0.0], [12.559270223182025, 0.0], [12.659270223182025, 0.0], [12.759270223182025, 0.0], [12.859270223182024, 0.0], [12.959270223182024, 0.0], [13.059270223182024, 0.0], [13.159270223182023, 0.0], [13.259270223182023, 0.0], [13.359270223182023, 0.0], [13.459270223182022, 0.0], [13.559270223182022, 0.0], [13.659270223182022, 0.0], [13.759270223182021, 0.0], [13.85927022318202, 0.0], [13.95927022318202, 0.0], [14.05927022318202, 0.0], [14.15927022318202, 0.0], [14.25927022318202, 0.0], [14.359270223182019, 0.0], [14.459270223182019, 0.0], [14.559270223182018, 0.0], [14.659270223182018, 0.0], [14.759184286144173, 0.0], [14.84733024150777, 0.0], [14.915476196871365, 0.0], [14.963622152234962, 0.0], [14.991768107598558, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552], "velocities": null}}, "time": 1740481171.9636266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660156595999737, "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": 1740481171.9636266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9836266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657353571330491, "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": 1740481171.9836266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481172.0036266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651753349448925, "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": 1740481172.0036266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481172.0236266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646160887491395, "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": 1740481172.0236266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.0336266, "x": 7.302977203492276, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0436265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447701443379183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640576173454803, "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": 1740481172.0436265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0636265} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.3029772034922757, 0.0], [3.4654286083757446, 0.0], [3.5654286083757443, 0.0], [3.6654286083757444, 0.0], [3.7654286083757444, 0.0], [3.8654286083757445, 0.0], [3.9654286083757446, 0.0], [4.065428608375744, 0.0], [4.165428608375745, 0.0], [4.2654286083757444, 0.0], [4.365428608375744, 0.0], [4.465428608375744, 0.0], [4.565428608375744, 0.0], [4.665428608375745, 0.0], [4.7654286083757444, 0.0], [4.865428608375744, 0.0], [4.965428608375745, 0.0], [5.065428608375745, 0.0], [5.165428608375745, 0.0], [5.2654286083757444, 0.0], [5.365428608375746, 0.0], [5.4654286083757455, 0.0], [5.565428608375745, 0.0], [5.665428608375746, 0.0], [5.765428608375746, 0.0], [5.865428608375746, 0.0], [5.9654286083757455, 0.0], [6.065428608375746, 0.0], [6.165428608375747, 0.0], [6.265428608375746, 0.0], [6.365428608375746, 0.0], [6.465428608375746, 0.0], [6.565428608375747, 0.0], [6.665428608375747, 0.0], [6.765428608375746, 0.0], [6.865428608375747, 0.0], [6.965428608375747, 0.0], [7.065428608375747, 0.0], [7.165428608375747, 0.0], [7.265428608375747, 0.0], [7.365428608375747, 0.0], [7.465428608375746, 0.0], [7.565428608375746, 0.0], [7.665428608375746, 0.0], [7.765428608375745, 0.0], [7.865428608375745, 0.0], [7.965428608375745, 0.0], [8.065428608375743, 0.0], [8.165428608375745, 0.0], [8.265428608375743, 0.0], [8.365428608375744, 0.0], [8.465428608375742, 0.0], [8.565428608375743, 0.0], [8.665428608375741, 0.0], [8.765428608375743, 0.0], [8.86542860837574, 0.0], [8.965428608375742, 0.0], [9.06542860837574, 0.0], [9.165428608375741, 0.0], [9.26542860837574, 0.0], [9.36542860837574, 0.0], [9.465428608375738, 0.0], [9.56542860837574, 0.0], [9.665428608375738, 0.0], [9.76542860837574, 0.0], [9.865428608375737, 0.0], [9.965428608375738, 0.0], [10.065428608375736, 0.0], [10.165428608375738, 0.0], [10.265428608375736, 0.0], [10.365428608375737, 0.0], [10.465428608375735, 0.0], [10.565428608375736, 0.0], [10.665428608375734, 0.0], [10.765428608375736, 0.0], [10.865428608375733, 0.0], [10.965428608375735, 0.0], [11.065428608375733, 0.0], [11.165428608375734, 0.0], [11.265428608375732, 0.0], [11.365428608375733, 0.0], [11.465428608375733, 0.0], [11.565428608375733, 0.0], [11.665428608375732, 0.0], [11.765428608375732, 0.0], [11.865428608375732, 0.0], [11.965428608375731, 0.0], [12.065428608375731, 0.0], [12.16542860837573, 0.0], [12.26542860837573, 0.0], [12.36542860837573, 0.0], [12.46542860837573, 0.0], [12.56542860837573, 0.0], [12.665428608375729, 0.0], [12.765428608375728, 0.0], [12.865428608375728, 0.0], [12.965428608375728, 0.0], [13.065428608375727, 0.0], [13.165428608375727, 0.0], [13.265428608375727, 0.0], [13.365428608375726, 0.0], [13.465428608375726, 0.0], [13.565428608375726, 0.0], [13.665428608375725, 0.0], [13.765428608375725, 0.0], [13.865428608375725, 0.0], [13.965428608375724, 0.0], [14.065428608375724, 0.0], [14.165428608375723, 0.0], [14.265428608375723, 0.0], [14.365428608375723, 0.0], [14.465428608375722, 0.0], [14.565428608375722, 0.0], [14.665428608375722, 0.0], [14.76519056641931, 0.0], [14.852104844744165, 0.0], [14.91901912306902, 0.0], [14.965933401393876, 0.0], [14.992847679718732, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552], "velocities": null}}, "time": 1740481172.0636265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647266471053665, "gear": 1, "accelerator_pedal_position": 0.2447701443379183, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.0636265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0836265} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.913456, "x": 15.0, "y": 4.37999999999995, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.0836265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644559227177874, "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": 1740481172.0836265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.1036265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639150365676138, "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": 1740481172.1036265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.1236265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633748996205559, "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": 1740481172.1236265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.1436265, "x": 7.409023071746164, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1436265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2455325200171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628355107222036, "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": 1740481172.1436265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1636264} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.409023071746164, 0.0], [3.5714015884228565, 0.0], [3.6714015884228566, 0.0], [3.771401588422856, 0.0], [3.8714015884228563, 0.0], [3.9714015884228564, 0.0], [4.071401588422856, 0.0], [4.171401588422857, 0.0], [4.271401588422856, 0.0], [4.371401588422856, 0.0], [4.471401588422856, 0.0], [4.571401588422856, 0.0], [4.671401588422857, 0.0], [4.771401588422856, 0.0], [4.871401588422857, 0.0], [4.971401588422856, 0.0], [5.071401588422857, 0.0], [5.171401588422857, 0.0], [5.271401588422857, 0.0], [5.371401588422857, 0.0], [5.471401588422857, 0.0], [5.571401588422857, 0.0], [5.671401588422857, 0.0], [5.771401588422857, 0.0], [5.871401588422858, 0.0], [5.971401588422857, 0.0], [6.071401588422857, 0.0], [6.1714015884228575, 0.0], [6.271401588422858, 0.0], [6.371401588422858, 0.0], [6.471401588422857, 0.0], [6.571401588422858, 0.0], [6.671401588422858, 0.0], [6.771401588422858, 0.0], [6.871401588422858, 0.0], [6.971401588422858, 0.0], [7.071401588422859, 0.0], [7.171401588422858, 0.0], [7.271401588422858, 0.0], [7.3714015884228585, 0.0], [7.471401588422859, 0.0], [7.571401588422859, 0.0], [7.671401588422858, 0.0], [7.771401588422858, 0.0], [7.871401588422858, 0.0], [7.971401588422857, 0.0], [8.071401588422857, 0.0], [8.171401588422857, 0.0], [8.271401588422856, 0.0], [8.371401588422856, 0.0], [8.471401588422856, 0.0], [8.571401588422855, 0.0], [8.671401588422855, 0.0], [8.771401588422854, 0.0], [8.871401588422854, 0.0], [8.971401588422854, 0.0], [9.071401588422853, 0.0], [9.171401588422853, 0.0], [9.271401588422853, 0.0], [9.371401588422852, 0.0], [9.471401588422852, 0.0], [9.571401588422852, 0.0], [9.671401588422851, 0.0], [9.771401588422851, 0.0], [9.87140158842285, 0.0], [9.97140158842285, 0.0], [10.07140158842285, 0.0], [10.17140158842285, 0.0], [10.27140158842285, 0.0], [10.371401588422849, 0.0], [10.471401588422848, 0.0], [10.571401588422848, 0.0], [10.671401588422848, 0.0], [10.771401588422847, 0.0], [10.871401588422847, 0.0], [10.971401588422847, 0.0], [11.071401588422846, 0.0], [11.171401588422846, 0.0], [11.271401588422846, 0.0], [11.371401588422845, 0.0], [11.471401588422845, 0.0], [11.571401588422844, 0.0], [11.671401588422844, 0.0], [11.771401588422844, 0.0], [11.871401588422843, 0.0], [11.971401588422843, 0.0], [12.071401588422843, 0.0], [12.171401588422842, 0.0], [12.271401588422842, 0.0], [12.371401588422842, 0.0], [12.471401588422841, 0.0], [12.571401588422841, 0.0], [12.67140158842284, 0.0], [12.77140158842284, 0.0], [12.87140158842284, 0.0], [12.97140158842284, 0.0], [13.07140158842284, 0.0], [13.171401588422839, 0.0], [13.271401588422838, 0.0], [13.371401588422838, 0.0], [13.471401588422838, 0.0], [13.571401588422837, 0.0], [13.671401588422837, 0.0], [13.771401588422837, 0.0], [13.871401588422836, 0.0], [13.971401588422836, 0.0], [14.071401588422836, 0.0], [14.171401588422835, 0.0], [14.271401588422835, 0.0], [14.371401588422835, 0.0], [14.471401588422834, 0.0], [14.571401588422834, 0.0], [14.671401588422833, 0.0], [14.770943560435812, 0.0], [14.856663242751246, 0.0], [14.92238292506668, 0.0], [14.968102607382113, 0.0], [14.993822289697546, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552], "velocities": null}}, "time": 1740481172.1636264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963649924959213, "gear": 1, "accelerator_pedal_position": 0.2455325200171985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.1636264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1836264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633904955479216, "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": 1740481172.1836264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2036264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628721757108132, "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": 1740481172.2036264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2236264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620960413517221, "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": 1740481172.2236264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2436264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618376881207433, "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": 1740481172.2436264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.2536263, "x": 7.514935739273505, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.2636263} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.514935739273505, 0.0], [3.6772509662843778, 0.0], [3.7772509662843774, 0.0], [3.8772509662843775, 0.0], [3.9772509662843776, 0.0], [4.077250966284377, 0.0], [4.177250966284378, 0.0], [4.277250966284377, 0.0], [4.377250966284377, 0.0], [4.477250966284378, 0.0], [4.577250966284377, 0.0], [4.677250966284378, 0.0], [4.777250966284377, 0.0], [4.877250966284377, 0.0], [4.977250966284378, 0.0], [5.077250966284378, 0.0], [5.177250966284378, 0.0], [5.277250966284377, 0.0], [5.377250966284378, 0.0], [5.4772509662843785, 0.0], [5.577250966284378, 0.0], [5.677250966284379, 0.0], [5.777250966284379, 0.0], [5.877250966284379, 0.0], [5.9772509662843785, 0.0], [6.077250966284379, 0.0], [6.1772509662843795, 0.0], [6.277250966284379, 0.0], [6.377250966284379, 0.0], [6.477250966284379, 0.0], [6.57725096628438, 0.0], [6.6772509662843795, 0.0], [6.777250966284379, 0.0], [6.87725096628438, 0.0], [6.97725096628438, 0.0], [7.07725096628438, 0.0], [7.1772509662843795, 0.0], [7.27725096628438, 0.0], [7.377250966284381, 0.0], [7.47725096628438, 0.0], [7.57725096628438, 0.0], [7.6772509662843795, 0.0], [7.777250966284379, 0.0], [7.877250966284379, 0.0], [7.9772509662843785, 0.0], [8.077250966284378, 0.0], [8.177250966284378, 0.0], [8.277250966284377, 0.0], [8.377250966284377, 0.0], [8.477250966284377, 0.0], [8.577250966284376, 0.0], [8.677250966284376, 0.0], [8.777250966284376, 0.0], [8.877250966284375, 0.0], [8.977250966284375, 0.0], [9.077250966284375, 0.0], [9.177250966284374, 0.0], [9.277250966284374, 0.0], [9.377250966284373, 0.0], [9.477250966284373, 0.0], [9.577250966284373, 0.0], [9.677250966284372, 0.0], [9.777250966284372, 0.0], [9.877250966284372, 0.0], [9.977250966284371, 0.0], [10.077250966284371, 0.0], [10.17725096628437, 0.0], [10.27725096628437, 0.0], [10.37725096628437, 0.0], [10.47725096628437, 0.0], [10.57725096628437, 0.0], [10.677250966284369, 0.0], [10.777250966284369, 0.0], [10.877250966284368, 0.0], [10.977250966284368, 0.0], [11.077250966284367, 0.0], [11.177250966284367, 0.0], [11.277250966284367, 0.0], [11.377250966284366, 0.0], [11.477250966284366, 0.0], [11.577250966284364, 0.0], [11.677250966284364, 0.0], [11.777250966284363, 0.0], [11.877250966284363, 0.0], [11.977250966284362, 0.0], [12.077250966284362, 0.0], [12.177250966284362, 0.0], [12.277250966284361, 0.0], [12.377250966284361, 0.0], [12.47725096628436, 0.0], [12.57725096628436, 0.0], [12.67725096628436, 0.0], [12.77725096628436, 0.0], [12.87725096628436, 0.0], [12.977250966284359, 0.0], [13.077250966284359, 0.0], [13.177250966284358, 0.0], [13.277250966284358, 0.0], [13.377250966284358, 0.0], [13.477250966284357, 0.0], [13.577250966284357, 0.0], [13.677250966284356, 0.0], [13.777250966284356, 0.0], [13.877250966284356, 0.0], [13.977250966284355, 0.0], [14.077250966284355, 0.0], [14.177250966284355, 0.0], [14.277250966284354, 0.0], [14.377250966284354, 0.0], [14.477250966284354, 0.0], [14.577250966284353, 0.0], [14.677250966284353, 0.0], [14.776508351120922, 0.0], [14.86105815786405, 0.0], [14.925607964607181, 0.0], [14.97015777135031, 0.0], [14.99470757809344, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552], "velocities": null}}, "time": 1740481172.2636263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24688829511344537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961678961947166, "gear": 1, "accelerator_pedal_position": 0.24688829511344537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.2636263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.2836263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620361582681975, "gear": 1, "accelerator_pedal_position": 0.24688829511344537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.2836263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3036263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627419170399103, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3036263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3236263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634466986557209, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3236263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3436263} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.1312976, "x": 15.0, "y": 4.489999999999948, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.3436263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964150504269929, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3436263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.3636262, "x": 7.620843135540897, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.3636262} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.6208431355408974, 0.0], [3.7833189263543843, 0.0], [3.8833189263543844, 0.0], [3.9833189263543844, 0.0], [4.0833189263543845, 0.0], [4.183318926354384, 0.0], [4.283318926354385, 0.0], [4.383318926354384, 0.0], [4.483318926354384, 0.0], [4.5833189263543845, 0.0], [4.683318926354384, 0.0], [4.783318926354385, 0.0], [4.883318926354384, 0.0], [4.983318926354384, 0.0], [5.0833189263543845, 0.0], [5.183318926354385, 0.0], [5.283318926354385, 0.0], [5.383318926354384, 0.0], [5.483318926354385, 0.0], [5.583318926354385, 0.0], [5.683318926354385, 0.0], [5.783318926354386, 0.0], [5.883318926354385, 0.0], [5.983318926354386, 0.0], [6.083318926354385, 0.0], [6.183318926354386, 0.0], [6.283318926354386, 0.0], [6.383318926354386, 0.0], [6.483318926354386, 0.0], [6.583318926354386, 0.0], [6.683318926354386, 0.0], [6.7833189263543865, 0.0], [6.883318926354386, 0.0], [6.983318926354387, 0.0], [7.083318926354386, 0.0], [7.183318926354387, 0.0], [7.2833189263543865, 0.0], [7.383318926354387, 0.0], [7.483318926354387, 0.0], [7.583318926354387, 0.0], [7.683318926354387, 0.0], [7.7833189263543865, 0.0], [7.883318926354386, 0.0], [7.983318926354386, 0.0], [8.083318926354385, 0.0], [8.183318926354385, 0.0], [8.283318926354385, 0.0], [8.383318926354384, 0.0], [8.483318926354384, 0.0], [8.583318926354384, 0.0], [8.683318926354383, 0.0], [8.783318926354383, 0.0], [8.883318926354383, 0.0], [8.983318926354382, 0.0], [9.083318926354382, 0.0], [9.183318926354382, 0.0], [9.283318926354381, 0.0], [9.38331892635438, 0.0], [9.48331892635438, 0.0], [9.58331892635438, 0.0], [9.68331892635438, 0.0], [9.78331892635438, 0.0], [9.883318926354379, 0.0], [9.983318926354379, 0.0], [10.083318926354378, 0.0], [10.183318926354378, 0.0], [10.283318926354378, 0.0], [10.383318926354377, 0.0], [10.483318926354377, 0.0], [10.583318926354377, 0.0], [10.683318926354376, 0.0], [10.783318926354376, 0.0], [10.883318926354375, 0.0], [10.983318926354375, 0.0], [11.083318926354375, 0.0], [11.183318926354374, 0.0], [11.283318926354374, 0.0], [11.383318926354374, 0.0], [11.483318926354373, 0.0], [11.583318926354373, 0.0], [11.683318926354373, 0.0], [11.783318926354372, 0.0], [11.883318926354372, 0.0], [11.983318926354372, 0.0], [12.083318926354371, 0.0], [12.18331892635437, 0.0], [12.28331892635437, 0.0], [12.38331892635437, 0.0], [12.48331892635437, 0.0], [12.58331892635437, 0.0], [12.683318926354369, 0.0], [12.783318926354369, 0.0], [12.883318926354368, 0.0], [12.983318926354368, 0.0], [13.083318926354368, 0.0], [13.183318926354367, 0.0], [13.283318926354367, 0.0], [13.383318926354367, 0.0], [13.483318926354366, 0.0], [13.583318926354366, 0.0], [13.683318926354366, 0.0], [13.783318926354365, 0.0], [13.883318926354365, 0.0], [13.983318926354364, 0.0], [14.083318926354364, 0.0], [14.183318926354364, 0.0], [14.283318926354363, 0.0], [14.383318926354363, 0.0], [14.483318926354363, 0.0], [14.583318926354362, 0.0], [14.683318926354362, 0.0], [14.782208775500955, 0.0], [14.865544990230081, 0.0], [14.92888120495921, 0.0], [14.972217419688336, 0.0], [14.995553634417465, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521], "velocities": null}}, "time": 1740481172.3636262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24471886014937735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648533350360611, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3636262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.3836262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652919987800211, "gear": 1, "accelerator_pedal_position": 0.24471886014937735, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3836262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4036262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657508709072564, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4036262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4236262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662091071414193, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4236262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4436262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666667082797507, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4436262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4636261} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.6208431355408974, 0.0], [3.7833189263543843, 0.0], [3.8833189263543844, 0.0], [3.9833189263543844, 0.0], [4.0833189263543845, 0.0], [4.183318926354384, 0.0], [4.283318926354385, 0.0], [4.383318926354384, 0.0], [4.483318926354384, 0.0], [4.5833189263543845, 0.0], [4.683318926354384, 0.0], [4.783318926354385, 0.0], [4.883318926354384, 0.0], [4.983318926354384, 0.0], [5.0833189263543845, 0.0], [5.183318926354385, 0.0], [5.283318926354385, 0.0], [5.383318926354384, 0.0], [5.483318926354385, 0.0], [5.583318926354385, 0.0], [5.683318926354385, 0.0], [5.783318926354386, 0.0], [5.883318926354385, 0.0], [5.983318926354386, 0.0], [6.083318926354385, 0.0], [6.183318926354386, 0.0], [6.283318926354386, 0.0], [6.383318926354386, 0.0], [6.483318926354386, 0.0], [6.583318926354386, 0.0], [6.683318926354386, 0.0], [6.7833189263543865, 0.0], [6.883318926354386, 0.0], [6.983318926354387, 0.0], [7.083318926354386, 0.0], [7.183318926354387, 0.0], [7.2833189263543865, 0.0], [7.383318926354387, 0.0], [7.483318926354387, 0.0], [7.583318926354387, 0.0], [7.683318926354387, 0.0], [7.7833189263543865, 0.0], [7.883318926354386, 0.0], [7.983318926354386, 0.0], [8.083318926354385, 0.0], [8.183318926354385, 0.0], [8.283318926354385, 0.0], [8.383318926354384, 0.0], [8.483318926354384, 0.0], [8.583318926354384, 0.0], [8.683318926354383, 0.0], [8.783318926354383, 0.0], [8.883318926354383, 0.0], [8.983318926354382, 0.0], [9.083318926354382, 0.0], [9.183318926354382, 0.0], [9.283318926354381, 0.0], [9.38331892635438, 0.0], [9.48331892635438, 0.0], [9.58331892635438, 0.0], [9.68331892635438, 0.0], [9.78331892635438, 0.0], [9.883318926354379, 0.0], [9.983318926354379, 0.0], [10.083318926354378, 0.0], [10.183318926354378, 0.0], [10.283318926354378, 0.0], [10.383318926354377, 0.0], [10.483318926354377, 0.0], [10.583318926354377, 0.0], [10.683318926354376, 0.0], [10.783318926354376, 0.0], [10.883318926354375, 0.0], [10.983318926354375, 0.0], [11.083318926354375, 0.0], [11.183318926354374, 0.0], [11.283318926354374, 0.0], [11.383318926354374, 0.0], [11.483318926354373, 0.0], [11.583318926354373, 0.0], [11.683318926354373, 0.0], [11.783318926354372, 0.0], [11.883318926354372, 0.0], [11.983318926354372, 0.0], [12.083318926354371, 0.0], [12.18331892635437, 0.0], [12.28331892635437, 0.0], [12.38331892635437, 0.0], [12.48331892635437, 0.0], [12.58331892635437, 0.0], [12.683318926354369, 0.0], [12.783318926354369, 0.0], [12.883318926354368, 0.0], [12.983318926354368, 0.0], [13.083318926354368, 0.0], [13.183318926354367, 0.0], [13.283318926354367, 0.0], [13.383318926354367, 0.0], [13.483318926354366, 0.0], [13.583318926354366, 0.0], [13.683318926354366, 0.0], [13.783318926354365, 0.0], [13.883318926354365, 0.0], [13.983318926354364, 0.0], [14.083318926354364, 0.0], [14.183318926354364, 0.0], [14.283318926354363, 0.0], [14.383318926354363, 0.0], [14.483318926354363, 0.0], [14.583318926354362, 0.0], [14.683318926354362, 0.0], [14.782208775500955, 0.0], [14.865544990230081, 0.0], [14.92888120495921, 0.0], [14.972217419688336, 0.0], [14.995553634417465, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521], "velocities": null}}, "time": 1740481172.4636261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673519209246686, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4636261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.4736261, "x": 7.72710116833111, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.4836261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23740874420968505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675800084541042, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4836261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.503626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671014452547584, "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": 1740481172.503626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.523626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966600422113699, "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": 1740481172.523626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.543626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966100093495708, "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": 1740481172.543626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.563626} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.72710116833111, 0.0], [3.889689886471783, 0.0], [3.9896898864717825, 0.0], [4.089689886471783, 0.0], [4.189689886471783, 0.0], [4.289689886471782, 0.0], [4.389689886471783, 0.0], [4.4896898864717825, 0.0], [4.589689886471783, 0.0], [4.689689886471783, 0.0], [4.789689886471782, 0.0], [4.889689886471783, 0.0], [4.9896898864717825, 0.0], [5.089689886471783, 0.0], [5.189689886471783, 0.0], [5.289689886471783, 0.0], [5.389689886471783, 0.0], [5.489689886471783, 0.0], [5.589689886471783, 0.0], [5.6896898864717835, 0.0], [5.789689886471783, 0.0], [5.889689886471784, 0.0], [5.989689886471783, 0.0], [6.089689886471784, 0.0], [6.1896898864717835, 0.0], [6.289689886471784, 0.0], [6.389689886471784, 0.0], [6.489689886471784, 0.0], [6.589689886471784, 0.0], [6.689689886471784, 0.0], [6.789689886471784, 0.0], [6.889689886471785, 0.0], [6.989689886471784, 0.0], [7.089689886471785, 0.0], [7.189689886471784, 0.0], [7.289689886471785, 0.0], [7.389689886471785, 0.0], [7.489689886471785, 0.0], [7.589689886471785, 0.0], [7.689689886471785, 0.0], [7.789689886471785, 0.0], [7.889689886471785, 0.0], [7.989689886471784, 0.0], [8.089689886471785, 0.0], [8.189689886471783, 0.0], [8.289689886471784, 0.0], [8.389689886471782, 0.0], [8.489689886471783, 0.0], [8.589689886471781, 0.0], [8.689689886471783, 0.0], [8.78968988647178, 0.0], [8.889689886471782, 0.0], [8.98968988647178, 0.0], [9.089689886471781, 0.0], [9.189689886471779, 0.0], [9.28968988647178, 0.0], [9.389689886471778, 0.0], [9.48968988647178, 0.0], [9.589689886471778, 0.0], [9.689689886471779, 0.0], [9.789689886471777, 0.0], [9.889689886471778, 0.0], [9.989689886471776, 0.0], [10.089689886471778, 0.0], [10.189689886471776, 0.0], [10.289689886471777, 0.0], [10.389689886471775, 0.0], [10.489689886471776, 0.0], [10.589689886471774, 0.0], [10.689689886471776, 0.0], [10.789689886471773, 0.0], [10.889689886471775, 0.0], [10.989689886471773, 0.0], [11.089689886471774, 0.0], [11.189689886471772, 0.0], [11.289689886471773, 0.0], [11.389689886471771, 0.0], [11.489689886471773, 0.0], [11.58968988647177, 0.0], [11.689689886471772, 0.0], [11.789689886471772, 0.0], [11.88968988647177, 0.0], [11.989689886471771, 0.0], [12.089689886471769, 0.0], [12.18968988647177, 0.0], [12.289689886471768, 0.0], [12.38968988647177, 0.0], [12.489689886471767, 0.0], [12.589689886471769, 0.0], [12.689689886471767, 0.0], [12.789689886471768, 0.0], [12.889689886471766, 0.0], [12.989689886471767, 0.0], [13.089689886471765, 0.0], [13.189689886471767, 0.0], [13.289689886471765, 0.0], [13.389689886471766, 0.0], [13.489689886471764, 0.0], [13.589689886471765, 0.0], [13.689689886471763, 0.0], [13.789689886471765, 0.0], [13.889689886471762, 0.0], [13.989689886471764, 0.0], [14.089689886471762, 0.0], [14.189689886471763, 0.0], [14.289689886471761, 0.0], [14.389689886471762, 0.0], [14.48968988647176, 0.0], [14.589689886471762, 0.0], [14.68968988647176, 0.0], [14.78811459938362, 0.0], [14.870176622089268, 0.0], [14.932238644794914, 0.0], [14.974300667500563, 0.0], [14.99636269020621, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521], "velocities": null}}, "time": 1740481172.563626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365274516031902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656004583379342, "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": 1740481172.563626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.583626, "x": 7.8334215041811595, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.583626} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.3513753, "x": 15.0, "y": 4.5999999999999455, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.583626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403384021874364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650145156071125, "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": 1740481172.583626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.603626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965367358209814, "gear": 1, "accelerator_pedal_position": 0.24403384021874364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.603626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.623626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656984701072164, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.623626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.643626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660291231610603, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.643626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.663626} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.8334215041811595, 0.0], [3.995904830954568, 0.0], [4.095904830954568, 0.0], [4.195904830954568, 0.0], [4.2959048309545675, 0.0], [4.395904830954568, 0.0], [4.495904830954568, 0.0], [4.595904830954568, 0.0], [4.695904830954568, 0.0], [4.7959048309545675, 0.0], [4.895904830954568, 0.0], [4.995904830954568, 0.0], [5.095904830954568, 0.0], [5.195904830954568, 0.0], [5.295904830954568, 0.0], [5.395904830954568, 0.0], [5.495904830954569, 0.0], [5.595904830954568, 0.0], [5.695904830954569, 0.0], [5.795904830954568, 0.0], [5.895904830954569, 0.0], [5.995904830954569, 0.0], [6.095904830954569, 0.0], [6.195904830954569, 0.0], [6.295904830954569, 0.0], [6.395904830954569, 0.0], [6.4959048309545695, 0.0], [6.595904830954569, 0.0], [6.69590483095457, 0.0], [6.795904830954569, 0.0], [6.89590483095457, 0.0], [6.9959048309545695, 0.0], [7.09590483095457, 0.0], [7.19590483095457, 0.0], [7.29590483095457, 0.0], [7.39590483095457, 0.0], [7.49590483095457, 0.0], [7.59590483095457, 0.0], [7.695904830954571, 0.0], [7.79590483095457, 0.0], [7.89590483095457, 0.0], [7.9959048309545695, 0.0], [8.09590483095457, 0.0], [8.195904830954568, 0.0], [8.29590483095457, 0.0], [8.395904830954567, 0.0], [8.495904830954569, 0.0], [8.595904830954566, 0.0], [8.695904830954568, 0.0], [8.795904830954566, 0.0], [8.895904830954567, 0.0], [8.995904830954565, 0.0], [9.095904830954566, 0.0], [9.195904830954564, 0.0], [9.295904830954566, 0.0], [9.395904830954564, 0.0], [9.495904830954565, 0.0], [9.595904830954563, 0.0], [9.695904830954564, 0.0], [9.795904830954562, 0.0], [9.895904830954564, 0.0], [9.995904830954562, 0.0], [10.095904830954563, 0.0], [10.19590483095456, 0.0], [10.295904830954562, 0.0], [10.39590483095456, 0.0], [10.495904830954562, 0.0], [10.59590483095456, 0.0], [10.69590483095456, 0.0], [10.795904830954559, 0.0], [10.89590483095456, 0.0], [10.995904830954558, 0.0], [11.09590483095456, 0.0], [11.195904830954559, 0.0], [11.295904830954559, 0.0], [11.395904830954558, 0.0], [11.495904830954558, 0.0], [11.595904830954558, 0.0], [11.695904830954557, 0.0], [11.795904830954557, 0.0], [11.895904830954557, 0.0], [11.995904830954556, 0.0], [12.095904830954556, 0.0], [12.195904830954555, 0.0], [12.295904830954555, 0.0], [12.395904830954555, 0.0], [12.495904830954554, 0.0], [12.595904830954554, 0.0], [12.695904830954554, 0.0], [12.795904830954553, 0.0], [12.895904830954553, 0.0], [12.995904830954553, 0.0], [13.095904830954552, 0.0], [13.195904830954552, 0.0], [13.295904830954552, 0.0], [13.395904830954551, 0.0], [13.49590483095455, 0.0], [13.59590483095455, 0.0], [13.69590483095455, 0.0], [13.79590483095455, 0.0], [13.89590483095455, 0.0], [13.995904830954549, 0.0], [14.095904830954549, 0.0], [14.195904830954548, 0.0], [14.295904830954548, 0.0], [14.395904830954548, 0.0], [14.495904830954547, 0.0], [14.595904830954547, 0.0], [14.695904830954547, 0.0], [14.793797577449581, 0.0], [14.874616611258672, 0.0], [14.935435645067763, 0.0], [14.976254678876852, 0.0], [14.997073712685944, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522], "velocities": null}}, "time": 1740481172.663626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367981744247628, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665242437052686, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.663626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.683626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367981744247628, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662474505735966, "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": 1740481172.683626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.693626, "x": 7.939661729988151, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.703626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24457064019881902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656944398449863, "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": 1740481172.703626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.723626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446401918090883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663270347864465, "gear": 1, "accelerator_pedal_position": 0.2446401918090883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.723626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7436259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446401918090883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665405044633054, "gear": 1, "accelerator_pedal_position": 0.2446401918090883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.7436259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7636259} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.939661729988151, 0.0], [4.102189057443767, 0.0], [4.202189057443767, 0.0], [4.3021890574437665, 0.0], [4.402189057443767, 0.0], [4.502189057443767, 0.0], [4.602189057443767, 0.0], [4.702189057443767, 0.0], [4.8021890574437665, 0.0], [4.902189057443767, 0.0], [5.002189057443767, 0.0], [5.102189057443766, 0.0], [5.202189057443767, 0.0], [5.302189057443767, 0.0], [5.402189057443767, 0.0], [5.502189057443767, 0.0], [5.602189057443767, 0.0], [5.702189057443768, 0.0], [5.802189057443767, 0.0], [5.902189057443767, 0.0], [6.0021890574437675, 0.0], [6.102189057443768, 0.0], [6.202189057443768, 0.0], [6.302189057443767, 0.0], [6.402189057443768, 0.0], [6.502189057443768, 0.0], [6.602189057443768, 0.0], [6.702189057443768, 0.0], [6.802189057443768, 0.0], [6.902189057443769, 0.0], [7.002189057443768, 0.0], [7.102189057443768, 0.0], [7.202189057443769, 0.0], [7.302189057443769, 0.0], [7.402189057443769, 0.0], [7.502189057443768, 0.0], [7.602189057443769, 0.0], [7.7021890574437695, 0.0], [7.802189057443769, 0.0], [7.902189057443769, 0.0], [8.002189057443768, 0.0], [8.10218905744377, 0.0], [8.202189057443768, 0.0], [8.30218905744377, 0.0], [8.402189057443767, 0.0], [8.502189057443768, 0.0], [8.602189057443766, 0.0], [8.702189057443768, 0.0], [8.802189057443766, 0.0], [8.902189057443767, 0.0], [9.002189057443765, 0.0], [9.102189057443766, 0.0], [9.202189057443764, 0.0], [9.302189057443766, 0.0], [9.402189057443763, 0.0], [9.502189057443765, 0.0], [9.602189057443763, 0.0], [9.702189057443764, 0.0], [9.802189057443762, 0.0], [9.902189057443763, 0.0], [10.002189057443761, 0.0], [10.102189057443763, 0.0], [10.20218905744376, 0.0], [10.302189057443762, 0.0], [10.40218905744376, 0.0], [10.502189057443761, 0.0], [10.60218905744376, 0.0], [10.70218905744376, 0.0], [10.802189057443758, 0.0], [10.90218905744376, 0.0], [11.002189057443758, 0.0], [11.10218905744376, 0.0], [11.202189057443757, 0.0], [11.302189057443758, 0.0], [11.402189057443756, 0.0], [11.502189057443758, 0.0], [11.602189057443756, 0.0], [11.702189057443757, 0.0], [11.802189057443755, 0.0], [11.902189057443756, 0.0], [12.002189057443756, 0.0], [12.102189057443756, 0.0], [12.202189057443755, 0.0], [12.302189057443755, 0.0], [12.402189057443755, 0.0], [12.502189057443754, 0.0], [12.602189057443754, 0.0], [12.702189057443753, 0.0], [12.802189057443753, 0.0], [12.902189057443753, 0.0], [13.002189057443752, 0.0], [13.102189057443752, 0.0], [13.202189057443752, 0.0], [13.302189057443751, 0.0], [13.402189057443751, 0.0], [13.50218905744375, 0.0], [13.60218905744375, 0.0], [13.70218905744375, 0.0], [13.80218905744375, 0.0], [13.90218905744375, 0.0], [14.002189057443749, 0.0], [14.102189057443749, 0.0], [14.202189057443748, 0.0], [14.302189057443748, 0.0], [14.402189057443747, 0.0], [14.502189057443747, 0.0], [14.602189057443747, 0.0], [14.702189057443746, 0.0], [14.799465359726879, 0.0], [14.87902754823813, 0.0], [14.93858973674938, 0.0], [14.978151925260631, 0.0], [14.997714113771883, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522], "velocities": null}}, "time": 1740481172.7636259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366882727159926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666830309503179, "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": 1740481172.7636259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7836258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366882727159926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663992588713596, "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": 1740481172.7836258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.8036258, "x": 8.045956420447522, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8036258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24428442972307024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658323047855043, "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": 1740481172.8036258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8236258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24427435374613163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662153269891404, "gear": 1, "accelerator_pedal_position": 0.24428442972307024, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8236258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8436258} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.6819758, "x": 15.0, "y": 4.764999999999942, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.8436258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24427435374613163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665965592760195, "gear": 1, "accelerator_pedal_position": 0.24427435374613163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8436258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8636258} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.0459564204475225, 0.0], [4.208477449035554, 0.0], [4.3084774490355535, 0.0], [4.408477449035554, 0.0], [4.508477449035554, 0.0], [4.608477449035554, 0.0], [4.708477449035554, 0.0], [4.8084774490355535, 0.0], [4.908477449035554, 0.0], [5.008477449035554, 0.0], [5.108477449035554, 0.0], [5.208477449035554, 0.0], [5.3084774490355535, 0.0], [5.408477449035554, 0.0], [5.508477449035555, 0.0], [5.608477449035554, 0.0], [5.708477449035554, 0.0], [5.808477449035554, 0.0], [5.908477449035555, 0.0], [6.008477449035555, 0.0], [6.108477449035554, 0.0], [6.208477449035555, 0.0], [6.308477449035555, 0.0], [6.408477449035555, 0.0], [6.508477449035555, 0.0], [6.608477449035555, 0.0], [6.708477449035556, 0.0], [6.808477449035555, 0.0], [6.908477449035555, 0.0], [7.0084774490355555, 0.0], [7.108477449035556, 0.0], [7.208477449035556, 0.0], [7.308477449035555, 0.0], [7.408477449035556, 0.0], [7.508477449035556, 0.0], [7.608477449035556, 0.0], [7.708477449035556, 0.0], [7.808477449035556, 0.0], [7.908477449035557, 0.0], [8.008477449035556, 0.0], [8.108477449035558, 0.0], [8.208477449035556, 0.0], [8.308477449035557, 0.0], [8.408477449035555, 0.0], [8.508477449035556, 0.0], [8.608477449035554, 0.0], [8.708477449035556, 0.0], [8.808477449035554, 0.0], [8.908477449035555, 0.0], [9.008477449035553, 0.0], [9.108477449035554, 0.0], [9.208477449035552, 0.0], [9.308477449035554, 0.0], [9.408477449035551, 0.0], [9.508477449035553, 0.0], [9.60847744903555, 0.0], [9.708477449035552, 0.0], [9.80847744903555, 0.0], [9.908477449035551, 0.0], [10.00847744903555, 0.0], [10.10847744903555, 0.0], [10.208477449035549, 0.0], [10.30847744903555, 0.0], [10.408477449035548, 0.0], [10.50847744903555, 0.0], [10.608477449035547, 0.0], [10.708477449035549, 0.0], [10.808477449035546, 0.0], [10.908477449035548, 0.0], [11.008477449035546, 0.0], [11.108477449035547, 0.0], [11.208477449035545, 0.0], [11.308477449035546, 0.0], [11.408477449035544, 0.0], [11.508477449035546, 0.0], [11.608477449035544, 0.0], [11.708477449035545, 0.0], [11.808477449035543, 0.0], [11.908477449035544, 0.0], [12.008477449035542, 0.0], [12.108477449035542, 0.0], [12.208477449035541, 0.0], [12.308477449035541, 0.0], [12.40847744903554, 0.0], [12.50847744903554, 0.0], [12.60847744903554, 0.0], [12.70847744903554, 0.0], [12.80847744903554, 0.0], [12.908477449035539, 0.0], [13.008477449035539, 0.0], [13.108477449035538, 0.0], [13.208477449035538, 0.0], [13.308477449035538, 0.0], [13.408477449035537, 0.0], [13.508477449035537, 0.0], [13.608477449035536, 0.0], [13.708477449035536, 0.0], [13.808477449035536, 0.0], [13.908477449035535, 0.0], [14.008477449035535, 0.0], [14.108477449035535, 0.0], [14.208477449035534, 0.0], [14.308477449035534, 0.0], [14.408477449035534, 0.0], [14.508477449035533, 0.0], [14.608477449035533, 0.0], [14.708477449035533, 0.0], [14.805057836989828, 0.0], [14.883362347182722, 0.0], [14.941666857375616, 0.0], [14.97997136756851, 0.0], [14.998275877761403, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523], "velocities": null}}, "time": 1740481172.8636258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671674171040967, "gear": 1, "accelerator_pedal_position": 0.24427435374613163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8636258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8836257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668843088792427, "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": 1740481172.8836257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.9036257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663186812035224, "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": 1740481172.9036257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.9136257, "x": 8.152274521718127, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9236257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442824551683253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965753837546247, "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": 1740481172.9236257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9436257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429728112159324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661367217618756, "gear": 1, "accelerator_pedal_position": 0.2442824551683253, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.9436257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9636257} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.152274521718127, 0.0], [4.314804809684238, 0.0], [4.414804809684238, 0.0], [4.514804809684239, 0.0], [4.614804809684238, 0.0], [4.714804809684238, 0.0], [4.814804809684238, 0.0], [4.914804809684238, 0.0], [5.014804809684238, 0.0], [5.114804809684238, 0.0], [5.214804809684238, 0.0], [5.314804809684238, 0.0], [5.414804809684238, 0.0], [5.514804809684239, 0.0], [5.614804809684238, 0.0], [5.714804809684239, 0.0], [5.814804809684238, 0.0], [5.914804809684239, 0.0], [6.014804809684239, 0.0], [6.114804809684239, 0.0], [6.214804809684239, 0.0], [6.314804809684238, 0.0], [6.414804809684239, 0.0], [6.5148048096842395, 0.0], [6.614804809684239, 0.0], [6.714804809684239, 0.0], [6.814804809684239, 0.0], [6.91480480968424, 0.0], [7.0148048096842395, 0.0], [7.114804809684239, 0.0], [7.21480480968424, 0.0], [7.31480480968424, 0.0], [7.41480480968424, 0.0], [7.5148048096842395, 0.0], [7.61480480968424, 0.0], [7.7148048096842405, 0.0], [7.81480480968424, 0.0], [7.91480480968424, 0.0], [8.01480480968424, 0.0], [8.114804809684241, 0.0], [8.21480480968424, 0.0], [8.31480480968424, 0.0], [8.41480480968424, 0.0], [8.51480480968424, 0.0], [8.61480480968424, 0.0], [8.714804809684239, 0.0], [8.814804809684238, 0.0], [8.914804809684238, 0.0], [9.014804809684238, 0.0], [9.114804809684237, 0.0], [9.214804809684237, 0.0], [9.314804809684237, 0.0], [9.414804809684236, 0.0], [9.514804809684236, 0.0], [9.614804809684236, 0.0], [9.714804809684235, 0.0], [9.814804809684235, 0.0], [9.914804809684234, 0.0], [10.014804809684234, 0.0], [10.114804809684234, 0.0], [10.214804809684233, 0.0], [10.314804809684233, 0.0], [10.414804809684233, 0.0], [10.514804809684232, 0.0], [10.614804809684232, 0.0], [10.714804809684232, 0.0], [10.814804809684231, 0.0], [10.914804809684231, 0.0], [11.01480480968423, 0.0], [11.11480480968423, 0.0], [11.21480480968423, 0.0], [11.31480480968423, 0.0], [11.41480480968423, 0.0], [11.514804809684229, 0.0], [11.614804809684228, 0.0], [11.714804809684228, 0.0], [11.814804809684228, 0.0], [11.914804809684227, 0.0], [12.014804809684227, 0.0], [12.114804809684227, 0.0], [12.214804809684226, 0.0], [12.314804809684226, 0.0], [12.414804809684226, 0.0], [12.514804809684225, 0.0], [12.614804809684225, 0.0], [12.714804809684225, 0.0], [12.814804809684224, 0.0], [12.914804809684224, 0.0], [13.014804809684223, 0.0], [13.114804809684223, 0.0], [13.214804809684223, 0.0], [13.314804809684222, 0.0], [13.414804809684222, 0.0], [13.514804809684222, 0.0], [13.614804809684221, 0.0], [13.714804809684221, 0.0], [13.81480480968422, 0.0], [13.91480480968422, 0.0], [14.01480480968422, 0.0], [14.11480480968422, 0.0], [14.21480480968422, 0.0], [14.314804809684219, 0.0], [14.414804809684219, 0.0], [14.514804809684218, 0.0], [14.614804809684218, 0.0], [14.714804809684217, 0.0], [14.81060514632601, 0.0], [14.887644184389165, 0.0], [14.944683222452323, 0.0], [14.981722260515479, 0.0], [14.998761298578636, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523], "velocities": null}}, "time": 1740481172.9636257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665209279263068, "gear": 1, "accelerator_pedal_position": 0.24429728112159324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.9636257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9836257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659528618733125, "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": 1740481172.9836257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481173.0036256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653855831356786, "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": 1740481173.0036256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.0236256, "x": 8.258525206621915, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0236256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449887610420004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648190904935419, "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": 1740481173.0236256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0436256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24441036176851466, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652303132057505, "gear": 1, "accelerator_pedal_position": 0.24449887610420004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0436256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0636256} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.258525206621915, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0]], "times": [0.0, 0.7414747933780852, 1.7414747933780852, 2.741474793378085, 3.741474793378085, 4.741474793378085, 5.741474793378085, 6.741474793378085, 7.741474793378085, 8.741474793378085, 10.741474793378085], "velocities": [0.9648190904935419, -4.96697925653114, -12.96697925653114, -20.96697925653114, -28.96697925653114, -36.96697925653114, -44.96697925653114, -52.96697925653114, -60.96697925653114, -68.96697925653115, -84.96697925653115]}}, "time": 1740481173.0636256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965829494228328, "gear": 1, "accelerator_pedal_position": 0.24441036176851466, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0636256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0836256} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.9011161, "x": 15.0, "y": 4.87499999999994, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.0836256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9563897548722172, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0836256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.1036255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9375298570171524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1036255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.1236255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9186959183898268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1236255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.1336255, "x": 8.363321661517297, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1436255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5378489118302194, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8998877614208954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1436255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1636255} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.363321661517297, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0]], "times": [0.0, 0.636678338482703, 1.636678338482703, 2.636678338482703, 3.636678338482703, 4.636678338482703, 5.636678338482703, 6.636678338482703, 7.636678338482703, 8.636678338482703, 10.636678338482703], "velocities": [0.9092886282637808, -4.184138079597844, -12.184138079597844, -20.184138079597844, -28.184138079597844, -36.184138079597844, -44.184138079597844, -52.184138079597844, -60.184138079597844, -68.18413807959784, -84.18413807959784]}}, "time": 1740481173.1636255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8741449882848346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5378489118302194, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1636255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1836255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8653502566001433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1836255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.2036254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8477785553980083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2036254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.2236254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8214651179490172, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2236254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.2436254, "x": 8.458498959719952, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2436254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5304775164466151, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8127056586515475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2436254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2636254} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.458498959719952, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0]], "times": [0.0, 0.541501040280048, 1.541501040280048, 2.541501040280048, 3.541501040280048, 4.541501040280048, 5.541501040280048, 6.541501040280048, 7.541501040280048, 8.541501040280048, 10.541501040280048], "velocities": [0.8127056586515475, -3.519302663588836, -11.519302663588837, -19.519302663588835, -27.519302663588835, -35.51930266358884, -43.51930266358884, -51.51930266358884, -59.51930266358884, -67.51930266358883, -83.51930266358883]}}, "time": 1740481173.2636254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7906738215682549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5304775164466151, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2636254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2836254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7828512490718237, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2836254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3036253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7672215150351948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3036253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3236253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7438152077843841, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3236253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3436253} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.1212618, "x": 15.0, "y": 4.984999999999937, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.3436253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.736023254997723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3436253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.3536253, "x": 8.543726168125094, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.3636253} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.543726168125094, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0]], "times": [0.0, 0.4562738318749062, 1.4562738318749062, 2.456273831874906, 3.456273831874906, 4.456273831874906, 5.456273831874906, 6.456273831874906, 7.456273831874906, 8.456273831874906, 10.456273831874906], "velocities": [0.7282363512705986, -2.921954303728651, -10.92195430372865, -18.92195430372865, -26.92195430372865, -34.921954303728654, -42.921954303728654, -50.921954303728654, -58.921954303728654, -66.92195430372865, -82.92195430372865]}}, "time": 1740481173.3636253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5261768140166697, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7126776294172122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3636253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.3836253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7060822094194893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5261768140166697, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3836253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4036252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.692169025072058, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4036252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4236252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6782736196995813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4236252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4436252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6643958933747952, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4436252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.4636252, "x": 8.619880446984732, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.4636252} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.619880446984732, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0]], "times": [0.0, 0.3801195530152679, 1.380119553015268, 2.380119553015268, 3.380119553015268, 4.380119553015268, 5.380119553015268, 6.380119553015268, 7.380119553015268, 8.380119553015268, 10.380119553015268], "velocities": [0.6505357465925913, -2.390420677529552, -10.390420677529551, -18.39042067752955, -26.39042067752955, -34.390420677529555, -42.390420677529555, -50.390420677529555, -58.390420677529555, -66.39042067752955, -82.39042067752955]}}, "time": 1740481173.4636252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5216891132467573, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6436122345492759, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4636252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.4836252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6377787466416739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5216891132467573, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4836252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.5036252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6254444250260436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.5036252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.5236251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6131255338944347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.5236251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.543625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6008219932598556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.543625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.563625} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.619880446984732, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0]], "times": [0.0, 0.3801195530152679, 1.380119553015268, 2.380119553015268, 3.380119553015268, 4.380119553015268, 5.380119553015268, 6.380119553015268, 7.380119553015268, 8.380119553015268, 10.380119553015268], "velocities": [0.6505357465925913, -2.390420677529552, -10.390420677529551, -18.39042067752955, -26.39042067752955, -34.390420677529555, -42.390420677529555, -50.390420677529555, -58.390420677529555, -66.39042067752955, -82.39042067752955]}}, "time": 1740481173.563625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5885337234620626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.563625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.573625, "x": 8.688004376137906, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.583625} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.3413217, "x": 15.0, "y": 5.094999999999935, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.583625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.517614967995438, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5762606451653008, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.583625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.603625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5659843390852461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.517614967995438, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.603625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.623625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5551013728091306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.623625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.643625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5442317137362668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.643625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.663625} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.688004376137906, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0]], "times": [0.0, 0.311995623862094, 1.311995623862094, 2.311995623862094, 3.311995623862094, 4.311995623862094, 5.311995623862094, 6.311995623862094, 7.311995623862094, 8.311995623862094, 10.311995623862094], "velocities": [0.5823952903219235, -1.9135697005748287, -9.91356970057483, -17.91356970057483, -25.91356970057483, -33.913569700574826, -41.913569700574826, -49.913569700574826, -57.913569700574826, -65.91356970057483, -81.91356970057483]}}, "time": 1740481173.663625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5196530480970096, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5333752983497857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.663625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.683625, "x": 8.7490585078663, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.683625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5142079607126203, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5224993469440395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.683625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.703625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5133784545965003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5142079607126203, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.703625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.723625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49890145168484795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5159095516358919, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.723625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.743625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4940815824314135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5159095516358919, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.743625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.763625} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.7490585078663, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0]], "times": [0.0, 0.2509414921337001, 1.2509414921337, 2.2509414921337, 3.2509414921337, 4.2509414921337, 5.2509414921337, 6.2509414921337, 7.2509414921337, 8.2509414921337, 10.2509414921337], "velocities": [0.5224993469440395, -1.4850325901255612, -9.485032590125561, -17.485032590125563, -25.485032590125563, -33.48503259012556, -41.48503259012556, -49.48503259012556, -57.48503259012556, -65.48503259012556, -81.48503259012556]}}, "time": 1740481173.763625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.515906501456509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.479639768456166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.763625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.783625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.515906501456509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47483190290814803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.783625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.7936249, "x": 8.803931100187649, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8036249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5111362776026898, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4652247539782239, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8036249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8236248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5126269735343847, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.457155025513187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5111362776026898, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8236248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8436248} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.671118, "x": 15.0, "y": 5.259999999999931, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.8436248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5126269735343847, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44861796427766876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5126269735343847, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8436248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8636248} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.803931100187649, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0]], "times": [0.0, 0.1960688998123512, 1.1960688998123512, 2.196068899812351, 3.196068899812351, 4.196068899812351, 5.196068899812351, 6.196068899812351, 7.196068899812351, 8.196068899812351, 10.196068899812351], "velocities": [0.47002690019005056, -1.098524298308759, -9.098524298308758, -17.09852429830876, -25.09852429830876, -33.09852429830876, -41.09852429830876, -49.09852429830876, -57.09852429830876, -65.09852429830876, -81.09852429830876]}}, "time": 1740481173.8636248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5124752213526939, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44009097637202393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5126269735343847, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8636248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8836248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5124752213526939, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.43162256727641535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8836248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.9036248, "x": 8.853275229652686, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9036248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5522295639676532, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4231640929105453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9036248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9236248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5535608949895681, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4031640929105453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5522295639676532, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9236248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9436247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5535608949895681, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.38316409291054526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5535608949895681, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9436247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9636247} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.853275229652686, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0]], "times": [0.0, 0.1467247703473138, 1.1467247703473138, 2.146724770347314, 3.146724770347314, 4.146724770347314, 5.146724770347314, 6.146724770347314, 7.146724770347314, 8.146724770347314, 10.146724770347314], "velocities": [0.4231640929105453, -0.750634069867965, -8.750634069867965, -16.750634069867964, -24.750634069867964, -32.750634069867964, -40.750634069867964, -48.750634069867964, -56.750634069867964, -64.75063406986797, -80.75063406986797]}}, "time": 1740481173.9636247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36316409291054524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5535608949895681, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9636247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9836247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3558389079903203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9836247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481174.0036247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.348522093863923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0036247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.0136247, "x": 8.89495712526174, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0236247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5497356905448343, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3412136195574876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0236247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0436246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5519600471191494, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.32121361955748756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5497356905448343, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0436246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0636246} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.89495712526174, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0]], "times": [0.0, 0.10504287473825968, 1.1050428747382597, 2.1050428747382597, 3.1050428747382597, 4.10504287473826, 5.10504287473826, 6.10504287473826, 7.10504287473826, 8.10504287473826, 10.10504287473826], "velocities": [0.34486681616482956, -0.4954761817412479, -8.495476181741248, -16.49547618174125, -24.49547618174125, -32.495476181741246, -40.495476181741246, -48.495476181741246, -56.495476181741246, -64.49547618174125, -80.49547618174125]}}, "time": 1740481174.0636246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29121361955748754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5519600471191494, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0636246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0836246} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.8934753, "x": 15.0, "y": 5.369999999999929, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.0836246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2883185103384375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0836246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.1036246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2825331353305991, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1036246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.1236246, "x": 8.928737805862013, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1236246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5048724789422753, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27675420107622084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1236246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1436245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5047971375672639, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2709045589328769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5048724789422753, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1436245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1636245} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9287378058620135, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0]], "times": [0.0, 0.07126219413798651, 1.0712621941379865, 2.0712621941379865, 3.0712621941379865, 4.0712621941379865, 5.0712621941379865, 6.0712621941379865, 7.0712621941379865, 8.071262194137987, 10.071262194137987], "velocities": [0.27675420107622084, -0.29334335202767126, -8.293343352027671, -16.293343352027673, -24.293343352027673, -32.29334335202767, -40.29334335202767, -48.29334335202767, -56.29334335202767, -64.29334335202768, -80.29334335202768]}}, "time": 1740481174.1636245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26508550450052204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5047971375672639, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1636245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1836245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24718467954384973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1836245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.2036245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2293035519672457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2036245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.2236245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.20251846624569364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2236245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.2336245, "x": 8.956310224595983, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2436244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19359979140476147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2436244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2636244} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.956310224595983, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0]], "times": [0.0, 0.043689775404017084, 1.043689775404017, 2.043689775404017, 3.043689775404017, 4.043689775404017, 5.043689775404017, 6.043689775404017, 7.043689775404017, 8.043689775404017, 10.043689775404017], "velocities": [0.20251846624569364, -0.14699973698644303, -8.146999736986443, -16.146999736986444, -24.146999736986444, -32.146999736986444, -40.146999736986444, -48.146999736986444, -56.146999736986444, -64.14699973698644, -80.14699973698644]}}, "time": 1740481174.2636244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.18939982660340224, "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": 1740481174.2636244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2836244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17459593466774637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2836244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.3036244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15980789817746538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3036244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.3236244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14503561269971094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3236244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.3436244, "x": 8.975267502031452, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3436244} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.114363, "x": 15.0, "y": 5.479999999999927, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.3436244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13027897419269516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3436244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3636243} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.975267502031452, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0]], "times": [0.0, 0.024732497968548373, 1.0247324979685484, 2.0247324979685484, 3.0247324979685484, 4.024732497968548, 5.024732497968548, 6.024732497968548, 7.024732497968548, 8.024732497968548, 10.024732497968548], "velocities": [0.13027897419269516, -0.06758100955569182, -8.067581009555692, -16.067581009555692, -24.067581009555692, -32.06758100955569, -40.06758100955569, -48.06758100955569, -56.06758100955569, -64.0675810095557, -80.0675810095557]}}, "time": 1740481174.3636243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1261463875405461, "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": 1740481174.3636243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3836243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11569393938614364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3836243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4036243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.10525243545580168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4036243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4236243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09482182069173653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4236243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4436243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08440204023012354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4436243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.4536242, "x": 8.98732594902868, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.4636242} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.98732594902868, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0]], "times": [0.0, 0.012674050971320128, 1.0126740509713201, 2.01267405097132, 3.01267405097132, 4.01267405097132, 5.01267405097132, 6.01267405097132, 7.01267405097132, 8.01267405097132, 10.01267405097132], "velocities": [0.07919619577051679, -0.022196212000044235, -8.022196212000043, -16.022196212000043, -24.022196212000043, -32.02219621200005, -40.02219621200005, -48.02219621200005, -56.02219621200005, -64.02219621200004, -80.02219621200004]}}, "time": 1740481174.4636242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07399303939983688, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4636242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.4836242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06991899987612585, "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": 1740481174.4836242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5036242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06584914891612209, "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": 1740481174.5036242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5236242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05975220213216229, "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": 1740481174.5236242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5436242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05772196899853024, "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": 1740481174.5436242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.5636241, "x": 8.99460157546006, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.5636241} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9946015754600595, 0], [4.994774707902231, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0]], "times": [0.0, 0.0053984245399405495, 1.0053984245399405, 2.0053984245399405, 3.0053984245399405, 4.0053984245399405, 5.0053984245399405, 6.0053984245399405, 7.0053984245399405, 8.00539842453994, 10.00539842453994], "velocities": [0.053664618275527896, 0.0104772219560035, -7.989522778043996, -15.989522778043996, -23.989522778043998, -31.989522778043998, -39.989522778044, -47.989522778044, -55.989522778044, -63.989522778044, -79.98952277804399]}}, "time": 1740481174.5636241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.053664618275527896, "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": 1740481174.5636241} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.5836241} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.3317926, "x": 15.0, "y": 5.589999999999924, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.5836241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0496114125851563, "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": 1740481174.5836241} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.603624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04556234112309009, "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": 1740481174.603624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.623624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04151739311613538, "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": 1740481174.623624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.643624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03747655782210765, "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": 1740481174.643624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.663624} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9946015754600595, 0], [4.994774707902231, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0]], "times": [0.0, 0.0053984245399405495, 1.0053984245399405, 2.0053984245399405, 3.0053984245399405, 4.0053984245399405, 5.0053984245399405, 6.0053984245399405, 7.0053984245399405, 8.00539842453994, 10.00539842453994], "velocities": [0.053664618275527896, 0.0104772219560035, -7.989522778043996, -15.989522778043996, -23.989522778043998, -31.989522778043998, -39.989522778044, -47.989522778044, -55.989522778044, -63.989522778044, -79.98952277804399]}}, "time": 1740481174.663624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.033439824529710324, "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": 1740481174.663624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.673624, "x": 8.999391470456887, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.683624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.029407182558413757, "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": 1740481174.683624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.703624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02537862125833487, "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": 1740481174.703624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.723624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02135413001011728, "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": 1740481174.723624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.743624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.017333698224811987, "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": 1740481174.743624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.763624} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.999391470456887, 0], [4.999409111043517, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0]], "times": [0.0, 0.0006085295431130788, 1.000608529543113, 2.000608529543113, 3.000608529543113, 4.000608529543113, 5.000608529543113, 6.000608529543113, 7.000608529543113, 8.000608529543113, 10.000608529543113], "velocities": [0.03142299279525901, 0.026554756450354378, -7.973445243549645, -15.973445243549646, -23.973445243549644, -31.973445243549644, -39.97344524354965, -47.97344524354965, -55.97344524354965, -63.97344524354965, -79.97344524354965]}}, "time": 1740481174.763624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5057426339044122, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.010391817526291966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.763624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.783624, "x": 9.001731794721099, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.783624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0074677893938357165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.783624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.803624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0034613149118056246, "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": 1740481174.803624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.823624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.823624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8436239} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.6614075, "x": 15.0, "y": 5.754999999999921, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.8436239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8436239} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8636239} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001731794721099, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0]], "times": [0.0, 0.9982682052789009, 1.998268205278901, 2.998268205278901, 3.998268205278901, 4.998268205278901, 5.998268205278901, 6.998268205278901, 7.998268205278901, 9.998268205278901], "velocities": [0.0074677893938357165, -7.978677852837372, -15.978677852837372, -23.97867785283737, -31.97867785283737, -39.97867785283737, -47.97867785283737, -55.97867785283737, -63.97867785283737, -79.97867785283738]}}, "time": 1740481174.8636239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8636239} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8836238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8836238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.8936238, "x": 9.001910322093941, "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": 1740481174.9036238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2325436711201126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.9036238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9236238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23200055864624486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794190017610891e-05, "gear": 1, "accelerator_pedal_position": 0.2325436711201126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9236238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9436238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23200055864624486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794378766131621e-05, "gear": 1, "accelerator_pedal_position": 0.23200055864624486, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9436238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9636238} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0]], "times": [0.0, 0.9980896779060586, 1.9980896779060586, 2.9980896779060586, 3.9980896779060586, 4.998089677906059, 5.998089677906059, 6.998089677906059, 7.998089677906059, 9.998089677906059], "velocities": [0.0, -7.984717423248469, -15.984717423248469, -23.98471742324847, -31.98471742324847, -39.98471742324847, -47.98471742324847, -55.98471742324847, -63.98471742324847, -79.98471742324847]}}, "time": 1740481174.9636238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794567325945883e-05, "gear": 1, "accelerator_pedal_position": 0.23200055864624486, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9636238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9836237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.9836237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.0036237, "x": 9.001914059077752, "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": 1740481175.0036237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0036237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0236237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0236237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0436237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0436237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0636237} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.0636237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0636237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0836236} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.8811684, "x": 15.0, "y": 5.8649999999999185, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.0836236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0836236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.1036236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1036236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.1136236, "x": 9.001914059077752, "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": 1740481175.1236236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1236236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1436236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1436236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1636236} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.1636236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1636236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1836236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1836236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.2036235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2036235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.2236235, "x": 9.001914059077752, "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": 1740481175.2236235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2236235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2436235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2436235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2636235} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.2636235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2636235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2836235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2836235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.3036234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3036234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.3236234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3236234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.3336234, "x": 9.001914059077752, "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": 1740481175.3436234} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.1014144, "x": 15.0, "y": 5.974999999999916, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.3436234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3436234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.3636234} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.3636234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3636234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.3836234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3836234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.4036233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4036233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.4236233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4236233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.4436233, "x": 9.001914059077752, "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": 1740481175.4436233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4436233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.4636233} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.4636233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4636233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.4836233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4836233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5036232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5036232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5236232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5236232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5436232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5436232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.5536232, "x": 9.001914059077752, "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": 1740481175.5636232} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.5636232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5636232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.5836232} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.4315019, "x": 15.0, "y": 6.139999999999913, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.5836232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5836232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.6036232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.6036232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.6236231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.6236231} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.643623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.643623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.663623, "x": 9.001914059077752, "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": 1740481175.663623} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.663623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.663623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.683623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.683623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.703623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.703623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.723623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.723623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.743623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.743623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.763623} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.763623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.763623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.773623, "x": 9.001914059077752, "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": 1740481175.783623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.783623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.803623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.803623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.823623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.823623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.843623} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.6514893, "x": 15.0, "y": 6.24999999999991, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.843623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.843623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.863623} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.863623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.863623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.883623, "x": 9.001914059077752, "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": 1740481175.883623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.883623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9036229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9036229} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9236228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9236228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9436228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9436228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9636228} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.9636228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9636228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9836228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9836228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.9936228, "x": 9.001914059077752, "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": 1740481176.0036228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0036228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0236228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0236228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0436227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0436227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0636227} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.0636227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0636227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0836227} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.8721457, "x": 15.0, "y": 6.359999999999908, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.0836227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0836227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.1036227, "x": 9.001914059077752, "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": 1740481176.1036227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1036227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1236227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1236227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1436226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1436226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1636226} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.1636226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1636226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1836226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1836226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.2036226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2036226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.2136226, "x": 9.001914059077752, "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": 1740481176.2236226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2236226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2436225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2436225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2636225} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.2636225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2636225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2836225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2836225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.3036225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3036225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.3236225, "x": 9.001914059077752, "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": 1740481176.3236225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3236225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3436224} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.0918632, "x": 15.0, "y": 6.469999999999906, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.3436224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3436224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3636224} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.3636224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3636224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3836224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3836224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.4036224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4036224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.4236224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4236224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.4336224, "x": 9.001914059077752, "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": 1740481176.4436224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4436224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.4636223} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.4636223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4636223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.4836223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4836223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.5036223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5036223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.5236223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5236223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.5436223, "x": 9.001914059077752, "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": 1740481176.5436223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5436223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.5636222} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.5636222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5636222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.5836222} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.421288, "x": 15.0, "y": 6.634999999999902, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.5836222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5836222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6036222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6036222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6236222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6236222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6436222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6436222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.6536222, "x": 9.001914059077752, "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": 1740481176.6636221} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.6636221} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6636221} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.6836221} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6836221} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.703622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.703622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.723622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.723622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.743622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.743622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.763622, "x": 9.001914059077752, "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": 1740481176.763622} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.763622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.763622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.783622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.783622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.803622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.803622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.823622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.823622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.843622} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.641529, "x": 15.0, "y": 6.7449999999999, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.843622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.843622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.863622} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.863622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.863622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.873622, "x": 9.001914059077752, "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": 1740481176.883622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.883622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.903622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.903622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.923622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.923622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.9436219} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9436219} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.9636219} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.9636219} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9636219} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.9836218, "x": 9.001914059077752, "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": 1740481176.9836218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9836218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0036218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0036218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0236218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0236218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0436218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0436218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0636218} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.0636218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0636218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0836217} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.861419, "x": 15.0, "y": 6.854999999999897, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.0836217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0836217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.0936217, "x": 9.001914059077752, "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": 1740481177.1036217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1036217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1236217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1236217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1436217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1436217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1636217} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.1636217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1636217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1836216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1836216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.2036216, "x": 9.001914059077752, "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": 1740481177.2036216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2036216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2236216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2236216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2436216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2436216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2636216} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.2636216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2636216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2836215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2836215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.3036215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3036215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.3136215, "x": 9.001914059077752, "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": 1740481177.3236215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3236215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3536215} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.1914217, "x": 15.0, "y": 7.019999999999894, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.3536215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3536215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3636215} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.3636215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3636215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3836215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3836215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.4036214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4036214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.4236214, "x": 9.001914059077752, "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": 1740481177.4236214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4236214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4436214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4436214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4636214} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.4636214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4636214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4836214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4836214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.5036213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5036213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.5236213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5236213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.5336213, "x": 9.001914059077752, "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": 1740481177.5436213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5436213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.5636213} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.5636213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5636213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.5836213} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.4143004, "x": 15.0, "y": 7.1299999999998915, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.5836213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5836213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.6036212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6036212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.6236212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6236212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.6436212, "x": 9.001914059077752, "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": 1740481177.6436212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6436212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.6636212} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.6636212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6636212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.6836212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6836212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.7036211} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.7036211} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.7236211} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.7236211} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.743621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.743621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.753621, "x": 9.001914059077752, "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": 1740481177.763621} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.763621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.763621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.783621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.783621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.803621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.803621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.823621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.823621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.843621} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.6313984, "x": 15.0, "y": 7.239999999999889, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.843621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.843621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.863621, "x": 9.001914059077752, "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": 1740481177.863621} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.863621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.863621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.883621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.883621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.903621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.903621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.923621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.923621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.943621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.943621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.963621} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.963621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.963621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.973621, "x": 9.001914059077752, "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": 1740481177.983621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.983621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0036209} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0036209} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0236208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0236208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0436208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0436208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0636208} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.0636208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0636208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.0836208, "x": 9.001914059077752, "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": 1740481178.0836208} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.8525784, "x": 15.0, "y": 7.349999999999887, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.0836208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0836208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1036208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1036208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1236207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1236207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1436207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1436207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1636207} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.1636207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1636207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1836207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1836207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.1936207, "x": 9.001914059077752, "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": 1740481178.2036207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2036207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2236207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2236207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2436206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2436206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2636206} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.2636206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2636206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2836206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2836206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.3036206, "x": 9.001914059077752, "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": 1740481178.3036206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3036206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3236206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3236206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3436205} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.181927, "x": 15.0, "y": 7.514999999999883, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.3436205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3436205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3636205} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.3636205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3636205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3836205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3836205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.4036205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4036205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.4136205, "x": 9.001914059077752, "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": 1740481178.4236205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4236205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4436204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4436204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4636204} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.4636204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4636204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4836204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4836204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.5036204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5036204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.5236204, "x": 9.001914059077752, "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": 1740481178.5236204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5236204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5436203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5436203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5636203} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.5636203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5636203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5836203} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.4017591, "x": 15.0, "y": 7.624999999999881, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.5836203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5836203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.6036203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6036203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.6236203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6236203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.6336203, "x": 9.001914059077752, "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": 1740481178.6436203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6436203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.6636202} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.6636202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6636202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.6836202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6836202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.7036202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7036202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.7236202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7236202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.7436202, "x": 9.001914059077752, "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": 1740481178.7436202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7436202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.7636201} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.7636201} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7636201} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.78362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.78362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.80362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.80362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.82362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.82362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.84362} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.6210592, "x": 15.0, "y": 7.734999999999879, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.84362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.84362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.85362, "x": 9.001914059077752, "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": 1740481178.86362} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.86362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.86362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.88362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.88362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.90362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.90362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.92362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.92362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.94362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.94362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.96362, "x": 9.001914059077752, "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": 1740481178.96362} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.96362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.96362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481178.98362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.98362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.00362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.00362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.02362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.02362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.0436199} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0436199} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.0636199} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481179.0636199} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0636199} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.0736198, "x": 9.001914059077752, "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": 1740481179.0836198} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.8461602, "x": 15.0, "y": 7.844999999999876, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.0836198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0836198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1036198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1036198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1236198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1236198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1436198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1436198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1636198} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0.0], [5.011914059077752, 0.0], [5.041914059077752, 0.0], [5.091914059077752, 0.0], [5.161914059077752, 0.0], [5.251914059077752, 0.0], [5.361914059077752, 0.0], [5.491914059077752, 0.0], [5.6419140590777515, 0.0], [5.804941238080992, 0.0], [5.904941238080992, 0.0], [6.004941238080992, 0.0], [6.1049412380809915, 0.0], [6.204941238080992, 0.0], [6.304941238080993, 0.0], [6.404941238080992, 0.0], [6.504941238080992, 0.0], [6.604941238080992, 0.0], [6.704941238080993, 0.0], [6.804941238080993, 0.0], [6.904941238080992, 0.0], [7.004941238080993, 0.0], [7.104941238080993, 0.0], [7.204941238080993, 0.0], [7.304941238080993, 0.0], [7.404941238080993, 0.0], [7.504941238080994, 0.0], [7.604941238080993, 0.0], [7.704941238080993, 0.0], [7.804941238080993, 0.0], [7.904941238080994, 0.0], [8.004941238080994, 0.0], [8.104941238080993, 0.0], [8.204941238080993, 0.0], [8.304941238080994, 0.0], [8.404941238080994, 0.0], [8.504941238080994, 0.0], [8.604941238080993, 0.0], [8.704941238080993, 0.0], [8.804941238080993, 0.0], [8.904941238080992, 0.0], [9.004941238080992, 0.0], [9.104941238080992, 0.0], [9.204941238080991, 0.0], [9.30494123808099, 0.0], [9.40494123808099, 0.0], [9.50494123808099, 0.0], [9.60494123808099, 0.0], [9.70494123808099, 0.0], [9.804941238080989, 0.0], [9.904941238080989, 0.0], [10.004941238080988, 0.0], [10.104941238080988, 0.0], [10.204941238080988, 0.0], [10.304941238080987, 0.0], [10.404941238080987, 0.0], [10.504941238080987, 0.0], [10.604941238080986, 0.0], [10.704941238080986, 0.0], [10.804941238080985, 0.0], [10.904941238080985, 0.0], [11.004941238080985, 0.0], [11.104941238080984, 0.0], [11.204941238080984, 0.0], [11.304941238080984, 0.0], [11.404941238080983, 0.0], [11.504941238080983, 0.0], [11.604941238080983, 0.0], [11.704941238080982, 0.0], [11.804941238080982, 0.0], [11.904941238080982, 0.0], [12.004941238080981, 0.0], [12.10494123808098, 0.0], [12.20494123808098, 0.0], [12.30494123808098, 0.0], [12.40494123808098, 0.0], [12.50494123808098, 0.0], [12.604941238080979, 0.0], [12.704941238080979, 0.0], [12.804941238080978, 0.0], [12.904941238080978, 0.0], [13.004941238080978, 0.0], [13.104941238080977, 0.0], [13.204941238080977, 0.0], [13.304941238080977, 0.0], [13.404941238080976, 0.0], [13.504941238080976, 0.0], [13.604941238080976, 0.0], [13.704941238080973, 0.0], [13.804941238080973, 0.0], [13.904941238080973, 0.0], [14.004941238080972, 0.0], [14.104941238080972, 0.0], [14.204941238080972, 0.0], [14.304941238080971, 0.0], [14.404941238080971, 0.0], [14.50494123808097, 0.0], [14.60494123808097, 0.0], [14.70494123808097, 0.0], [14.8019226984391, 0.0], [14.880934450822906, 0.0], [14.939946203206711, 0.0], [14.978957955590518, 0.0], [14.997969707974324, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884], "velocities": null}}, "time": 1740481179.1636198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1636198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.1836197, "x": 9.00192018280211, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.1836197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.001224438647673715, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.1836197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2036197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02121820176785803, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2036197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2236197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04119184648083958, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2236197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2436197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06114523349238528, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2436197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2636197} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.00192018280211, 0.0], [5.012120132795986, 0.0], [5.042320082789862, 0.0], [5.092520032783739, 0.0], [5.162719982777615, 0.0], [5.252919932771491, 0.0], [5.363119882765368, 0.0], [5.493319832759243, 0.0], [5.64351978275312, 0.0], [5.806578947168913, 0.0], [5.906578947168914, 0.0], [6.006578947168913, 0.0], [6.106578947168914, 0.0], [6.206578947168914, 0.0], [6.306578947168914, 0.0], [6.406578947168914, 0.0], [6.506578947168913, 0.0], [6.606578947168914, 0.0], [6.706578947168914, 0.0], [6.806578947168914, 0.0], [6.906578947168914, 0.0], [7.006578947168914, 0.0], [7.106578947168915, 0.0], [7.206578947168914, 0.0], [7.306578947168914, 0.0], [7.4065789471689145, 0.0], [7.506578947168915, 0.0], [7.606578947168915, 0.0], [7.706578947168914, 0.0], [7.806578947168916, 0.0], [7.906578947168915, 0.0], [8.006578947168915, 0.0], [8.106578947168915, 0.0], [8.206578947168916, 0.0], [8.306578947168916, 0.0], [8.406578947168915, 0.0], [8.506578947168915, 0.0], [8.606578947168915, 0.0], [8.706578947168914, 0.0], [8.806578947168914, 0.0], [8.906578947168914, 0.0], [9.006578947168911, 0.0], [9.106578947168913, 0.0], [9.20657894716891, 0.0], [9.306578947168912, 0.0], [9.40657894716891, 0.0], [9.506578947168911, 0.0], [9.60657894716891, 0.0], [9.70657894716891, 0.0], [9.806578947168909, 0.0], [9.90657894716891, 0.0], [10.006578947168908, 0.0], [10.10657894716891, 0.0], [10.206578947168907, 0.0], [10.306578947168909, 0.0], [10.406578947168907, 0.0], [10.506578947168908, 0.0], [10.606578947168906, 0.0], [10.706578947168907, 0.0], [10.806578947168905, 0.0], [10.906578947168907, 0.0], [11.006578947168904, 0.0], [11.106578947168906, 0.0], [11.206578947168904, 0.0], [11.306578947168905, 0.0], [11.406578947168903, 0.0], [11.506578947168904, 0.0], [11.606578947168902, 0.0], [11.706578947168904, 0.0], [11.806578947168902, 0.0], [11.906578947168903, 0.0], [12.0065789471689, 0.0], [12.106578947168902, 0.0], [12.2065789471689, 0.0], [12.306578947168902, 0.0], [12.4065789471689, 0.0], [12.5065789471689, 0.0], [12.606578947168899, 0.0], [12.7065789471689, 0.0], [12.806578947168898, 0.0], [12.9065789471689, 0.0], [13.006578947168899, 0.0], [13.106578947168899, 0.0], [13.206578947168898, 0.0], [13.306578947168898, 0.0], [13.406578947168898, 0.0], [13.506578947168897, 0.0], [13.606578947168897, 0.0], [13.706578947168897, 0.0], [13.806578947168896, 0.0], [13.906578947168896, 0.0], [14.006578947168896, 0.0], [14.106578947168895, 0.0], [14.206578947168895, 0.0], [14.306578947168894, 0.0], [14.406578947168894, 0.0], [14.506578947168894, 0.0], [14.606578947168893, 0.0], [14.706578947168893, 0.0], [14.803377769906152, 0.0], [14.882061980472374, 0.0], [14.940746191038595, 0.0], [14.979430401604816, 0.0], [14.998114612171038, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884], "velocities": null}}, "time": 1740481179.2636197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09103702765408891, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2636197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2836196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09160305280191727, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2836196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.2936196, "x": 9.007452330469965, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3036196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3806327230601132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09273422313419458, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3036196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3236196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3872468636188754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11121405824940593, "gear": 1, "accelerator_pedal_position": 0.3806327230601132, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3236196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3436196} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.1714432, "x": 15.0, "y": 8.009999999999874, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.3436196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3872468636188754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1305011815268707, "gear": 1, "accelerator_pedal_position": 0.3872468636188754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3436196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3636196} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.007452330469965, 0.0], [5.032503429968681, 0.0], [5.077554529467396, 0.0], [5.142605628966113, 0.0], [5.2276567284648285, 0.0], [5.332707827963544, 0.0], [5.45775892746226, 0.0], [5.6028100269609755, 0.0], [5.764408516183699, 0.0], [5.864408516183699, 0.0], [5.964408516183699, 0.0], [6.064408516183699, 0.0], [6.164408516183699, 0.0], [6.2644085161837, 0.0], [6.364408516183699, 0.0], [6.464408516183699, 0.0], [6.5644085161837, 0.0], [6.6644085161837, 0.0], [6.7644085161837, 0.0], [6.864408516183699, 0.0], [6.9644085161837, 0.0], [7.0644085161837005, 0.0], [7.1644085161837, 0.0], [7.2644085161837, 0.0], [7.3644085161837, 0.0], [7.464408516183701, 0.0], [7.5644085161837005, 0.0], [7.6644085161837, 0.0], [7.7644085161837, 0.0], [7.864408516183701, 0.0], [7.964408516183701, 0.0], [8.0644085161837, 0.0], [8.1644085161837, 0.0], [8.264408516183702, 0.0], [8.364408516183701, 0.0], [8.4644085161837, 0.0], [8.5644085161837, 0.0], [8.6644085161837, 0.0], [8.7644085161837, 0.0], [8.8644085161837, 0.0], [8.964408516183699, 0.0], [9.064408516183699, 0.0], [9.164408516183698, 0.0], [9.264408516183698, 0.0], [9.364408516183698, 0.0], [9.464408516183697, 0.0], [9.564408516183697, 0.0], [9.664408516183697, 0.0], [9.764408516183696, 0.0], [9.864408516183696, 0.0], [9.964408516183695, 0.0], [10.064408516183695, 0.0], [10.164408516183695, 0.0], [10.264408516183694, 0.0], [10.364408516183694, 0.0], [10.464408516183694, 0.0], [10.564408516183693, 0.0], [10.664408516183693, 0.0], [10.764408516183693, 0.0], [10.864408516183692, 0.0], [10.964408516183692, 0.0], [11.064408516183692, 0.0], [11.164408516183691, 0.0], [11.26440851618369, 0.0], [11.36440851618369, 0.0], [11.46440851618369, 0.0], [11.56440851618369, 0.0], [11.66440851618369, 0.0], [11.764408516183689, 0.0], [11.864408516183689, 0.0], [11.964408516183688, 0.0], [12.064408516183688, 0.0], [12.164408516183688, 0.0], [12.264408516183687, 0.0], [12.364408516183687, 0.0], [12.464408516183688, 0.0], [12.564408516183686, 0.0], [12.664408516183688, 0.0], [12.764408516183686, 0.0], [12.864408516183687, 0.0], [12.964408516183685, 0.0], [13.064408516183684, 0.0], [13.164408516183684, 0.0], [13.264408516183684, 0.0], [13.364408516183683, 0.0], [13.464408516183683, 0.0], [13.564408516183683, 0.0], [13.664408516183682, 0.0], [13.764408516183682, 0.0], [13.864408516183682, 0.0], [13.964408516183681, 0.0], [14.064408516183681, 0.0], [14.16440851618368, 0.0], [14.26440851618368, 0.0], [14.36440851618368, 0.0], [14.46440851618368, 0.0], [14.56440851618368, 0.0], [14.664408516183679, 0.0], [14.764200910845062, 0.0], [14.851319207608327, 0.0], [14.91843750437159, 0.0], [14.965555801134856, 0.0], [14.99267409789812, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434], "velocities": null}}, "time": 1740481179.3636196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14976805341192728, "gear": 1, "accelerator_pedal_position": 0.3872468636188754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3636196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3836195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15083826045208149, "gear": 1, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3836195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.4036195, "x": 9.021371076871302, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4036195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38789516535171176, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15190733312924354, "gear": 1, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4036195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4236195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17123257072008768, "gear": 1, "accelerator_pedal_position": 0.38789516535171176, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4236195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4436195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19105016904852815, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4436195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4636195} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.0213710768713025, 0.0], [5.056177440494878, 0.0], [5.110983804118453, 0.0], [5.185790167742028, 0.0], [5.280596531365604, 0.0], [5.395402894989179, 0.0], [5.5302092586127545, 0.0], [5.684958842436817, 0.0], [5.784958842436818, 0.0], [5.884958842436817, 0.0], [5.984958842436818, 0.0], [6.0849588424368175, 0.0], [6.184958842436818, 0.0], [6.284958842436819, 0.0], [6.384958842436818, 0.0], [6.484958842436818, 0.0], [6.5849588424368175, 0.0], [6.684958842436818, 0.0], [6.784958842436819, 0.0], [6.884958842436818, 0.0], [6.984958842436818, 0.0], [7.084958842436818, 0.0], [7.184958842436819, 0.0], [7.284958842436819, 0.0], [7.384958842436818, 0.0], [7.484958842436819, 0.0], [7.584958842436819, 0.0], [7.684958842436819, 0.0], [7.784958842436819, 0.0], [7.88495884243682, 0.0], [7.98495884243682, 0.0], [8.08495884243682, 0.0], [8.184958842436819, 0.0], [8.28495884243682, 0.0], [8.38495884243682, 0.0], [8.48495884243682, 0.0], [8.58495884243682, 0.0], [8.684958842436819, 0.0], [8.784958842436819, 0.0], [8.884958842436818, 0.0], [8.984958842436818, 0.0], [9.084958842436818, 0.0], [9.184958842436817, 0.0], [9.284958842436817, 0.0], [9.384958842436816, 0.0], [9.484958842436816, 0.0], [9.584958842436816, 0.0], [9.684958842436815, 0.0], [9.784958842436815, 0.0], [9.884958842436815, 0.0], [9.984958842436814, 0.0], [10.084958842436814, 0.0], [10.184958842436814, 0.0], [10.284958842436813, 0.0], [10.384958842436813, 0.0], [10.484958842436813, 0.0], [10.584958842436812, 0.0], [10.684958842436812, 0.0], [10.784958842436811, 0.0], [10.884958842436811, 0.0], [10.98495884243681, 0.0], [11.08495884243681, 0.0], [11.18495884243681, 0.0], [11.28495884243681, 0.0], [11.38495884243681, 0.0], [11.484958842436809, 0.0], [11.584958842436809, 0.0], [11.684958842436808, 0.0], [11.784958842436808, 0.0], [11.884958842436808, 0.0], [11.984958842436807, 0.0], [12.084958842436807, 0.0], [12.184958842436806, 0.0], [12.284958842436806, 0.0], [12.384958842436806, 0.0], [12.484958842436805, 0.0], [12.584958842436805, 0.0], [12.684958842436806, 0.0], [12.784958842436804, 0.0], [12.884958842436806, 0.0], [12.984958842436804, 0.0], [13.084958842436805, 0.0], [13.184958842436805, 0.0], [13.284958842436804, 0.0], [13.384958842436804, 0.0], [13.484958842436804, 0.0], [13.584958842436803, 0.0], [13.684958842436803, 0.0], [13.784958842436803, 0.0], [13.884958842436802, 0.0], [13.984958842436802, 0.0], [14.084958842436802, 0.0], [14.184958842436801, 0.0], [14.2849588424368, 0.0], [14.3849588424368, 0.0], [14.4849588424368, 0.0], [14.5849588424368, 0.0], [14.6849588424368, 0.0], [14.783736721772279, 0.0], [14.866744953284918, 0.0], [14.929753184797558, 0.0], [14.972761416310199, 0.0], [14.995769647822838, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796], "velocities": null}}, "time": 1740481179.4636195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21084648032012404, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4636195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4836195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2118512149962841, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4836195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.5036194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2128548601925433, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5036194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.5136194, "x": 9.042542200091958, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5236194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38749711017683985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21385741668746241, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5236194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5436194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3919661283551731, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23306632737226865, "gear": 1, "accelerator_pedal_position": 0.38749711017683985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5436194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5636194} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.042542200091958, 0.0], [5.087383133818273, 0.0], [5.152224067544588, 0.0], [5.237065001270903, 0.0], [5.341905934997218, 0.0], [5.466746868723533, 0.0], [5.611587802449847, 0.0], [5.773098512789727, 0.0], [5.873098512789728, 0.0], [5.973098512789727, 0.0], [6.073098512789727, 0.0], [6.1730985127897275, 0.0], [6.273098512789728, 0.0], [6.373098512789728, 0.0], [6.473098512789727, 0.0], [6.573098512789728, 0.0], [6.673098512789728, 0.0], [6.773098512789728, 0.0], [6.873098512789728, 0.0], [6.973098512789728, 0.0], [7.073098512789729, 0.0], [7.173098512789728, 0.0], [7.273098512789728, 0.0], [7.373098512789729, 0.0], [7.473098512789729, 0.0], [7.573098512789729, 0.0], [7.673098512789728, 0.0], [7.773098512789729, 0.0], [7.8730985127897295, 0.0], [7.973098512789729, 0.0], [8.073098512789729, 0.0], [8.173098512789728, 0.0], [8.27309851278973, 0.0], [8.37309851278973, 0.0], [8.47309851278973, 0.0], [8.57309851278973, 0.0], [8.67309851278973, 0.0], [8.77309851278973, 0.0], [8.87309851278973, 0.0], [8.97309851278973, 0.0], [9.073098512789727, 0.0], [9.173098512789728, 0.0], [9.273098512789726, 0.0], [9.373098512789728, 0.0], [9.473098512789726, 0.0], [9.573098512789727, 0.0], [9.673098512789725, 0.0], [9.773098512789726, 0.0], [9.873098512789724, 0.0], [9.973098512789726, 0.0], [10.073098512789723, 0.0], [10.173098512789725, 0.0], [10.273098512789723, 0.0], [10.373098512789724, 0.0], [10.473098512789722, 0.0], [10.573098512789723, 0.0], [10.673098512789721, 0.0], [10.773098512789723, 0.0], [10.87309851278972, 0.0], [10.973098512789722, 0.0], [11.07309851278972, 0.0], [11.173098512789721, 0.0], [11.27309851278972, 0.0], [11.37309851278972, 0.0], [11.473098512789718, 0.0], [11.57309851278972, 0.0], [11.673098512789718, 0.0], [11.77309851278972, 0.0], [11.873098512789717, 0.0], [11.973098512789718, 0.0], [12.073098512789716, 0.0], [12.173098512789718, 0.0], [12.273098512789716, 0.0], [12.373098512789717, 0.0], [12.473098512789715, 0.0], [12.573098512789716, 0.0], [12.673098512789716, 0.0], [12.773098512789716, 0.0], [12.873098512789715, 0.0], [12.973098512789715, 0.0], [13.073098512789715, 0.0], [13.173098512789714, 0.0], [13.273098512789714, 0.0], [13.373098512789714, 0.0], [13.473098512789713, 0.0], [13.573098512789713, 0.0], [13.673098512789712, 0.0], [13.773098512789712, 0.0], [13.873098512789712, 0.0], [13.973098512789711, 0.0], [14.073098512789711, 0.0], [14.17309851278971, 0.0], [14.27309851278971, 0.0], [14.37309851278971, 0.0], [14.47309851278971, 0.0], [14.57309851278971, 0.0], [14.673098512789709, 0.0], [14.772564971496612, 0.0], [14.85794526893867, 0.0], [14.92332556638073, 0.0], [14.968705863822787, 0.0], [14.994086161264844, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797], "velocities": null}}, "time": 1740481179.5636194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25281275504561174, "gear": 1, "accelerator_pedal_position": 0.3919661283551731, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5636194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5836194} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.3912098, "x": 15.0, "y": 8.11999999999989, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.5836194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2537716402453045, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5836194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.6036193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2547294696074293, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6036193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.6236193, "x": 9.069049716268669, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6236193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39194661769077443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25568624392770506, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6236193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6436193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2754053646061096, "gear": 1, "accelerator_pedal_position": 0.39194661769077443, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6436193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6636193} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.069049716268669, 0.0], [5.120803105060114, 0.0], [5.1925564938515585, 0.0], [5.2843098826430035, 0.0], [5.396063271434448, 0.0], [5.527816660225893, 0.0], [5.679570049017338, 0.0], [5.8428096179151865, 0.0], [5.942809617915187, 0.0], [6.042809617915187, 0.0], [6.142809617915187, 0.0], [6.242809617915187, 0.0], [6.342809617915187, 0.0], [6.442809617915187, 0.0], [6.542809617915188, 0.0], [6.642809617915187, 0.0], [6.742809617915187, 0.0], [6.842809617915187, 0.0], [6.942809617915188, 0.0], [7.042809617915188, 0.0], [7.142809617915187, 0.0], [7.242809617915188, 0.0], [7.342809617915188, 0.0], [7.442809617915188, 0.0], [7.542809617915188, 0.0], [7.642809617915188, 0.0], [7.742809617915189, 0.0], [7.842809617915188, 0.0], [7.942809617915188, 0.0], [8.04280961791519, 0.0], [8.142809617915189, 0.0], [8.242809617915189, 0.0], [8.342809617915188, 0.0], [8.442809617915188, 0.0], [8.54280961791519, 0.0], [8.642809617915189, 0.0], [8.742809617915189, 0.0], [8.842809617915188, 0.0], [8.942809617915188, 0.0], [9.042809617915188, 0.0], [9.142809617915187, 0.0], [9.242809617915189, 0.0], [9.342809617915186, 0.0], [9.442809617915188, 0.0], [9.542809617915186, 0.0], [9.642809617915187, 0.0], [9.742809617915185, 0.0], [9.842809617915185, 0.0], [9.942809617915184, 0.0], [10.042809617915184, 0.0], [10.142809617915184, 0.0], [10.242809617915183, 0.0], [10.342809617915183, 0.0], [10.442809617915183, 0.0], [10.542809617915182, 0.0], [10.642809617915182, 0.0], [10.742809617915182, 0.0], [10.842809617915181, 0.0], [10.94280961791518, 0.0], [11.04280961791518, 0.0], [11.14280961791518, 0.0], [11.24280961791518, 0.0], [11.34280961791518, 0.0], [11.442809617915179, 0.0], [11.542809617915179, 0.0], [11.642809617915178, 0.0], [11.742809617915178, 0.0], [11.842809617915178, 0.0], [11.942809617915177, 0.0], [12.042809617915177, 0.0], [12.142809617915177, 0.0], [12.242809617915176, 0.0], [12.342809617915176, 0.0], [12.442809617915175, 0.0], [12.542809617915175, 0.0], [12.642809617915175, 0.0], [12.742809617915174, 0.0], [12.842809617915176, 0.0], [12.942809617915174, 0.0], [13.042809617915175, 0.0], [13.142809617915175, 0.0], [13.242809617915174, 0.0], [13.342809617915174, 0.0], [13.442809617915174, 0.0], [13.542809617915173, 0.0], [13.642809617915173, 0.0], [13.742809617915173, 0.0], [13.842809617915172, 0.0], [13.942809617915172, 0.0], [14.042809617915172, 0.0], [14.142809617915171, 0.0], [14.24280961791517, 0.0], [14.34280961791517, 0.0], [14.44280961791517, 0.0], [14.54280961791517, 0.0], [14.64280961791517, 0.0], [14.742809617915169, 0.0], [14.834195992737609, 0.0], [14.905634069154575, 0.0], [14.95707214557154, 0.0], [14.988510221988507, 0.0], [14.999948298405474, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797], "velocities": null}}, "time": 1740481179.6636193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3049530461372646, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6636193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6836193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3054036424138569, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6836193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.7036192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30630407666654824, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7036192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.7236192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30765283381337716, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7236192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.7336192, "x": 9.101184533156012, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7436192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38970391262979476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30810191480555094, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7436192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7636192} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.101184533156012, 0.0], [5.161424030540282, 0.0], [5.241663527924551, 0.0], [5.341903025308821, 0.0], [5.462142522693091, 0.0], [5.60238202007736, 0.0], [5.761417364584852, 0.0], [5.8614173645848515, 0.0], [5.961417364584852, 0.0], [6.061417364584852, 0.0], [6.161417364584851, 0.0], [6.261417364584852, 0.0], [6.361417364584852, 0.0], [6.461417364584852, 0.0], [6.561417364584852, 0.0], [6.661417364584852, 0.0], [6.761417364584853, 0.0], [6.861417364584852, 0.0], [6.961417364584852, 0.0], [7.061417364584853, 0.0], [7.161417364584853, 0.0], [7.261417364584853, 0.0], [7.361417364584852, 0.0], [7.461417364584853, 0.0], [7.5614173645848535, 0.0], [7.661417364584853, 0.0], [7.761417364584853, 0.0], [7.861417364584853, 0.0], [7.961417364584854, 0.0], [8.061417364584853, 0.0], [8.161417364584853, 0.0], [8.261417364584855, 0.0], [8.361417364584854, 0.0], [8.461417364584854, 0.0], [8.561417364584853, 0.0], [8.661417364584853, 0.0], [8.761417364584855, 0.0], [8.861417364584854, 0.0], [8.961417364584854, 0.0], [9.061417364584853, 0.0], [9.161417364584853, 0.0], [9.261417364584853, 0.0], [9.361417364584852, 0.0], [9.461417364584852, 0.0], [9.561417364584852, 0.0], [9.661417364584851, 0.0], [9.761417364584851, 0.0], [9.86141736458485, 0.0], [9.96141736458485, 0.0], [10.06141736458485, 0.0], [10.16141736458485, 0.0], [10.26141736458485, 0.0], [10.361417364584849, 0.0], [10.461417364584848, 0.0], [10.561417364584848, 0.0], [10.661417364584848, 0.0], [10.761417364584847, 0.0], [10.861417364584847, 0.0], [10.961417364584847, 0.0], [11.061417364584846, 0.0], [11.161417364584846, 0.0], [11.261417364584846, 0.0], [11.361417364584845, 0.0], [11.461417364584845, 0.0], [11.561417364584845, 0.0], [11.661417364584844, 0.0], [11.761417364584844, 0.0], [11.861417364584844, 0.0], [11.961417364584843, 0.0], [12.061417364584843, 0.0], [12.161417364584842, 0.0], [12.261417364584842, 0.0], [12.361417364584842, 0.0], [12.461417364584841, 0.0], [12.561417364584841, 0.0], [12.66141736458484, 0.0], [12.76141736458484, 0.0], [12.86141736458484, 0.0], [12.96141736458484, 0.0], [13.06141736458484, 0.0], [13.161417364584839, 0.0], [13.261417364584839, 0.0], [13.361417364584838, 0.0], [13.461417364584838, 0.0], [13.561417364584837, 0.0], [13.661417364584837, 0.0], [13.761417364584835, 0.0], [13.861417364584835, 0.0], [13.961417364584834, 0.0], [14.061417364584834, 0.0], [14.161417364584834, 0.0], [14.261417364584833, 0.0], [14.361417364584833, 0.0], [14.461417364584833, 0.0], [14.561417364584832, 0.0], [14.661417364584832, 0.0], [14.761287008370768, 0.0], [14.849003535453802, 0.0], [14.916720062536836, 0.0], [14.964436589619869, 0.0], [14.992153116702903, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251], "velocities": null}}, "time": 1740481179.7636192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34684093670559946, "gear": 1, "accelerator_pedal_position": 0.38970391262979476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7636192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7836192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34684093670559946, "gear": 1, "accelerator_pedal_position": 0.38970391262979476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7836192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.8036191} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34769453781911985, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.8036191} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.8236191} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34897311730373193, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.8236191} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.843619, "x": 9.138040942771699, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.843619} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.6112149, "x": 15.0, "y": 8.229999999999908, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.843619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34939882495711583, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.843619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.863619} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.138040942771699, 0.0], [5.205097531963229, 0.0], [5.292154121154759, 0.0], [5.399210710346289, 0.0], [5.526267299537819, 0.0], [5.67332388872935, 0.0], [5.835648913906849, 0.0], [5.935648913906849, 0.0], [6.035648913906849, 0.0], [6.1356489139068495, 0.0], [6.23564891390685, 0.0], [6.33564891390685, 0.0], [6.435648913906849, 0.0], [6.53564891390685, 0.0], [6.63564891390685, 0.0], [6.73564891390685, 0.0], [6.83564891390685, 0.0], [6.935648913906849, 0.0], [7.03564891390685, 0.0], [7.13564891390685, 0.0], [7.23564891390685, 0.0], [7.33564891390685, 0.0], [7.43564891390685, 0.0], [7.535648913906851, 0.0], [7.63564891390685, 0.0], [7.73564891390685, 0.0], [7.835648913906851, 0.0], [7.935648913906851, 0.0], [8.03564891390685, 0.0], [8.13564891390685, 0.0], [8.23564891390685, 0.0], [8.335648913906851, 0.0], [8.435648913906851, 0.0], [8.53564891390685, 0.0], [8.635648913906852, 0.0], [8.735648913906852, 0.0], [8.835648913906851, 0.0], [8.935648913906851, 0.0], [9.03564891390685, 0.0], [9.13564891390685, 0.0], [9.23564891390685, 0.0], [9.33564891390685, 0.0], [9.43564891390685, 0.0], [9.535648913906849, 0.0], [9.635648913906849, 0.0], [9.735648913906848, 0.0], [9.835648913906848, 0.0], [9.935648913906848, 0.0], [10.035648913906847, 0.0], [10.135648913906847, 0.0], [10.235648913906847, 0.0], [10.335648913906846, 0.0], [10.435648913906846, 0.0], [10.535648913906845, 0.0], [10.635648913906845, 0.0], [10.735648913906845, 0.0], [10.835648913906844, 0.0], [10.935648913906844, 0.0], [11.035648913906844, 0.0], [11.135648913906843, 0.0], [11.235648913906843, 0.0], [11.335648913906843, 0.0], [11.435648913906842, 0.0], [11.535648913906842, 0.0], [11.635648913906842, 0.0], [11.735648913906841, 0.0], [11.83564891390684, 0.0], [11.93564891390684, 0.0], [12.03564891390684, 0.0], [12.13564891390684, 0.0], [12.23564891390684, 0.0], [12.335648913906839, 0.0], [12.435648913906839, 0.0], [12.535648913906838, 0.0], [12.635648913906838, 0.0], [12.735648913906838, 0.0], [12.835648913906837, 0.0], [12.935648913906837, 0.0], [13.035648913906837, 0.0], [13.135648913906836, 0.0], [13.235648913906836, 0.0], [13.335648913906835, 0.0], [13.435648913906835, 0.0], [13.535648913906835, 0.0], [13.635648913906834, 0.0], [13.735648913906834, 0.0], [13.835648913906834, 0.0], [13.935648913906833, 0.0], [14.035648913906833, 0.0], [14.135648913906833, 0.0], [14.235648913906832, 0.0], [14.335648913906832, 0.0], [14.435648913906832, 0.0], [14.535648913906831, 0.0], [14.63564891390683, 0.0], [14.73564891390683, 0.0], [14.82831317745341, 0.0], [14.901183394672044, 0.0], [14.954053611890679, 0.0], [14.986923829109312, 0.0], [14.999794046327946, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251], "velocities": null}}, "time": 1740481179.863619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36943365351094865, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.863619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.883619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3698476609974543, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.883619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.903619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3706749632409567, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.903619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.923619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3719141363142496, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.923619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.943619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37232671966930925, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.943619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.953619, "x": 9.178487725666972, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481179.963619} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.178487725666972, 0.0], [5.249355760264747, 0.0], [5.340223794862522, 0.0], [5.451091829460297, 0.0], [5.581959864058072, 0.0], [5.732827898655846, 0.0], [5.895979436587416, 0.0], [5.995979436587415, 0.0], [6.095979436587416, 0.0], [6.195979436587416, 0.0], [6.295979436587416, 0.0], [6.395979436587416, 0.0], [6.495979436587416, 0.0], [6.595979436587417, 0.0], [6.695979436587416, 0.0], [6.795979436587416, 0.0], [6.8959794365874165, 0.0], [6.995979436587417, 0.0], [7.095979436587417, 0.0], [7.195979436587416, 0.0], [7.295979436587417, 0.0], [7.395979436587417, 0.0], [7.495979436587417, 0.0], [7.595979436587417, 0.0], [7.695979436587417, 0.0], [7.795979436587418, 0.0], [7.895979436587417, 0.0], [7.995979436587417, 0.0], [8.095979436587417, 0.0], [8.195979436587418, 0.0], [8.295979436587418, 0.0], [8.395979436587417, 0.0], [8.495979436587419, 0.0], [8.595979436587418, 0.0], [8.695979436587418, 0.0], [8.795979436587418, 0.0], [8.895979436587417, 0.0], [8.995979436587419, 0.0], [9.095979436587417, 0.0], [9.195979436587418, 0.0], [9.295979436587416, 0.0], [9.395979436587417, 0.0], [9.495979436587415, 0.0], [9.595979436587417, 0.0], [9.695979436587415, 0.0], [9.795979436587414, 0.0], [9.895979436587414, 0.0], [9.995979436587414, 0.0], [10.095979436587413, 0.0], [10.195979436587413, 0.0], [10.295979436587412, 0.0], [10.395979436587412, 0.0], [10.495979436587412, 0.0], [10.595979436587411, 0.0], [10.695979436587411, 0.0], [10.79597943658741, 0.0], [10.89597943658741, 0.0], [10.99597943658741, 0.0], [11.09597943658741, 0.0], [11.19597943658741, 0.0], [11.295979436587409, 0.0], [11.395979436587409, 0.0], [11.495979436587408, 0.0], [11.595979436587408, 0.0], [11.695979436587407, 0.0], [11.795979436587407, 0.0], [11.895979436587407, 0.0], [11.995979436587406, 0.0], [12.095979436587406, 0.0], [12.195979436587406, 0.0], [12.295979436587405, 0.0], [12.395979436587405, 0.0], [12.495979436587405, 0.0], [12.595979436587404, 0.0], [12.695979436587404, 0.0], [12.795979436587404, 0.0], [12.895979436587403, 0.0], [12.995979436587403, 0.0], [13.095979436587402, 0.0], [13.195979436587402, 0.0], [13.295979436587402, 0.0], [13.395979436587401, 0.0], [13.495979436587401, 0.0], [13.5959794365874, 0.0], [13.6959794365874, 0.0], [13.795979436587402, 0.0], [13.895979436587401, 0.0], [13.995979436587401, 0.0], [14.0959794365874, 0.0], [14.1959794365874, 0.0], [14.2959794365874, 0.0], [14.3959794365874, 0.0], [14.4959794365874, 0.0], [14.595979436587399, 0.0], [14.695979436587399, 0.0], [14.793865327998503, 0.0], [14.874669440681023, 0.0], [14.935473553363543, 0.0], [14.976277666046064, 0.0], [14.997081778728585, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251], "velocities": null}}, "time": 1740481179.963619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3829506757203799, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.963619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481179.983619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3927445352605162, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.983619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.003619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41231526853627576, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.003619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.023619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44162866607304435, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.023619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.043619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4513883481521381, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.043619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.063619, "x": 9.223933206777517, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.063619} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.223933206777517, 0.0], [5.310829294031899, 0.0], [5.4177253812862824, 0.0], [5.544621468540665, 0.0], [5.6915175557950475, 0.0], [5.853791838461971, 0.0], [5.953791838461971, 0.0], [6.053791838461971, 0.0], [6.153791838461971, 0.0], [6.2537918384619715, 0.0], [6.353791838461971, 0.0], [6.453791838461971, 0.0], [6.553791838461971, 0.0], [6.653791838461972, 0.0], [6.7537918384619715, 0.0], [6.853791838461971, 0.0], [6.953791838461972, 0.0], [7.053791838461972, 0.0], [7.153791838461972, 0.0], [7.2537918384619715, 0.0], [7.353791838461972, 0.0], [7.453791838461973, 0.0], [7.553791838461972, 0.0], [7.653791838461972, 0.0], [7.753791838461972, 0.0], [7.853791838461973, 0.0], [7.953791838461973, 0.0], [8.053791838461972, 0.0], [8.153791838461974, 0.0], [8.253791838461973, 0.0], [8.353791838461973, 0.0], [8.453791838461973, 0.0], [8.553791838461972, 0.0], [8.653791838461974, 0.0], [8.753791838461973, 0.0], [8.853791838461973, 0.0], [8.953791838461974, 0.0], [9.053791838461972, 0.0], [9.153791838461974, 0.0], [9.253791838461972, 0.0], [9.353791838461973, 0.0], [9.45379183846197, 0.0], [9.553791838461972, 0.0], [9.65379183846197, 0.0], [9.753791838461972, 0.0], [9.85379183846197, 0.0], [9.95379183846197, 0.0], [10.053791838461969, 0.0], [10.15379183846197, 0.0], [10.253791838461968, 0.0], [10.35379183846197, 0.0], [10.453791838461967, 0.0], [10.553791838461969, 0.0], [10.653791838461967, 0.0], [10.753791838461968, 0.0], [10.853791838461966, 0.0], [10.953791838461967, 0.0], [11.053791838461965, 0.0], [11.153791838461967, 0.0], [11.253791838461964, 0.0], [11.353791838461966, 0.0], [11.453791838461964, 0.0], [11.553791838461965, 0.0], [11.653791838461963, 0.0], [11.753791838461964, 0.0], [11.853791838461962, 0.0], [11.953791838461964, 0.0], [12.053791838461962, 0.0], [12.153791838461963, 0.0], [12.25379183846196, 0.0], [12.353791838461962, 0.0], [12.45379183846196, 0.0], [12.553791838461962, 0.0], [12.65379183846196, 0.0], [12.75379183846196, 0.0], [12.853791838461959, 0.0], [12.95379183846196, 0.0], [13.05379183846196, 0.0], [13.15379183846196, 0.0], [13.253791838461959, 0.0], [13.353791838461959, 0.0], [13.453791838461958, 0.0], [13.553791838461958, 0.0], [13.653791838461958, 0.0], [13.753791838461959, 0.0], [13.853791838461957, 0.0], [13.953791838461958, 0.0], [14.053791838461956, 0.0], [14.153791838461958, 0.0], [14.253791838461956, 0.0], [14.353791838461957, 0.0], [14.453791838461955, 0.0], [14.553791838461956, 0.0], [14.653791838461954, 0.0], [14.753777460423034, 0.0], [14.843019092730643, 0.0], [14.912260725038252, 0.0], [14.96150235734586, 0.0], [14.990743989653469, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707], "velocities": null}}, "time": 1740481180.063619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4806328234723088, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.063619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.0836189} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.8789096, "x": 15.0, "y": 8.339999999999925, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.0836189} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49036940626947273, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.0836189} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1036189} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5098251152446635, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1036189} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1236188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5292574457982978, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1236188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1436188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5486662750219582, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1436188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1636188} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.223933206777517, 0.0], [5.310829294031899, 0.0], [5.4177253812862824, 0.0], [5.544621468540665, 0.0], [5.6915175557950475, 0.0], [5.853791838461971, 0.0], [5.953791838461971, 0.0], [6.053791838461971, 0.0], [6.153791838461971, 0.0], [6.2537918384619715, 0.0], [6.353791838461971, 0.0], [6.453791838461971, 0.0], [6.553791838461971, 0.0], [6.653791838461972, 0.0], [6.7537918384619715, 0.0], [6.853791838461971, 0.0], [6.953791838461972, 0.0], [7.053791838461972, 0.0], [7.153791838461972, 0.0], [7.2537918384619715, 0.0], [7.353791838461972, 0.0], [7.453791838461973, 0.0], [7.553791838461972, 0.0], [7.653791838461972, 0.0], [7.753791838461972, 0.0], [7.853791838461973, 0.0], [7.953791838461973, 0.0], [8.053791838461972, 0.0], [8.153791838461974, 0.0], [8.253791838461973, 0.0], [8.353791838461973, 0.0], [8.453791838461973, 0.0], [8.553791838461972, 0.0], [8.653791838461974, 0.0], [8.753791838461973, 0.0], [8.853791838461973, 0.0], [8.953791838461974, 0.0], [9.053791838461972, 0.0], [9.153791838461974, 0.0], [9.253791838461972, 0.0], [9.353791838461973, 0.0], [9.45379183846197, 0.0], [9.553791838461972, 0.0], [9.65379183846197, 0.0], [9.753791838461972, 0.0], [9.85379183846197, 0.0], [9.95379183846197, 0.0], [10.053791838461969, 0.0], [10.15379183846197, 0.0], [10.253791838461968, 0.0], [10.35379183846197, 0.0], [10.453791838461967, 0.0], [10.553791838461969, 0.0], [10.653791838461967, 0.0], [10.753791838461968, 0.0], [10.853791838461966, 0.0], [10.953791838461967, 0.0], [11.053791838461965, 0.0], [11.153791838461967, 0.0], [11.253791838461964, 0.0], [11.353791838461966, 0.0], [11.453791838461964, 0.0], [11.553791838461965, 0.0], [11.653791838461963, 0.0], [11.753791838461964, 0.0], [11.853791838461962, 0.0], [11.953791838461964, 0.0], [12.053791838461962, 0.0], [12.153791838461963, 0.0], [12.25379183846196, 0.0], [12.353791838461962, 0.0], [12.45379183846196, 0.0], [12.553791838461962, 0.0], [12.65379183846196, 0.0], [12.75379183846196, 0.0], [12.853791838461959, 0.0], [12.95379183846196, 0.0], [13.05379183846196, 0.0], [13.15379183846196, 0.0], [13.253791838461959, 0.0], [13.353791838461959, 0.0], [13.453791838461958, 0.0], [13.553791838461958, 0.0], [13.653791838461958, 0.0], [13.753791838461959, 0.0], [13.853791838461957, 0.0], [13.953791838461958, 0.0], [14.053791838461956, 0.0], [14.153791838461958, 0.0], [14.253791838461956, 0.0], [14.353791838461957, 0.0], [14.453791838461955, 0.0], [14.553791838461956, 0.0], [14.653791838461954, 0.0], [14.753777460423034, 0.0], [14.843019092730643, 0.0], [14.912260725038252, 0.0], [14.96150235734586, 0.0], [14.990743989653469, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707], "velocities": null}}, "time": 1740481180.1636188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5680514807028445, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1636188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.1736188, "x": 9.281079846967561, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.1836188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454354274936285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5874129413260665, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1836188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2036188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5884356301587572, "gear": 1, "accelerator_pedal_position": 0.2454354274936285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2036188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2236187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5893150112653633, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2236187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2436187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5901933061108833, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2436187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2636187} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.281079846967561, 0.0], [5.385423607894289, 0.0], [5.5097673688210165, 0.0], [5.654111129747744, 0.0], [5.815405396683446, 0.0], [5.915405396683447, 0.0], [6.015405396683446, 0.0], [6.115405396683446, 0.0], [6.215405396683447, 0.0], [6.315405396683446, 0.0], [6.415405396683447, 0.0], [6.515405396683446, 0.0], [6.615405396683446, 0.0], [6.715405396683447, 0.0], [6.815405396683447, 0.0], [6.915405396683447, 0.0], [7.015405396683446, 0.0], [7.115405396683447, 0.0], [7.2154053966834475, 0.0], [7.315405396683447, 0.0], [7.415405396683447, 0.0], [7.515405396683447, 0.0], [7.615405396683448, 0.0], [7.7154053966834475, 0.0], [7.815405396683447, 0.0], [7.915405396683448, 0.0], [8.015405396683448, 0.0], [8.115405396683448, 0.0], [8.215405396683447, 0.0], [8.315405396683449, 0.0], [8.415405396683449, 0.0], [8.515405396683448, 0.0], [8.615405396683448, 0.0], [8.715405396683447, 0.0], [8.815405396683449, 0.0], [8.915405396683449, 0.0], [9.015405396683448, 0.0], [9.11540539668345, 0.0], [9.215405396683447, 0.0], [9.315405396683449, 0.0], [9.415405396683447, 0.0], [9.515405396683448, 0.0], [9.615405396683446, 0.0], [9.715405396683447, 0.0], [9.815405396683445, 0.0], [9.915405396683447, 0.0], [10.015405396683445, 0.0], [10.115405396683446, 0.0], [10.215405396683444, 0.0], [10.315405396683445, 0.0], [10.415405396683443, 0.0], [10.515405396683445, 0.0], [10.615405396683443, 0.0], [10.715405396683444, 0.0], [10.815405396683442, 0.0], [10.915405396683443, 0.0], [11.015405396683441, 0.0], [11.115405396683443, 0.0], [11.21540539668344, 0.0], [11.315405396683442, 0.0], [11.41540539668344, 0.0], [11.515405396683441, 0.0], [11.615405396683439, 0.0], [11.71540539668344, 0.0], [11.815405396683438, 0.0], [11.91540539668344, 0.0], [12.015405396683438, 0.0], [12.115405396683439, 0.0], [12.215405396683437, 0.0], [12.315405396683438, 0.0], [12.415405396683436, 0.0], [12.515405396683438, 0.0], [12.615405396683435, 0.0], [12.715405396683437, 0.0], [12.815405396683435, 0.0], [12.915405396683436, 0.0], [13.015405396683434, 0.0], [13.115405396683435, 0.0], [13.215405396683433, 0.0], [13.315405396683435, 0.0], [13.415405396683433, 0.0], [13.515405396683434, 0.0], [13.615405396683432, 0.0], [13.715405396683433, 0.0], [13.815405396683431, 0.0], [13.915405396683433, 0.0], [14.01540539668343, 0.0], [14.115405396683432, 0.0], [14.21540539668343, 0.0], [14.315405396683431, 0.0], [14.415405396683429, 0.0], [14.51540539668343, 0.0], [14.615405396683428, 0.0], [14.71540539668343, 0.0], [14.811127530768111, 0.0], [14.888046451431425, 0.0], [14.944965372094739, 0.0], [14.981884292758055, 0.0], [14.998803213421368, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161], "velocities": null}}, "time": 1740481180.2636187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5910705157286623, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2636187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.2836187, "x": 9.345806859456825, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.2836187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5916341429304511, "gear": 1, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2836187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3036187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6109665145330997, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3036187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3236187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6302748740379055, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3236187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3436186} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.2090857, "x": 15.0, "y": 8.504999999999951, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.3436186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6495591021910521, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3436186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3636186} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.345806859456825, 0.0], [5.452420310429389, 0.0], [5.579033761401953, 0.0], [5.725647212374517, 0.0], [5.887829008718908, 0.0], [5.987829008718908, 0.0], [6.0878290087189075, 0.0], [6.187829008718908, 0.0], [6.287829008718908, 0.0], [6.387829008718908, 0.0], [6.487829008718908, 0.0], [6.587829008718908, 0.0], [6.687829008718908, 0.0], [6.787829008718909, 0.0], [6.887829008718908, 0.0], [6.987829008718909, 0.0], [7.087829008718908, 0.0], [7.187829008718909, 0.0], [7.287829008718909, 0.0], [7.387829008718908, 0.0], [7.487829008718909, 0.0], [7.587829008718909, 0.0], [7.687829008718909, 0.0], [7.787829008718909, 0.0], [7.887829008718909, 0.0], [7.98782900871891, 0.0], [8.08782900871891, 0.0], [8.187829008718909, 0.0], [8.287829008718909, 0.0], [8.38782900871891, 0.0], [8.48782900871891, 0.0], [8.58782900871891, 0.0], [8.68782900871891, 0.0], [8.78782900871891, 0.0], [8.88782900871891, 0.0], [8.98782900871891, 0.0], [9.08782900871891, 0.0], [9.18782900871891, 0.0], [9.28782900871891, 0.0], [9.38782900871891, 0.0], [9.48782900871891, 0.0], [9.58782900871891, 0.0], [9.687829008718909, 0.0], [9.787829008718909, 0.0], [9.887829008718908, 0.0], [9.987829008718908, 0.0], [10.087829008718908, 0.0], [10.187829008718907, 0.0], [10.287829008718907, 0.0], [10.387829008718906, 0.0], [10.487829008718906, 0.0], [10.587829008718906, 0.0], [10.687829008718905, 0.0], [10.787829008718905, 0.0], [10.887829008718905, 0.0], [10.987829008718904, 0.0], [11.087829008718904, 0.0], [11.187829008718904, 0.0], [11.287829008718903, 0.0], [11.387829008718903, 0.0], [11.487829008718903, 0.0], [11.587829008718902, 0.0], [11.687829008718902, 0.0], [11.787829008718901, 0.0], [11.887829008718901, 0.0], [11.9878290087189, 0.0], [12.0878290087189, 0.0], [12.1878290087189, 0.0], [12.2878290087189, 0.0], [12.3878290087189, 0.0], [12.487829008718899, 0.0], [12.587829008718899, 0.0], [12.687829008718898, 0.0], [12.787829008718898, 0.0], [12.887829008718898, 0.0], [12.987829008718897, 0.0], [13.087829008718897, 0.0], [13.187829008718897, 0.0], [13.287829008718896, 0.0], [13.387829008718896, 0.0], [13.487829008718895, 0.0], [13.587829008718895, 0.0], [13.687829008718895, 0.0], [13.787829008718893, 0.0], [13.887829008718892, 0.0], [13.987829008718892, 0.0], [14.087829008718892, 0.0], [14.187829008718891, 0.0], [14.28782900871889, 0.0], [14.38782900871889, 0.0], [14.48782900871889, 0.0], [14.58782900871889, 0.0], [14.68782900871889, 0.0], [14.786397974818236, 0.0], [14.868832173074457, 0.0], [14.931266371330679, 0.0], [14.973700569586901, 0.0], [14.996134767843124, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162], "velocities": null}}, "time": 1740481180.3636186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6688190804458469, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3636186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3836186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6692853946255112, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3836186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.3936186, "x": 9.41591316533819, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4036186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38367217910766993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6697511178611791, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4036186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4236186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38933648902881296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6879448987322853, "gear": 1, "accelerator_pedal_position": 0.38367217910766993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4236186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4436185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38933648902881296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7068233321472241, "gear": 1, "accelerator_pedal_position": 0.38933648902881296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4436185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4636185} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.415913165338189, 0.0], [5.5352450508123, 0.0], [5.67457693628641, 0.0], [5.832999024454987, 0.0], [5.932999024454988, 0.0], [6.032999024454988, 0.0], [6.132999024454987, 0.0], [6.232999024454988, 0.0], [6.332999024454987, 0.0], [6.432999024454988, 0.0], [6.532999024454988, 0.0], [6.632999024454988, 0.0], [6.732999024454988, 0.0], [6.832999024454988, 0.0], [6.932999024454988, 0.0], [7.0329990244549885, 0.0], [7.132999024454988, 0.0], [7.232999024454989, 0.0], [7.332999024454988, 0.0], [7.432999024454988, 0.0], [7.5329990244549885, 0.0], [7.632999024454989, 0.0], [7.732999024454989, 0.0], [7.832999024454988, 0.0], [7.932999024454989, 0.0], [8.03299902445499, 0.0], [8.132999024454989, 0.0], [8.232999024454989, 0.0], [8.332999024454988, 0.0], [8.43299902445499, 0.0], [8.53299902445499, 0.0], [8.632999024454989, 0.0], [8.73299902445499, 0.0], [8.83299902445499, 0.0], [8.93299902445499, 0.0], [9.03299902445499, 0.0], [9.132999024454989, 0.0], [9.23299902445499, 0.0], [9.33299902445499, 0.0], [9.43299902445499, 0.0], [9.532999024454991, 0.0], [9.632999024454989, 0.0], [9.73299902445499, 0.0], [9.832999024454988, 0.0], [9.93299902445499, 0.0], [10.032999024454988, 0.0], [10.132999024454989, 0.0], [10.232999024454987, 0.0], [10.332999024454988, 0.0], [10.432999024454986, 0.0], [10.532999024454988, 0.0], [10.632999024454985, 0.0], [10.732999024454987, 0.0], [10.832999024454985, 0.0], [10.932999024454986, 0.0], [11.032999024454984, 0.0], [11.132999024454985, 0.0], [11.232999024454983, 0.0], [11.332999024454985, 0.0], [11.432999024454983, 0.0], [11.532999024454984, 0.0], [11.632999024454982, 0.0], [11.732999024454983, 0.0], [11.832999024454981, 0.0], [11.932999024454983, 0.0], [12.03299902445498, 0.0], [12.132999024454982, 0.0], [12.23299902445498, 0.0], [12.332999024454981, 0.0], [12.432999024454979, 0.0], [12.53299902445498, 0.0], [12.632999024454978, 0.0], [12.73299902445498, 0.0], [12.832999024454978, 0.0], [12.932999024454979, 0.0], [13.032999024454977, 0.0], [13.132999024454978, 0.0], [13.232999024454976, 0.0], [13.332999024454978, 0.0], [13.432999024454976, 0.0], [13.532999024454975, 0.0], [13.632999024454975, 0.0], [13.732999024454974, 0.0], [13.832999024454974, 0.0], [13.932999024454974, 0.0], [14.032999024454973, 0.0], [14.132999024454973, 0.0], [14.232999024454973, 0.0], [14.332999024454972, 0.0], [14.432999024454972, 0.0], [14.532999024454972, 0.0], [14.632999024454971, 0.0], [14.732999024454971, 0.0], [14.826110186394494, 0.0], [14.8995103815035, 0.0], [14.952910576612505, 0.0], [14.986310771721511, 0.0], [14.999710966830516, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618], "velocities": null}}, "time": 1740481180.4636185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7258744658778239, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4636185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4836185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7260712117065594, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4836185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.5036185, "x": 9.493217368318382, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5036185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38854506948249906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.726464322620177, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5036185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5236185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7451943879823668, "gear": 1, "accelerator_pedal_position": 0.38854506948249906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5236185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5436184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7643319089805063, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5436184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5636184} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.493217368318382, 0.0], [5.621848495435452, 0.0], [5.770479622552522, 0.0], [5.933234139008592, 0.0], [6.0332341390085915, 0.0], [6.133234139008591, 0.0], [6.233234139008592, 0.0], [6.333234139008591, 0.0], [6.433234139008592, 0.0], [6.5332341390085915, 0.0], [6.633234139008591, 0.0], [6.733234139008592, 0.0], [6.833234139008592, 0.0], [6.933234139008592, 0.0], [7.0332341390085915, 0.0], [7.133234139008592, 0.0], [7.233234139008593, 0.0], [7.333234139008592, 0.0], [7.433234139008592, 0.0], [7.533234139008592, 0.0], [7.633234139008593, 0.0], [7.733234139008593, 0.0], [7.833234139008592, 0.0], [7.933234139008593, 0.0], [8.033234139008593, 0.0], [8.133234139008593, 0.0], [8.233234139008593, 0.0], [8.333234139008592, 0.0], [8.433234139008594, 0.0], [8.533234139008593, 0.0], [8.633234139008593, 0.0], [8.733234139008594, 0.0], [8.833234139008594, 0.0], [8.933234139008594, 0.0], [9.033234139008593, 0.0], [9.133234139008593, 0.0], [9.233234139008594, 0.0], [9.333234139008594, 0.0], [9.433234139008594, 0.0], [9.533234139008595, 0.0], [9.633234139008593, 0.0], [9.733234139008594, 0.0], [9.833234139008592, 0.0], [9.933234139008594, 0.0], [10.033234139008592, 0.0], [10.133234139008593, 0.0], [10.23323413900859, 0.0], [10.333234139008592, 0.0], [10.43323413900859, 0.0], [10.533234139008592, 0.0], [10.63323413900859, 0.0], [10.73323413900859, 0.0], [10.833234139008589, 0.0], [10.93323413900859, 0.0], [11.033234139008588, 0.0], [11.13323413900859, 0.0], [11.233234139008587, 0.0], [11.333234139008589, 0.0], [11.433234139008587, 0.0], [11.533234139008588, 0.0], [11.633234139008586, 0.0], [11.733234139008587, 0.0], [11.833234139008585, 0.0], [11.933234139008587, 0.0], [12.033234139008584, 0.0], [12.133234139008586, 0.0], [12.233234139008584, 0.0], [12.333234139008585, 0.0], [12.433234139008583, 0.0], [12.533234139008584, 0.0], [12.633234139008582, 0.0], [12.733234139008584, 0.0], [12.833234139008582, 0.0], [12.933234139008583, 0.0], [13.03323413900858, 0.0], [13.133234139008582, 0.0], [13.23323413900858, 0.0], [13.333234139008582, 0.0], [13.43323413900858, 0.0], [13.533234139008579, 0.0], [13.633234139008579, 0.0], [13.733234139008578, 0.0], [13.83323413900858, 0.0], [13.933234139008578, 0.0], [14.033234139008579, 0.0], [14.133234139008577, 0.0], [14.233234139008578, 0.0], [14.333234139008576, 0.0], [14.433234139008578, 0.0], [14.533234139008576, 0.0], [14.633234139008577, 0.0], [14.733234139008575, 0.0], [14.826306217112077, 0.0], [14.899659389310361, 0.0], [14.953012561508645, 0.0], [14.986365733706931, 0.0], [14.999718905905215, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618], "velocities": null}}, "time": 1740481180.5636184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7834444862600229, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5636184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5836184} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.4290733, "x": 15.0, "y": 8.614999999999968, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.5836184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7837629249980725, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5836184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.6036184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7840809456126807, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6036184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.6136184, "x": 9.577410315180376, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6236184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3883520258497558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7843985486124194, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6236184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6436183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8030289674101166, "gear": 1, "accelerator_pedal_position": 0.3883520258497558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6436183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6636183} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.577410315180376, 0.0], [5.715476138128722, 0.0], [5.8729739714090705, 0.0], [5.972973971409071, 0.0], [6.072973971409071, 0.0], [6.17297397140907, 0.0], [6.272973971409071, 0.0], [6.3729739714090705, 0.0], [6.47297397140907, 0.0], [6.572973971409071, 0.0], [6.67297397140907, 0.0], [6.772973971409071, 0.0], [6.8729739714090705, 0.0], [6.972973971409071, 0.0], [7.072973971409071, 0.0], [7.172973971409071, 0.0], [7.272973971409071, 0.0], [7.372973971409071, 0.0], [7.472973971409071, 0.0], [7.572973971409072, 0.0], [7.672973971409071, 0.0], [7.772973971409071, 0.0], [7.872973971409071, 0.0], [7.972973971409072, 0.0], [8.072973971409072, 0.0], [8.172973971409071, 0.0], [8.272973971409073, 0.0], [8.372973971409072, 0.0], [8.472973971409072, 0.0], [8.572973971409073, 0.0], [8.672973971409071, 0.0], [8.772973971409073, 0.0], [8.872973971409072, 0.0], [8.972973971409072, 0.0], [9.072973971409073, 0.0], [9.172973971409073, 0.0], [9.272973971409073, 0.0], [9.372973971409074, 0.0], [9.472973971409072, 0.0], [9.572973971409073, 0.0], [9.672973971409071, 0.0], [9.772973971409073, 0.0], [9.87297397140907, 0.0], [9.972973971409072, 0.0], [10.07297397140907, 0.0], [10.172973971409071, 0.0], [10.272973971409069, 0.0], [10.37297397140907, 0.0], [10.472973971409068, 0.0], [10.57297397140907, 0.0], [10.672973971409068, 0.0], [10.772973971409069, 0.0], [10.872973971409067, 0.0], [10.972973971409068, 0.0], [11.072973971409066, 0.0], [11.172973971409068, 0.0], [11.272973971409066, 0.0], [11.372973971409067, 0.0], [11.472973971409065, 0.0], [11.572973971409066, 0.0], [11.672973971409064, 0.0], [11.772973971409066, 0.0], [11.872973971409063, 0.0], [11.972973971409065, 0.0], [12.072973971409063, 0.0], [12.172973971409064, 0.0], [12.272973971409062, 0.0], [12.372973971409063, 0.0], [12.472973971409061, 0.0], [12.572973971409063, 0.0], [12.67297397140906, 0.0], [12.772973971409062, 0.0], [12.87297397140906, 0.0], [12.972973971409061, 0.0], [13.07297397140906, 0.0], [13.17297397140906, 0.0], [13.272973971409058, 0.0], [13.37297397140906, 0.0], [13.472973971409058, 0.0], [13.57297397140906, 0.0], [13.672973971409057, 0.0], [13.772973971409057, 0.0], [13.872973971409056, 0.0], [13.972973971409056, 0.0], [14.072973971409056, 0.0], [14.172973971409055, 0.0], [14.272973971409055, 0.0], [14.372973971409055, 0.0], [14.472973971409054, 0.0], [14.572973971409054, 0.0], [14.672973971409053, 0.0], [14.772446168046748, 0.0], [14.857851373764937, 0.0], [14.923256579483127, 0.0], [14.968661785201316, 0.0], [14.994066990919507, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072], "velocities": null}}, "time": 1740481180.6636183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8220906600328797, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6636183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6836183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.822358058769981, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6836183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.7036183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8226251022745532, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7036183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.7236183, "x": 9.66653526964325, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7236183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8228917909899981, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7236183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7436182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8419271326108738, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7436182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7636182} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.66653526964325, 0.0], [5.8109129364066145, 0.0], [5.972222356881853, 0.0], [6.072222356881853, 0.0], [6.1722223568818535, 0.0], [6.272222356881853, 0.0], [6.372222356881853, 0.0], [6.472222356881853, 0.0], [6.572222356881853, 0.0], [6.672222356881853, 0.0], [6.772222356881853, 0.0], [6.872222356881853, 0.0], [6.972222356881853, 0.0], [7.072222356881853, 0.0], [7.1722223568818535, 0.0], [7.272222356881853, 0.0], [7.372222356881854, 0.0], [7.472222356881853, 0.0], [7.572222356881854, 0.0], [7.6722223568818535, 0.0], [7.772222356881853, 0.0], [7.872222356881854, 0.0], [7.972222356881854, 0.0], [8.072222356881854, 0.0], [8.172222356881853, 0.0], [8.272222356881855, 0.0], [8.372222356881855, 0.0], [8.472222356881854, 0.0], [8.572222356881854, 0.0], [8.672222356881853, 0.0], [8.772222356881855, 0.0], [8.872222356881855, 0.0], [8.972222356881854, 0.0], [9.072222356881856, 0.0], [9.172222356881855, 0.0], [9.272222356881855, 0.0], [9.372222356881855, 0.0], [9.472222356881854, 0.0], [9.572222356881856, 0.0], [9.672222356881855, 0.0], [9.772222356881855, 0.0], [9.872222356881855, 0.0], [9.972222356881854, 0.0], [10.072222356881852, 0.0], [10.172222356881853, 0.0], [10.272222356881851, 0.0], [10.372222356881853, 0.0], [10.47222235688185, 0.0], [10.572222356881852, 0.0], [10.67222235688185, 0.0], [10.772222356881851, 0.0], [10.87222235688185, 0.0], [10.97222235688185, 0.0], [11.072222356881849, 0.0], [11.17222235688185, 0.0], [11.272222356881848, 0.0], [11.37222235688185, 0.0], [11.472222356881847, 0.0], [11.572222356881849, 0.0], [11.672222356881846, 0.0], [11.772222356881848, 0.0], [11.872222356881846, 0.0], [11.972222356881847, 0.0], [12.072222356881845, 0.0], [12.172222356881846, 0.0], [12.272222356881844, 0.0], [12.372222356881846, 0.0], [12.472222356881844, 0.0], [12.572222356881845, 0.0], [12.672222356881843, 0.0], [12.772222356881844, 0.0], [12.872222356881842, 0.0], [12.972222356881844, 0.0], [13.072222356881841, 0.0], [13.172222356881843, 0.0], [13.27222235688184, 0.0], [13.372222356881842, 0.0], [13.47222235688184, 0.0], [13.572222356881841, 0.0], [13.672222356881841, 0.0], [13.77222235688184, 0.0], [13.87222235688184, 0.0], [13.97222235688184, 0.0], [14.07222235688184, 0.0], [14.17222235688184, 0.0], [14.272222356881839, 0.0], [14.372222356881839, 0.0], [14.472222356881838, 0.0], [14.572222356881838, 0.0], [14.672222356881838, 0.0], [14.771728523736453, 0.0], [14.857284052360086, 0.0], [14.922839580983718, 0.0], [14.96839510960735, 0.0], [14.993950638230983, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073], "velocities": null}}, "time": 1740481180.7636182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8609370730680085, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7636182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7836182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8611525658862832, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7836182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.8036182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8613677690848842, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8036182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.8236182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8615826830345381, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8236182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.8336182, "x": 9.760310142154793, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.8436182} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.6489406, "x": 15.0, "y": 8.724999999999985, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.8436182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8617973081055478, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8436182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.8636181} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.760310142154793, 0.0], [5.9110235350882405, 0.0], [6.074155676297142, 0.0], [6.174155676297143, 0.0], [6.274155676297142, 0.0], [6.374155676297143, 0.0], [6.474155676297142, 0.0], [6.574155676297142, 0.0], [6.674155676297143, 0.0], [6.774155676297142, 0.0], [6.874155676297143, 0.0], [6.974155676297142, 0.0], [7.074155676297142, 0.0], [7.174155676297143, 0.0], [7.274155676297143, 0.0], [7.374155676297143, 0.0], [7.474155676297142, 0.0], [7.574155676297143, 0.0], [7.6741556762971435, 0.0], [7.774155676297143, 0.0], [7.874155676297143, 0.0], [7.974155676297143, 0.0], [8.074155676297144, 0.0], [8.174155676297143, 0.0], [8.274155676297143, 0.0], [8.374155676297143, 0.0], [8.474155676297144, 0.0], [8.574155676297144, 0.0], [8.674155676297143, 0.0], [8.774155676297145, 0.0], [8.874155676297145, 0.0], [8.974155676297144, 0.0], [9.074155676297144, 0.0], [9.174155676297143, 0.0], [9.274155676297145, 0.0], [9.374155676297145, 0.0], [9.474155676297144, 0.0], [9.574155676297146, 0.0], [9.674155676297145, 0.0], [9.774155676297145, 0.0], [9.874155676297143, 0.0], [9.974155676297144, 0.0], [10.074155676297144, 0.0], [10.174155676297143, 0.0], [10.274155676297143, 0.0], [10.374155676297143, 0.0], [10.474155676297142, 0.0], [10.574155676297142, 0.0], [10.674155676297142, 0.0], [10.774155676297141, 0.0], [10.874155676297141, 0.0], [10.97415567629714, 0.0], [11.07415567629714, 0.0], [11.17415567629714, 0.0], [11.27415567629714, 0.0], [11.37415567629714, 0.0], [11.474155676297139, 0.0], [11.574155676297138, 0.0], [11.674155676297138, 0.0], [11.774155676297138, 0.0], [11.874155676297137, 0.0], [11.974155676297137, 0.0], [12.074155676297137, 0.0], [12.174155676297136, 0.0], [12.274155676297136, 0.0], [12.374155676297136, 0.0], [12.474155676297135, 0.0], [12.574155676297135, 0.0], [12.674155676297135, 0.0], [12.774155676297134, 0.0], [12.874155676297134, 0.0], [12.974155676297134, 0.0], [13.074155676297133, 0.0], [13.174155676297133, 0.0], [13.274155676297132, 0.0], [13.374155676297132, 0.0], [13.474155676297132, 0.0], [13.574155676297131, 0.0], [13.674155676297131, 0.0], [13.77415567629713, 0.0], [13.87415567629713, 0.0], [13.97415567629713, 0.0], [14.07415567629713, 0.0], [14.17415567629713, 0.0], [14.274155676297129, 0.0], [14.374155676297129, 0.0], [14.474155676297128, 0.0], [14.574155676297128, 0.0], [14.674155676297127, 0.0], [14.773572179599755, 0.0], [14.85874104434033, 0.0], [14.923909909080905, 0.0], [14.96907877382148, 0.0], [14.994247638562054, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073], "velocities": null}}, "time": 1740481180.8636181} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8902626111898707, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8636181} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.883618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8903505955682833, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.883618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.903618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8905263853876026, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.903618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.923618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8907019368828357, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.923618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.943618, "x": 9.857402581377343, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.943618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35668368121407473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8908772503647633, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.943618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.963618} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.857402581377343, 0.0], [6.012763381237585, 0.0], [6.112763381237586, 0.0], [6.212763381237585, 0.0], [6.312763381237586, 0.0], [6.4127633812375855, 0.0], [6.512763381237585, 0.0], [6.612763381237586, 0.0], [6.712763381237585, 0.0], [6.812763381237585, 0.0], [6.9127633812375855, 0.0], [7.012763381237585, 0.0], [7.112763381237585, 0.0], [7.212763381237585, 0.0], [7.312763381237586, 0.0], [7.4127633812375855, 0.0], [7.512763381237585, 0.0], [7.612763381237586, 0.0], [7.712763381237586, 0.0], [7.812763381237586, 0.0], [7.9127633812375855, 0.0], [8.012763381237587, 0.0], [8.112763381237587, 0.0], [8.212763381237586, 0.0], [8.312763381237588, 0.0], [8.412763381237587, 0.0], [8.512763381237587, 0.0], [8.612763381237587, 0.0], [8.712763381237586, 0.0], [8.812763381237588, 0.0], [8.912763381237587, 0.0], [9.012763381237587, 0.0], [9.112763381237588, 0.0], [9.212763381237588, 0.0], [9.312763381237588, 0.0], [9.412763381237587, 0.0], [9.512763381237587, 0.0], [9.612763381237588, 0.0], [9.712763381237588, 0.0], [9.812763381237588, 0.0], [9.912763381237589, 0.0], [10.012763381237587, 0.0], [10.112763381237587, 0.0], [10.212763381237586, 0.0], [10.312763381237586, 0.0], [10.412763381237585, 0.0], [10.512763381237585, 0.0], [10.612763381237585, 0.0], [10.712763381237584, 0.0], [10.812763381237584, 0.0], [10.912763381237584, 0.0], [11.012763381237583, 0.0], [11.112763381237583, 0.0], [11.212763381237583, 0.0], [11.312763381237582, 0.0], [11.412763381237582, 0.0], [11.512763381237582, 0.0], [11.612763381237581, 0.0], [11.71276338123758, 0.0], [11.81276338123758, 0.0], [11.91276338123758, 0.0], [12.01276338123758, 0.0], [12.11276338123758, 0.0], [12.212763381237579, 0.0], [12.312763381237579, 0.0], [12.412763381237578, 0.0], [12.512763381237578, 0.0], [12.612763381237578, 0.0], [12.712763381237577, 0.0], [12.812763381237577, 0.0], [12.912763381237577, 0.0], [13.012763381237576, 0.0], [13.112763381237576, 0.0], [13.212763381237576, 0.0], [13.312763381237575, 0.0], [13.412763381237575, 0.0], [13.512763381237574, 0.0], [13.612763381237574, 0.0], [13.712763381237574, 0.0], [13.812763381237573, 0.0], [13.912763381237573, 0.0], [14.012763381237574, 0.0], [14.112763381237574, 0.0], [14.212763381237574, 0.0], [14.312763381237573, 0.0], [14.412763381237573, 0.0], [14.512763381237573, 0.0], [14.612763381237572, 0.0], [14.712763381237572, 0.0], [14.808824139213199, 0.0], [14.886271462965684, 0.0], [14.94371878671817, 0.0], [14.981166110470655, 0.0], [14.998613434223142, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529], "velocities": null}}, "time": 1740481180.963618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9054785807608252, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.963618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.983618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9055489469629818, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.983618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.003618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9057597581363629, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.003618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.023618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9059000597073356, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.023618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.043618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9059701388242228, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.043618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.053618, "x": 9.956804849483587, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.063618} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.9568048494835875, 0.0], [6.114218532592286, 0.0], [6.2142185325922865, 0.0], [6.314218532592286, 0.0], [6.414218532592286, 0.0], [6.514218532592286, 0.0], [6.614218532592286, 0.0], [6.7142185325922865, 0.0], [6.814218532592286, 0.0], [6.914218532592286, 0.0], [7.014218532592286, 0.0], [7.114218532592286, 0.0], [7.214218532592286, 0.0], [7.314218532592286, 0.0], [7.414218532592287, 0.0], [7.514218532592286, 0.0], [7.614218532592286, 0.0], [7.7142185325922865, 0.0], [7.814218532592287, 0.0], [7.914218532592287, 0.0], [8.014218532592286, 0.0], [8.114218532592288, 0.0], [8.214218532592287, 0.0], [8.314218532592287, 0.0], [8.414218532592287, 0.0], [8.514218532592288, 0.0], [8.614218532592288, 0.0], [8.714218532592287, 0.0], [8.814218532592289, 0.0], [8.914218532592288, 0.0], [9.014218532592288, 0.0], [9.114218532592288, 0.0], [9.214218532592287, 0.0], [9.314218532592289, 0.0], [9.414218532592288, 0.0], [9.514218532592288, 0.0], [9.61421853259229, 0.0], [9.71421853259229, 0.0], [9.814218532592289, 0.0], [9.914218532592288, 0.0], [10.014218532592288, 0.0], [10.11421853259229, 0.0], [10.214218532592287, 0.0], [10.314218532592289, 0.0], [10.414218532592287, 0.0], [10.514218532592288, 0.0], [10.614218532592286, 0.0], [10.714218532592287, 0.0], [10.814218532592285, 0.0], [10.914218532592287, 0.0], [11.014218532592285, 0.0], [11.114218532592286, 0.0], [11.214218532592284, 0.0], [11.314218532592285, 0.0], [11.414218532592283, 0.0], [11.514218532592285, 0.0], [11.614218532592282, 0.0], [11.714218532592284, 0.0], [11.814218532592282, 0.0], [11.914218532592283, 0.0], [12.014218532592281, 0.0], [12.114218532592282, 0.0], [12.21421853259228, 0.0], [12.314218532592282, 0.0], [12.41421853259228, 0.0], [12.514218532592281, 0.0], [12.614218532592279, 0.0], [12.71421853259228, 0.0], [12.814218532592278, 0.0], [12.91421853259228, 0.0], [13.014218532592277, 0.0], [13.114218532592279, 0.0], [13.214218532592277, 0.0], [13.314218532592278, 0.0], [13.414218532592276, 0.0], [13.514218532592277, 0.0], [13.614218532592275, 0.0], [13.714218532592277, 0.0], [13.814218532592275, 0.0], [13.914218532592276, 0.0], [14.014218532592274, 0.0], [14.114218532592274, 0.0], [14.214218532592273, 0.0], [14.314218532592273, 0.0], [14.414218532592272, 0.0], [14.514218532592272, 0.0], [14.614218532592272, 0.0], [14.714218532592271, 0.0], [14.810094512663966, 0.0], [14.887250806145513, 0.0], [14.944407099627059, 0.0], [14.981563393108603, 0.0], [14.99871968659015, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553], "velocities": null}}, "time": 1740481181.063618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.298745562766616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9061800898791028, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.063618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.083618} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.9801464, "x": 15.0, "y": 8.890000000000011, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.083618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9098164812715475, "gear": 1, "accelerator_pedal_position": 0.298745562766616, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.083618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.103618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9171053796555569, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.103618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.123618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9243843239813849, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.123618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.1436179} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9316533066567959, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1436179} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.1636178, "x": 10.057792872457066, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.1636178} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.057792872457066, 0.0], [6.218604385559311, 0.0], [6.318604385559311, 0.0], [6.418604385559311, 0.0], [6.5186043855593105, 0.0], [6.618604385559311, 0.0], [6.718604385559311, 0.0], [6.818604385559311, 0.0], [6.918604385559311, 0.0], [7.0186043855593105, 0.0], [7.11860438555931, 0.0], [7.218604385559311, 0.0], [7.318604385559311, 0.0], [7.418604385559311, 0.0], [7.5186043855593105, 0.0], [7.618604385559311, 0.0], [7.718604385559312, 0.0], [7.818604385559311, 0.0], [7.918604385559311, 0.0], [8.01860438555931, 0.0], [8.118604385559312, 0.0], [8.218604385559312, 0.0], [8.318604385559311, 0.0], [8.418604385559313, 0.0], [8.518604385559312, 0.0], [8.618604385559312, 0.0], [8.718604385559312, 0.0], [8.818604385559311, 0.0], [8.918604385559313, 0.0], [9.018604385559312, 0.0], [9.118604385559312, 0.0], [9.218604385559313, 0.0], [9.318604385559313, 0.0], [9.418604385559313, 0.0], [9.518604385559312, 0.0], [9.618604385559312, 0.0], [9.718604385559313, 0.0], [9.818604385559313, 0.0], [9.918604385559313, 0.0], [10.018604385559314, 0.0], [10.118604385559314, 0.0], [10.218604385559313, 0.0], [10.318604385559313, 0.0], [10.418604385559313, 0.0], [10.518604385559312, 0.0], [10.618604385559312, 0.0], [10.718604385559312, 0.0], [10.818604385559311, 0.0], [10.918604385559311, 0.0], [11.01860438555931, 0.0], [11.11860438555931, 0.0], [11.21860438555931, 0.0], [11.31860438555931, 0.0], [11.41860438555931, 0.0], [11.518604385559309, 0.0], [11.618604385559308, 0.0], [11.718604385559308, 0.0], [11.818604385559308, 0.0], [11.918604385559307, 0.0], [12.018604385559307, 0.0], [12.118604385559307, 0.0], [12.218604385559306, 0.0], [12.318604385559306, 0.0], [12.418604385559306, 0.0], [12.518604385559305, 0.0], [12.618604385559305, 0.0], [12.718604385559305, 0.0], [12.818604385559304, 0.0], [12.918604385559304, 0.0], [13.018604385559303, 0.0], [13.118604385559303, 0.0], [13.218604385559303, 0.0], [13.318604385559302, 0.0], [13.418604385559302, 0.0], [13.518604385559302, 0.0], [13.618604385559301, 0.0], [13.718604385559301, 0.0], [13.8186043855593, 0.0], [13.9186043855593, 0.0], [14.0186043855593, 0.0], [14.1186043855593, 0.0], [14.2186043855593, 0.0], [14.318604385559299, 0.0], [14.418604385559298, 0.0], [14.518604385559298, 0.0], [14.618604385559298, 0.0], [14.718604385559297, 0.0], [14.813897823841328, 0.0], [14.890176946729468, 0.0], [14.946456069617609, 0.0], [14.98273519250575, 0.0], [14.999014315393891, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553], "velocities": null}}, "time": 1740481181.1636178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628344429858715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389123201868808, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1636178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.1836178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9416504598371546, "gear": 1, "accelerator_pedal_position": 0.2628344429858715, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1836178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2036178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.944494474166722, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2036178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2236178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9473345721779124, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2236178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2436178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9501707560382973, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2436178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2636178} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.057792872457066, 0.0], [6.218604385559311, 0.0], [6.318604385559311, 0.0], [6.418604385559311, 0.0], [6.5186043855593105, 0.0], [6.618604385559311, 0.0], [6.718604385559311, 0.0], [6.818604385559311, 0.0], [6.918604385559311, 0.0], [7.0186043855593105, 0.0], [7.11860438555931, 0.0], [7.218604385559311, 0.0], [7.318604385559311, 0.0], [7.418604385559311, 0.0], [7.5186043855593105, 0.0], [7.618604385559311, 0.0], [7.718604385559312, 0.0], [7.818604385559311, 0.0], [7.918604385559311, 0.0], [8.01860438555931, 0.0], [8.118604385559312, 0.0], [8.218604385559312, 0.0], [8.318604385559311, 0.0], [8.418604385559313, 0.0], [8.518604385559312, 0.0], [8.618604385559312, 0.0], [8.718604385559312, 0.0], [8.818604385559311, 0.0], [8.918604385559313, 0.0], [9.018604385559312, 0.0], [9.118604385559312, 0.0], [9.218604385559313, 0.0], [9.318604385559313, 0.0], [9.418604385559313, 0.0], [9.518604385559312, 0.0], [9.618604385559312, 0.0], [9.718604385559313, 0.0], [9.818604385559313, 0.0], [9.918604385559313, 0.0], [10.018604385559314, 0.0], [10.118604385559314, 0.0], [10.218604385559313, 0.0], [10.318604385559313, 0.0], [10.418604385559313, 0.0], [10.518604385559312, 0.0], [10.618604385559312, 0.0], [10.718604385559312, 0.0], [10.818604385559311, 0.0], [10.918604385559311, 0.0], [11.01860438555931, 0.0], [11.11860438555931, 0.0], [11.21860438555931, 0.0], [11.31860438555931, 0.0], [11.41860438555931, 0.0], [11.518604385559309, 0.0], [11.618604385559308, 0.0], [11.718604385559308, 0.0], [11.818604385559308, 0.0], [11.918604385559307, 0.0], [12.018604385559307, 0.0], [12.118604385559307, 0.0], [12.218604385559306, 0.0], [12.318604385559306, 0.0], [12.418604385559306, 0.0], [12.518604385559305, 0.0], [12.618604385559305, 0.0], [12.718604385559305, 0.0], [12.818604385559304, 0.0], [12.918604385559304, 0.0], [13.018604385559303, 0.0], [13.118604385559303, 0.0], [13.218604385559303, 0.0], [13.318604385559302, 0.0], [13.418604385559302, 0.0], [13.518604385559302, 0.0], [13.618604385559301, 0.0], [13.718604385559301, 0.0], [13.8186043855593, 0.0], [13.9186043855593, 0.0], [14.0186043855593, 0.0], [14.1186043855593, 0.0], [14.2186043855593, 0.0], [14.318604385559299, 0.0], [14.418604385559298, 0.0], [14.518604385559298, 0.0], [14.618604385559298, 0.0], [14.718604385559297, 0.0], [14.813897823841328, 0.0], [14.890176946729468, 0.0], [14.946456069617609, 0.0], [14.98273519250575, 0.0], [14.999014315393891, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553], "velocities": null}}, "time": 1740481181.2636178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9544176975631254, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2636178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.2736177, "x": 10.161844632204554, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.2836177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2392734769500379, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558313900286203, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2836177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3036177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556020997930303, "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": 1740481181.3036177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3236177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553755869669408, "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": 1740481181.3236177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3436177} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.1993787, "x": 15.0, "y": 9.000000000000028, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.3436177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955149387112557, "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": 1740481181.3436177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3636177} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.161844632204554, 0.0], [6.323758784193135, 0.0], [6.423758784193135, 0.0], [6.523758784193134, 0.0], [6.623758784193135, 0.0], [6.7237587841931346, 0.0], [6.823758784193135, 0.0], [6.923758784193135, 0.0], [7.023758784193134, 0.0], [7.123758784193135, 0.0], [7.2237587841931346, 0.0], [7.323758784193135, 0.0], [7.423758784193135, 0.0], [7.523758784193134, 0.0], [7.623758784193135, 0.0], [7.723758784193135, 0.0], [7.823758784193135, 0.0], [7.923758784193135, 0.0], [8.023758784193134, 0.0], [8.123758784193136, 0.0], [8.223758784193135, 0.0], [8.323758784193135, 0.0], [8.423758784193137, 0.0], [8.523758784193136, 0.0], [8.623758784193136, 0.0], [8.723758784193135, 0.0], [8.823758784193135, 0.0], [8.923758784193137, 0.0], [9.023758784193136, 0.0], [9.123758784193136, 0.0], [9.223758784193137, 0.0], [9.323758784193137, 0.0], [9.423758784193137, 0.0], [9.523758784193136, 0.0], [9.623758784193136, 0.0], [9.723758784193137, 0.0], [9.823758784193137, 0.0], [9.923758784193137, 0.0], [10.023758784193138, 0.0], [10.123758784193138, 0.0], [10.223758784193137, 0.0], [10.323758784193137, 0.0], [10.423758784193137, 0.0], [10.523758784193136, 0.0], [10.623758784193136, 0.0], [10.723758784193135, 0.0], [10.823758784193135, 0.0], [10.923758784193135, 0.0], [11.023758784193134, 0.0], [11.123758784193134, 0.0], [11.223758784193134, 0.0], [11.323758784193133, 0.0], [11.423758784193133, 0.0], [11.523758784193133, 0.0], [11.623758784193132, 0.0], [11.723758784193132, 0.0], [11.823758784193132, 0.0], [11.923758784193131, 0.0], [12.02375878419313, 0.0], [12.12375878419313, 0.0], [12.22375878419313, 0.0], [12.32375878419313, 0.0], [12.42375878419313, 0.0], [12.523758784193129, 0.0], [12.623758784193129, 0.0], [12.723758784193128, 0.0], [12.823758784193128, 0.0], [12.923758784193128, 0.0], [13.023758784193127, 0.0], [13.123758784193127, 0.0], [13.223758784193127, 0.0], [13.323758784193126, 0.0], [13.423758784193126, 0.0], [13.523758784193125, 0.0], [13.623758784193125, 0.0], [13.723758784193125, 0.0], [13.823758784193124, 0.0], [13.923758784193124, 0.0], [14.023758784193124, 0.0], [14.123758784193123, 0.0], [14.223758784193123, 0.0], [14.323758784193123, 0.0], [14.423758784193122, 0.0], [14.523758784193122, 0.0], [14.623758784193122, 0.0], [14.723758784193121, 0.0], [14.818318425947474, 0.0], [14.89356666910885, 0.0], [14.948814912270224, 0.0], [14.9840631554316, 0.0], [14.999311398592976, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553], "velocities": null}}, "time": 1740481181.3636177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23793599019288636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547258495251123, "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": 1740481181.3636177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.3836176, "x": 10.266919930930852, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.3836176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25148202361029387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95452833584263, "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": 1740481181.3836176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4036176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558263869767193, "gear": 1, "accelerator_pedal_position": 0.25148202361029387, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4036176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4236176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571236500194377, "gear": 1, "accelerator_pedal_position": 0.25149007003829515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4236176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4436176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958419119931069, "gear": 1, "accelerator_pedal_position": 0.25149007003829515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4436176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4636176} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.266919930930852, 0.0], [6.42884079895557, 0.0], [6.52884079895557, 0.0], [6.62884079895557, 0.0], [6.72884079895557, 0.0], [6.82884079895557, 0.0], [6.92884079895557, 0.0], [7.02884079895557, 0.0], [7.12884079895557, 0.0], [7.22884079895557, 0.0], [7.32884079895557, 0.0], [7.42884079895557, 0.0], [7.528840798955571, 0.0], [7.62884079895557, 0.0], [7.72884079895557, 0.0], [7.828840798955571, 0.0], [7.928840798955571, 0.0], [8.02884079895557, 0.0], [8.12884079895557, 0.0], [8.22884079895557, 0.0], [8.328840798955572, 0.0], [8.428840798955571, 0.0], [8.52884079895557, 0.0], [8.628840798955572, 0.0], [8.728840798955572, 0.0], [8.828840798955572, 0.0], [8.928840798955571, 0.0], [9.02884079895557, 0.0], [9.128840798955572, 0.0], [9.228840798955572, 0.0], [9.328840798955572, 0.0], [9.428840798955573, 0.0], [9.528840798955573, 0.0], [9.628840798955572, 0.0], [9.728840798955572, 0.0], [9.828840798955572, 0.0], [9.928840798955573, 0.0], [10.028840798955573, 0.0], [10.128840798955572, 0.0], [10.228840798955574, 0.0], [10.328840798955572, 0.0], [10.428840798955573, 0.0], [10.52884079895557, 0.0], [10.628840798955572, 0.0], [10.72884079895557, 0.0], [10.828840798955572, 0.0], [10.92884079895557, 0.0], [11.02884079895557, 0.0], [11.128840798955569, 0.0], [11.22884079895557, 0.0], [11.328840798955568, 0.0], [11.42884079895557, 0.0], [11.528840798955567, 0.0], [11.628840798955569, 0.0], [11.728840798955567, 0.0], [11.828840798955568, 0.0], [11.928840798955566, 0.0], [12.028840798955567, 0.0], [12.128840798955565, 0.0], [12.228840798955567, 0.0], [12.328840798955564, 0.0], [12.428840798955566, 0.0], [12.528840798955564, 0.0], [12.628840798955565, 0.0], [12.728840798955563, 0.0], [12.828840798955564, 0.0], [12.928840798955562, 0.0], [13.028840798955564, 0.0], [13.128840798955562, 0.0], [13.228840798955563, 0.0], [13.32884079895556, 0.0], [13.428840798955562, 0.0], [13.52884079895556, 0.0], [13.628840798955562, 0.0], [13.72884079895556, 0.0], [13.82884079895556, 0.0], [13.928840798955559, 0.0], [14.02884079895556, 0.0], [14.128840798955558, 0.0], [14.22884079895556, 0.0], [14.328840798955559, 0.0], [14.428840798955559, 0.0], [14.528840798955558, 0.0], [14.628840798955558, 0.0], [14.728840798955558, 0.0], [14.822624927375607, 0.0], [14.896856767584495, 0.0], [14.951088607793384, 0.0], [14.985320448002271, 0.0], [14.999552288211161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553], "velocities": null}}, "time": 1740481181.4636176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23792486841281754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595111415300663, "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": 1740481181.4636176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4836175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23792486841281754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593096240720304, "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": 1740481181.4836175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.4936175, "x": 10.37224914770476, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5036175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649766091315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9589070073303304, "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": 1740481181.5036175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5236175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250698061304799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600594230883468, "gear": 1, "accelerator_pedal_position": 0.2503649766091315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5236175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5436175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250698061304799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612518657385496, "gear": 1, "accelerator_pedal_position": 0.250698061304799, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5436175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5636175} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.3722491477047605, 0.0], [6.534433706862372, 0.0], [6.634433706862373, 0.0], [6.734433706862372, 0.0], [6.834433706862373, 0.0], [6.9344337068623725, 0.0], [7.034433706862372, 0.0], [7.134433706862373, 0.0], [7.234433706862372, 0.0], [7.334433706862372, 0.0], [7.4344337068623725, 0.0], [7.534433706862373, 0.0], [7.634433706862373, 0.0], [7.734433706862372, 0.0], [7.834433706862373, 0.0], [7.934433706862373, 0.0], [8.034433706862373, 0.0], [8.134433706862373, 0.0], [8.234433706862372, 0.0], [8.334433706862374, 0.0], [8.434433706862373, 0.0], [8.534433706862373, 0.0], [8.634433706862374, 0.0], [8.734433706862374, 0.0], [8.834433706862374, 0.0], [8.934433706862373, 0.0], [9.034433706862373, 0.0], [9.134433706862374, 0.0], [9.234433706862374, 0.0], [9.334433706862374, 0.0], [9.434433706862375, 0.0], [9.534433706862375, 0.0], [9.634433706862374, 0.0], [9.734433706862374, 0.0], [9.834433706862374, 0.0], [9.934433706862375, 0.0], [10.034433706862375, 0.0], [10.134433706862374, 0.0], [10.234433706862376, 0.0], [10.334433706862376, 0.0], [10.434433706862375, 0.0], [10.534433706862375, 0.0], [10.634433706862374, 0.0], [10.734433706862374, 0.0], [10.834433706862374, 0.0], [10.934433706862373, 0.0], [11.034433706862373, 0.0], [11.134433706862373, 0.0], [11.234433706862372, 0.0], [11.334433706862372, 0.0], [11.434433706862372, 0.0], [11.534433706862371, 0.0], [11.63443370686237, 0.0], [11.73443370686237, 0.0], [11.83443370686237, 0.0], [11.93443370686237, 0.0], [12.03443370686237, 0.0], [12.134433706862369, 0.0], [12.234433706862369, 0.0], [12.334433706862368, 0.0], [12.434433706862368, 0.0], [12.534433706862368, 0.0], [12.634433706862367, 0.0], [12.734433706862367, 0.0], [12.834433706862367, 0.0], [12.934433706862366, 0.0], [13.034433706862366, 0.0], [13.134433706862366, 0.0], [13.234433706862365, 0.0], [13.334433706862365, 0.0], [13.434433706862364, 0.0], [13.534433706862364, 0.0], [13.634433706862364, 0.0], [13.734433706862363, 0.0], [13.834433706862363, 0.0], [13.934433706862363, 0.0], [14.034433706862362, 0.0], [14.134433706862362, 0.0], [14.234433706862362, 0.0], [14.334433706862361, 0.0], [14.434433706862361, 0.0], [14.53443370686236, 0.0], [14.63443370686236, 0.0], [14.73443370686236, 0.0], [14.82730465600784, 0.0], [14.90041791463537, 0.0], [14.953531173262897, 0.0], [14.986644431890424, 0.0], [14.999757690517953, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553], "velocities": null}}, "time": 1740481181.5636175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23745044627130266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624426581645872, "gear": 1, "accelerator_pedal_position": 0.250698061304799, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5636175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5836174} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.4189186, "x": 15.0, "y": 9.110000000000046, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.5836174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23745044627130266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619764235978037, "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": 1740481181.5836174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.6036174, "x": 10.477946001365115, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6036174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24781364187524182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615108344664631, "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": 1740481181.6036174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6236174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24798837574560112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627663338994108, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6236174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6436174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24798837574560112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631915323151922, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6436174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6636174} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.477946001365115, 0.0], [6.6402577069750155, 0.0], [6.740257706975015, 0.0], [6.840257706975015, 0.0], [6.940257706975015, 0.0], [7.040257706975015, 0.0], [7.1402577069750155, 0.0], [7.240257706975015, 0.0], [7.340257706975015, 0.0], [7.440257706975015, 0.0], [7.540257706975015, 0.0], [7.6402577069750155, 0.0], [7.740257706975015, 0.0], [7.840257706975015, 0.0], [7.940257706975015, 0.0], [8.040257706975016, 0.0], [8.140257706975015, 0.0], [8.240257706975015, 0.0], [8.340257706975017, 0.0], [8.440257706975016, 0.0], [8.540257706975016, 0.0], [8.640257706975017, 0.0], [8.740257706975017, 0.0], [8.840257706975017, 0.0], [8.940257706975016, 0.0], [9.040257706975016, 0.0], [9.140257706975017, 0.0], [9.240257706975017, 0.0], [9.340257706975017, 0.0], [9.440257706975018, 0.0], [9.540257706975018, 0.0], [9.640257706975017, 0.0], [9.740257706975017, 0.0], [9.840257706975017, 0.0], [9.940257706975018, 0.0], [10.040257706975018, 0.0], [10.140257706975017, 0.0], [10.240257706975019, 0.0], [10.340257706975018, 0.0], [10.440257706975018, 0.0], [10.540257706975018, 0.0], [10.640257706975017, 0.0], [10.740257706975017, 0.0], [10.840257706975017, 0.0], [10.940257706975016, 0.0], [11.040257706975016, 0.0], [11.140257706975015, 0.0], [11.240257706975015, 0.0], [11.340257706975015, 0.0], [11.440257706975014, 0.0], [11.540257706975014, 0.0], [11.640257706975014, 0.0], [11.740257706975013, 0.0], [11.840257706975013, 0.0], [11.940257706975013, 0.0], [12.040257706975012, 0.0], [12.140257706975012, 0.0], [12.240257706975012, 0.0], [12.340257706975011, 0.0], [12.44025770697501, 0.0], [12.54025770697501, 0.0], [12.64025770697501, 0.0], [12.74025770697501, 0.0], [12.84025770697501, 0.0], [12.940257706975009, 0.0], [13.040257706975009, 0.0], [13.140257706975008, 0.0], [13.240257706975008, 0.0], [13.340257706975008, 0.0], [13.440257706975007, 0.0], [13.540257706975007, 0.0], [13.640257706975007, 0.0], [13.740257706975006, 0.0], [13.840257706975006, 0.0], [13.940257706975006, 0.0], [14.040257706975005, 0.0], [14.140257706975005, 0.0], [14.240257706975004, 0.0], [14.340257706975004, 0.0], [14.440257706975004, 0.0], [14.540257706975003, 0.0], [14.640257706975003, 0.0], [14.740257706975003, 0.0], [14.832111253306618, 0.0], [14.904059711911616, 0.0], [14.956008170516617, 0.0], [14.987956629121616, 0.0], [14.999905087726615, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531], "velocities": null}}, "time": 1740481181.6636174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644653612900748, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6636174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6836174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642145223720796, "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": 1740481181.6836174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.7036173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637133657978686, "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": 1740481181.7036173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.7136173, "x": 10.583903502481709, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7236173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464128441570876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635393217517758, "gear": 1, "accelerator_pedal_position": 0.2464128441570876, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.7236173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7436173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465548234495316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638655140482617, "gear": 1, "accelerator_pedal_position": 0.2464128441570876, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.7436173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7636173} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.583903502481709, 0.0], [6.74631285275357, 0.0], [6.84631285275357, 0.0], [6.94631285275357, 0.0], [7.0463128527535694, 0.0], [7.14631285275357, 0.0], [7.24631285275357, 0.0], [7.346312852753569, 0.0], [7.44631285275357, 0.0], [7.5463128527535694, 0.0], [7.646312852753569, 0.0], [7.74631285275357, 0.0], [7.84631285275357, 0.0], [7.94631285275357, 0.0], [8.04631285275357, 0.0], [8.14631285275357, 0.0], [8.24631285275357, 0.0], [8.34631285275357, 0.0], [8.44631285275357, 0.0], [8.54631285275357, 0.0], [8.64631285275357, 0.0], [8.74631285275357, 0.0], [8.84631285275357, 0.0], [8.946312852753572, 0.0], [9.046312852753571, 0.0], [9.14631285275357, 0.0], [9.24631285275357, 0.0], [9.34631285275357, 0.0], [9.446312852753572, 0.0], [9.546312852753571, 0.0], [9.64631285275357, 0.0], [9.746312852753572, 0.0], [9.846312852753572, 0.0], [9.946312852753572, 0.0], [10.046312852753571, 0.0], [10.14631285275357, 0.0], [10.246312852753572, 0.0], [10.346312852753572, 0.0], [10.446312852753572, 0.0], [10.546312852753573, 0.0], [10.646312852753573, 0.0], [10.746312852753572, 0.0], [10.846312852753572, 0.0], [10.946312852753572, 0.0], [11.046312852753571, 0.0], [11.14631285275357, 0.0], [11.24631285275357, 0.0], [11.34631285275357, 0.0], [11.44631285275357, 0.0], [11.54631285275357, 0.0], [11.646312852753569, 0.0], [11.746312852753569, 0.0], [11.846312852753568, 0.0], [11.946312852753568, 0.0], [12.046312852753568, 0.0], [12.146312852753567, 0.0], [12.246312852753567, 0.0], [12.346312852753567, 0.0], [12.446312852753566, 0.0], [12.546312852753566, 0.0], [12.646312852753566, 0.0], [12.746312852753565, 0.0], [12.846312852753565, 0.0], [12.946312852753564, 0.0], [13.046312852753564, 0.0], [13.146312852753564, 0.0], [13.246312852753563, 0.0], [13.346312852753563, 0.0], [13.446312852753563, 0.0], [13.546312852753562, 0.0], [13.646312852753562, 0.0], [13.746312852753562, 0.0], [13.846312852753561, 0.0], [13.946312852753561, 0.0], [14.04631285275356, 0.0], [14.14631285275356, 0.0], [14.24631285275356, 0.0], [14.34631285275356, 0.0], [14.44631285275356, 0.0], [14.546312852753559, 0.0], [14.646312852753558, 0.0], [14.746312852753558, 0.0], [14.837036687148029, 0.0], [14.907774116597318, 0.0], [14.958511546046607, 0.0], [14.989248975495894, 0.0], [14.999986404945183, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531], "velocities": null}}, "time": 1740481181.7636173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642705323516163, "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": 1740481181.7636173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7836173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640062857813015, "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": 1740481181.7836173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.8036172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634783417318964, "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": 1740481181.8036172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.8236172, "x": 10.689918783775488, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8236172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24581291444754838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629511288661443, "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": 1740481181.8236172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8436172} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.639108, "x": 15.0, "y": 9.220000000000063, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.8436172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457756839386138, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635291368288722, "gear": 1, "accelerator_pedal_position": 0.24581291444754838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.8436172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8636172} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.689918783775488, 0.0], [6.852303020726171, 0.0], [6.952303020726171, 0.0], [7.052303020726171, 0.0], [7.152303020726171, 0.0], [7.2523030207261705, 0.0], [7.352303020726171, 0.0], [7.452303020726171, 0.0], [7.552303020726171, 0.0], [7.652303020726171, 0.0], [7.7523030207261705, 0.0], [7.852303020726171, 0.0], [7.952303020726171, 0.0], [8.052303020726171, 0.0], [8.15230302072617, 0.0], [8.25230302072617, 0.0], [8.352303020726172, 0.0], [8.452303020726172, 0.0], [8.552303020726171, 0.0], [8.65230302072617, 0.0], [8.75230302072617, 0.0], [8.852303020726172, 0.0], [8.952303020726172, 0.0], [9.052303020726171, 0.0], [9.152303020726173, 0.0], [9.252303020726172, 0.0], [9.352303020726172, 0.0], [9.452303020726173, 0.0], [9.552303020726171, 0.0], [9.652303020726173, 0.0], [9.752303020726172, 0.0], [9.852303020726172, 0.0], [9.952303020726173, 0.0], [10.052303020726173, 0.0], [10.152303020726173, 0.0], [10.252303020726174, 0.0], [10.352303020726172, 0.0], [10.452303020726173, 0.0], [10.552303020726173, 0.0], [10.652303020726173, 0.0], [10.752303020726174, 0.0], [10.852303020726172, 0.0], [10.952303020726173, 0.0], [11.052303020726171, 0.0], [11.152303020726173, 0.0], [11.25230302072617, 0.0], [11.352303020726172, 0.0], [11.45230302072617, 0.0], [11.552303020726171, 0.0], [11.652303020726169, 0.0], [11.75230302072617, 0.0], [11.852303020726168, 0.0], [11.95230302072617, 0.0], [12.052303020726168, 0.0], [12.152303020726169, 0.0], [12.252303020726167, 0.0], [12.352303020726168, 0.0], [12.452303020726166, 0.0], [12.552303020726168, 0.0], [12.652303020726166, 0.0], [12.752303020726167, 0.0], [12.852303020726165, 0.0], [12.952303020726166, 0.0], [13.052303020726164, 0.0], [13.152303020726166, 0.0], [13.252303020726163, 0.0], [13.352303020726165, 0.0], [13.452303020726163, 0.0], [13.552303020726164, 0.0], [13.652303020726162, 0.0], [13.752303020726163, 0.0], [13.852303020726161, 0.0], [13.952303020726163, 0.0], [14.05230302072616, 0.0], [14.152303020726162, 0.0], [14.25230302072616, 0.0], [14.352303020726161, 0.0], [14.45230302072616, 0.0], [14.55230302072616, 0.0], [14.652303020726158, 0.0], [14.752297716821694, 0.0], [14.841837112676462, 0.0], [14.91137650853123, 0.0], [14.960915904385999, 0.0], [14.990455300240766, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532], "velocities": null}}, "time": 1740481181.8636172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9641016921217608, "gear": 1, "accelerator_pedal_position": 0.2457756839386138, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.8636172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8836172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635807760841378, "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": 1740481181.8836172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.9036171} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630605815175858, "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": 1740481181.9036171} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.9236171} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625411073146605, "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": 1740481181.9236171} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.933617, "x": 10.795886610338917, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.943617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24615294566350834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620223523699009, "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": 1740481181.943617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.963617} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.795886610338917, 0.0], [6.958237476737271, 0.0], [7.058237476737271, 0.0], [7.158237476737271, 0.0], [7.258237476737271, 0.0], [7.358237476737271, 0.0], [7.458237476737271, 0.0], [7.558237476737271, 0.0], [7.658237476737271, 0.0], [7.758237476737271, 0.0], [7.858237476737271, 0.0], [7.9582374767372706, 0.0], [8.058237476737272, 0.0], [8.158237476737272, 0.0], [8.258237476737271, 0.0], [8.358237476737271, 0.0], [8.45823747673727, 0.0], [8.558237476737272, 0.0], [8.658237476737272, 0.0], [8.758237476737271, 0.0], [8.858237476737273, 0.0], [8.958237476737272, 0.0], [9.058237476737272, 0.0], [9.158237476737272, 0.0], [9.258237476737271, 0.0], [9.358237476737273, 0.0], [9.458237476737272, 0.0], [9.558237476737272, 0.0], [9.658237476737273, 0.0], [9.758237476737273, 0.0], [9.858237476737273, 0.0], [9.958237476737272, 0.0], [10.058237476737272, 0.0], [10.158237476737273, 0.0], [10.258237476737273, 0.0], [10.358237476737273, 0.0], [10.458237476737274, 0.0], [10.558237476737274, 0.0], [10.658237476737273, 0.0], [10.758237476737273, 0.0], [10.858237476737273, 0.0], [10.958237476737274, 0.0], [11.058237476737272, 0.0], [11.158237476737273, 0.0], [11.258237476737271, 0.0], [11.358237476737273, 0.0], [11.45823747673727, 0.0], [11.558237476737272, 0.0], [11.65823747673727, 0.0], [11.758237476737271, 0.0], [11.85823747673727, 0.0], [11.95823747673727, 0.0], [12.058237476737268, 0.0], [12.15823747673727, 0.0], [12.258237476737268, 0.0], [12.35823747673727, 0.0], [12.458237476737267, 0.0], [12.558237476737268, 0.0], [12.658237476737266, 0.0], [12.758237476737268, 0.0], [12.858237476737266, 0.0], [12.958237476737267, 0.0], [13.058237476737265, 0.0], [13.158237476737266, 0.0], [13.258237476737264, 0.0], [13.358237476737266, 0.0], [13.458237476737263, 0.0], [13.558237476737265, 0.0], [13.658237476737263, 0.0], [13.758237476737264, 0.0], [13.858237476737262, 0.0], [13.958237476737263, 0.0], [14.058237476737261, 0.0], [14.158237476737263, 0.0], [14.25823747673726, 0.0], [14.358237476737262, 0.0], [14.45823747673726, 0.0], [14.558237476737261, 0.0], [14.65823747673726, 0.0], [14.758169620714263, 0.0], [14.84652212536681, 0.0], [14.914874630019359, 0.0], [14.963227134671907, 0.0], [14.991579639324454, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532], "velocities": null}}, "time": 1740481181.963617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623892481856829, "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": 1740481181.963617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.983617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621345374044158, "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": 1740481181.983617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481182.003617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616256448320473, "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": 1740481182.003617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481182.023617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611174566798791, "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": 1740481182.023617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.043617, "x": 10.90169324492635, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.043617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24678756537209398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9606099718695712, "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": 1740481182.043617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.063617} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.901693244926349, 0.0], [7.063958178234484, 0.0], [7.163958178234484, 0.0], [7.263958178234484, 0.0], [7.363958178234483, 0.0], [7.463958178234484, 0.0], [7.563958178234484, 0.0], [7.663958178234484, 0.0], [7.763958178234484, 0.0], [7.863958178234483, 0.0], [7.963958178234484, 0.0], [8.063958178234484, 0.0], [8.163958178234484, 0.0], [8.263958178234484, 0.0], [8.363958178234483, 0.0], [8.463958178234485, 0.0], [8.563958178234484, 0.0], [8.663958178234484, 0.0], [8.763958178234484, 0.0], [8.863958178234485, 0.0], [8.963958178234485, 0.0], [9.063958178234484, 0.0], [9.163958178234484, 0.0], [9.263958178234486, 0.0], [9.363958178234485, 0.0], [9.463958178234485, 0.0], [9.563958178234484, 0.0], [9.663958178234484, 0.0], [9.763958178234486, 0.0], [9.863958178234485, 0.0], [9.963958178234485, 0.0], [10.063958178234486, 0.0], [10.163958178234486, 0.0], [10.263958178234486, 0.0], [10.363958178234485, 0.0], [10.463958178234485, 0.0], [10.563958178234486, 0.0], [10.663958178234486, 0.0], [10.763958178234486, 0.0], [10.863958178234487, 0.0], [10.963958178234487, 0.0], [11.063958178234486, 0.0], [11.163958178234486, 0.0], [11.263958178234486, 0.0], [11.363958178234485, 0.0], [11.463958178234485, 0.0], [11.563958178234484, 0.0], [11.663958178234484, 0.0], [11.763958178234484, 0.0], [11.863958178234483, 0.0], [11.963958178234483, 0.0], [12.063958178234483, 0.0], [12.163958178234482, 0.0], [12.263958178234482, 0.0], [12.363958178234482, 0.0], [12.463958178234481, 0.0], [12.563958178234481, 0.0], [12.66395817823448, 0.0], [12.76395817823448, 0.0], [12.86395817823448, 0.0], [12.96395817823448, 0.0], [13.06395817823448, 0.0], [13.163958178234479, 0.0], [13.263958178234478, 0.0], [13.363958178234478, 0.0], [13.463958178234478, 0.0], [13.563958178234477, 0.0], [13.663958178234477, 0.0], [13.763958178234477, 0.0], [13.863958178234476, 0.0], [13.963958178234476, 0.0], [14.063958178234476, 0.0], [14.163958178234475, 0.0], [14.263958178234475, 0.0], [14.363958178234475, 0.0], [14.463958178234474, 0.0], [14.563958178234474, 0.0], [14.663958178234473, 0.0], [14.763763347494848, 0.0], [14.850971711847953, 0.0], [14.918180076201057, 0.0], [14.965388440554163, 0.0], [14.992596804907269, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533], "velocities": null}}, "time": 1740481182.063617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610704986248391, "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": 1740481182.063617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.083617} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.9689176, "x": 15.0, "y": 9.385000000000089, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.083617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96082815525029, "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": 1740481182.083617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.103617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603439716162283, "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": 1740481182.103617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.123617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598604579504653, "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": 1740481182.123617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.143617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593776132324794, "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": 1740481182.143617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.153617, "x": 11.007339968463826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.163617} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.0073399684638265, 0.0], [7.169526064368973, 0.0], [7.269526064368972, 0.0], [7.369526064368972, 0.0], [7.4695260643689725, 0.0], [7.569526064368972, 0.0], [7.669526064368973, 0.0], [7.769526064368972, 0.0], [7.869526064368972, 0.0], [7.9695260643689725, 0.0], [8.069526064368972, 0.0], [8.169526064368972, 0.0], [8.269526064368971, 0.0], [8.369526064368973, 0.0], [8.469526064368972, 0.0], [8.569526064368972, 0.0], [8.669526064368974, 0.0], [8.769526064368973, 0.0], [8.869526064368973, 0.0], [8.969526064368972, 0.0], [9.069526064368972, 0.0], [9.169526064368974, 0.0], [9.269526064368973, 0.0], [9.369526064368973, 0.0], [9.469526064368974, 0.0], [9.569526064368974, 0.0], [9.669526064368974, 0.0], [9.769526064368973, 0.0], [9.869526064368973, 0.0], [9.969526064368974, 0.0], [10.069526064368974, 0.0], [10.169526064368974, 0.0], [10.269526064368975, 0.0], [10.369526064368975, 0.0], [10.469526064368974, 0.0], [10.569526064368974, 0.0], [10.669526064368974, 0.0], [10.769526064368975, 0.0], [10.869526064368975, 0.0], [10.969526064368974, 0.0], [11.069526064368976, 0.0], [11.169526064368975, 0.0], [11.269526064368975, 0.0], [11.369526064368975, 0.0], [11.469526064368974, 0.0], [11.569526064368974, 0.0], [11.669526064368974, 0.0], [11.769526064368973, 0.0], [11.869526064368973, 0.0], [11.969526064368972, 0.0], [12.069526064368972, 0.0], [12.169526064368972, 0.0], [12.269526064368971, 0.0], [12.369526064368971, 0.0], [12.46952606436897, 0.0], [12.56952606436897, 0.0], [12.66952606436897, 0.0], [12.76952606436897, 0.0], [12.86952606436897, 0.0], [12.969526064368969, 0.0], [13.069526064368969, 0.0], [13.169526064368968, 0.0], [13.269526064368968, 0.0], [13.369526064368968, 0.0], [13.469526064368967, 0.0], [13.569526064368967, 0.0], [13.669526064368966, 0.0], [13.769526064368966, 0.0], [13.869526064368966, 0.0], [13.969526064368965, 0.0], [14.069526064368965, 0.0], [14.169526064368965, 0.0], [14.269526064368964, 0.0], [14.369526064368964, 0.0], [14.469526064368964, 0.0], [14.569526064368963, 0.0], [14.669526064368963, 0.0], [14.769144797179223, 0.0], [14.85523958430543, 0.0], [14.921334371431637, 0.0], [14.967429158557843, 0.0], [14.993523945684052, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533], "velocities": null}}, "time": 1740481182.163617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24842678209901897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586545982046197, "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": 1740481182.163617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.1836169} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591100429228402, "gear": 1, "accelerator_pedal_position": 0.24842678209901897, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.1836169} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2036169} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600109836096028, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2036169} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2236168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609106779030688, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2236168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2436168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618091272038749, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2436168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.2636168, "x": 11.112961637532111, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.2636168} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.112961637532111, 0.0], [7.275333741981079, 0.0], [7.375333741981079, 0.0], [7.475333741981079, 0.0], [7.575333741981079, 0.0], [7.6753337419810785, 0.0], [7.775333741981079, 0.0], [7.875333741981079, 0.0], [7.975333741981078, 0.0], [8.075333741981078, 0.0], [8.17533374198108, 0.0], [8.275333741981079, 0.0], [8.375333741981079, 0.0], [8.475333741981078, 0.0], [8.57533374198108, 0.0], [8.67533374198108, 0.0], [8.775333741981079, 0.0], [8.87533374198108, 0.0], [8.97533374198108, 0.0], [9.07533374198108, 0.0], [9.17533374198108, 0.0], [9.275333741981079, 0.0], [9.37533374198108, 0.0], [9.47533374198108, 0.0], [9.57533374198108, 0.0], [9.67533374198108, 0.0], [9.775333741981079, 0.0], [9.87533374198108, 0.0], [9.97533374198108, 0.0], [10.07533374198108, 0.0], [10.175333741981081, 0.0], [10.27533374198108, 0.0], [10.37533374198108, 0.0], [10.47533374198108, 0.0], [10.57533374198108, 0.0], [10.675333741981081, 0.0], [10.77533374198108, 0.0], [10.87533374198108, 0.0], [10.975333741981082, 0.0], [11.075333741981082, 0.0], [11.175333741981081, 0.0], [11.275333741981083, 0.0], [11.37533374198108, 0.0], [11.475333741981082, 0.0], [11.57533374198108, 0.0], [11.675333741981081, 0.0], [11.775333741981079, 0.0], [11.87533374198108, 0.0], [11.975333741981078, 0.0], [12.07533374198108, 0.0], [12.175333741981078, 0.0], [12.275333741981079, 0.0], [12.375333741981077, 0.0], [12.475333741981078, 0.0], [12.575333741981076, 0.0], [12.675333741981078, 0.0], [12.775333741981076, 0.0], [12.875333741981077, 0.0], [12.975333741981075, 0.0], [13.075333741981076, 0.0], [13.175333741981074, 0.0], [13.275333741981076, 0.0], [13.375333741981073, 0.0], [13.475333741981075, 0.0], [13.575333741981073, 0.0], [13.675333741981074, 0.0], [13.775333741981072, 0.0], [13.875333741981073, 0.0], [13.975333741981071, 0.0], [14.075333741981073, 0.0], [14.17533374198107, 0.0], [14.275333741981072, 0.0], [14.37533374198107, 0.0], [14.475333741981071, 0.0], [14.57533374198107, 0.0], [14.67533374198107, 0.0], [14.774691943498306, 0.0], [14.859625195102092, 0.0], [14.924558446705877, 0.0], [14.969491698309664, 0.0], [14.994424949913451, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534], "velocities": null}}, "time": 1740481182.2636168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24596650348448013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627063329120633, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2636168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.2836168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633038718272395, "gear": 1, "accelerator_pedal_position": 0.24596650348448013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2836168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3036168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639226740705839, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3036168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3236167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645406192559522, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3236167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3436167} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.1888819, "x": 15.0, "y": 9.495000000000106, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.3436167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651577084177039, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3436167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3636167} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.112961637532111, 0.0], [7.275333741981079, 0.0], [7.375333741981079, 0.0], [7.475333741981079, 0.0], [7.575333741981079, 0.0], [7.6753337419810785, 0.0], [7.775333741981079, 0.0], [7.875333741981079, 0.0], [7.975333741981078, 0.0], [8.075333741981078, 0.0], [8.17533374198108, 0.0], [8.275333741981079, 0.0], [8.375333741981079, 0.0], [8.475333741981078, 0.0], [8.57533374198108, 0.0], [8.67533374198108, 0.0], [8.775333741981079, 0.0], [8.87533374198108, 0.0], [8.97533374198108, 0.0], [9.07533374198108, 0.0], [9.17533374198108, 0.0], [9.275333741981079, 0.0], [9.37533374198108, 0.0], [9.47533374198108, 0.0], [9.57533374198108, 0.0], [9.67533374198108, 0.0], [9.775333741981079, 0.0], [9.87533374198108, 0.0], [9.97533374198108, 0.0], [10.07533374198108, 0.0], [10.175333741981081, 0.0], [10.27533374198108, 0.0], [10.37533374198108, 0.0], [10.47533374198108, 0.0], [10.57533374198108, 0.0], [10.675333741981081, 0.0], [10.77533374198108, 0.0], [10.87533374198108, 0.0], [10.975333741981082, 0.0], [11.075333741981082, 0.0], [11.175333741981081, 0.0], [11.275333741981083, 0.0], [11.37533374198108, 0.0], [11.475333741981082, 0.0], [11.57533374198108, 0.0], [11.675333741981081, 0.0], [11.775333741981079, 0.0], [11.87533374198108, 0.0], [11.975333741981078, 0.0], [12.07533374198108, 0.0], [12.175333741981078, 0.0], [12.275333741981079, 0.0], [12.375333741981077, 0.0], [12.475333741981078, 0.0], [12.575333741981076, 0.0], [12.675333741981078, 0.0], [12.775333741981076, 0.0], [12.875333741981077, 0.0], [12.975333741981075, 0.0], [13.075333741981076, 0.0], [13.175333741981074, 0.0], [13.275333741981076, 0.0], [13.375333741981073, 0.0], [13.475333741981075, 0.0], [13.575333741981073, 0.0], [13.675333741981074, 0.0], [13.775333741981072, 0.0], [13.875333741981073, 0.0], [13.975333741981071, 0.0], [14.075333741981073, 0.0], [14.17533374198107, 0.0], [14.275333741981072, 0.0], [14.37533374198107, 0.0], [14.475333741981071, 0.0], [14.57533374198107, 0.0], [14.67533374198107, 0.0], [14.774691943498306, 0.0], [14.859625195102092, 0.0], [14.924558446705877, 0.0], [14.969491698309664, 0.0], [14.994424949913451, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534], "velocities": null}}, "time": 1740481182.3636167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660817393767452, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3636167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.3736167, "x": 11.219027344451137, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.3836167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375943824143945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663893228038002, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3836167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4036167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659356069431163, "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": 1740481182.4036167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4236166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654615945702626, "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": 1740481182.4236166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4436166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649882390608345, "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": 1740481182.4436166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4636166} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.219027344451137, 0.0], [7.381559695034211, 0.0], [7.4815596950342105, 0.0], [7.58155969503421, 0.0], [7.681559695034211, 0.0], [7.78155969503421, 0.0], [7.881559695034211, 0.0], [7.9815596950342105, 0.0], [8.08155969503421, 0.0], [8.18155969503421, 0.0], [8.281559695034211, 0.0], [8.38155969503421, 0.0], [8.48155969503421, 0.0], [8.58155969503421, 0.0], [8.68155969503421, 0.0], [8.781559695034211, 0.0], [8.88155969503421, 0.0], [8.98155969503421, 0.0], [9.081559695034212, 0.0], [9.181559695034212, 0.0], [9.281559695034211, 0.0], [9.38155969503421, 0.0], [9.48155969503421, 0.0], [9.581559695034212, 0.0], [9.681559695034212, 0.0], [9.781559695034211, 0.0], [9.881559695034213, 0.0], [9.981559695034212, 0.0], [10.081559695034212, 0.0], [10.181559695034212, 0.0], [10.281559695034211, 0.0], [10.381559695034213, 0.0], [10.481559695034212, 0.0], [10.581559695034212, 0.0], [10.681559695034213, 0.0], [10.781559695034213, 0.0], [10.881559695034213, 0.0], [10.981559695034212, 0.0], [11.081559695034212, 0.0], [11.181559695034213, 0.0], [11.281559695034213, 0.0], [11.381559695034213, 0.0], [11.481559695034212, 0.0], [11.581559695034212, 0.0], [11.681559695034212, 0.0], [11.781559695034211, 0.0], [11.88155969503421, 0.0], [11.98155969503421, 0.0], [12.08155969503421, 0.0], [12.18155969503421, 0.0], [12.28155969503421, 0.0], [12.381559695034209, 0.0], [12.481559695034209, 0.0], [12.581559695034208, 0.0], [12.681559695034208, 0.0], [12.781559695034208, 0.0], [12.881559695034207, 0.0], [12.981559695034207, 0.0], [13.081559695034207, 0.0], [13.181559695034206, 0.0], [13.281559695034206, 0.0], [13.381559695034206, 0.0], [13.481559695034205, 0.0], [13.581559695034205, 0.0], [13.681559695034204, 0.0], [13.781559695034204, 0.0], [13.881559695034204, 0.0], [13.981559695034203, 0.0], [14.081559695034203, 0.0], [14.181559695034203, 0.0], [14.281559695034202, 0.0], [14.381559695034202, 0.0], [14.481559695034202, 0.0], [14.581559695034201, 0.0], [14.6815596950342, 0.0], [14.78056368068355, 0.0], [14.864251741676709, 0.0], [14.927939802669869, 0.0], [14.971627863663027, 0.0], [14.995315924656188, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534], "velocities": null}}, "time": 1740481182.4636166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23667545194919273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645155394149875, "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": 1740481182.4636166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.4836166, "x": 11.325221765025375, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.4836166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468635810733996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639495934568613, "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": 1740481182.4836166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5036166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643854478282493, "gear": 1, "accelerator_pedal_position": 0.24468635810733996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5036166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5236166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650090429731459, "gear": 1, "accelerator_pedal_position": 0.24453129280164843, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5236166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5436165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652166200064604, "gear": 1, "accelerator_pedal_position": 0.24453129280164843, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5436165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5636165} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.3252217650253755, 0.0], [7.4876546600029705, 0.0], [7.58765466000297, 0.0], [7.687654660002971, 0.0], [7.78765466000297, 0.0], [7.88765466000297, 0.0], [7.9876546600029705, 0.0], [8.08765466000297, 0.0], [8.18765466000297, 0.0], [8.28765466000297, 0.0], [8.38765466000297, 0.0], [8.48765466000297, 0.0], [8.58765466000297, 0.0], [8.68765466000297, 0.0], [8.787654660002971, 0.0], [8.88765466000297, 0.0], [8.98765466000297, 0.0], [9.08765466000297, 0.0], [9.187654660002972, 0.0], [9.287654660002971, 0.0], [9.38765466000297, 0.0], [9.48765466000297, 0.0], [9.587654660002972, 0.0], [9.687654660002972, 0.0], [9.787654660002971, 0.0], [9.88765466000297, 0.0], [9.98765466000297, 0.0], [10.087654660002972, 0.0], [10.187654660002972, 0.0], [10.287654660002971, 0.0], [10.387654660002973, 0.0], [10.487654660002972, 0.0], [10.587654660002972, 0.0], [10.687654660002972, 0.0], [10.787654660002971, 0.0], [10.887654660002973, 0.0], [10.987654660002972, 0.0], [11.087654660002972, 0.0], [11.187654660002973, 0.0], [11.287654660002973, 0.0], [11.387654660002973, 0.0], [11.487654660002972, 0.0], [11.587654660002972, 0.0], [11.687654660002972, 0.0], [11.787654660002971, 0.0], [11.88765466000297, 0.0], [11.98765466000297, 0.0], [12.08765466000297, 0.0], [12.18765466000297, 0.0], [12.28765466000297, 0.0], [12.387654660002969, 0.0], [12.487654660002969, 0.0], [12.587654660002968, 0.0], [12.687654660002968, 0.0], [12.787654660002968, 0.0], [12.887654660002967, 0.0], [12.987654660002967, 0.0], [13.087654660002967, 0.0], [13.187654660002966, 0.0], [13.287654660002966, 0.0], [13.387654660002966, 0.0], [13.487654660002965, 0.0], [13.587654660002965, 0.0], [13.687654660002964, 0.0], [13.787654660002964, 0.0], [13.887654660002964, 0.0], [13.987654660002963, 0.0], [14.087654660002963, 0.0], [14.187654660002963, 0.0], [14.287654660002962, 0.0], [14.387654660002962, 0.0], [14.487654660002962, 0.0], [14.587654660002961, 0.0], [14.687654660002961, 0.0], [14.786236786583022, 0.0], [14.86870585458243, 0.0], [14.931174922581837, 0.0], [14.973643990581245, 0.0], [14.996113058580654, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534], "velocities": null}}, "time": 1740481182.5636165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23691914910218073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653627293560777, "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": 1740481182.5636165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5836165} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.4100251, "x": 15.0, "y": 9.605000000000123, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.5836165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23691914910218073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965094302290363, "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": 1740481182.5836165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.5936165, "x": 11.431358120093588, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6036165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452043305278692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645580061122826, "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": 1740481182.6036165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6236165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24526807370138753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650577417901438, "gear": 1, "accelerator_pedal_position": 0.2452043305278692, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6236165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6436164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24526807370138753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655647502233509, "gear": 1, "accelerator_pedal_position": 0.24526807370138753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6436164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6636164} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.431358120093588, 0.0], [7.593832632301329, 0.0], [7.69383263230133, 0.0], [7.79383263230133, 0.0], [7.893832632301329, 0.0], [7.99383263230133, 0.0], [8.09383263230133, 0.0], [8.19383263230133, 0.0], [8.29383263230133, 0.0], [8.39383263230133, 0.0], [8.493832632301329, 0.0], [8.593832632301329, 0.0], [8.69383263230133, 0.0], [8.79383263230133, 0.0], [8.89383263230133, 0.0], [8.99383263230133, 0.0], [9.09383263230133, 0.0], [9.19383263230133, 0.0], [9.29383263230133, 0.0], [9.39383263230133, 0.0], [9.49383263230133, 0.0], [9.59383263230133, 0.0], [9.69383263230133, 0.0], [9.793832632301331, 0.0], [9.893832632301331, 0.0], [9.99383263230133, 0.0], [10.09383263230133, 0.0], [10.19383263230133, 0.0], [10.293832632301331, 0.0], [10.393832632301331, 0.0], [10.49383263230133, 0.0], [10.593832632301332, 0.0], [10.693832632301332, 0.0], [10.793832632301331, 0.0], [10.893832632301331, 0.0], [10.99383263230133, 0.0], [11.093832632301332, 0.0], [11.193832632301332, 0.0], [11.293832632301331, 0.0], [11.393832632301333, 0.0], [11.49383263230133, 0.0], [11.593832632301332, 0.0], [11.69383263230133, 0.0], [11.793832632301331, 0.0], [11.89383263230133, 0.0], [11.99383263230133, 0.0], [12.093832632301329, 0.0], [12.19383263230133, 0.0], [12.293832632301328, 0.0], [12.39383263230133, 0.0], [12.493832632301327, 0.0], [12.593832632301329, 0.0], [12.693832632301326, 0.0], [12.793832632301328, 0.0], [12.893832632301326, 0.0], [12.993832632301327, 0.0], [13.093832632301325, 0.0], [13.193832632301326, 0.0], [13.293832632301324, 0.0], [13.393832632301326, 0.0], [13.493832632301324, 0.0], [13.593832632301325, 0.0], [13.693832632301323, 0.0], [13.793832632301324, 0.0], [13.893832632301322, 0.0], [13.993832632301324, 0.0], [14.093832632301321, 0.0], [14.193832632301323, 0.0], [14.29383263230132, 0.0], [14.393832632301322, 0.0], [14.49383263230132, 0.0], [14.593832632301321, 0.0], [14.69383263230132, 0.0], [14.791911332646858, 0.0], [14.873144806186595, 0.0], [14.934378279726328, 0.0], [14.975611753266065, 0.0], [14.996845226805801, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535], "velocities": null}}, "time": 1740481182.6636164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23681969064552566, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660710560976027, "gear": 1, "accelerator_pedal_position": 0.24526807370138753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6636164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6836164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23681969064552566, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655209784344714, "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": 1740481182.6836164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.7036164, "x": 11.537543900360738, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7036164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448672006587275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964971663059607, "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": 1740481182.7036164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7236164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487778989084322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654286989950118, "gear": 1, "accelerator_pedal_position": 0.2448672006587275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7236164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7436163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487778989084322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658864248359456, "gear": 1, "accelerator_pedal_position": 0.24487778989084322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7436163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7636163} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.537543900360738, 0.0], [7.700025226953744, 0.0], [7.800025226953744, 0.0], [7.900025226953744, 0.0], [8.000025226953744, 0.0], [8.100025226953743, 0.0], [8.200025226953743, 0.0], [8.300025226953743, 0.0], [8.400025226953744, 0.0], [8.500025226953744, 0.0], [8.600025226953743, 0.0], [8.700025226953743, 0.0], [8.800025226953744, 0.0], [8.900025226953744, 0.0], [9.000025226953744, 0.0], [9.100025226953743, 0.0], [9.200025226953745, 0.0], [9.300025226953744, 0.0], [9.400025226953744, 0.0], [9.500025226953744, 0.0], [9.600025226953743, 0.0], [9.700025226953745, 0.0], [9.800025226953744, 0.0], [9.900025226953744, 0.0], [10.000025226953746, 0.0], [10.100025226953745, 0.0], [10.200025226953745, 0.0], [10.300025226953744, 0.0], [10.400025226953744, 0.0], [10.500025226953746, 0.0], [10.600025226953745, 0.0], [10.700025226953745, 0.0], [10.800025226953746, 0.0], [10.900025226953746, 0.0], [11.000025226953746, 0.0], [11.100025226953745, 0.0], [11.200025226953745, 0.0], [11.300025226953746, 0.0], [11.400025226953746, 0.0], [11.500025226953746, 0.0], [11.600025226953747, 0.0], [11.700025226953745, 0.0], [11.800025226953746, 0.0], [11.900025226953744, 0.0], [12.000025226953746, 0.0], [12.100025226953743, 0.0], [12.200025226953745, 0.0], [12.300025226953743, 0.0], [12.400025226953744, 0.0], [12.500025226953742, 0.0], [12.600025226953743, 0.0], [12.700025226953741, 0.0], [12.800025226953743, 0.0], [12.90002522695374, 0.0], [13.000025226953742, 0.0], [13.10002522695374, 0.0], [13.200025226953741, 0.0], [13.30002522695374, 0.0], [13.40002522695374, 0.0], [13.500025226953738, 0.0], [13.60002522695374, 0.0], [13.700025226953738, 0.0], [13.80002522695374, 0.0], [13.900025226953737, 0.0], [14.000025226953738, 0.0], [14.100025226953736, 0.0], [14.200025226953738, 0.0], [14.300025226953736, 0.0], [14.400025226953737, 0.0], [14.500025226953735, 0.0], [14.600025226953736, 0.0], [14.700025226953734, 0.0], [14.797522703621961, 0.0], [14.877517658231215, 0.0], [14.937512612840468, 0.0], [14.97750756744972, 0.0], [14.997502522058973, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535], "velocities": null}}, "time": 1740481182.7636163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663435163474468, "gear": 1, "accelerator_pedal_position": 0.24487778989084322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7636163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7836163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657909843411046, "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": 1740481182.7836163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.8036163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652392180839853, "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": 1740481182.8036163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.8136163, "x": 11.64376605653184, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8236163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24481957096488366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646882163931076, "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": 1740481182.8236163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8436162} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.740566, "x": 15.0, "y": 9.770000000000149, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.8436162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448189861411995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651396933943354, "gear": 1, "accelerator_pedal_position": 0.24481957096488366, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.8436162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8636162} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.64376605653184, 0.0], [7.806247007516409, 0.0], [7.906247007516409, 0.0], [8.006247007516409, 0.0], [8.106247007516409, 0.0], [8.206247007516408, 0.0], [8.30624700751641, 0.0], [8.40624700751641, 0.0], [8.506247007516409, 0.0], [8.606247007516409, 0.0], [8.706247007516408, 0.0], [8.806247007516408, 0.0], [8.90624700751641, 0.0], [9.006247007516409, 0.0], [9.106247007516409, 0.0], [9.20624700751641, 0.0], [9.30624700751641, 0.0], [9.40624700751641, 0.0], [9.506247007516409, 0.0], [9.606247007516409, 0.0], [9.70624700751641, 0.0], [9.80624700751641, 0.0], [9.90624700751641, 0.0], [10.00624700751641, 0.0], [10.10624700751641, 0.0], [10.20624700751641, 0.0], [10.306247007516411, 0.0], [10.40624700751641, 0.0], [10.50624700751641, 0.0], [10.60624700751641, 0.0], [10.70624700751641, 0.0], [10.806247007516411, 0.0], [10.906247007516411, 0.0], [11.00624700751641, 0.0], [11.106247007516412, 0.0], [11.20624700751641, 0.0], [11.306247007516411, 0.0], [11.406247007516411, 0.0], [11.50624700751641, 0.0], [11.606247007516412, 0.0], [11.706247007516412, 0.0], [11.806247007516411, 0.0], [11.906247007516411, 0.0], [12.00624700751641, 0.0], [12.10624700751641, 0.0], [12.20624700751641, 0.0], [12.30624700751641, 0.0], [12.40624700751641, 0.0], [12.506247007516409, 0.0], [12.606247007516409, 0.0], [12.706247007516408, 0.0], [12.806247007516408, 0.0], [12.906247007516408, 0.0], [13.006247007516407, 0.0], [13.106247007516407, 0.0], [13.206247007516406, 0.0], [13.306247007516406, 0.0], [13.406247007516406, 0.0], [13.506247007516405, 0.0], [13.606247007516405, 0.0], [13.706247007516405, 0.0], [13.806247007516404, 0.0], [13.906247007516404, 0.0], [14.006247007516404, 0.0], [14.106247007516403, 0.0], [14.206247007516403, 0.0], [14.306247007516403, 0.0], [14.406247007516402, 0.0], [14.506247007516402, 0.0], [14.606247007516401, 0.0], [14.706247007516401, 0.0], [14.80308328166185, 0.0], [14.88183388015857, 0.0], [14.940584478655289, 0.0], [14.97933507715201, 0.0], [14.998085675648731, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535], "velocities": null}}, "time": 1740481182.8636162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655904717827993, "gear": 1, "accelerator_pedal_position": 0.2448189861411995, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.8636162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8836162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650390981682134, "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": 1740481182.8836162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.9036162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644884885316686, "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": 1740481182.9036162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.9236162, "x": 11.749910862942164, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9236162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245060839199979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639386416933776, "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": 1740481182.9236162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9436162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24498629512537978, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644213051552657, "gear": 1, "accelerator_pedal_position": 0.245060839199979, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.9436162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9636161} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.749910862942164, 0.0], [7.912343231419096, 0.0], [8.012343231419097, 0.0], [8.112343231419096, 0.0], [8.212343231419096, 0.0], [8.312343231419096, 0.0], [8.412343231419097, 0.0], [8.512343231419097, 0.0], [8.612343231419096, 0.0], [8.712343231419096, 0.0], [8.812343231419096, 0.0], [8.912343231419097, 0.0], [9.012343231419097, 0.0], [9.112343231419096, 0.0], [9.212343231419096, 0.0], [9.312343231419097, 0.0], [9.412343231419097, 0.0], [9.512343231419097, 0.0], [9.612343231419096, 0.0], [9.712343231419098, 0.0], [9.812343231419097, 0.0], [9.912343231419097, 0.0], [10.012343231419099, 0.0], [10.112343231419098, 0.0], [10.212343231419098, 0.0], [10.312343231419097, 0.0], [10.412343231419097, 0.0], [10.512343231419099, 0.0], [10.612343231419098, 0.0], [10.712343231419098, 0.0], [10.8123432314191, 0.0], [10.912343231419099, 0.0], [11.012343231419099, 0.0], [11.112343231419098, 0.0], [11.212343231419098, 0.0], [11.3123432314191, 0.0], [11.412343231419099, 0.0], [11.512343231419099, 0.0], [11.6123432314191, 0.0], [11.7123432314191, 0.0], [11.8123432314191, 0.0], [11.912343231419099, 0.0], [12.012343231419099, 0.0], [12.112343231419098, 0.0], [12.212343231419098, 0.0], [12.312343231419097, 0.0], [12.412343231419097, 0.0], [12.512343231419097, 0.0], [12.612343231419096, 0.0], [12.712343231419096, 0.0], [12.812343231419096, 0.0], [12.912343231419095, 0.0], [13.012343231419095, 0.0], [13.112343231419095, 0.0], [13.212343231419094, 0.0], [13.312343231419094, 0.0], [13.412343231419094, 0.0], [13.512343231419093, 0.0], [13.612343231419093, 0.0], [13.712343231419093, 0.0], [13.812343231419092, 0.0], [13.912343231419092, 0.0], [14.012343231419091, 0.0], [14.112343231419091, 0.0], [14.21234323141909, 0.0], [14.31234323141909, 0.0], [14.41234323141909, 0.0], [14.51234323141909, 0.0], [14.61234323141909, 0.0], [14.712343231419089, 0.0], [14.808456552915315, 0.0], [14.885987906631495, 0.0], [14.943519260347678, 0.0], [14.98105061406386, 0.0], [14.998581967780044, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536], "velocities": null}}, "time": 1740481182.9636161} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646259602935622, "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": 1740481182.9636161} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.983616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96435812108416, "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": 1740481182.983616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481183.003616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638229992785167, "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": 1740481183.003616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481183.023616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632886186715688, "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": 1740481183.023616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.033616, "x": 11.855969198936354, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.043616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562809961611756, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627549781224947, "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": 1740481183.043616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.063616} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.855969198936354, 0.0], [8.018356918968543, 0.0], [8.118356918968543, 0.0], [8.218356918968544, 0.0], [8.318356918968544, 0.0], [8.418356918968543, 0.0], [8.518356918968543, 0.0], [8.618356918968543, 0.0], [8.718356918968544, 0.0], [8.818356918968544, 0.0], [8.918356918968543, 0.0], [9.018356918968543, 0.0], [9.118356918968543, 0.0], [9.218356918968544, 0.0], [9.318356918968544, 0.0], [9.418356918968543, 0.0], [9.518356918968543, 0.0], [9.618356918968544, 0.0], [9.718356918968544, 0.0], [9.818356918968544, 0.0], [9.918356918968545, 0.0], [10.018356918968545, 0.0], [10.118356918968544, 0.0], [10.218356918968544, 0.0], [10.318356918968544, 0.0], [10.418356918968545, 0.0], [10.518356918968545, 0.0], [10.618356918968544, 0.0], [10.718356918968546, 0.0], [10.818356918968545, 0.0], [10.918356918968545, 0.0], [11.018356918968545, 0.0], [11.118356918968544, 0.0], [11.218356918968546, 0.0], [11.318356918968545, 0.0], [11.418356918968545, 0.0], [11.518356918968546, 0.0], [11.618356918968546, 0.0], [11.718356918968546, 0.0], [11.818356918968545, 0.0], [11.918356918968545, 0.0], [12.018356918968546, 0.0], [12.118356918968544, 0.0], [12.218356918968546, 0.0], [12.318356918968544, 0.0], [12.418356918968545, 0.0], [12.518356918968543, 0.0], [12.618356918968544, 0.0], [12.718356918968542, 0.0], [12.818356918968544, 0.0], [12.918356918968541, 0.0], [13.018356918968543, 0.0], [13.11835691896854, 0.0], [13.218356918968542, 0.0], [13.31835691896854, 0.0], [13.418356918968541, 0.0], [13.51835691896854, 0.0], [13.61835691896854, 0.0], [13.718356918968539, 0.0], [13.81835691896854, 0.0], [13.918356918968538, 0.0], [14.01835691896854, 0.0], [14.118356918968537, 0.0], [14.218356918968539, 0.0], [14.318356918968536, 0.0], [14.418356918968538, 0.0], [14.518356918968536, 0.0], [14.618356918968537, 0.0], [14.718356918968535, 0.0], [14.813684250597664, 0.0], [14.890012866803957, 0.0], [14.94634148301025, 0.0], [14.982670099216543, 0.0], [14.998998715422836, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536], "velocities": null}}, "time": 1740481183.063616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963310163845287, "gear": 1, "accelerator_pedal_position": 0.24562809961611756, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.063616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.083616} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.9589896, "x": 15.0, "y": 9.878400000000156, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.4800000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.083616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627893594229341, "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": 1740481183.083616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.103616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622692761523036, "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": 1740481183.103616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.123616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961749912926668, "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": 1740481183.123616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.143616, "x": 11.96184926861933, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.143616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24637181430276553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612312686412813, "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": 1740481183.143616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.163616} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.96184926861933, 0.0], [8.124146575117432, 0.0], [8.224146575117432, 0.0], [8.324146575117432, 0.0], [8.424146575117433, 0.0], [8.524146575117433, 0.0], [8.624146575117432, 0.0], [8.724146575117432, 0.0], [8.824146575117432, 0.0], [8.924146575117433, 0.0], [9.024146575117433, 0.0], [9.124146575117432, 0.0], [9.224146575117432, 0.0], [9.324146575117432, 0.0], [9.424146575117433, 0.0], [9.524146575117433, 0.0], [9.624146575117432, 0.0], [9.724146575117434, 0.0], [9.824146575117433, 0.0], [9.924146575117433, 0.0], [10.024146575117433, 0.0], [10.124146575117432, 0.0], [10.224146575117434, 0.0], [10.324146575117433, 0.0], [10.424146575117433, 0.0], [10.524146575117435, 0.0], [10.624146575117434, 0.0], [10.724146575117434, 0.0], [10.824146575117433, 0.0], [10.924146575117433, 0.0], [11.024146575117435, 0.0], [11.124146575117434, 0.0], [11.224146575117434, 0.0], [11.324146575117435, 0.0], [11.424146575117435, 0.0], [11.524146575117435, 0.0], [11.624146575117434, 0.0], [11.724146575117434, 0.0], [11.824146575117435, 0.0], [11.924146575117435, 0.0], [12.024146575117435, 0.0], [12.124146575117434, 0.0], [12.224146575117434, 0.0], [12.324146575117433, 0.0], [12.424146575117433, 0.0], [12.524146575117433, 0.0], [12.624146575117432, 0.0], [12.724146575117432, 0.0], [12.824146575117432, 0.0], [12.924146575117431, 0.0], [13.024146575117431, 0.0], [13.12414657511743, 0.0], [13.22414657511743, 0.0], [13.32414657511743, 0.0], [13.42414657511743, 0.0], [13.52414657511743, 0.0], [13.624146575117429, 0.0], [13.724146575117429, 0.0], [13.824146575117428, 0.0], [13.924146575117428, 0.0], [14.024146575117427, 0.0], [14.124146575117427, 0.0], [14.224146575117427, 0.0], [14.324146575117426, 0.0], [14.424146575117426, 0.0], [14.524146575117426, 0.0], [14.624146575117425, 0.0], [14.724146575117425, 0.0], [14.818648860515781, 0.0], [14.893819545492295, 0.0], [14.94899023046881, 0.0], [14.984160915445326, 0.0], [14.99933160042184, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536], "velocities": null}}, "time": 1740481183.163616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622062719476795, "gear": 1, "accelerator_pedal_position": 0.24637181430276553, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.163616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.183616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619589117230263, "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": 1740481183.183616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.203616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614647049718171, "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": 1740481183.203616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.223616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609711822798559, "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": 1740481183.223616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.2436159} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604783426029057, "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": 1740481183.2436159} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.2536159, "x": 12.067603297929363, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.2636158} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.067603297929363, 0.0], [8.229848294367342, 0.0], [8.329848294367343, 0.0], [8.429848294367343, 0.0], [8.529848294367342, 0.0], [8.629848294367342, 0.0], [8.729848294367342, 0.0], [8.829848294367343, 0.0], [8.929848294367343, 0.0], [9.029848294367342, 0.0], [9.129848294367342, 0.0], [9.229848294367342, 0.0], [9.329848294367343, 0.0], [9.429848294367343, 0.0], [9.529848294367342, 0.0], [9.629848294367342, 0.0], [9.729848294367343, 0.0], [9.829848294367343, 0.0], [9.929848294367343, 0.0], [10.029848294367342, 0.0], [10.129848294367344, 0.0], [10.229848294367343, 0.0], [10.329848294367343, 0.0], [10.429848294367343, 0.0], [10.529848294367344, 0.0], [10.629848294367344, 0.0], [10.729848294367343, 0.0], [10.829848294367345, 0.0], [10.929848294367345, 0.0], [11.029848294367344, 0.0], [11.129848294367344, 0.0], [11.229848294367343, 0.0], [11.329848294367345, 0.0], [11.429848294367345, 0.0], [11.529848294367344, 0.0], [11.629848294367346, 0.0], [11.729848294367345, 0.0], [11.829848294367345, 0.0], [11.929848294367345, 0.0], [12.029848294367344, 0.0], [12.129848294367346, 0.0], [12.229848294367345, 0.0], [12.329848294367345, 0.0], [12.429848294367345, 0.0], [12.529848294367344, 0.0], [12.629848294367344, 0.0], [12.729848294367343, 0.0], [12.829848294367343, 0.0], [12.929848294367343, 0.0], [13.029848294367342, 0.0], [13.129848294367342, 0.0], [13.229848294367342, 0.0], [13.329848294367341, 0.0], [13.429848294367341, 0.0], [13.52984829436734, 0.0], [13.62984829436734, 0.0], [13.72984829436734, 0.0], [13.82984829436734, 0.0], [13.92984829436734, 0.0], [14.029848294367339, 0.0], [14.129848294367338, 0.0], [14.229848294367338, 0.0], [14.329848294367338, 0.0], [14.429848294367337, 0.0], [14.529848294367337, 0.0], [14.629848294367337, 0.0], [14.729848294367336, 0.0], [14.823472544253963, 0.0], [14.897502885380495, 0.0], [14.951533226507028, 0.0], [14.985563567633562, 0.0], [14.999593908760094, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537], "velocities": null}}, "time": 1740481183.2636158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770937913733085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959986184898579, "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": 1740481183.2636158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.2836158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960805272892612, "gear": 1, "accelerator_pedal_position": 0.24770937913733085, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.2836158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3036158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616170590699857, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3036158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3236158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962427721665183, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3236158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3436158} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.1787477, "x": 15.0, "y": 9.81740000000014, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.3436158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632372619705599, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3436158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.3636158, "x": 12.173387394235935, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.3636158} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.173387394235935, 0.0], [8.335824901731627, 0.0], [8.435824901731626, 0.0], [8.535824901731626, 0.0], [8.635824901731628, 0.0], [8.735824901731627, 0.0], [8.835824901731627, 0.0], [8.935824901731626, 0.0], [9.035824901731626, 0.0], [9.135824901731628, 0.0], [9.235824901731627, 0.0], [9.335824901731627, 0.0], [9.435824901731626, 0.0], [9.535824901731626, 0.0], [9.635824901731628, 0.0], [9.735824901731627, 0.0], [9.835824901731627, 0.0], [9.935824901731628, 0.0], [10.035824901731628, 0.0], [10.135824901731628, 0.0], [10.235824901731627, 0.0], [10.335824901731627, 0.0], [10.435824901731628, 0.0], [10.535824901731628, 0.0], [10.635824901731628, 0.0], [10.735824901731629, 0.0], [10.835824901731629, 0.0], [10.935824901731628, 0.0], [11.035824901731628, 0.0], [11.135824901731628, 0.0], [11.235824901731629, 0.0], [11.335824901731629, 0.0], [11.435824901731628, 0.0], [11.53582490173163, 0.0], [11.63582490173163, 0.0], [11.735824901731629, 0.0], [11.835824901731629, 0.0], [11.935824901731628, 0.0], [12.03582490173163, 0.0], [12.13582490173163, 0.0], [12.235824901731629, 0.0], [12.33582490173163, 0.0], [12.435824901731628, 0.0], [12.53582490173163, 0.0], [12.635824901731628, 0.0], [12.735824901731629, 0.0], [12.835824901731627, 0.0], [12.935824901731628, 0.0], [13.035824901731626, 0.0], [13.135824901731628, 0.0], [13.235824901731625, 0.0], [13.335824901731627, 0.0], [13.435824901731625, 0.0], [13.535824901731626, 0.0], [13.635824901731624, 0.0], [13.735824901731625, 0.0], [13.835824901731623, 0.0], [13.935824901731625, 0.0], [14.035824901731623, 0.0], [14.135824901731624, 0.0], [14.235824901731622, 0.0], [14.335824901731623, 0.0], [14.435824901731621, 0.0], [14.535824901731623, 0.0], [14.63582490173162, 0.0], [14.735824901731622, 0.0], [14.82845898797438, 0.0], [14.901294007628053, 0.0], [14.95412902728173, 0.0], [14.986964046935405, 0.0], [14.999799066589082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537], "velocities": null}}, "time": 1740481183.3636158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516065179269803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644494709605235, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3636158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.3836157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646967706838833, "gear": 1, "accelerator_pedal_position": 0.24516065179269803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3836157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4036157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652147989614736, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4036157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4236157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657321094830018, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4236157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4436157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662487031359507, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4436157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4636157} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.173387394235935, 0.0], [8.335824901731627, 0.0], [8.435824901731626, 0.0], [8.535824901731626, 0.0], [8.635824901731628, 0.0], [8.735824901731627, 0.0], [8.835824901731627, 0.0], [8.935824901731626, 0.0], [9.035824901731626, 0.0], [9.135824901731628, 0.0], [9.235824901731627, 0.0], [9.335824901731627, 0.0], [9.435824901731626, 0.0], [9.535824901731626, 0.0], [9.635824901731628, 0.0], [9.735824901731627, 0.0], [9.835824901731627, 0.0], [9.935824901731628, 0.0], [10.035824901731628, 0.0], [10.135824901731628, 0.0], [10.235824901731627, 0.0], [10.335824901731627, 0.0], [10.435824901731628, 0.0], [10.535824901731628, 0.0], [10.635824901731628, 0.0], [10.735824901731629, 0.0], [10.835824901731629, 0.0], [10.935824901731628, 0.0], [11.035824901731628, 0.0], [11.135824901731628, 0.0], [11.235824901731629, 0.0], [11.335824901731629, 0.0], [11.435824901731628, 0.0], [11.53582490173163, 0.0], [11.63582490173163, 0.0], [11.735824901731629, 0.0], [11.835824901731629, 0.0], [11.935824901731628, 0.0], [12.03582490173163, 0.0], [12.13582490173163, 0.0], [12.235824901731629, 0.0], [12.33582490173163, 0.0], [12.435824901731628, 0.0], [12.53582490173163, 0.0], [12.635824901731628, 0.0], [12.735824901731629, 0.0], [12.835824901731627, 0.0], [12.935824901731628, 0.0], [13.035824901731626, 0.0], [13.135824901731628, 0.0], [13.235824901731625, 0.0], [13.335824901731627, 0.0], [13.435824901731625, 0.0], [13.535824901731626, 0.0], [13.635824901731624, 0.0], [13.735824901731625, 0.0], [13.835824901731623, 0.0], [13.935824901731625, 0.0], [14.035824901731623, 0.0], [14.135824901731624, 0.0], [14.235824901731622, 0.0], [14.335824901731623, 0.0], [14.435824901731621, 0.0], [14.535824901731623, 0.0], [14.63582490173162, 0.0], [14.735824901731622, 0.0], [14.82845898797438, 0.0], [14.901294007628053, 0.0], [14.95412902728173, 0.0], [14.986964046935405, 0.0], [14.999799066589082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537], "velocities": null}}, "time": 1740481183.4636157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967022251426224, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4636157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.4736156, "x": 12.279588181846634, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.4836156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744377874714676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672797433821155, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4836156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5036156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668059742820948, "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": 1740481183.5036156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5236156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663119518421894, "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": 1740481183.5236156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5436156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965818614163603, "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": 1740481183.5436156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5636156} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.279588181846634, 0.0], [8.44216247676485, 0.0], [8.54216247676485, 0.0], [8.642162476764849, 0.0], [8.742162476764848, 0.0], [8.84216247676485, 0.0], [8.94216247676485, 0.0], [9.04216247676485, 0.0], [9.142162476764849, 0.0], [9.242162476764848, 0.0], [9.34216247676485, 0.0], [9.44216247676485, 0.0], [9.54216247676485, 0.0], [9.642162476764849, 0.0], [9.74216247676485, 0.0], [9.84216247676485, 0.0], [9.94216247676485, 0.0], [10.04216247676485, 0.0], [10.14216247676485, 0.0], [10.24216247676485, 0.0], [10.34216247676485, 0.0], [10.44216247676485, 0.0], [10.542162476764851, 0.0], [10.64216247676485, 0.0], [10.74216247676485, 0.0], [10.84216247676485, 0.0], [10.94216247676485, 0.0], [11.042162476764851, 0.0], [11.14216247676485, 0.0], [11.24216247676485, 0.0], [11.342162476764852, 0.0], [11.442162476764851, 0.0], [11.542162476764851, 0.0], [11.64216247676485, 0.0], [11.74216247676485, 0.0], [11.842162476764852, 0.0], [11.942162476764851, 0.0], [12.042162476764851, 0.0], [12.142162476764852, 0.0], [12.242162476764852, 0.0], [12.342162476764852, 0.0], [12.442162476764851, 0.0], [12.542162476764851, 0.0], [12.64216247676485, 0.0], [12.74216247676485, 0.0], [12.84216247676485, 0.0], [12.94216247676485, 0.0], [13.04216247676485, 0.0], [13.142162476764849, 0.0], [13.242162476764848, 0.0], [13.342162476764848, 0.0], [13.442162476764848, 0.0], [13.542162476764847, 0.0], [13.642162476764847, 0.0], [13.742162476764847, 0.0], [13.842162476764846, 0.0], [13.942162476764846, 0.0], [14.042162476764846, 0.0], [14.142162476764845, 0.0], [14.242162476764845, 0.0], [14.342162476764845, 0.0], [14.442162476764844, 0.0], [14.542162476764844, 0.0], [14.642162476764844, 0.0], [14.742162476764843, 0.0], [14.833668554641413, 0.0], [14.905236059288445, 0.0], [14.956803563935475, 0.0], [14.988371068582506, 0.0], [14.999938573229539, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537], "velocities": null}}, "time": 1740481183.5636156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23656606690875456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653259601998734, "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": 1740481183.5636156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.5836155, "x": 12.385876572242696, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.5836155} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.3999505, "x": 15.0, "y": 9.707400000000122, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.5836155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419972229712852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647452230670487, "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": 1740481183.5836155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6036155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651191668516375, "gear": 1, "accelerator_pedal_position": 0.24419972229712852, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6036155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6236155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654718994216099, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6236155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6436155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965824143219542, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6436155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6636155} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.385876572242696, 0.0], [8.54834728889718, 0.0], [8.64834728889718, 0.0], [8.748347288897179, 0.0], [8.848347288897179, 0.0], [8.94834728889718, 0.0], [9.04834728889718, 0.0], [9.14834728889718, 0.0], [9.248347288897179, 0.0], [9.348347288897179, 0.0], [9.448347288897178, 0.0], [9.54834728889718, 0.0], [9.64834728889718, 0.0], [9.748347288897179, 0.0], [9.84834728889718, 0.0], [9.94834728889718, 0.0], [10.04834728889718, 0.0], [10.14834728889718, 0.0], [10.248347288897179, 0.0], [10.34834728889718, 0.0], [10.44834728889718, 0.0], [10.54834728889718, 0.0], [10.648347288897181, 0.0], [10.74834728889718, 0.0], [10.84834728889718, 0.0], [10.94834728889718, 0.0], [11.04834728889718, 0.0], [11.148347288897181, 0.0], [11.24834728889718, 0.0], [11.34834728889718, 0.0], [11.448347288897182, 0.0], [11.548347288897181, 0.0], [11.648347288897181, 0.0], [11.74834728889718, 0.0], [11.84834728889718, 0.0], [11.948347288897182, 0.0], [12.048347288897181, 0.0], [12.148347288897181, 0.0], [12.248347288897182, 0.0], [12.348347288897182, 0.0], [12.448347288897182, 0.0], [12.548347288897183, 0.0], [12.648347288897181, 0.0], [12.748347288897182, 0.0], [12.84834728889718, 0.0], [12.948347288897182, 0.0], [13.04834728889718, 0.0], [13.148347288897181, 0.0], [13.248347288897179, 0.0], [13.34834728889718, 0.0], [13.448347288897178, 0.0], [13.54834728889718, 0.0], [13.648347288897178, 0.0], [13.748347288897179, 0.0], [13.848347288897177, 0.0], [13.948347288897178, 0.0], [14.048347288897176, 0.0], [14.148347288897178, 0.0], [14.248347288897175, 0.0], [14.348347288897177, 0.0], [14.448347288897175, 0.0], [14.548347288897176, 0.0], [14.648347288897174, 0.0], [14.748347288897175, 0.0], [14.83867509966375, 0.0], [14.909005641884313, 0.0], [14.95933618410488, 0.0], [14.989666726325446, 0.0], [14.99999726854601, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538], "velocities": null}}, "time": 1740481183.6636155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682890588838856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661758988730988, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6636155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6836154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682890588838856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656268274130334, "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": 1740481183.6836154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.6936154, "x": 12.4920839766951, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7036154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24480614220733946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650785168700318, "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": 1740481183.7036154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7236154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485031345188774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655277750898226, "gear": 1, "accelerator_pedal_position": 0.24480614220733946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7236154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7436154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485031345188774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659819302708612, "gear": 1, "accelerator_pedal_position": 0.24485031345188774, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7436154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7636154} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.4920839766951, 0.0], [8.654582996938256, 0.0], [8.754582996938256, 0.0], [8.854582996938255, 0.0], [8.954582996938255, 0.0], [9.054582996938256, 0.0], [9.154582996938256, 0.0], [9.254582996938256, 0.0], [9.354582996938255, 0.0], [9.454582996938255, 0.0], [9.554582996938255, 0.0], [9.654582996938256, 0.0], [9.754582996938256, 0.0], [9.854582996938255, 0.0], [9.954582996938255, 0.0], [10.054582996938256, 0.0], [10.154582996938256, 0.0], [10.254582996938256, 0.0], [10.354582996938255, 0.0], [10.454582996938257, 0.0], [10.554582996938256, 0.0], [10.654582996938256, 0.0], [10.754582996938257, 0.0], [10.854582996938257, 0.0], [10.954582996938257, 0.0], [11.054582996938256, 0.0], [11.154582996938256, 0.0], [11.254582996938257, 0.0], [11.354582996938257, 0.0], [11.454582996938257, 0.0], [11.554582996938258, 0.0], [11.654582996938258, 0.0], [11.754582996938257, 0.0], [11.854582996938257, 0.0], [11.954582996938257, 0.0], [12.054582996938258, 0.0], [12.154582996938258, 0.0], [12.254582996938257, 0.0], [12.354582996938259, 0.0], [12.454582996938258, 0.0], [12.554582996938258, 0.0], [12.654582996938258, 0.0], [12.754582996938257, 0.0], [12.854582996938257, 0.0], [12.954582996938257, 0.0], [13.054582996938256, 0.0], [13.154582996938256, 0.0], [13.254582996938256, 0.0], [13.354582996938255, 0.0], [13.454582996938255, 0.0], [13.554582996938255, 0.0], [13.654582996938254, 0.0], [13.754582996938254, 0.0], [13.854582996938253, 0.0], [13.954582996938253, 0.0], [14.054582996938253, 0.0], [14.154582996938252, 0.0], [14.254582996938252, 0.0], [14.354582996938252, 0.0], [14.454582996938251, 0.0], [14.554582996938251, 0.0], [14.65458299693825, 0.0], [14.754561993077314, 0.0], [14.843645393689663, 0.0], [14.912728794302014, 0.0], [14.961812194914364, 0.0], [14.990895595526712, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385], "velocities": null}}, "time": 1740481183.7636154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23675946098311074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664354560532891, "gear": 1, "accelerator_pedal_position": 0.24485031345188774, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7636154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7836154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23675946098311074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658773472460883, "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": 1740481183.7836154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.8036153, "x": 12.598316730870444, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8036153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446083065954322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653200119365273, "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": 1740481183.8036153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8236153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460593821762142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657442146486548, "gear": 1, "accelerator_pedal_position": 0.2446083065954322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.8236153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8436153} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.728798, "x": 15.0, "y": 9.542400000000097, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.8436153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460593821762142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661675335667255, "gear": 1, "accelerator_pedal_position": 0.24460593821762142, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.8436153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8636153} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.598316730870444, 0.0], [8.760814246007934, 0.0], [8.860814246007934, 0.0], [8.960814246007933, 0.0], [9.060814246007935, 0.0], [9.160814246007934, 0.0], [9.260814246007934, 0.0], [9.360814246007934, 0.0], [9.460814246007933, 0.0], [9.560814246007935, 0.0], [9.660814246007934, 0.0], [9.760814246007934, 0.0], [9.860814246007934, 0.0], [9.960814246007935, 0.0], [10.060814246007935, 0.0], [10.160814246007934, 0.0], [10.260814246007934, 0.0], [10.360814246007934, 0.0], [10.460814246007935, 0.0], [10.560814246007935, 0.0], [10.660814246007934, 0.0], [10.760814246007936, 0.0], [10.860814246007935, 0.0], [10.960814246007935, 0.0], [11.060814246007935, 0.0], [11.160814246007934, 0.0], [11.260814246007936, 0.0], [11.360814246007935, 0.0], [11.460814246007935, 0.0], [11.560814246007936, 0.0], [11.660814246007936, 0.0], [11.760814246007936, 0.0], [11.860814246007935, 0.0], [11.960814246007935, 0.0], [12.060814246007936, 0.0], [12.160814246007936, 0.0], [12.260814246007936, 0.0], [12.360814246007937, 0.0], [12.460814246007937, 0.0], [12.560814246007936, 0.0], [12.660814246007936, 0.0], [12.760814246007936, 0.0], [12.860814246007935, 0.0], [12.960814246007935, 0.0], [13.060814246007935, 0.0], [13.160814246007934, 0.0], [13.260814246007934, 0.0], [13.360814246007934, 0.0], [13.460814246007933, 0.0], [13.560814246007933, 0.0], [13.660814246007932, 0.0], [13.760814246007932, 0.0], [13.860814246007932, 0.0], [13.960814246007931, 0.0], [14.060814246007931, 0.0], [14.16081424600793, 0.0], [14.26081424600793, 0.0], [14.36081424600793, 0.0], [14.46081424600793, 0.0], [14.56081424600793, 0.0], [14.660814246007929, 0.0], [14.760697298091209, 0.0], [14.848534448889623, 0.0], [14.916371599688038, 0.0], [14.964208750486451, 0.0], [14.992045901284865, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539], "velocities": null}}, "time": 1740481183.8636153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966311240775904, "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": 1740481183.8636153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8836153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660324092086717, "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": 1740481183.8836153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.9036152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965475325811548, "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": 1740481183.9036152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.9136152, "x": 12.704569349669976, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9236152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24464782157786638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649190144013424, "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": 1740481183.9236152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9436152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24463888060542693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653487104008933, "gear": 1, "accelerator_pedal_position": 0.24464782157786638, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.9436152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9636152} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.704569349669976, 0.0], [8.867061170068691, 0.0], [8.96706117006869, 0.0], [9.06706117006869, 0.0], [9.16706117006869, 0.0], [9.26706117006869, 0.0], [9.367061170068691, 0.0], [9.46706117006869, 0.0], [9.56706117006869, 0.0], [9.66706117006869, 0.0], [9.76706117006869, 0.0], [9.867061170068691, 0.0], [9.96706117006869, 0.0], [10.06706117006869, 0.0], [10.167061170068692, 0.0], [10.267061170068692, 0.0], [10.367061170068691, 0.0], [10.46706117006869, 0.0], [10.56706117006869, 0.0], [10.667061170068692, 0.0], [10.767061170068692, 0.0], [10.867061170068691, 0.0], [10.967061170068693, 0.0], [11.06706117006869, 0.0], [11.167061170068692, 0.0], [11.267061170068692, 0.0], [11.367061170068691, 0.0], [11.467061170068693, 0.0], [11.567061170068692, 0.0], [11.667061170068692, 0.0], [11.767061170068693, 0.0], [11.867061170068691, 0.0], [11.967061170068693, 0.0], [12.067061170068692, 0.0], [12.167061170068692, 0.0], [12.267061170068693, 0.0], [12.367061170068693, 0.0], [12.467061170068693, 0.0], [12.567061170068694, 0.0], [12.667061170068692, 0.0], [12.767061170068693, 0.0], [12.867061170068693, 0.0], [12.967061170068693, 0.0], [13.067061170068692, 0.0], [13.167061170068692, 0.0], [13.267061170068692, 0.0], [13.367061170068691, 0.0], [13.46706117006869, 0.0], [13.56706117006869, 0.0], [13.66706117006869, 0.0], [13.76706117006869, 0.0], [13.86706117006869, 0.0], [13.967061170068689, 0.0], [14.067061170068689, 0.0], [14.167061170068688, 0.0], [14.267061170068688, 0.0], [14.367061170068688, 0.0], [14.467061170068687, 0.0], [14.567061170068687, 0.0], [14.667061170068687, 0.0], [14.766770086544573, 0.0], [14.853357852530836, 0.0], [14.919945618517099, 0.0], [14.96653338450336, 0.0], [14.993121150489625, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539], "velocities": null}}, "time": 1740481183.9636152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965776693772477, "gear": 1, "accelerator_pedal_position": 0.24463888060542693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.9636152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9836152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652217254468489, "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": 1740481183.9836152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481184.0036151} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646675261207717, "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": 1740481184.0036151} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.0236151, "x": 12.810735967815697, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.0236151} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24494113658270075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9641140946058581, "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": 1740481184.0236151} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.043615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486237439290584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96458155739058, "gear": 1, "accelerator_pedal_position": 0.24494113658270075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.043615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.063615} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.810735967815697, 0.0], [8.973176751863937, 0.0], [9.073176751863938, 0.0], [9.173176751863938, 0.0], [9.273176751863938, 0.0], [9.373176751863937, 0.0], [9.473176751863937, 0.0], [9.573176751863937, 0.0], [9.673176751863938, 0.0], [9.773176751863938, 0.0], [9.873176751863937, 0.0], [9.973176751863937, 0.0], [10.073176751863937, 0.0], [10.173176751863938, 0.0], [10.273176751863938, 0.0], [10.373176751863937, 0.0], [10.473176751863939, 0.0], [10.573176751863938, 0.0], [10.673176751863938, 0.0], [10.773176751863938, 0.0], [10.873176751863937, 0.0], [10.973176751863939, 0.0], [11.073176751863938, 0.0], [11.173176751863938, 0.0], [11.27317675186394, 0.0], [11.373176751863939, 0.0], [11.473176751863939, 0.0], [11.573176751863938, 0.0], [11.673176751863938, 0.0], [11.77317675186394, 0.0], [11.873176751863939, 0.0], [11.973176751863939, 0.0], [12.07317675186394, 0.0], [12.17317675186394, 0.0], [12.27317675186394, 0.0], [12.373176751863939, 0.0], [12.473176751863939, 0.0], [12.57317675186394, 0.0], [12.67317675186394, 0.0], [12.77317675186394, 0.0], [12.87317675186394, 0.0], [12.973176751863939, 0.0], [13.07317675186394, 0.0], [13.173176751863938, 0.0], [13.27317675186394, 0.0], [13.373176751863937, 0.0], [13.473176751863939, 0.0], [13.573176751863937, 0.0], [13.673176751863938, 0.0], [13.773176751863936, 0.0], [13.873176751863937, 0.0], [13.973176751863935, 0.0], [14.073176751863937, 0.0], [14.173176751863934, 0.0], [14.273176751863936, 0.0], [14.373176751863934, 0.0], [14.473176751863935, 0.0], [14.573176751863933, 0.0], [14.673176751863934, 0.0], [14.772639590036972, 0.0], [14.858004239664185, 0.0], [14.923368889291398, 0.0], [14.96873353891861, 0.0], [14.994098188545824, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554], "velocities": null}}, "time": 1740481184.063615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647691664442822, "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": 1740481184.063615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.083615} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.9488657, "x": 15.0, "y": 9.43240000000008, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.083615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644999888189448, "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": 1740481184.083615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.103615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639621929858138, "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": 1740481184.103615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.123615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634251420852472, "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": 1740481184.123615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.133615, "x": 12.916810700570888, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.143615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24553518762853593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628888349700659, "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": 1740481184.143615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.163615} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.916810700570888, 0.0], [9.079205073863163, 0.0], [9.179205073863162, 0.0], [9.279205073863164, 0.0], [9.379205073863163, 0.0], [9.479205073863163, 0.0], [9.579205073863163, 0.0], [9.679205073863162, 0.0], [9.779205073863162, 0.0], [9.879205073863163, 0.0], [9.979205073863163, 0.0], [10.079205073863163, 0.0], [10.179205073863162, 0.0], [10.279205073863164, 0.0], [10.379205073863163, 0.0], [10.479205073863163, 0.0], [10.579205073863163, 0.0], [10.679205073863164, 0.0], [10.779205073863164, 0.0], [10.879205073863163, 0.0], [10.979205073863163, 0.0], [11.079205073863164, 0.0], [11.179205073863164, 0.0], [11.279205073863164, 0.0], [11.379205073863163, 0.0], [11.479205073863163, 0.0], [11.579205073863164, 0.0], [11.679205073863164, 0.0], [11.779205073863164, 0.0], [11.879205073863165, 0.0], [11.979205073863165, 0.0], [12.079205073863164, 0.0], [12.179205073863164, 0.0], [12.279205073863164, 0.0], [12.379205073863165, 0.0], [12.479205073863165, 0.0], [12.579205073863164, 0.0], [12.679205073863166, 0.0], [12.779205073863166, 0.0], [12.879205073863165, 0.0], [12.979205073863165, 0.0], [13.079205073863164, 0.0], [13.179205073863164, 0.0], [13.279205073863164, 0.0], [13.379205073863163, 0.0], [13.479205073863163, 0.0], [13.579205073863163, 0.0], [13.679205073863162, 0.0], [13.779205073863162, 0.0], [13.879205073863162, 0.0], [13.979205073863161, 0.0], [14.079205073863161, 0.0], [14.17920507386316, 0.0], [14.27920507386316, 0.0], [14.37920507386316, 0.0], [14.47920507386316, 0.0], [14.57920507386316, 0.0], [14.679205073863159, 0.0], [14.778352137523807, 0.0], [14.862511122751174, 0.0], [14.926670107978541, 0.0], [14.97082909320591, 0.0], [14.994988078433279, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554], "velocities": null}}, "time": 1740481184.163615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634322253643347, "gear": 1, "accelerator_pedal_position": 0.24553518762853593, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.163615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.183615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629093636246496, "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": 1740481184.183615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.203615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623872259106184, "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": 1740481184.203615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.223615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616053744565964, "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": 1740481184.223615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.243615, "x": 13.022704217489116, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.243615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2462964808699367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613451181151169, "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": 1740481184.243615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.263615} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.022704217489116, 0.0], [9.185007400412305, 0.0], [9.285007400412304, 0.0], [9.385007400412304, 0.0], [9.485007400412306, 0.0], [9.585007400412305, 0.0], [9.685007400412305, 0.0], [9.785007400412304, 0.0], [9.885007400412304, 0.0], [9.985007400412304, 0.0], [10.085007400412305, 0.0], [10.185007400412305, 0.0], [10.285007400412304, 0.0], [10.385007400412304, 0.0], [10.485007400412306, 0.0], [10.585007400412305, 0.0], [10.685007400412305, 0.0], [10.785007400412304, 0.0], [10.885007400412306, 0.0], [10.985007400412306, 0.0], [11.085007400412305, 0.0], [11.185007400412307, 0.0], [11.285007400412306, 0.0], [11.385007400412306, 0.0], [11.485007400412306, 0.0], [11.585007400412305, 0.0], [11.685007400412307, 0.0], [11.785007400412306, 0.0], [11.885007400412306, 0.0], [11.985007400412307, 0.0], [12.085007400412307, 0.0], [12.185007400412307, 0.0], [12.285007400412306, 0.0], [12.385007400412306, 0.0], [12.485007400412307, 0.0], [12.585007400412307, 0.0], [12.685007400412307, 0.0], [12.785007400412308, 0.0], [12.885007400412308, 0.0], [12.985007400412307, 0.0], [13.085007400412307, 0.0], [13.185007400412307, 0.0], [13.285007400412306, 0.0], [13.385007400412306, 0.0], [13.485007400412306, 0.0], [13.585007400412305, 0.0], [13.685007400412305, 0.0], [13.785007400412304, 0.0], [13.885007400412304, 0.0], [13.985007400412304, 0.0], [14.085007400412303, 0.0], [14.185007400412303, 0.0], [14.285007400412303, 0.0], [14.385007400412302, 0.0], [14.485007400412302, 0.0], [14.585007400412302, 0.0], [14.685007400412301, 0.0], [14.783781882328674, 0.0], [14.866780402246214, 0.0], [14.929778922163752, 0.0], [14.972777442081293, 0.0], [14.995775961998833, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554], "velocities": null}}, "time": 1740481184.263615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961737788191656, "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": 1740481184.263615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.2836149} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614899737038708, "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": 1740481184.2836149} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3036149} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960994859300093, "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": 1740481184.3036149} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3236148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605004301189541, "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": 1740481184.3236148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3436148} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.169243, "x": 15.0, "y": 9.322400000000062, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.3436148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600066851143777, "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": 1740481184.3436148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.3536148, "x": 13.128423912970664, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.3636148} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.128423912970664, 0.0], [9.290643727783674, 0.0], [9.390643727783674, 0.0], [9.490643727783674, 0.0], [9.590643727783673, 0.0], [9.690643727783673, 0.0], [9.790643727783674, 0.0], [9.890643727783674, 0.0], [9.990643727783674, 0.0], [10.090643727783673, 0.0], [10.190643727783673, 0.0], [10.290643727783674, 0.0], [10.390643727783674, 0.0], [10.490643727783674, 0.0], [10.590643727783673, 0.0], [10.690643727783675, 0.0], [10.790643727783674, 0.0], [10.890643727783674, 0.0], [10.990643727783674, 0.0], [11.090643727783675, 0.0], [11.190643727783675, 0.0], [11.290643727783674, 0.0], [11.390643727783676, 0.0], [11.490643727783675, 0.0], [11.590643727783675, 0.0], [11.690643727783675, 0.0], [11.790643727783674, 0.0], [11.890643727783676, 0.0], [11.990643727783675, 0.0], [12.090643727783675, 0.0], [12.190643727783677, 0.0], [12.290643727783676, 0.0], [12.390643727783676, 0.0], [12.490643727783675, 0.0], [12.590643727783675, 0.0], [12.690643727783677, 0.0], [12.790643727783676, 0.0], [12.890643727783676, 0.0], [12.990643727783677, 0.0], [13.090643727783677, 0.0], [13.190643727783677, 0.0], [13.290643727783676, 0.0], [13.390643727783676, 0.0], [13.490643727783675, 0.0], [13.590643727783675, 0.0], [13.690643727783675, 0.0], [13.790643727783674, 0.0], [13.890643727783674, 0.0], [13.990643727783674, 0.0], [14.090643727783673, 0.0], [14.190643727783673, 0.0], [14.290643727783673, 0.0], [14.390643727783672, 0.0], [14.490643727783672, 0.0], [14.590643727783672, 0.0], [14.690643727783671, 0.0], [14.788991815175518, 0.0], [14.870863069618784, 0.0], [14.93273432406205, 0.0], [14.974605578505315, 0.0], [14.99647683294858, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541], "velocities": null}}, "time": 1740481184.3636148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2480357555406792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595136232421402, "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": 1740481184.3636148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.3836148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603741479615895, "gear": 1, "accelerator_pedal_position": 0.2480357555406792, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.3836148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4036148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612237170259696, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4036148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4236147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624958665282861, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4236147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4436147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629193292735466, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4436147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.4636147, "x": 13.234164838336826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.4636147} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.234164838336826, 0.0], [9.39658885582962, 0.0], [9.49658885582962, 0.0], [9.59658885582962, 0.0], [9.69658885582962, 0.0], [9.79658885582962, 0.0], [9.89658885582962, 0.0], [9.99658885582962, 0.0], [10.09658885582962, 0.0], [10.19658885582962, 0.0], [10.29658885582962, 0.0], [10.39658885582962, 0.0], [10.49658885582962, 0.0], [10.59658885582962, 0.0], [10.69658885582962, 0.0], [10.79658885582962, 0.0], [10.89658885582962, 0.0], [10.996588855829621, 0.0], [11.096588855829621, 0.0], [11.19658885582962, 0.0], [11.29658885582962, 0.0], [11.39658885582962, 0.0], [11.496588855829621, 0.0], [11.596588855829621, 0.0], [11.69658885582962, 0.0], [11.796588855829622, 0.0], [11.896588855829622, 0.0], [11.996588855829621, 0.0], [12.096588855829621, 0.0], [12.19658885582962, 0.0], [12.296588855829622, 0.0], [12.396588855829622, 0.0], [12.496588855829621, 0.0], [12.596588855829623, 0.0], [12.696588855829622, 0.0], [12.796588855829622, 0.0], [12.896588855829622, 0.0], [12.996588855829621, 0.0], [13.096588855829623, 0.0], [13.196588855829622, 0.0], [13.296588855829622, 0.0], [13.396588855829622, 0.0], [13.496588855829621, 0.0], [13.596588855829621, 0.0], [13.69658885582962, 0.0], [13.79658885582962, 0.0], [13.89658885582962, 0.0], [13.99658885582962, 0.0], [14.09658885582962, 0.0], [14.196588855829619, 0.0], [14.296588855829619, 0.0], [14.396588855829618, 0.0], [14.496588855829618, 0.0], [14.596588855829618, 0.0], [14.696588855829617, 0.0], [14.794418334342105, 0.0], [14.87510056317618, 0.0], [14.935782792010258, 0.0], [14.976465020844334, 0.0], [14.99714724967841, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541], "velocities": null}}, "time": 1740481184.4636147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24531571546332662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640228402937997, "gear": 1, "accelerator_pedal_position": 0.24531571546332662, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4636147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.4836147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96428012708645, "gear": 1, "accelerator_pedal_position": 0.24531571546332662, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4836147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5036147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964819201227989, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5036147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5236146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653575285396664, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5236146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5436146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658951099402568, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5436146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5636146} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.234164838336826, 0.0], [9.39658885582962, 0.0], [9.49658885582962, 0.0], [9.59658885582962, 0.0], [9.69658885582962, 0.0], [9.79658885582962, 0.0], [9.89658885582962, 0.0], [9.99658885582962, 0.0], [10.09658885582962, 0.0], [10.19658885582962, 0.0], [10.29658885582962, 0.0], [10.39658885582962, 0.0], [10.49658885582962, 0.0], [10.59658885582962, 0.0], [10.69658885582962, 0.0], [10.79658885582962, 0.0], [10.89658885582962, 0.0], [10.996588855829621, 0.0], [11.096588855829621, 0.0], [11.19658885582962, 0.0], [11.29658885582962, 0.0], [11.39658885582962, 0.0], [11.496588855829621, 0.0], [11.596588855829621, 0.0], [11.69658885582962, 0.0], [11.796588855829622, 0.0], [11.896588855829622, 0.0], [11.996588855829621, 0.0], [12.096588855829621, 0.0], [12.19658885582962, 0.0], [12.296588855829622, 0.0], [12.396588855829622, 0.0], [12.496588855829621, 0.0], [12.596588855829623, 0.0], [12.696588855829622, 0.0], [12.796588855829622, 0.0], [12.896588855829622, 0.0], [12.996588855829621, 0.0], [13.096588855829623, 0.0], [13.196588855829622, 0.0], [13.296588855829622, 0.0], [13.396588855829622, 0.0], [13.496588855829621, 0.0], [13.596588855829621, 0.0], [13.69658885582962, 0.0], [13.79658885582962, 0.0], [13.89658885582962, 0.0], [13.99658885582962, 0.0], [14.09658885582962, 0.0], [14.196588855829619, 0.0], [14.296588855829619, 0.0], [14.396588855829618, 0.0], [14.496588855829618, 0.0], [14.596588855829618, 0.0], [14.696588855829617, 0.0], [14.794418334342105, 0.0], [14.87510056317618, 0.0], [14.935782792010258, 0.0], [14.976465020844334, 0.0], [14.99714724967841, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541], "velocities": null}}, "time": 1740481184.5636146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664319463477441, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5636146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.5736146, "x": 13.340324842116338, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.5836146} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.389323, "x": 15.0, "y": 9.212400000000045, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.5836146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23750437759140702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669680386793197, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5836146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6036146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665022739317247, "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": 1740481184.6036146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6236145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660151135462551, "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": 1740481184.6236145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6436145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965528628352518, "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": 1740481184.6436145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6636145} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.340324842116338, 0.0], [9.502884902096557, 0.0], [9.602884902096557, 0.0], [9.702884902096557, 0.0], [9.802884902096556, 0.0], [9.902884902096558, 0.0], [10.002884902096557, 0.0], [10.102884902096557, 0.0], [10.202884902096557, 0.0], [10.302884902096556, 0.0], [10.402884902096556, 0.0], [10.502884902096557, 0.0], [10.602884902096557, 0.0], [10.702884902096557, 0.0], [10.802884902096558, 0.0], [10.902884902096558, 0.0], [11.002884902096557, 0.0], [11.102884902096557, 0.0], [11.202884902096557, 0.0], [11.302884902096558, 0.0], [11.402884902096558, 0.0], [11.502884902096557, 0.0], [11.602884902096559, 0.0], [11.702884902096558, 0.0], [11.802884902096558, 0.0], [11.902884902096558, 0.0], [12.002884902096557, 0.0], [12.102884902096559, 0.0], [12.202884902096558, 0.0], [12.302884902096558, 0.0], [12.40288490209656, 0.0], [12.50288490209656, 0.0], [12.602884902096559, 0.0], [12.702884902096558, 0.0], [12.802884902096558, 0.0], [12.90288490209656, 0.0], [13.00288490209656, 0.0], [13.102884902096559, 0.0], [13.20288490209656, 0.0], [13.30288490209656, 0.0], [13.40288490209656, 0.0], [13.50288490209656, 0.0], [13.602884902096559, 0.0], [13.702884902096558, 0.0], [13.802884902096558, 0.0], [13.902884902096558, 0.0], [14.002884902096557, 0.0], [14.102884902096557, 0.0], [14.202884902096557, 0.0], [14.302884902096556, 0.0], [14.402884902096556, 0.0], [14.502884902096556, 0.0], [14.602884902096555, 0.0], [14.702884902096555, 0.0], [14.800088089226794, 0.0], [14.879511108807481, 0.0], [14.93893412838817, 0.0], [14.97835714796886, 0.0], [14.99778016754955, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541], "velocities": null}}, "time": 1740481184.6636145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23660366612858955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650428173200805, "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": 1740481184.6636145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.6836145, "x": 13.446580471732716, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.6836145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436652840073644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644671707658239, "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": 1740481184.6836145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7036145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648623433028697, "gear": 1, "accelerator_pedal_position": 0.24436652840073644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7036145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7236145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652366761478108, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7236145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7436144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656104903257958, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7436144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7636144} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.446580471732716, 0.0], [9.609038066616005, 0.0], [9.709038066616005, 0.0], [9.809038066616004, 0.0], [9.909038066616004, 0.0], [10.009038066616004, 0.0], [10.109038066616005, 0.0], [10.209038066616005, 0.0], [10.309038066616004, 0.0], [10.409038066616004, 0.0], [10.509038066616004, 0.0], [10.609038066616005, 0.0], [10.709038066616005, 0.0], [10.809038066616004, 0.0], [10.909038066616004, 0.0], [11.009038066616005, 0.0], [11.109038066616005, 0.0], [11.209038066616005, 0.0], [11.309038066616004, 0.0], [11.409038066616006, 0.0], [11.509038066616005, 0.0], [11.609038066616005, 0.0], [11.709038066616005, 0.0], [11.809038066616004, 0.0], [11.909038066616006, 0.0], [12.009038066616005, 0.0], [12.109038066616005, 0.0], [12.209038066616007, 0.0], [12.309038066616006, 0.0], [12.409038066616006, 0.0], [12.509038066616005, 0.0], [12.609038066616005, 0.0], [12.709038066616007, 0.0], [12.809038066616006, 0.0], [12.909038066616006, 0.0], [13.009038066616007, 0.0], [13.109038066616007, 0.0], [13.209038066616007, 0.0], [13.309038066616006, 0.0], [13.409038066616006, 0.0], [13.509038066616007, 0.0], [13.609038066616007, 0.0], [13.709038066616007, 0.0], [13.809038066616006, 0.0], [13.909038066616006, 0.0], [14.009038066616005, 0.0], [14.109038066616005, 0.0], [14.209038066616005, 0.0], [14.309038066616004, 0.0], [14.409038066616004, 0.0], [14.509038066616004, 0.0], [14.609038066616003, 0.0], [14.709038066616003, 0.0], [14.805552573306247, 0.0], [14.883744959983046, 0.0], [14.941937346659845, 0.0], [14.980129733336646, 0.0], [14.998322120013444, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542], "velocities": null}}, "time": 1740481184.7636144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686053759900488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965983786499602, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7636144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7836144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686053759900488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965438933880903, "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": 1740481184.7836144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.7936144, "x": 13.55276293091197, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8036144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449448676771709, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96489483629154, "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": 1740481184.8036144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8236144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449957491813005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653616836866404, "gear": 1, "accelerator_pedal_position": 0.2449448676771709, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.8236144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8436143} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.7192879, "x": 15.0, "y": 9.04740000000002, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.8436143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449957491813005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658342421935795, "gear": 1, "accelerator_pedal_position": 0.2449957491813005, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.8436143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8636143} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.55276293091197, 0.0], [9.71525334545449, 0.0], [9.81525334545449, 0.0], [9.91525334545449, 0.0], [10.01525334545449, 0.0], [10.115253345454489, 0.0], [10.21525334545449, 0.0], [10.31525334545449, 0.0], [10.41525334545449, 0.0], [10.51525334545449, 0.0], [10.61525334545449, 0.0], [10.71525334545449, 0.0], [10.81525334545449, 0.0], [10.91525334545449, 0.0], [11.01525334545449, 0.0], [11.11525334545449, 0.0], [11.21525334545449, 0.0], [11.31525334545449, 0.0], [11.415253345454492, 0.0], [11.515253345454491, 0.0], [11.61525334545449, 0.0], [11.71525334545449, 0.0], [11.81525334545449, 0.0], [11.915253345454492, 0.0], [12.015253345454491, 0.0], [12.11525334545449, 0.0], [12.21525334545449, 0.0], [12.31525334545449, 0.0], [12.415253345454492, 0.0], [12.515253345454491, 0.0], [12.61525334545449, 0.0], [12.715253345454492, 0.0], [12.815253345454492, 0.0], [12.915253345454492, 0.0], [13.015253345454491, 0.0], [13.11525334545449, 0.0], [13.215253345454492, 0.0], [13.315253345454492, 0.0], [13.415253345454492, 0.0], [13.515253345454493, 0.0], [13.615253345454493, 0.0], [13.715253345454492, 0.0], [13.815253345454492, 0.0], [13.915253345454492, 0.0], [14.015253345454491, 0.0], [14.11525334545449, 0.0], [14.21525334545449, 0.0], [14.31525334545449, 0.0], [14.41525334545449, 0.0], [14.51525334545449, 0.0], [14.615253345454489, 0.0], [14.715253345454489, 0.0], [14.810995346361485, 0.0], [14.887944677270587, 0.0], [14.94489400817969, 0.0], [14.981843339088792, 0.0], [14.998792669997894, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542], "velocities": null}}, "time": 1740481184.8636143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678075496413373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660284151817142, "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": 1740481184.8636143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8836143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678075496413373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657508770694879, "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": 1740481184.8836143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.9036143, "x": 13.658979062751342, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9036143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469945435498003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651963778461716, "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": 1740481184.9036143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9236143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447016061436341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656321413954142, "gear": 1, "accelerator_pedal_position": 0.24469945435498003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.9236143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9436142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447016061436341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660675699748852, "gear": 1, "accelerator_pedal_position": 0.2447016061436341, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.9436142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9636142} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.658979062751342, 0.0], [9.821470850860203, 0.0], [9.921470850860203, 0.0], [10.021470850860203, 0.0], [10.121470850860204, 0.0], [10.221470850860204, 0.0], [10.321470850860203, 0.0], [10.421470850860203, 0.0], [10.521470850860203, 0.0], [10.621470850860202, 0.0], [10.721470850860204, 0.0], [10.821470850860203, 0.0], [10.921470850860203, 0.0], [11.021470850860203, 0.0], [11.121470850860204, 0.0], [11.221470850860204, 0.0], [11.321470850860203, 0.0], [11.421470850860203, 0.0], [11.521470850860204, 0.0], [11.621470850860204, 0.0], [11.721470850860204, 0.0], [11.821470850860205, 0.0], [11.921470850860205, 0.0], [12.021470850860204, 0.0], [12.121470850860204, 0.0], [12.221470850860204, 0.0], [12.321470850860205, 0.0], [12.421470850860205, 0.0], [12.521470850860204, 0.0], [12.621470850860206, 0.0], [12.721470850860205, 0.0], [12.821470850860205, 0.0], [12.921470850860205, 0.0], [13.021470850860204, 0.0], [13.121470850860206, 0.0], [13.221470850860205, 0.0], [13.321470850860205, 0.0], [13.421470850860207, 0.0], [13.521470850860206, 0.0], [13.621470850860206, 0.0], [13.721470850860205, 0.0], [13.821470850860205, 0.0], [13.921470850860205, 0.0], [14.021470850860204, 0.0], [14.121470850860204, 0.0], [14.221470850860204, 0.0], [14.321470850860203, 0.0], [14.421470850860203, 0.0], [14.521470850860203, 0.0], [14.621470850860202, 0.0], [14.721470850860202, 0.0], [14.81636276833752, 0.0], [14.89206859816548, 0.0], [14.94777442799344, 0.0], [14.983480257821398, 0.0], [14.99918608764936, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542], "velocities": null}}, "time": 1740481184.9636142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662243166351, "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": 1740481184.9636142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9836142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659464309617939, "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": 1740481184.9836142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481185.0036142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653912373714963, "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": 1740481185.0036142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.0136142, "x": 13.765220848065695, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0236142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470868187601422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648368131305218, "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": 1740481185.0236142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0436141} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470268560197111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652742279222929, "gear": 1, "accelerator_pedal_position": 0.24470868187601422, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.0436141} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0636141} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.765220848065695, 0.0], [9.927708805625318, 0.0], [10.027708805625318, 0.0], [10.127708805625318, 0.0], [10.22770880562532, 0.0], [10.327708805625319, 0.0], [10.427708805625318, 0.0], [10.527708805625318, 0.0], [10.627708805625318, 0.0], [10.727708805625317, 0.0], [10.827708805625319, 0.0], [10.927708805625318, 0.0], [11.027708805625318, 0.0], [11.127708805625318, 0.0], [11.22770880562532, 0.0], [11.327708805625319, 0.0], [11.427708805625318, 0.0], [11.52770880562532, 0.0], [11.62770880562532, 0.0], [11.72770880562532, 0.0], [11.827708805625319, 0.0], [11.927708805625318, 0.0], [12.02770880562532, 0.0], [12.12770880562532, 0.0], [12.22770880562532, 0.0], [12.327708805625319, 0.0], [12.427708805625318, 0.0], [12.52770880562532, 0.0], [12.62770880562532, 0.0], [12.72770880562532, 0.0], [12.82770880562532, 0.0], [12.92770880562532, 0.0], [13.02770880562532, 0.0], [13.12770880562532, 0.0], [13.22770880562532, 0.0], [13.32770880562532, 0.0], [13.42770880562532, 0.0], [13.52770880562532, 0.0], [13.627708805625321, 0.0], [13.727708805625321, 0.0], [13.82770880562532, 0.0], [13.927708805625322, 0.0], [14.02770880562532, 0.0], [14.127708805625321, 0.0], [14.22770880562532, 0.0], [14.32770880562532, 0.0], [14.427708805625318, 0.0], [14.52770880562532, 0.0], [14.627708805625318, 0.0], [14.72770880562532, 0.0], [14.821670147153604, 0.0], [14.89612838602854, 0.0], [14.950586624903476, 0.0], [14.985044863778413, 0.0], [14.99950310265335, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543], "velocities": null}}, "time": 1740481185.0636141} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659280904344342, "gear": 1, "accelerator_pedal_position": 0.24470268560197111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.0636141} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.083614} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.9393387, "x": 15.0, "y": 8.937400000000002, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.083614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965651000024263, "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": 1740481185.083614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.103614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650973952576756, "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": 1740481185.103614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.123614, "x": 13.871404394617036, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.123614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486897234500515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647735614460378, "gear": 1, "accelerator_pedal_position": 0.24486897234500515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.123614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.143614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482756346310786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650024066343911, "gear": 1, "accelerator_pedal_position": 0.24486897234500515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.143614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.163614} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.871404394617036, 0.0], [10.033865651870814, 0.0], [10.133865651870813, 0.0], [10.233865651870815, 0.0], [10.333865651870815, 0.0], [10.433865651870814, 0.0], [10.533865651870814, 0.0], [10.633865651870813, 0.0], [10.733865651870815, 0.0], [10.833865651870815, 0.0], [10.933865651870814, 0.0], [11.033865651870814, 0.0], [11.133865651870813, 0.0], [11.233865651870815, 0.0], [11.333865651870815, 0.0], [11.433865651870814, 0.0], [11.533865651870814, 0.0], [11.633865651870815, 0.0], [11.733865651870815, 0.0], [11.833865651870815, 0.0], [11.933865651870814, 0.0], [12.033865651870816, 0.0], [12.133865651870815, 0.0], [12.233865651870815, 0.0], [12.333865651870816, 0.0], [12.433865651870816, 0.0], [12.533865651870816, 0.0], [12.633865651870815, 0.0], [12.733865651870815, 0.0], [12.833865651870816, 0.0], [12.933865651870816, 0.0], [13.033865651870816, 0.0], [13.133865651870817, 0.0], [13.233865651870817, 0.0], [13.333865651870816, 0.0], [13.433865651870816, 0.0], [13.533865651870816, 0.0], [13.633865651870817, 0.0], [13.733865651870817, 0.0], [13.833865651870816, 0.0], [13.933865651870816, 0.0], [14.033865651870816, 0.0], [14.133865651870815, 0.0], [14.233865651870815, 0.0], [14.333865651870815, 0.0], [14.433865651870814, 0.0], [14.533865651870814, 0.0], [14.633865651870813, 0.0], [14.733865651870813, 0.0], [14.826832204307097, 0.0], [14.900059073932933, 0.0], [14.953285943558772, 0.0], [14.986512813184609, 0.0], [14.999739682810446, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543], "velocities": null}}, "time": 1740481185.163614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651817435930506, "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": 1740481185.163614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.183614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649092291467711, "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": 1740481185.183614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.203614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643647666734677, "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": 1740481185.203614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.223614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638210584550599, "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": 1740481185.223614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.233614, "x": 13.977524494593599, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.243614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24529459128401765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632781033284568, "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": 1740481185.243614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.263614} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.977524494593599, 0.0], [10.139938050838804, 0.0], [10.239938050838804, 0.0], [10.339938050838803, 0.0], [10.439938050838805, 0.0], [10.539938050838805, 0.0], [10.639938050838804, 0.0], [10.739938050838804, 0.0], [10.839938050838803, 0.0], [10.939938050838805, 0.0], [11.039938050838805, 0.0], [11.139938050838804, 0.0], [11.239938050838804, 0.0], [11.339938050838803, 0.0], [11.439938050838805, 0.0], [11.539938050838805, 0.0], [11.639938050838804, 0.0], [11.739938050838804, 0.0], [11.839938050838805, 0.0], [11.939938050838805, 0.0], [12.039938050838805, 0.0], [12.139938050838804, 0.0], [12.239938050838806, 0.0], [12.339938050838805, 0.0], [12.439938050838805, 0.0], [12.539938050838806, 0.0], [12.639938050838806, 0.0], [12.739938050838806, 0.0], [12.839938050838805, 0.0], [12.939938050838805, 0.0], [13.039938050838806, 0.0], [13.139938050838806, 0.0], [13.239938050838806, 0.0], [13.339938050838807, 0.0], [13.439938050838807, 0.0], [13.539938050838806, 0.0], [13.639938050838806, 0.0], [13.739938050838806, 0.0], [13.839938050838807, 0.0], [13.939938050838807, 0.0], [14.039938050838806, 0.0], [14.139938050838806, 0.0], [14.239938050838806, 0.0], [14.339938050838805, 0.0], [14.439938050838805, 0.0], [14.539938050838805, 0.0], [14.639938050838804, 0.0], [14.739938050838804, 0.0], [14.83184919785012, 0.0], [14.90386158768236, 0.0], [14.9558739775146, 0.0], [14.987886367346839, 0.0], [14.999898757179079, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435], "velocities": null}}, "time": 1740481185.263614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635263694353584, "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": 1740481185.263614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.283614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632620315786913, "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": 1740481185.283614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.303614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627339050282862, "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": 1740481185.303614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.323614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622065097571474, "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": 1740481185.323614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.3436139, "x": 14.083457424204878, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3436139} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.1588736, "x": 15.0, "y": 8.827399999999985, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.3436139} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607797456257674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616798446414772, "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": 1740481185.3436139} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3636138} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.083457424204878, 0.0], [10.245777784185956, 0.0], [10.345777784185955, 0.0], [10.445777784185957, 0.0], [10.545777784185956, 0.0], [10.645777784185956, 0.0], [10.745777784185956, 0.0], [10.845777784185955, 0.0], [10.945777784185957, 0.0], [11.045777784185956, 0.0], [11.145777784185956, 0.0], [11.245777784185956, 0.0], [11.345777784185955, 0.0], [11.445777784185957, 0.0], [11.545777784185956, 0.0], [11.645777784185956, 0.0], [11.745777784185957, 0.0], [11.845777784185957, 0.0], [11.945777784185957, 0.0], [12.045777784185956, 0.0], [12.145777784185956, 0.0], [12.245777784185957, 0.0], [12.345777784185957, 0.0], [12.445777784185957, 0.0], [12.545777784185958, 0.0], [12.645777784185958, 0.0], [12.745777784185957, 0.0], [12.845777784185957, 0.0], [12.945777784185957, 0.0], [13.045777784185958, 0.0], [13.145777784185958, 0.0], [13.245777784185957, 0.0], [13.345777784185959, 0.0], [13.445777784185958, 0.0], [13.545777784185958, 0.0], [13.645777784185958, 0.0], [13.745777784185957, 0.0], [13.845777784185959, 0.0], [13.945777784185958, 0.0], [14.045777784185958, 0.0], [14.14577778418596, 0.0], [14.245777784185957, 0.0], [14.345777784185959, 0.0], [14.445777784185957, 0.0], [14.545777784185958, 0.0], [14.645777784185956, 0.0], [14.745777784185957, 0.0], [14.836604400242384, 0.0], [14.907448843405193, 0.0], [14.958293286568, 0.0], [14.98913772973081, 0.0], [14.99998217289362, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544], "velocities": null}}, "time": 1740481185.3636138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622927337469835, "gear": 1, "accelerator_pedal_position": 0.24607797456257674, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.3636138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3836138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617919189507705, "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": 1740481185.3836138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4036138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612917974262055, "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": 1740481185.4036138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4236138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607923681135871, "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": 1740481185.4236138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4436138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9602936299550964, "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": 1740481185.4436138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.4536138, "x": 14.189210400288738, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.4636137} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.189210400288738, 0.0], [10.351445422871805, 0.0], [10.451445422871805, 0.0], [10.551445422871804, 0.0], [10.651445422871804, 0.0], [10.751445422871804, 0.0], [10.851445422871805, 0.0], [10.951445422871805, 0.0], [11.051445422871804, 0.0], [11.151445422871804, 0.0], [11.251445422871804, 0.0], [11.351445422871805, 0.0], [11.451445422871805, 0.0], [11.551445422871804, 0.0], [11.651445422871804, 0.0], [11.751445422871804, 0.0], [11.851445422871805, 0.0], [11.951445422871805, 0.0], [12.051445422871804, 0.0], [12.151445422871806, 0.0], [12.251445422871805, 0.0], [12.351445422871805, 0.0], [12.451445422871805, 0.0], [12.551445422871804, 0.0], [12.651445422871806, 0.0], [12.751445422871805, 0.0], [12.851445422871805, 0.0], [12.951445422871807, 0.0], [13.051445422871806, 0.0], [13.151445422871806, 0.0], [13.251445422871805, 0.0], [13.351445422871805, 0.0], [13.451445422871807, 0.0], [13.551445422871806, 0.0], [13.651445422871806, 0.0], [13.751445422871807, 0.0], [13.851445422871807, 0.0], [13.951445422871807, 0.0], [14.051445422871806, 0.0], [14.151445422871806, 0.0], [14.251445422871807, 0.0], [14.351445422871807, 0.0], [14.451445422871807, 0.0], [14.551445422871806, 0.0], [14.651445422871806, 0.0], [14.751443333624527, 0.0], [14.841154249050167, 0.0], [14.910865164475805, 0.0], [14.960576079901443, 0.0], [14.990286995327082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445], "velocities": null}}, "time": 1740481185.4636137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478589181720773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595468163219901, "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": 1740481185.4636137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.4836137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599661522903126, "gear": 1, "accelerator_pedal_position": 0.2478589181720773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.4836137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5036137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607938415649502, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5036137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5236137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620332284122753, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5236137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5436137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624457854666065, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5436137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.5636137, "x": 14.2949173179372, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.5636137} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.2949173179372, 0.0], [10.457317240948036, 0.0], [10.557317240948036, 0.0], [10.657317240948036, 0.0], [10.757317240948035, 0.0], [10.857317240948035, 0.0], [10.957317240948036, 0.0], [11.057317240948036, 0.0], [11.157317240948036, 0.0], [11.257317240948035, 0.0], [11.357317240948035, 0.0], [11.457317240948036, 0.0], [11.557317240948036, 0.0], [11.657317240948036, 0.0], [11.757317240948037, 0.0], [11.857317240948037, 0.0], [11.957317240948036, 0.0], [12.057317240948036, 0.0], [12.157317240948036, 0.0], [12.257317240948037, 0.0], [12.357317240948037, 0.0], [12.457317240948036, 0.0], [12.557317240948038, 0.0], [12.657317240948037, 0.0], [12.757317240948037, 0.0], [12.857317240948037, 0.0], [12.957317240948036, 0.0], [13.057317240948038, 0.0], [13.157317240948037, 0.0], [13.257317240948037, 0.0], [13.357317240948039, 0.0], [13.457317240948038, 0.0], [13.557317240948038, 0.0], [13.657317240948037, 0.0], [13.757317240948037, 0.0], [13.857317240948039, 0.0], [13.957317240948038, 0.0], [14.057317240948038, 0.0], [14.15731724094804, 0.0], [14.257317240948039, 0.0], [14.357317240948039, 0.0], [14.457317240948038, 0.0], [14.557317240948038, 0.0], [14.657317240948037, 0.0], [14.757263698932945, 0.0], [14.845800250743338, 0.0], [14.91433680255373, 0.0], [14.962873354364124, 0.0], [14.991409906174516, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545], "velocities": null}}, "time": 1740481185.5636137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24564664555055848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9636817432391954, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5636137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.5836136} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.379688, "x": 15.0, "y": 8.717399999999968, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.5836136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639599494642604, "gear": 1, "accelerator_pedal_position": 0.24564664555055848, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5836136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6036136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964535919772671, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6036136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6236136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651110922028504, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6236136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6436136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656854677277973, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6436136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6636136} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.2949173179372, 0.0], [10.457317240948036, 0.0], [10.557317240948036, 0.0], [10.657317240948036, 0.0], [10.757317240948035, 0.0], [10.857317240948035, 0.0], [10.957317240948036, 0.0], [11.057317240948036, 0.0], [11.157317240948036, 0.0], [11.257317240948035, 0.0], [11.357317240948035, 0.0], [11.457317240948036, 0.0], [11.557317240948036, 0.0], [11.657317240948036, 0.0], [11.757317240948037, 0.0], [11.857317240948037, 0.0], [11.957317240948036, 0.0], [12.057317240948036, 0.0], [12.157317240948036, 0.0], [12.257317240948037, 0.0], [12.357317240948037, 0.0], [12.457317240948036, 0.0], [12.557317240948038, 0.0], [12.657317240948037, 0.0], [12.757317240948037, 0.0], [12.857317240948037, 0.0], [12.957317240948036, 0.0], [13.057317240948038, 0.0], [13.157317240948037, 0.0], [13.257317240948037, 0.0], [13.357317240948039, 0.0], [13.457317240948038, 0.0], [13.557317240948038, 0.0], [13.657317240948037, 0.0], [13.757317240948037, 0.0], [13.857317240948039, 0.0], [13.957317240948038, 0.0], [14.057317240948038, 0.0], [14.15731724094804, 0.0], [14.257317240948039, 0.0], [14.357317240948039, 0.0], [14.457317240948038, 0.0], [14.557317240948038, 0.0], [14.657317240948037, 0.0], [14.757263698932945, 0.0], [14.845800250743338, 0.0], [14.91433680255373, 0.0], [14.962873354364124, 0.0], [14.991409906174516, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545], "velocities": null}}, "time": 1740481185.6636136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665455389443763, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6636136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.6736135, "x": 14.40104677432711, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.6836135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23751505135370596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668318319499958, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6836135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7036135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663675897743825, "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": 1740481185.7036135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7236135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656420155504944, "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": 1740481185.7236135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7436135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654004927030558, "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": 1740481185.7436135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7636135} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.40104677432711, 0.0], [10.563599956536308, 0.0], [10.663599956536308, 0.0], [10.763599956536307, 0.0], [10.863599956536307, 0.0], [10.963599956536306, 0.0], [11.063599956536308, 0.0], [11.163599956536308, 0.0], [11.263599956536307, 0.0], [11.363599956536307, 0.0], [11.463599956536306, 0.0], [11.563599956536308, 0.0], [11.663599956536308, 0.0], [11.763599956536307, 0.0], [11.863599956536307, 0.0], [11.963599956536306, 0.0], [12.063599956536308, 0.0], [12.163599956536308, 0.0], [12.263599956536307, 0.0], [12.363599956536309, 0.0], [12.463599956536308, 0.0], [12.563599956536308, 0.0], [12.663599956536308, 0.0], [12.763599956536307, 0.0], [12.863599956536309, 0.0], [12.963599956536308, 0.0], [13.063599956536308, 0.0], [13.16359995653631, 0.0], [13.263599956536309, 0.0], [13.363599956536309, 0.0], [13.463599956536308, 0.0], [13.563599956536308, 0.0], [13.66359995653631, 0.0], [13.763599956536309, 0.0], [13.863599956536309, 0.0], [13.96359995653631, 0.0], [14.06359995653631, 0.0], [14.16359995653631, 0.0], [14.263599956536309, 0.0], [14.363599956536309, 0.0], [14.46359995653631, 0.0], [14.56359995653631, 0.0], [14.66359995653631, 0.0], [14.76341499771852, 0.0], [14.850695006411257, 0.0], [14.917975015103995, 0.0], [14.965255023796733, 0.0], [14.99253503248947, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545], "velocities": null}}, "time": 1740481185.7636135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23662165476017788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646312368651588, "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": 1740481185.7636135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.7836134, "x": 14.507287821250857, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.7836134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24444443481646072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643447233269238, "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": 1740481185.7836134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8036134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964749800421164, "gear": 1, "accelerator_pedal_position": 0.24444443481646072, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8036134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8236134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651343158286897, "gear": 1, "accelerator_pedal_position": 0.2442843753461832, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8236134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8436134} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.7099507, "x": 15.0, "y": 8.552399999999942, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.8436134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655182984766596, "gear": 1, "accelerator_pedal_position": 0.2442843753461832, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8436134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8636134} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.507287821250857, 0.0], [10.669739604933314, 0.0], [10.769739604933314, 0.0], [10.869739604933313, 0.0], [10.969739604933313, 0.0], [11.069739604933314, 0.0], [11.169739604933314, 0.0], [11.269739604933314, 0.0], [11.369739604933313, 0.0], [11.469739604933313, 0.0], [11.569739604933314, 0.0], [11.669739604933314, 0.0], [11.769739604933314, 0.0], [11.869739604933313, 0.0], [11.969739604933313, 0.0], [12.069739604933314, 0.0], [12.169739604933314, 0.0], [12.269739604933314, 0.0], [12.369739604933315, 0.0], [12.469739604933315, 0.0], [12.569739604933314, 0.0], [12.669739604933314, 0.0], [12.769739604933314, 0.0], [12.869739604933315, 0.0], [12.969739604933315, 0.0], [13.069739604933314, 0.0], [13.169739604933316, 0.0], [13.269739604933315, 0.0], [13.369739604933315, 0.0], [13.469739604933315, 0.0], [13.569739604933314, 0.0], [13.669739604933316, 0.0], [13.769739604933315, 0.0], [13.869739604933315, 0.0], [13.969739604933316, 0.0], [14.069739604933316, 0.0], [14.169739604933316, 0.0], [14.269739604933315, 0.0], [14.369739604933315, 0.0], [14.469739604933316, 0.0], [14.569739604933316, 0.0], [14.669739604933316, 0.0], [14.769349952930392, 0.0], [14.85540203194373, 0.0], [14.921454110957065, 0.0], [14.967506189970402, 0.0], [14.99355826898374, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546], "velocities": null}}, "time": 1740481185.8636134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687443539849587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656301537632771, "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": 1740481185.8636134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8836133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687443539849587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653587467394158, "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": 1740481185.8836133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.8936133, "x": 14.613459458334486, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9036133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450056531733539, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648164968823169, "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": 1740481185.9036133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9236133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24505967537036713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652910483715643, "gear": 1, "accelerator_pedal_position": 0.2450056531733539, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.9236133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9436133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24505967537036713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657716927620865, "gear": 1, "accelerator_pedal_position": 0.24505967537036713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.9436133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9636133} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.613459458334486, 0.0], [10.7759461873779, 0.0], [10.875946187377899, 0.0], [10.975946187377899, 0.0], [11.075946187377898, 0.0], [11.1759461873779, 0.0], [11.2759461873779, 0.0], [11.375946187377899, 0.0], [11.475946187377899, 0.0], [11.575946187377898, 0.0], [11.675946187377898, 0.0], [11.7759461873779, 0.0], [11.875946187377899, 0.0], [11.975946187377899, 0.0], [12.075946187377898, 0.0], [12.1759461873779, 0.0], [12.2759461873779, 0.0], [12.375946187377899, 0.0], [12.475946187377899, 0.0], [12.5759461873779, 0.0], [12.6759461873779, 0.0], [12.7759461873779, 0.0], [12.875946187377899, 0.0], [12.9759461873779, 0.0], [13.0759461873779, 0.0], [13.1759461873779, 0.0], [13.275946187377901, 0.0], [13.3759461873779, 0.0], [13.4759461873779, 0.0], [13.5759461873779, 0.0], [13.6759461873779, 0.0], [13.775946187377901, 0.0], [13.8759461873779, 0.0], [13.9759461873779, 0.0], [14.075946187377902, 0.0], [14.175946187377901, 0.0], [14.275946187377901, 0.0], [14.3759461873779, 0.0], [14.4759461873779, 0.0], [14.575946187377902, 0.0], [14.675946187377901, 0.0], [14.775272982738452, 0.0], [14.860083745262871, 0.0], [14.924894507787291, 0.0], [14.96970527031171, 0.0], [14.994516032836131, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546], "velocities": null}}, "time": 1740481185.9636133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678982599969858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659745451453964, "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": 1740481185.9636133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9836133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678982599969858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656976113156179, "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": 1740481185.9836133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.0036132, "x": 14.719668543701626, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0036132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24473830452889292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651443193920323, "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": 1740481186.0036132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0236132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24474243482843702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965805383894825, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0236132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0436132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24474243482843702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660256053756988, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0436132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0636132} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.719668543701626, 0.0], [10.882157914240075, 0.0], [10.982157914240075, 0.0], [11.082157914240074, 0.0], [11.182157914240076, 0.0], [11.282157914240075, 0.0], [11.382157914240075, 0.0], [11.482157914240075, 0.0], [11.582157914240074, 0.0], [11.682157914240076, 0.0], [11.782157914240075, 0.0], [11.882157914240075, 0.0], [11.982157914240075, 0.0], [12.082157914240074, 0.0], [12.182157914240076, 0.0], [12.282157914240075, 0.0], [12.382157914240075, 0.0], [12.482157914240076, 0.0], [12.582157914240076, 0.0], [12.682157914240076, 0.0], [12.782157914240075, 0.0], [12.882157914240075, 0.0], [12.982157914240076, 0.0], [13.082157914240076, 0.0], [13.182157914240076, 0.0], [13.282157914240077, 0.0], [13.382157914240077, 0.0], [13.482157914240076, 0.0], [13.582157914240076, 0.0], [13.682157914240076, 0.0], [13.782157914240077, 0.0], [13.882157914240077, 0.0], [13.982157914240076, 0.0], [14.082157914240078, 0.0], [14.182157914240078, 0.0], [14.282157914240077, 0.0], [14.382157914240077, 0.0], [14.482157914240076, 0.0], [14.582157914240078, 0.0], [14.682157914240078, 0.0], [14.781123782791806, 0.0], [14.86469219994379, 0.0], [14.928260617095773, 0.0], [14.971829034247758, 0.0], [14.995397451399743, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546], "velocities": null}}, "time": 1740481186.0636132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966685354279933, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0636132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0836132} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.9288304, "x": 15.0, "y": 8.442399999999925, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.0836132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664075215125854, "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": 1740481186.0836132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.1036131} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965852433701034, "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": 1740481186.1036131} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.1136131, "x": 14.825925658849366, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.123613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.244618869032256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652981151945497, "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": 1740481186.123613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.143613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465020425973907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657236680957294, "gear": 1, "accelerator_pedal_position": 0.244618869032256, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.143613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.163613} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.825925658849366, 0.0], [10.98843492947157, 0.0], [11.08843492947157, 0.0], [11.188434929471569, 0.0], [11.288434929471569, 0.0], [11.388434929471568, 0.0], [11.48843492947157, 0.0], [11.58843492947157, 0.0], [11.688434929471569, 0.0], [11.788434929471569, 0.0], [11.888434929471568, 0.0], [11.98843492947157, 0.0], [12.08843492947157, 0.0], [12.188434929471569, 0.0], [12.288434929471569, 0.0], [12.38843492947157, 0.0], [12.48843492947157, 0.0], [12.58843492947157, 0.0], [12.688434929471569, 0.0], [12.78843492947157, 0.0], [12.88843492947157, 0.0], [12.98843492947157, 0.0], [13.088434929471571, 0.0], [13.18843492947157, 0.0], [13.28843492947157, 0.0], [13.38843492947157, 0.0], [13.48843492947157, 0.0], [13.588434929471571, 0.0], [13.68843492947157, 0.0], [13.78843492947157, 0.0], [13.888434929471572, 0.0], [13.988434929471572, 0.0], [14.088434929471571, 0.0], [14.18843492947157, 0.0], [14.28843492947157, 0.0], [14.388434929471572, 0.0], [14.488434929471572, 0.0], [14.588434929471571, 0.0], [14.688434929471573, 0.0], [14.786957685668087, 0.0], [14.869270699773772, 0.0], [14.931583713879458, 0.0], [14.973896727985144, 0.0], [14.99620974209083, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547], "velocities": null}}, "time": 1740481186.163613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661525468258256, "gear": 1, "accelerator_pedal_position": 0.24465020425973907, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.163613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.183613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655916346181515, "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": 1740481186.183613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.203613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965031499729521, "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": 1740481186.203613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.223613, "x": 14.932133228619435, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.223613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24473142903873404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644721409572589, "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": 1740481186.223613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.243613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465120806028273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649129033853086, "gear": 1, "accelerator_pedal_position": 0.24473142903873404, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.243613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.263613} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.932133228619435, 0.0], [11.094591058959539, 0.0], [11.19459105895954, 0.0], [11.29459105895954, 0.0], [11.39459105895954, 0.0], [11.49459105895954, 0.0], [11.594591058959539, 0.0], [11.694591058959539, 0.0], [11.79459105895954, 0.0], [11.89459105895954, 0.0], [11.99459105895954, 0.0], [12.094591058959539, 0.0], [12.194591058959539, 0.0], [12.29459105895954, 0.0], [12.39459105895954, 0.0], [12.49459105895954, 0.0], [12.59459105895954, 0.0], [12.69459105895954, 0.0], [12.79459105895954, 0.0], [12.89459105895954, 0.0], [12.99459105895954, 0.0], [13.09459105895954, 0.0], [13.19459105895954, 0.0], [13.29459105895954, 0.0], [13.394591058959541, 0.0], [13.494591058959541, 0.0], [13.59459105895954, 0.0], [13.69459105895954, 0.0], [13.79459105895954, 0.0], [13.894591058959541, 0.0], [13.994591058959541, 0.0], [14.09459105895954, 0.0], [14.194591058959542, 0.0], [14.294591058959542, 0.0], [14.394591058959541, 0.0], [14.494591058959541, 0.0], [14.59459105895954, 0.0], [14.694591058959542, 0.0], [14.79260269642041, 0.0], [14.8736844846285, 0.0], [14.934766272836592, 0.0], [14.975848061044683, 0.0], [14.996929849252776, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547], "velocities": null}}, "time": 1740481186.263613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653430310154697, "gear": 1, "accelerator_pedal_position": 0.24465120806028273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.263613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.283613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647989957692692, "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": 1740481186.283613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.303613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642557142805238, "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": 1740481186.303613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.323613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963713185386886, "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": 1740481186.323613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.333613, "x": 15.03824222008845, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.343613} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.1501093, "x": 15.0, "y": 8.332399999999907, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.343613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24534451162615734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631714079281093, "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": 1740481186.343613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.363613} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.03824222008845, 0.0], [11.200650554583278, 0.0], [11.300650554583278, 0.0], [11.400650554583278, 0.0], [11.500650554583277, 0.0], [11.600650554583279, 0.0], [11.700650554583278, 0.0], [11.800650554583278, 0.0], [11.900650554583278, 0.0], [12.000650554583277, 0.0], [12.100650554583279, 0.0], [12.200650554583278, 0.0], [12.300650554583278, 0.0], [12.400650554583278, 0.0], [12.500650554583277, 0.0], [12.600650554583279, 0.0], [12.700650554583278, 0.0], [12.800650554583278, 0.0], [12.90065055458328, 0.0], [13.00065055458328, 0.0], [13.100650554583279, 0.0], [13.20065055458328, 0.0], [13.300650554583278, 0.0], [13.40065055458328, 0.0], [13.50065055458328, 0.0], [13.600650554583279, 0.0], [13.70065055458328, 0.0], [13.80065055458328, 0.0], [13.90065055458328, 0.0], [14.000650554583281, 0.0], [14.100650554583279, 0.0], [14.20065055458328, 0.0], [14.30065055458328, 0.0], [14.40065055458328, 0.0], [14.500650554583281, 0.0], [14.60065055458328, 0.0], [14.70065055458328, 0.0], [14.798085075903685, 0.0], [14.87795496498703, 0.0], [14.937824854070374, 0.0], [14.977694743153718, 0.0], [14.997564632237061, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547], "velocities": null}}, "time": 1740481186.363613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9636905807737509, "gear": 1, "accelerator_pedal_position": 0.24534451162615734, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.363613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.3836129} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963163366371323, "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": 1740481186.3836129} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.4036129} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962636882075597, "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": 1740481186.4036129} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.4236128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618485221284343, "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": 1740481186.4236128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.4436128, "x": 15.144164180106086, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4436128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613803542659557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615860993186018, "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": 1740481186.4436128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4636128} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.144164180106086, 0.0], [11.306479744447925, 0.0], [11.406479744447925, 0.0], [11.506479744447924, 0.0], [11.606479744447924, 0.0], [11.706479744447925, 0.0], [11.806479744447925, 0.0], [11.906479744447925, 0.0], [12.006479744447924, 0.0], [12.106479744447924, 0.0], [12.206479744447925, 0.0], [12.306479744447925, 0.0], [12.406479744447925, 0.0], [12.506479744447924, 0.0], [12.606479744447924, 0.0], [12.706479744447925, 0.0], [12.806479744447925, 0.0], [12.906479744447925, 0.0], [13.006479744447926, 0.0], [13.106479744447926, 0.0], [13.206479744447925, 0.0], [13.306479744447927, 0.0], [13.406479744447926, 0.0], [13.506479744447926, 0.0], [13.606479744447926, 0.0], [13.706479744447925, 0.0], [13.806479744447927, 0.0], [13.906479744447926, 0.0], [14.006479744447926, 0.0], [14.106479744447928, 0.0], [14.206479744447927, 0.0], [14.306479744447927, 0.0], [14.406479744447926, 0.0], [14.506479744447926, 0.0], [14.606479744447928, 0.0], [14.706479744447927, 0.0], [14.803289782915025, 0.0], [14.881993834025439, 0.0], [14.940697885135853, 0.0], [14.979401936246267, 0.0], [14.998105987356682, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548], "velocities": null}}, "time": 1740481186.4636128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622066231986267, "gear": 1, "accelerator_pedal_position": 0.24613803542659557, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.4636128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4836128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617072147285541, "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": 1740481186.4836128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5036128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612084975663907, "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": 1740481186.5036128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5236127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607104706557378, "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": 1740481186.5236127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5436127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960213132942072, "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": 1740481186.5436127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.5536127, "x": 15.24990782233614, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.5636127} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.24990782233614, 0.0], [11.412138589542941, 0.0], [11.512138589542943, 0.0], [11.612138589542942, 0.0], [11.712138589542942, 0.0], [11.812138589542942, 0.0], [11.912138589542941, 0.0], [12.012138589542943, 0.0], [12.112138589542942, 0.0], [12.212138589542942, 0.0], [12.312138589542942, 0.0], [12.412138589542941, 0.0], [12.512138589542943, 0.0], [12.612138589542942, 0.0], [12.712138589542942, 0.0], [12.812138589542942, 0.0], [12.912138589542943, 0.0], [13.012138589542943, 0.0], [13.112138589542942, 0.0], [13.212138589542942, 0.0], [13.312138589542943, 0.0], [13.412138589542943, 0.0], [13.512138589542943, 0.0], [13.612138589542942, 0.0], [13.712138589542942, 0.0], [13.812138589542943, 0.0], [13.912138589542943, 0.0], [14.012138589542943, 0.0], [14.112138589542944, 0.0], [14.212138589542944, 0.0], [14.312138589542943, 0.0], [14.412138589542943, 0.0], [14.512138589542943, 0.0], [14.612138589542944, 0.0], [14.712138589542944, 0.0], [14.808277385232557, 0.0], [14.885849667323969, 0.0], [14.94342194941538, 0.0], [14.980994231506791, 0.0], [14.998566513598202, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476], "velocities": null}}, "time": 1740481186.5636127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24790843660405454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959716483372741, "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": 1740481186.5636127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.5836127} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.4792216, "x": 15.0, "y": 8.167399999999882, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.5836127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605608180843718, "gear": 1, "accelerator_pedal_position": 0.24790843660405454, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.5836127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6036127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613939688644598, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6036127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6236126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622259665679913, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6236126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6436126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963056812514026, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6436126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.6636126, "x": 15.355667407889465, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.6636126} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.355667407889465, 0.0], [11.518097267873063, 0.0], [11.618097267873063, 0.0], [11.718097267873063, 0.0], [11.818097267873062, 0.0], [11.918097267873062, 0.0], [12.018097267873063, 0.0], [12.118097267873063, 0.0], [12.218097267873063, 0.0], [12.318097267873062, 0.0], [12.418097267873062, 0.0], [12.518097267873063, 0.0], [12.618097267873063, 0.0], [12.718097267873063, 0.0], [12.818097267873062, 0.0], [12.918097267873064, 0.0], [13.018097267873063, 0.0], [13.118097267873063, 0.0], [13.218097267873063, 0.0], [13.318097267873064, 0.0], [13.418097267873064, 0.0], [13.518097267873063, 0.0], [13.618097267873063, 0.0], [13.718097267873063, 0.0], [13.818097267873064, 0.0], [13.918097267873064, 0.0], [14.018097267873063, 0.0], [14.118097267873065, 0.0], [14.218097267873064, 0.0], [14.318097267873064, 0.0], [14.418097267873064, 0.0], [14.518097267873063, 0.0], [14.618097267873065, 0.0], [14.718097267873064, 0.0], [14.81346002998129, 0.0], [14.889840576406677, 0.0], [14.946221122832062, 0.0], [14.98260166925745, 0.0], [14.998982215682837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476], "velocities": null}}, "time": 1740481186.6636126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452486126288212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638865080209473, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6636126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.6836126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643927072426246, "gear": 1, "accelerator_pedal_position": 0.2452486126288212, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6836126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7036126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649227658342332, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7036126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7236125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654520900636444, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7236125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7436125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659806808362352, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7436125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7636125} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.355667407889465, 0.0], [11.518097267873063, 0.0], [11.618097267873063, 0.0], [11.718097267873063, 0.0], [11.818097267873062, 0.0], [11.918097267873062, 0.0], [12.018097267873063, 0.0], [12.118097267873063, 0.0], [12.218097267873063, 0.0], [12.318097267873062, 0.0], [12.418097267873062, 0.0], [12.518097267873063, 0.0], [12.618097267873063, 0.0], [12.718097267873063, 0.0], [12.818097267873062, 0.0], [12.918097267873064, 0.0], [13.018097267873063, 0.0], [13.118097267873063, 0.0], [13.218097267873063, 0.0], [13.318097267873064, 0.0], [13.418097267873064, 0.0], [13.518097267873063, 0.0], [13.618097267873063, 0.0], [13.718097267873063, 0.0], [13.818097267873064, 0.0], [13.918097267873064, 0.0], [14.018097267873063, 0.0], [14.118097267873065, 0.0], [14.218097267873064, 0.0], [14.318097267873064, 0.0], [14.418097267873064, 0.0], [14.518097267873063, 0.0], [14.618097267873065, 0.0], [14.718097267873064, 0.0], [14.81346002998129, 0.0], [14.889840576406677, 0.0], [14.946221122832062, 0.0], [14.98260166925745, 0.0], [14.998982215682837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476], "velocities": null}}, "time": 1740481186.7636125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667721937421538, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7636125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.7736125, "x": 15.46183830301949, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.7836125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23749380367220946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670356656285188, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7836125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8036125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665684858498065, "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": 1740481186.8036125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8236125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660797920233782, "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": 1740481186.8236125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8436124} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.6989007, "x": 15.0, "y": 8.057399999999864, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.8436124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655917755267014, "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": 1740481186.8436124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8636124} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.46183830301949, 0.0], [11.624401561132563, 0.0], [11.724401561132563, 0.0], [11.824401561132563, 0.0], [11.924401561132564, 0.0], [12.024401561132564, 0.0], [12.124401561132563, 0.0], [12.224401561132563, 0.0], [12.324401561132563, 0.0], [12.424401561132562, 0.0], [12.524401561132564, 0.0], [12.624401561132563, 0.0], [12.724401561132563, 0.0], [12.824401561132564, 0.0], [12.924401561132564, 0.0], [13.024401561132564, 0.0], [13.124401561132563, 0.0], [13.224401561132563, 0.0], [13.324401561132564, 0.0], [13.424401561132564, 0.0], [13.524401561132564, 0.0], [13.624401561132563, 0.0], [13.724401561132563, 0.0], [13.824401561132564, 0.0], [13.924401561132564, 0.0], [14.024401561132564, 0.0], [14.124401561132565, 0.0], [14.224401561132565, 0.0], [14.324401561132564, 0.0], [14.424401561132564, 0.0], [14.524401561132564, 0.0], [14.624401561132565, 0.0], [14.724401561132565, 0.0], [14.818865968833602, 0.0], [14.89398565660709, 0.0], [14.949105344380577, 0.0], [14.984225032154063, 0.0], [14.99934471992755, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475], "velocities": null}}, "time": 1740481186.8636124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23659526232180972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651044353257656, "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": 1740481186.8636124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.8836124, "x": 15.56810108363452, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.8836124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24432949505026547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645276532884008, "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": 1740481186.8836124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9036124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649181144705492, "gear": 1, "accelerator_pedal_position": 0.24432949505026547, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9036124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9236124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652876368268928, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9236124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9436123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656566471738772, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9436123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9636123} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.56810108363452, 0.0], [11.730561541565914, 0.0], [11.830561541565913, 0.0], [11.930561541565913, 0.0], [12.030561541565913, 0.0], [12.130561541565914, 0.0], [12.230561541565914, 0.0], [12.330561541565913, 0.0], [12.430561541565913, 0.0], [12.530561541565913, 0.0], [12.630561541565914, 0.0], [12.730561541565914, 0.0], [12.830561541565913, 0.0], [12.930561541565913, 0.0], [13.030561541565914, 0.0], [13.130561541565914, 0.0], [13.230561541565914, 0.0], [13.330561541565913, 0.0], [13.430561541565915, 0.0], [13.530561541565914, 0.0], [13.630561541565914, 0.0], [13.730561541565914, 0.0], [13.830561541565913, 0.0], [13.930561541565915, 0.0], [14.030561541565914, 0.0], [14.130561541565914, 0.0], [14.230561541565915, 0.0], [14.330561541565915, 0.0], [14.430561541565915, 0.0], [14.530561541565914, 0.0], [14.630561541565914, 0.0], [14.730561541565915, 0.0], [14.824071379586439, 0.0], [14.897959071273256, 0.0], [14.951846762960074, 0.0], [14.98573445464689, 0.0], [14.999622146333706, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474], "velocities": null}}, "time": 1740481186.9636123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685366559817847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660251461664932, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9636123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9836123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685366559817847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654793775264102, "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": 1740481186.9836123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.9936123, "x": 15.674288941638826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0036123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24491471372310722, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649343651939127, "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": 1740481187.0036123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0236123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24496410457794013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965397389882291, "gear": 1, "accelerator_pedal_position": 0.24491471372310722, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0236123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0436122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24496410457794013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658659447059241, "gear": 1, "accelerator_pedal_position": 0.24496410457794013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0436122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0636122} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.674288941638826, 0.0], [11.836781212241668, 0.0], [11.936781212241668, 0.0], [12.036781212241667, 0.0], [12.136781212241667, 0.0], [12.236781212241667, 0.0], [12.336781212241668, 0.0], [12.436781212241668, 0.0], [12.536781212241667, 0.0], [12.636781212241667, 0.0], [12.736781212241667, 0.0], [12.836781212241668, 0.0], [12.936781212241668, 0.0], [13.036781212241667, 0.0], [13.136781212241669, 0.0], [13.236781212241668, 0.0], [13.336781212241668, 0.0], [13.436781212241668, 0.0], [13.536781212241667, 0.0], [13.636781212241669, 0.0], [13.736781212241668, 0.0], [13.836781212241668, 0.0], [13.93678121224167, 0.0], [14.036781212241669, 0.0], [14.136781212241669, 0.0], [14.236781212241668, 0.0], [14.336781212241668, 0.0], [14.43678121224167, 0.0], [14.536781212241669, 0.0], [14.636781212241669, 0.0], [14.73678121224167, 0.0], [14.829250233443535, 0.0], [14.901893990995202, 0.0], [14.95453774854687, 0.0], [14.987181506098533, 0.0], [14.9998252636502, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473], "velocities": null}}, "time": 1740481187.0636122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677617574613335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966333850197357, "gear": 1, "accelerator_pedal_position": 0.24496410457794013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0636122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0836122} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.9188466, "x": 15.0, "y": 7.947399999999857, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.0836122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677617574613335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657779708388441, "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": 1740481187.0836122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.1036122, "x": 15.780508642807344, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1036122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467983184068887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652228618659144, "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": 1740481187.1036122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1236122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468100165789353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656561367533736, "gear": 1, "accelerator_pedal_position": 0.24467983184068887, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1236122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1436121} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468100165789353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660889574115187, "gear": 1, "accelerator_pedal_position": 0.24468100165789353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1436121} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1636121} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.780508642807344, 0.0], [11.943001659435025, 0.0], [12.043001659435024, 0.0], [12.143001659435026, 0.0], [12.243001659435025, 0.0], [12.343001659435025, 0.0], [12.443001659435025, 0.0], [12.543001659435024, 0.0], [12.643001659435026, 0.0], [12.743001659435025, 0.0], [12.843001659435025, 0.0], [12.943001659435025, 0.0], [13.043001659435024, 0.0], [13.143001659435026, 0.0], [13.243001659435025, 0.0], [13.343001659435025, 0.0], [13.443001659435025, 0.0], [13.543001659435026, 0.0], [13.643001659435026, 0.0], [13.743001659435025, 0.0], [13.843001659435025, 0.0], [13.943001659435026, 0.0], [14.043001659435026, 0.0], [14.143001659435026, 0.0], [14.243001659435027, 0.0], [14.343001659435027, 0.0], [14.443001659435026, 0.0], [14.543001659435026, 0.0], [14.643001659435026, 0.0], [14.743001659435027, 0.0], [14.834352350777358, 0.0], [14.905752018890352, 0.0], [14.957151687003346, 0.0], [14.988551355116343, 0.0], [14.999951023229336, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547], "velocities": null}}, "time": 1740481187.1636121} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665211782184214, "gear": 1, "accelerator_pedal_position": 0.24468100165789353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1636121} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.183612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659648089661793, "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": 1740481187.183612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.203612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654092108200362, "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": 1740481187.203612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.213612, "x": 15.886752745847467, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.223612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469563882249779, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650723384249884, "gear": 1, "accelerator_pedal_position": 0.24469563882249779, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.223612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.243612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468900890149894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652901432203427, "gear": 1, "accelerator_pedal_position": 0.24469563882249779, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.243612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.263612} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.886752745847467, 0.0], [12.04924152982815, 0.0], [12.14924152982815, 0.0], [12.249241529828149, 0.0], [12.34924152982815, 0.0], [12.44924152982815, 0.0], [12.54924152982815, 0.0], [12.64924152982815, 0.0], [12.749241529828149, 0.0], [12.849241529828149, 0.0], [12.94924152982815, 0.0], [13.04924152982815, 0.0], [13.14924152982815, 0.0], [13.24924152982815, 0.0], [13.34924152982815, 0.0], [13.44924152982815, 0.0], [13.54924152982815, 0.0], [13.64924152982815, 0.0], [13.74924152982815, 0.0], [13.84924152982815, 0.0], [13.94924152982815, 0.0], [14.049241529828151, 0.0], [14.14924152982815, 0.0], [14.24924152982815, 0.0], [14.34924152982815, 0.0], [14.44924152982815, 0.0], [14.549241529828151, 0.0], [14.649241529828151, 0.0], [14.74924152982815, 0.0], [14.83939264858552, 0.0], [14.909544342619888, 0.0], [14.95969603665426, 0.0], [14.989847730688629, 0.0], [14.999999424722999, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547], "velocities": null}}, "time": 1740481187.263612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659414100584356, "gear": 1, "accelerator_pedal_position": 0.24468900890149894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.263612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.283612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656641833091985, "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": 1740481187.283612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.303612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651103061501154, "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": 1740481187.303612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.323612, "x": 15.992937917075146, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.323612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486003588173463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964785633039723, "gear": 1, "accelerator_pedal_position": 0.24486003588173463, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.323612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.343612} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.140291, "x": 15.0, "y": 7.837399999999859, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.343612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24481825372659688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650139113340396, "gear": 1, "accelerator_pedal_position": 0.24486003588173463, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.343612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.363612} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.992937917075146, 0.0], [12.155399771711885, 0.0], [12.255399771711884, 0.0], [12.355399771711884, 0.0], [12.455399771711885, 0.0], [12.555399771711885, 0.0], [12.655399771711885, 0.0], [12.755399771711884, 0.0], [12.855399771711884, 0.0], [12.955399771711885, 0.0], [13.055399771711885, 0.0], [13.155399771711885, 0.0], [13.255399771711884, 0.0], [13.355399771711884, 0.0], [13.455399771711885, 0.0], [13.555399771711885, 0.0], [13.655399771711885, 0.0], [13.755399771711884, 0.0], [13.855399771711886, 0.0], [13.955399771711885, 0.0], [14.055399771711885, 0.0], [14.155399771711885, 0.0], [14.255399771711886, 0.0], [14.355399771711886, 0.0], [14.455399771711885, 0.0], [14.555399771711887, 0.0], [14.655399771711886, 0.0], [14.755370614177345, 0.0], [14.844290659834968, 0.0], [14.913210705492592, 0.0], [14.962130751150214, 0.0], [14.991050796807837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547], "velocities": null}}, "time": 1740481187.363612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651919720751457, "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": 1740481187.363612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.383612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649193607334292, "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": 1740481187.383612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.403612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643747046723075, "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": 1740481187.403612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.4236119} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638308031364365, "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": 1740481187.4236119} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.4336119, "x": 16.099059190794723, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4436119} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24528799727359077, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963287654962264, "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": 1740481187.4436119} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4636118} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.099059190794723, 0.0], [12.261473215883292, 0.0], [12.361473215883294, 0.0], [12.461473215883293, 0.0], [12.561473215883293, 0.0], [12.661473215883293, 0.0], [12.761473215883292, 0.0], [12.861473215883292, 0.0], [12.961473215883293, 0.0], [13.061473215883293, 0.0], [13.161473215883293, 0.0], [13.261473215883292, 0.0], [13.361473215883294, 0.0], [13.461473215883293, 0.0], [13.561473215883293, 0.0], [13.661473215883293, 0.0], [13.761473215883294, 0.0], [13.861473215883294, 0.0], [13.961473215883293, 0.0], [14.061473215883293, 0.0], [14.161473215883294, 0.0], [14.261473215883294, 0.0], [14.361473215883294, 0.0], [14.461473215883293, 0.0], [14.561473215883293, 0.0], [14.661473215883294, 0.0], [14.76134158120059, 0.0], [14.84904693802393, 0.0], [14.91675229484727, 0.0], [14.964457651670614, 0.0], [14.992163008493954, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547], "velocities": null}}, "time": 1740481187.4636118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637996049742588, "gear": 1, "accelerator_pedal_position": 0.24528799727359077, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.4636118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4836118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632705984552138, "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": 1740481187.4836118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.5036118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627423245474319, "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": 1740481187.5036118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.5236118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622147821247431, "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": 1740481187.5236118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.5436118, "x": 16.204993080250453, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5436118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607265090001587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616879700629998, "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": 1740481187.5436118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5636117} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.204993080250453, 0.0], [12.367313855344069, 0.0], [12.46731385534407, 0.0], [12.56731385534407, 0.0], [12.66731385534407, 0.0], [12.767313855344069, 0.0], [12.867313855344069, 0.0], [12.96731385534407, 0.0], [13.06731385534407, 0.0], [13.16731385534407, 0.0], [13.267313855344069, 0.0], [13.367313855344069, 0.0], [13.46731385534407, 0.0], [13.56731385534407, 0.0], [13.66731385534407, 0.0], [13.76731385534407, 0.0], [13.86731385534407, 0.0], [13.96731385534407, 0.0], [14.06731385534407, 0.0], [14.16731385534407, 0.0], [14.26731385534407, 0.0], [14.36731385534407, 0.0], [14.46731385534407, 0.0], [14.567313855344072, 0.0], [14.66731385534407, 0.0], [14.767014085757195, 0.0], [14.853551314688382, 0.0], [14.920088543619567, 0.0], [14.966625772550753, 0.0], [14.993163001481939, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468], "velocities": null}}, "time": 1740481187.5636117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623001826934078, "gear": 1, "accelerator_pedal_position": 0.24607265090001587, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.5636117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5836117} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.4695618, "x": 15.0, "y": 7.672399999999863, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.5836117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617992459558798, "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": 1740481187.5836117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6036117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961299002660275, "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": 1740481187.6036117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6236117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607994517466054, "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": 1740481187.6236117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6436117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603005921567661, "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": 1740481187.6436117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.6536117, "x": 16.31074686394302, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.6636117} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.31074686394302, 0.0], [12.4729822541673, 0.0], [12.5729822541673, 0.0], [12.672982254167302, 0.0], [12.772982254167301, 0.0], [12.872982254167301, 0.0], [12.9729822541673, 0.0], [13.0729822541673, 0.0], [13.172982254167302, 0.0], [13.272982254167301, 0.0], [13.372982254167301, 0.0], [13.4729822541673, 0.0], [13.5729822541673, 0.0], [13.672982254167302, 0.0], [13.772982254167301, 0.0], [13.872982254167301, 0.0], [13.972982254167302, 0.0], [14.072982254167302, 0.0], [14.172982254167302, 0.0], [14.272982254167301, 0.0], [14.372982254167301, 0.0], [14.472982254167302, 0.0], [14.572982254167302, 0.0], [14.672982254167302, 0.0], [14.772454070160691, 0.0], [14.85785761932723, 0.0], [14.92326116849377, 0.0], [14.96866471766031, 0.0], [14.99406826682685, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467], "velocities": null}}, "time": 1740481187.6636117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478546398709996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598024228345304, "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": 1740481187.6636117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.6836116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9606399163833363, "gear": 1, "accelerator_pedal_position": 0.2478546398709996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.6836116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7036116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614661302707981, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7036116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7236116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622912006579234, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7236116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7436116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631151288551426, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7436116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.7636116, "x": 16.41651435876285, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.7636116} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.41651435876285, 0.0], [12.57894669235506, 0.0], [12.67894669235506, 0.0], [12.77894669235506, 0.0], [12.87894669235506, 0.0], [12.97894669235506, 0.0], [13.07894669235506, 0.0], [13.17894669235506, 0.0], [13.27894669235506, 0.0], [13.37894669235506, 0.0], [13.47894669235506, 0.0], [13.57894669235506, 0.0], [13.67894669235506, 0.0], [13.77894669235506, 0.0], [13.87894669235506, 0.0], [13.97894669235506, 0.0], [14.07894669235506, 0.0], [14.17894669235506, 0.0], [14.27894669235506, 0.0], [14.378946692355061, 0.0], [14.478946692355061, 0.0], [14.57894669235506, 0.0], [14.67894669235506, 0.0], [14.778108781356762, 0.0], [14.86231944288575, 0.0], [14.926530104414738, 0.0], [14.970740765943725, 0.0], [14.994951427472714, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466], "velocities": null}}, "time": 1740481187.7636116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452201839899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639379161722026, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7636116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.7836115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644404918377959, "gear": 1, "accelerator_pedal_position": 0.2452201839899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7836115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8036115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649667307838844, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8036115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8236115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654922406502007, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8236115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8436115} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.6890776, "x": 15.0, "y": 7.562399999999865, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.8436115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660170223364252, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8436115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8636115} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.41651435876285, 0.0], [12.57894669235506, 0.0], [12.67894669235506, 0.0], [12.77894669235506, 0.0], [12.87894669235506, 0.0], [12.97894669235506, 0.0], [13.07894669235506, 0.0], [13.17894669235506, 0.0], [13.27894669235506, 0.0], [13.37894669235506, 0.0], [13.47894669235506, 0.0], [13.57894669235506, 0.0], [13.67894669235506, 0.0], [13.77894669235506, 0.0], [13.87894669235506, 0.0], [13.97894669235506, 0.0], [14.07894669235506, 0.0], [14.17894669235506, 0.0], [14.27894669235506, 0.0], [14.378946692355061, 0.0], [14.478946692355061, 0.0], [14.57894669235506, 0.0], [14.67894669235506, 0.0], [14.778108781356762, 0.0], [14.86231944288575, 0.0], [14.926530104414738, 0.0], [14.970740765943725, 0.0], [14.994951427472714, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466], "velocities": null}}, "time": 1740481187.8636115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665410767414505, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8636115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.8736115, "x": 16.522689877880403, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.8836114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374893105560462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670644047633816, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8836114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9036114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665966236990129, "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": 1740481187.9036114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9236114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661072783279755, "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": 1740481187.9236114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9436114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656186111951386, "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": 1740481187.9436114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9636114} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.522689877880403, 0.0], [12.685254492734746, 0.0], [12.785254492734747, 0.0], [12.885254492734747, 0.0], [12.985254492734747, 0.0], [13.085254492734746, 0.0], [13.185254492734746, 0.0], [13.285254492734746, 0.0], [13.385254492734747, 0.0], [13.485254492734747, 0.0], [13.585254492734746, 0.0], [13.685254492734746, 0.0], [13.785254492734747, 0.0], [13.885254492734747, 0.0], [13.985254492734747, 0.0], [14.085254492734746, 0.0], [14.185254492734746, 0.0], [14.285254492734747, 0.0], [14.385254492734747, 0.0], [14.485254492734747, 0.0], [14.585254492734748, 0.0], [14.685254492734748, 0.0], [14.784011613476764, 0.0], [14.866960714929814, 0.0], [14.929909816382864, 0.0], [14.972858917835914, 0.0], [14.995808019288965, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465], "velocities": null}}, "time": 1740481187.9636114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23659168961101223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651306212649714, "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": 1740481187.9636114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.9836113, "x": 16.62895569738603, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481187.9836113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24431377744373622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645533565126366, "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": 1740481187.9836113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0036113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964941818066081, "gear": 1, "accelerator_pedal_position": 0.24431377744373622, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0036113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0236113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965309298716548, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0236113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0436113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656762701833823, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0436113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0636113} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.62895569738603, 0.0], [12.791417370548562, 0.0], [12.891417370548561, 0.0], [12.991417370548561, 0.0], [13.09141737054856, 0.0], [13.19141737054856, 0.0], [13.291417370548562, 0.0], [13.391417370548561, 0.0], [13.491417370548561, 0.0], [13.59141737054856, 0.0], [13.69141737054856, 0.0], [13.791417370548562, 0.0], [13.891417370548561, 0.0], [13.991417370548561, 0.0], [14.09141737054856, 0.0], [14.191417370548562, 0.0], [14.291417370548562, 0.0], [14.391417370548561, 0.0], [14.491417370548561, 0.0], [14.591417370548562, 0.0], [14.691417370548562, 0.0], [14.789701971965405, 0.0], [14.871418497855693, 0.0], [14.93313502374598, 0.0], [14.974851549636268, 0.0], [14.996568075526556, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464], "velocities": null}}, "time": 1740481188.0636113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368507437607846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660427331182634, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0636113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0836112} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.908753, "x": 15.0, "y": 7.452399999999868, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.0836112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368507437607846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654965750017084, "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": 1740481188.0836112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.0936112, "x": 16.73514585039503, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1036112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24490190989468333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649511737362377, "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": 1740481188.1036112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1236112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449506680010362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656460835301184, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1236112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1436112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449506680010362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658794300025544, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1436112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1636112} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.735145850395028, 0.0], [12.89763890958796, 0.0], [12.997638909587959, 0.0], [13.097638909587959, 0.0], [13.19763890958796, 0.0], [13.29763890958796, 0.0], [13.39763890958796, 0.0], [13.497638909587959, 0.0], [13.597638909587959, 0.0], [13.69763890958796, 0.0], [13.79763890958796, 0.0], [13.89763890958796, 0.0], [13.997638909587959, 0.0], [14.09763890958796, 0.0], [14.19763890958796, 0.0], [14.29763890958796, 0.0], [14.39763890958796, 0.0], [14.497638909587959, 0.0], [14.59763890958796, 0.0], [14.69763890958796, 0.0], [14.795369443881231, 0.0], [14.875841661963639, 0.0], [14.936313880046047, 0.0], [14.976786098128454, 0.0], [14.997258316210862, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463], "velocities": null}}, "time": 1740481188.1636112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367742279329181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663456378145532, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1636112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1836112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367742279329181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657894987261451, "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": 1740481188.1836112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.2036111, "x": 16.8413670697767, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.2036111} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467149201069047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652341303858534, "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": 1740481188.2036111} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.223611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467224477869787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656663475415543, "gear": 1, "accelerator_pedal_position": 0.24467149201069047, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.223611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.243611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467224477869787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660980598187895, "gear": 1, "accelerator_pedal_position": 0.24467224477869787, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.243611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.263611} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.841367069776702, 0.0], [13.003860608835561, 0.0], [13.103860608835562, 0.0], [13.203860608835562, 0.0], [13.303860608835562, 0.0], [13.403860608835561, 0.0], [13.503860608835561, 0.0], [13.60386060883556, 0.0], [13.703860608835562, 0.0], [13.803860608835562, 0.0], [13.903860608835561, 0.0], [14.003860608835561, 0.0], [14.103860608835562, 0.0], [14.203860608835562, 0.0], [14.303860608835562, 0.0], [14.403860608835561, 0.0], [14.503860608835563, 0.0], [14.603860608835562, 0.0], [14.703860608835562, 0.0], [14.800959643651424, 0.0], [14.880187521884313, 0.0], [14.9394154001172, 0.0], [14.978643278350088, 0.0], [14.997871156582974, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462], "velocities": null}}, "time": 1740481188.263611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662508064539874, "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": 1740481188.263611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.283611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659726321146349, "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": 1740481188.283611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.303611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654168617967938, "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": 1740481188.303611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.313611, "x": 16.9476121592411, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.323611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469009089076577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648618616331899, "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": 1740481188.323611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.343611} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.2399144, "x": 15.0, "y": 7.287399999999871, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.343611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468319162122681, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652969186522636, "gear": 1, "accelerator_pedal_position": 0.24469009089076577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.343611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.363611} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.9476121592411, 0.0], [13.110101294887663, 0.0], [13.210101294887663, 0.0], [13.310101294887662, 0.0], [13.410101294887662, 0.0], [13.510101294887663, 0.0], [13.610101294887663, 0.0], [13.710101294887663, 0.0], [13.810101294887662, 0.0], [13.910101294887662, 0.0], [14.010101294887662, 0.0], [14.110101294887663, 0.0], [14.210101294887663, 0.0], [14.310101294887662, 0.0], [14.410101294887662, 0.0], [14.510101294887663, 0.0], [14.610101294887663, 0.0], [14.710101294887663, 0.0], [14.80648912924049, 0.0], [14.884468870262957, 0.0], [14.942448611285425, 0.0], [14.980428352307891, 0.0], [14.998408093330358, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546], "velocities": null}}, "time": 1740481188.363611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657305107487073, "gear": 1, "accelerator_pedal_position": 0.24468319162122681, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.363611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.383611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965176433484815, "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": 1740481188.383611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.403611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646231239756808, "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": 1740481188.403611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.423611, "x": 17.053773371091882, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.423611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497073372865627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640705810350507, "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": 1740481188.423611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.443611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24489301114652606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645418024565058, "gear": 1, "accelerator_pedal_position": 0.24497073372865627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.443611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.463611} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.053773371091882, 0.0], [13.216212071845987, 0.0], [13.316212071845989, 0.0], [13.416212071845989, 0.0], [13.516212071845988, 0.0], [13.616212071845988, 0.0], [13.716212071845987, 0.0], [13.816212071845989, 0.0], [13.916212071845989, 0.0], [14.016212071845988, 0.0], [14.116212071845988, 0.0], [14.216212071845987, 0.0], [14.316212071845989, 0.0], [14.416212071845989, 0.0], [14.516212071845988, 0.0], [14.616212071845988, 0.0], [14.71621207184599, 0.0], [14.811828033387851, 0.0], [14.888585619018652, 0.0], [14.945343204649454, 0.0], [14.982100790280256, 0.0], [14.998858375911059, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546], "velocities": null}}, "time": 1740481188.463611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650026591432509, "gear": 1, "accelerator_pedal_position": 0.24489301114652606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.463611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.4836109} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644647818353774, "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": 1740481188.4836109} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.5036108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639276496809859, "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": 1740481188.5036108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.5236108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633912615324063, "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": 1740481188.5236108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.5336108, "x": 17.15984403541566, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5436108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555820172111825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628556162440379, "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": 1740481188.5436108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5636108} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.15984403541566, 0.0], [13.322236759866072, 0.0], [13.422236759866074, 0.0], [13.522236759866074, 0.0], [13.622236759866073, 0.0], [13.722236759866073, 0.0], [13.822236759866072, 0.0], [13.922236759866074, 0.0], [14.022236759866074, 0.0], [14.122236759866073, 0.0], [14.222236759866073, 0.0], [14.322236759866072, 0.0], [14.422236759866074, 0.0], [14.522236759866074, 0.0], [14.622236759866073, 0.0], [14.722236759866073, 0.0], [14.817018610390125, 0.0], [14.89257125841691, 0.0], [14.948123906443696, 0.0], [14.983676554470481, 0.0], [14.999229202497267, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546], "velocities": null}}, "time": 1740481188.5636108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634019284023724, "gear": 1, "accelerator_pedal_position": 0.24555820172111825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.5636108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5836108} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.459951, "x": 15.0, "y": 7.177399999999873, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.5836108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628795775059512, "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": 1740481188.5836108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.6036108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623579499215548, "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": 1740481188.6036108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.6236107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618370445387947, "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": 1740481188.6236107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.6436107, "x": 17.265734214764212, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6436107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24631515703669135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961316860249272, "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": 1740481188.6436107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6636107} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.265734214764212, 0.0], [13.428035940749108, 0.0], [13.528035940749108, 0.0], [13.628035940749108, 0.0], [13.728035940749107, 0.0], [13.828035940749107, 0.0], [13.928035940749108, 0.0], [14.028035940749108, 0.0], [14.128035940749108, 0.0], [14.228035940749107, 0.0], [14.328035940749107, 0.0], [14.428035940749108, 0.0], [14.528035940749108, 0.0], [14.628035940749108, 0.0], [14.728035940749107, 0.0], [14.82194633270051, 0.0], [14.896339144550687, 0.0], [14.950731956400867, 0.0], [14.985124768251044, 0.0], [14.999517580101223, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459], "velocities": null}}, "time": 1740481188.6636107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619598893372927, "gear": 1, "accelerator_pedal_position": 0.24631515703669135, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.6636107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6836107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614645110802483, "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": 1740481188.6836107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7036107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609698185040184, "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": 1740481188.7036107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7236106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604758105616591, "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": 1740481188.7236106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7436106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599824862080818, "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": 1740481188.7436106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.7536106, "x": 17.371451103240858, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.7636106} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.371451103240858, 0.0], [13.533669630593296, 0.0], [13.633669630593298, 0.0], [13.733669630593297, 0.0], [13.833669630593297, 0.0], [13.933669630593297, 0.0], [14.033669630593296, 0.0], [14.133669630593296, 0.0], [14.233669630593297, 0.0], [14.333669630593297, 0.0], [14.433669630593297, 0.0], [14.533669630593296, 0.0], [14.633669630593298, 0.0], [14.733669630593297, 0.0], [14.826669023509679, 0.0], [14.899935097391019, 0.0], [14.95320117127236, 0.0], [14.986467245153701, 0.0], [14.999733319035041, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458], "velocities": null}}, "time": 1740481188.7636106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2480507117873506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594898444000495, "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": 1740481188.7636106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.7836106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96035227089933, "gear": 1, "accelerator_pedal_position": 0.2480507117873506, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.7836106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8036106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612037684846342, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8036106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8236105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962054087667793, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8236105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8436105} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.6799552, "x": 15.0, "y": 7.067399999999876, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.8436105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629032297905002, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8436105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.8636105, "x": 17.477189842202876, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.8636105} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.477189842202876, 0.0], [13.639613174536834, 0.0], [13.739613174536833, 0.0], [13.839613174536833, 0.0], [13.939613174536833, 0.0], [14.039613174536834, 0.0], [14.139613174536834, 0.0], [14.239613174536833, 0.0], [14.339613174536833, 0.0], [14.439613174536833, 0.0], [14.539613174536834, 0.0], [14.639613174536834, 0.0], [14.739613174536833, 0.0], [14.831582653486265, 0.0], [14.903660018578897, 0.0], [14.955737383671531, 0.0], [14.987814748764164, 0.0], [14.999892113856799, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457], "velocities": null}}, "time": 1740481188.8636105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24532358073361102, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640091627547306, "gear": 1, "accelerator_pedal_position": 0.24532358073361102, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8636105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.8836105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642669506026164, "gear": 1, "accelerator_pedal_position": 0.24532358073361102, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8836105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9036105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648070814465315, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9036105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9236104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653464639993098, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9236104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9436104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658850991812923, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9436104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9636104} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.477189842202876, 0.0], [13.639613174536834, 0.0], [13.739613174536833, 0.0], [13.839613174536833, 0.0], [13.939613174536833, 0.0], [14.039613174536834, 0.0], [14.139613174536834, 0.0], [14.239613174536833, 0.0], [14.339613174536833, 0.0], [14.439613174536833, 0.0], [14.539613174536834, 0.0], [14.639613174536834, 0.0], [14.739613174536833, 0.0], [14.831582653486265, 0.0], [14.903660018578897, 0.0], [14.955737383671531, 0.0], [14.987814748764164, 0.0], [14.999892113856799, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457], "velocities": null}}, "time": 1740481188.9636104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664229879120283, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9636104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.9736104, "x": 17.583348571499474, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481188.9836104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23750561408644177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669601311102749, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9836104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0036104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96649453183291, "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": 1740481189.0036104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0236104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660075507764788, "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": 1740481189.0236104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0436103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655212446617538, "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": 1740481189.0436103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0636103} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.583348571499474, 0.0], [13.74590825701602, 0.0], [13.84590825701602, 0.0], [13.94590825701602, 0.0], [14.04590825701602, 0.0], [14.14590825701602, 0.0], [14.24590825701602, 0.0], [14.345908257016019, 0.0], [14.44590825701602, 0.0], [14.54590825701602, 0.0], [14.64590825701602, 0.0], [14.74590825701602, 0.0], [14.83670986325217, 0.0], [14.907528211848964, 0.0], [14.958346560445761, 0.0], [14.989164909042557, 0.0], [14.999983257639354, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456], "velocities": null}}, "time": 1740481189.0636103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366046484818828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650356124587205, "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": 1740481189.0636103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.0836103, "x": 17.689603364946514, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.0836103} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.9006577, "x": 15.0, "y": 6.957399999999878, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.0836103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24437086306334707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644600986382565, "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": 1740481189.0836103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1036103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648558226177377, "gear": 1, "accelerator_pedal_position": 0.24437086306334707, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1036103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1236103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652307185078329, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1236103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1436102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656050949517435, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1436102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1636102} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.689603364946514, 0.0], [13.852060624739524, 0.0], [13.952060624739524, 0.0], [14.052060624739525, 0.0], [14.152060624739525, 0.0], [14.252060624739524, 0.0], [14.352060624739524, 0.0], [14.452060624739524, 0.0], [14.552060624739523, 0.0], [14.652060624739525, 0.0], [14.752056378565207, 0.0], [14.841644253617302, 0.0], [14.911232128669397, 0.0], [14.960820003721492, 0.0], [14.990407878773588, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454], "velocities": null}}, "time": 1740481189.1636102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686134081933502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659789526131571, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1636102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1836102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686134081933502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654342070612809, "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": 1740481189.1836102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.1936102, "x": 17.795785192993907, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2036102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24494839583537673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648902163893379, "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": 1740481189.2036102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2236102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499945179678645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653575110523781, "gear": 1, "accelerator_pedal_position": 0.24494839583537673, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.2236102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2436101} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499945179678645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658305380079198, "gear": 1, "accelerator_pedal_position": 0.24499945179678645, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.2436101} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2636101} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.795785192993907, 0.0], [13.958275390471856, 0.0], [14.058275390471858, 0.0], [14.158275390471857, 0.0], [14.258275390471857, 0.0], [14.358275390471857, 0.0], [14.458275390471856, 0.0], [14.558275390471858, 0.0], [14.658275390471857, 0.0], [14.758206908384395, 0.0], [14.846551830290023, 0.0], [14.914896752195652, 0.0], [14.963241674101281, 0.0], [14.99158659600691, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453], "velocities": null}}, "time": 1740481189.2636101} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966025214480847, "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": 1740481189.2636101} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.28361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657477120283501, "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": 1740481189.28361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654704019342519, "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": 1740481189.29361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.30361, "x": 17.902000907770052, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.32361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470174859704583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648581108304626, "gear": 1, "accelerator_pedal_position": 0.24470174859704583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.32361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.34361} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.2305155, "x": 15.0, "y": 6.792399999999882, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.34361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470401526187557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650764459449592, "gear": 1, "accelerator_pedal_position": 0.24470174859704583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.34361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.36361} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.902000907770052, 0.0], [14.06449255230544, 0.0], [14.16449255230544, 0.0], [14.26449255230544, 0.0], [14.36449255230544, 0.0], [14.46449255230544, 0.0], [14.56449255230544, 0.0], [14.66449255230544, 0.0], [14.764282518233115, 0.0], [14.851384007772026, 0.0], [14.918485497310938, 0.0], [14.96558698684985, 0.0], [14.992688476388762, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453], "velocities": null}}, "time": 1740481189.36361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655129455897855, "gear": 1, "accelerator_pedal_position": 0.24470401526187557, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.36361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.38361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649583969809143, "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": 1740481189.38361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.40361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644046167316135, "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": 1740481189.40361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.41361, "x": 18.008148623171483, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.42361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24493917225439704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638516036546492, "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": 1740481189.42361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.44361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448616980220303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643191845753359, "gear": 1, "accelerator_pedal_position": 0.24493917225439704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.44361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.46361} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.008148623171483, 0.0], [14.170590073121703, 0.0], [14.270590073121703, 0.0], [14.370590073121702, 0.0], [14.470590073121702, 0.0], [14.570590073121702, 0.0], [14.670590073121703, 0.0], [14.770166122010545, 0.0], [14.856048107386204, 0.0], [14.921930092761864, 0.0], [14.967812078137523, 0.0], [14.993694063513184, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452], "velocities": null}}, "time": 1740481189.46361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645071557955804, "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": 1740481189.46361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.48361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642380613050148, "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": 1740481189.48361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.49361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639691532631656, "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": 1740481189.49361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.5236099, "x": 18.11420417619556, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5236099} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552878012820667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631635463940356, "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": 1740481189.5236099} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5436099} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454586369357368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637057557118827, "gear": 1, "accelerator_pedal_position": 0.24552878012820667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.5436099} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5636098} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.11420417619556, 0.0], [14.276598876171596, 0.0], [14.376598876171595, 0.0], [14.476598876171597, 0.0], [14.576598876171596, 0.0], [14.676598876171596, 0.0], [14.775891375958004, 0.0], [14.860571600723684, 0.0], [14.925251825489365, 0.0], [14.969932050255046, 0.0], [14.994612275020728, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545], "velocities": null}}, "time": 1740481189.5636098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642422084177084, "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": 1740481189.5636098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5836098} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.449891, "x": 15.0, "y": 6.682399999999884, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.5836098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642422084177084, "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": 1740481189.5836098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.6036098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637181318766436, "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": 1740481189.6036098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.6136098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631947812129009, "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": 1740481189.6136098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.6336098, "x": 18.2202202839661, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6436098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24592445237169827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626721553115765, "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": 1740481189.6436098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6636097} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.2202202839661, 0.0], [14.38260364382763, 0.0], [14.48260364382763, 0.0], [14.58260364382763, 0.0], [14.68260364382763, 0.0], [14.781540646236792, 0.0], [14.865019917471265, 0.0], [14.92849918870574, 0.0], [14.971978459940214, 0.0], [14.995457731174687, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451], "velocities": null}}, "time": 1740481189.6636097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632644869821402, "gear": 1, "accelerator_pedal_position": 0.24592445237169827, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.6636097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6836097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627449779403253, "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": 1740481189.6836097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.7036097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622261882472513, "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": 1740481189.7036097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.7236097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617081167992372, "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": 1740481189.7236097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.7436097, "x": 18.326094526719686, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7436097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24641326600952393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611907624945776, "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": 1740481189.7436097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7636096} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.326094526719686, 0.0], [14.48838973829473, 0.0], [14.58838973829473, 0.0], [14.68838973829473, 0.0], [14.786915966288392, 0.0], [14.869238018629446, 0.0], [14.9315600709705, 0.0], [14.973882123311554, 0.0], [14.996204175652608, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451], "velocities": null}}, "time": 1740481189.7636096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619265558472894, "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": 1740481189.7636096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7836096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619265558472894, "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": 1740481189.7836096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8036096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614329472413322, "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": 1740481189.8036096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8236096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960940021860401, "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": 1740481189.8236096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8436096} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.670971, "x": 15.0, "y": 6.572399999999886, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.8436096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604477786616578, "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": 1740481189.8436096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.8536096, "x": 18.431844890680622, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.8636096} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.431844890680622, 0.0], [14.594088281689993, 0.0], [14.694088281689993, 0.0], [14.792144505107617, 0.0], [14.873326848769619, 0.0], [14.93450919243162, 0.0], [14.97569153609362, 0.0], [14.996873879755622, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451], "velocities": null}}, "time": 1740481189.8636096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477278518955033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599562166041115, "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": 1740481189.8636096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.8836095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607776543577623, "gear": 1, "accelerator_pedal_position": 0.2477278518955033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.8836095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9036095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615918528716176, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9036095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9236095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624049244728141, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9236095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9436095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963216870456742, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9436095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.9636095, "x": 18.537626224608736, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481189.9636095} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.537626224608736, 0.0], [14.700062869504714, 0.0], [14.797556578601668, 0.0], [14.877544004700725, 0.0], [14.937531430799783, 0.0], [14.97751885689884, 0.0], [14.997506282997897, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452], "velocities": null}}, "time": 1740481189.9636095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640276921180959, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9636095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481189.9836094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9588795778234872, "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": 1740481189.9836094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0036094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.953738586397578, "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": 1740481190.0036094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0236094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9486046974169852, "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": 1740481190.0236094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0436094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9434778905303582, "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": 1740481190.0436094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0636094} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.537626224608736, 0.0], [14.700062869504714, 0.0], [14.797556578601668, 0.0], [14.877544004700725, 0.0], [14.937531430799783, 0.0], [14.97751885689884, 0.0], [14.997506282997897, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452], "velocities": null}}, "time": 1740481190.0636094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9383581454580531, "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": 1740481190.0636094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.0736094, "x": 18.642255982888702, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.0836093} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.8895564, "x": 15.0, "y": 6.462399999999889, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.0836093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5942282964313452, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9332454419918059, "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": 1740481190.0836093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1036093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9132454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5942282964313452, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1036093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1236093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8932454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1236093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1436093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8732454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1436093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1636093} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.642255982888702, 0.0], [14.800018972925963, 0.0], [14.879457449450117, 0.0], [14.93889592597427, 0.0], [14.978334402498422, 0.0], [14.997772879022575, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452], "velocities": null}}, "time": 1740481190.1636093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23684738398932476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8532454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1636093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.1836092, "x": 18.740536571595726, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.1836092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.585385923823698, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8528526457461664, "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": 1740481190.1836092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2036092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8328526457461664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.585385923823698, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2036092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2236092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8128526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2236092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2436092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7928526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2436092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2636092} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.740536571595726, 0.0], [14.876350259737517, 0.0], [14.936677989762732, 0.0], [14.977005719787945, 0.0], [14.997333449813159, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452], "velocities": null}}, "time": 1740481190.2636092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22861327109376184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7728526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2636092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2836092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22861327109376184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7715374222956273, "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": 1740481190.2836092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.2936091, "x": 18.829130632123295, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.3036091} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6063709215110569, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7702239195760366, "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": 1740481190.3036091} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.323609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6086996791216414, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7502239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6063709215110569, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.323609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.343609} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.2199366, "x": 15.0, "y": 6.297399999999892, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.343609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6086996791216414, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7302239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6086996791216414, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.343609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.363609} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.829130632123295, 0.0], [14.937106716406817, 0.0], [14.977263783144489, 0.0], [14.997420849882161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523], "velocities": null}}, "time": 1740481190.363609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7102239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6086996791216414, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.363609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.383609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.705414355947849, "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": 1740481190.383609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.403609, "x": 18.909817557149807, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.403609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7006109593131602, "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": 1740481190.403609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.423609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6806109593131602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.423609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.443609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6606109593131602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.443609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.463609} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.909817557149807, 0.0], [14.96729843016162, 0.0], [15.0, 0.0]], "times": [0, 0.1, 0.2], "velocities": null}}, "time": 1740481190.463609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.628255886815303, "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": 1740481190.463609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.483609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.628255886815303, "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": 1740481190.483609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.503609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6235501618143473, "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": 1740481190.503609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.513609, "x": 18.981843517264423, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.523609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5106700600388568, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6188503166178511, "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": 1740481190.523609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.543609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5058864879293254, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6107429796470758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5106700600388568, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.543609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.563609} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.981843517264423, 0.0], [15.0, 0.0]], "times": [0.0, 0.01815648273557713], "velocities": null}}, "time": 1740481190.563609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.604176001507251, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5058864879293254, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.563609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.5836089} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.4398854, "x": 15.0, "y": 6.1873999999998945, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.5836089} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6110726869649955, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.5836089} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.6036088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.61796079741184, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6036088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.6236088, "x": 19.049341527320987, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6236088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917607609645343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6248403245370329, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6236088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6436088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29202554807407477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6316053784694852, "gear": 1, "accelerator_pedal_position": 0.2917607609645343, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6436088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6636088} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.6636088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6383950534515388, "gear": 1, "accelerator_pedal_position": 0.29202554807407477, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6636088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6836088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6183950534515388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6836088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.7036088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5983950534515388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7036088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.7236087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5783950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7236087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.7336087, "x": 19.117125889986575, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7436087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5583950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7436087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7636087} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.7636087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5383950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7636087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7836087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5183950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7836087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.8036087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49839505345153867, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8036087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.8236086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47839505345153865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8236086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.8436086, "x": 19.174149345866248, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8436086} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.6606176, "x": 15.0, "y": 6.077399999999897, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.8436086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45839505345153864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8436086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8636086} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.8636086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4283950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8636086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8836086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4183950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8836086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9036086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3983950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9036086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9236085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37839505345153857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9236085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9436085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35839505345153855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9436085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.9536085, "x": 19.219072801745913, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481190.9636085} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.9636085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33839505345153853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9636085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481190.9836085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3183950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9836085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0036085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2983950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0036085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0236084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2783950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0236084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0436084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25839505345153846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0436084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.0636084, "x": 19.25189625762558, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.0636084} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.0636084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23839505345153844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0636084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.0836084} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.8799243, "x": 15.0, "y": 5.967399999999899, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.0836084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21839505345153842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0836084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1036084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1983950534515384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1036084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1236084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1783950534515384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1236084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1436083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1436083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1636083} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.1636083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12839505345153834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1636083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.1736083, "x": 19.272619713505254, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.1836083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11839505345153835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1836083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2036083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09839505345153836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2036083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2236083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2236083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2436082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2436082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2636082} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.2636082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2636082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.2836082, "x": 19.281243169384922, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.2836082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6105246878604861, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.018395053451538364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2836082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3036082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6105246878604861, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3036082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3236082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3236082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3436081} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.2097847, "x": 15.0, "y": 5.802399999999903, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.3436081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3436081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3636081} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.3636081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3636081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.383608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.383608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.393608, "x": 19.281511070453956, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.393608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.393608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.423608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.423608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.443608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.443608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.463608} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.463608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.463608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.483608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.483608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.503608, "x": 19.281511070453956, "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": 1740481191.503608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.503608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.523608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.523608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.543608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.543608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.563608} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.563608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.563608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.583608} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.4298215, "x": 15.0, "y": 5.692399999999905, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.583608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.583608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.603608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.603608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.613608, "x": 19.281511070453956, "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": 1740481191.6236079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6236079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6436079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6436079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6636078} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.6636078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6636078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6836078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6836078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.7036078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7036078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.7236078, "x": 19.281511070453956, "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": 1740481191.7236078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7236078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7436078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7436078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7636077} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.7636077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7636077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7836077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7836077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.8036077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8036077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.8236077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8236077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.8336077, "x": 19.281511070453956, "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": 1740481191.8436077} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.650066, "x": 15.0, "y": 5.582399999999907, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.8436077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8436077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.8636076} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.8636076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8636076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.8836076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8836076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.9036076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9036076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.9236076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9236076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.9436076, "x": 19.281511070453956, "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": 1740481191.9436076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9436076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481191.9636075} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.9636075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9636075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481191.9836075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9836075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0036075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0036075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0236075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0236075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0436075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0436075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.0536075, "x": 19.281511070453956, "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": 1740481192.0636075} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.0636075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0636075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.0836074} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.9799073, "x": 15.0, "y": 5.417399999999911, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481192.0836074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0836074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1036074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1036074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1236074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1236074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1436074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1436074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.1636074, "x": 19.281511070453956, "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": 1740481192.1636074} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.1636074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1636074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.1836073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1836073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2036073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2036073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2236073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2236073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2436073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2436073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2636073} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.2636073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2636073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.2736073, "x": 19.281511070453956, "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": 1740481192.2836072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2836072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3036072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3036072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3236072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3236072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3436072} +{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481193.2001073, "x": 15.0, "y": 5.307399999999913, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481192.3436072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3436072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3636072} +{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.3636072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3636072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.3836071, "x": 19.281511070453956, "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": 1740481192.3836071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3836071} diff --git a/tuning logs/2025-02-25_02-59-27/meta.yaml b/tuning logs/2025-02-25_02-59-27/meta.yaml new file mode 100644 index 000000000..985dc782e --- /dev/null +++ b/tuning logs/2025-02-25_02-59-27/meta.yaml @@ -0,0 +1,19 @@ +events: +- description: Ctrl+C pressed, switching to recovery mode + time: 1740481193.2877665 + vehicle_time: 1740481192.3836071 +- description: Mission execution ended + time: 1740481193.2983646 + vehicle_time: 1740481192.3836071 +exit_reason: normal exit +git_branch: infra_a_auto_plot +git_commit_id: bb666ba8618d89aba11f7662d2aa8c2b78955b47 +pipelines: +- name: drive + time: 1740481168.1473489 + vehicle_time: 1740481167.323631 +- name: recovery + time: 1740481193.291234 + vehicle_time: 1740481192.3836071 +start_time: 1740481167.9695773 +start_time_human_readable: '2025-02-25 02:59:27' diff --git a/tuning logs/2025-02-25_02-59-27/plots/accel.png b/tuning logs/2025-02-25_02-59-27/plots/accel.png new file mode 100644 index 0000000000000000000000000000000000000000..1bfa24a3542d8b8ce480451056b552acba1d910b GIT binary patch literal 229317 zcmeFa_dnNt8$PZyl_W%j(jbZuqEJ>#Mpl_+M3IrbD=Ax|VTbGxl1;-dGeVh>y?5sK zc-4KmuIq>I=kxgkE|153SMImB*ZcWApXYg;$8ns`+g(oP3^^G+83_pq`MI+amqcn%IlRZf!opODi|gQdq~bnoL0068EU;?)bKOsU1w(9izjOG)QS>YG{^2KadV$9-m|lw&hqO19W2f6 z`*iXo-ATQr&TQQ;R1-(JX*1b_GN~wu%`A5lDCIY=TmMphT@lBvyUJUl2e(%FRkpF_ z(q4{EnX-Mna^I;vvn@mUTSLsE@&z(ivAuZwe|+7cmKhjX^N(-fuXmg&Nl5?oty3&( zum0;BBxfZ^w*LD&?wjuX`+fFMt~vVem+WUDAy)eDuR9X!-u?YA;%|@KNa+6kogM!@ z%=$#dt<1*=@Vc+uK-v#?L~MUuG% z4lXW}+3CE3f`Z)Ab;Qry*+%vM+%(s?2#>uZmA`bUF2eBLoi(-f_4Td$&~Z;)R)~@A zAFDQHtx!@`{nkox;`h^7Z28kjpQ4!V4R&{Z(}If%E6j zf6F_6;XsN{97PtK2Z?O!kJ;QB)#++m85V=D>~H21MvN!G~KE`NML@*kgI-{wCYg5C4z z3(rbshQIsvd*LI{+@SyKjYyXL|M&YI1`3+@aEFh#*^d^F7OrUCzd`b1p`pHBB0|n! zG9e*hV1#?ko}Q}E?<0oF+{xTJB^Cx@j3=xtejPq?G`6laz2eg+-=CcuiFd!# zb^d=J)}_9op*T{~)8|(R>BenEE!pOtM=4hyVCCFjFU$MY6I|QU($W*;FDoLLkeK*g z*zoJCE5-C%{(AA9eg7jx>>l|@@3lvH9y^NEVs@`V}=TExS$fr+^bhc*43}Br2E|9|NG?{H>?R(jfCV> zW3Zt4^;|=fb z*(PU>%F4>rYabsprRiNTYR%zuS{TkWxOvl~q@<*;AyFm7ZXmukMXQjG-{`WUqGFNW zGmV`t8!1LcQf1FtT3Ql6Ik&tps#6^%oNCfu(3ER!GW0!@Ya62wwVs}yyt496mks0| z5#kR^vU|fAqNKb%){t(nnC+u(t_nRt;XM33+gyLBy-<{%fuXA=LY#QezAv$|A+|k% z+zxYNblln!Ub_W(WQ58W#LO)Q1_plQjuv=+`}VD=z|nrFHCF&X7?qtZh@FU(4Hw}y z?RXa#7w1N~PpT;TnI=7+p;eeabgIi&v?S(Yu=e2Br16gwqPv%KZg;%9`>}fR#c7vq zqSeo|oNNQ0&W|2^*REw~Xy~xAG%K&B#-NsI>>chje~9=U*a%fMH40}F%PPTM2}wyw zb%*g{;t@xf7>JGTJH06No7d}Dm#I_gGdI`e`(4AjTWe+MQ+K()&bK!=YU}DIv}S3@ zT%RLHoLm@6FXibmQ(~jmZb(oXAITjpi4Aw6PgF_qiHV7k2{$jL6!~W8KdnAHUKn6alCCaCUZ}frFicLx=c@8+9+~gzYS7 zWfo?qe?HSHK|JgHtay@YH$7lrY&=rGOstT%KpP#7m$jmb%E~ZlL~E{fX2ZjnfMXM3i4$ru_7b%QvN9 zo}J&QX?x+~#D&=ELx&EzcYb_WN-of{J+swHO*-T__x$Xrvvj)IA|D@LF}9Hb8O!OF zdNz;MP*ZLE66uDmZiC6WoX8M{PbWK(!a>= z*yZVi+x0^&l@XK@*k!L>ya$c5IyaczJb`V}`8Dx#yz0bgkp~Tj(30x+T?1{2ut|ZtN#PRzO+&+|h={#N>9k2nNkpt3AAa-Y$Gt6_ZiXrO{KVyjHU(} z68qBMynQQ0?5=7CJMt;jU}K7}u>FjLxVSiRUStG+1`yeRIFn_5`*enyQsp%?81=&) zt!nlA$ucrBh{AZez`@pG`B!hM^=O;SFf)(tSrqbO4eM4K>o(h1fxzFTDM#^K1aD!| zZ?e0?q!;VsiA)+($(L_8?Gbvyy5!Mb@#XeX2gfgeekZ5|nhjaCCQzCFJ< zsL95g^}~xrSAJE`b^FU|R|fIbB8kNF3Prwpb$BFyw#{bj{l>0@#ANpQUzC(UAnpR~ z4(S)FM!bk{3quy%mQp>Joqgj=%ySV(yS$~D@3l=$mjifZh5BF82^gzO2lF2}DE(Y6 zfcJ#qTyqskW0n{EbAkXxjBhKNod&ighV=Bhqh4sCC;e-;)z()y*sU zLff2K5)%_WpK011(sW*$Zpyc}uC2Vzf zwTzoehc)xES}pNCn`gzk94g5;2-k~#6nl2PyGtr5nEvwRe&d|}7@LW5)-IG&&Wga{ zD>)W7aN;wwuOm^UTJ+cPH=;zajt?ZJl$>F9q$VdPXDnFq32|iUD>Kw7S}EwPM`Zhc zlod(U}PlFY-q?>Gq=l*CiU)m%0~u69y{zMUZoakMzRQii+8F!6WFh zw#Nes1`pwb{1OsW3_FL&x6ItT!*Y+sv1<0?r@V58pF@XwKOYsDwfw~@lHU03<5B&i zuhKt`0R}~gxsnM9&)8Ol2)c}onJ&%`rkuTav7tXzSy|bjy+F9cmzir}=?2;Q_3Pa{ zJU-l8zr}Q_Pd+MXu&>Vz`R(eDBKNV$N#1Wc602X%er~H@W!g6~RLe_C&#aXj3YQ5L z$~W~!UMd%1x<@#4w6oPp5eFC06E6wlkFY#um zQ!~jwa79gxBZt|<#NH zs;a8)b0BZ@;-W+GtZte4V#j;Zegv~`cSpyISxw7d^NhlFit~L@zWcejxEcza*PNyI zmKta;EVP&&P|^_|cHVW&;8B9TZEZML;o_y(g35k-UOql0dLCW3AESMD1+=wj`>IX_=FgQ|9fn zj*bpm5fLFF)dYoDpSFd=#wQHADJfBJ1$!1klRL9P) zXIxswZ>sMA7C*&_XN`}GJDZZPo@XOZfAs2|m$e37b+Uj{(F_8{eGB#UO7il4)J#mt zbG^4v({I$r$xGQgQm%dp>#S#4{Yty+yg0rQVEkY(gOEkvmX&1t*%2|;{YS2(NyN6* z%PA_}M*`oOk~cy2^zaq!H~v);>RG01x=MY|sHz6B464nyU9S%FR?WD14b_~Do&D0w zDqaEOmQ%h=!ZpA|p)$@K{cnw1J@AUo#FPRtW#y-l8Hkbb@lxg}`6#L5&dYg`8B-ZI z8`$xnq@pW}ytmEGX;NlULIHBX{TYK*L9rYNe!$#cHYA>opyx zm0n#=6&s%|xPO1$F~hH05mn-vnqiR{TT`uuRr3HI5W=TUpT1lB)!WBMDpbhwwZpI5 zQAtf~`y>rf{*N5?h zHtKm59vcntWR{HYt@`MJO2z=w(hjm-&j-E;#tz?xAyNX2moJY@tWiU7$wKM{$CqZjc zTSuoh%S>nYanpBfgO+_YYo2hZJgtm z&iL#`)hBw4M}1{vBnw)o>X+3I1?PZ_kJ^k~RoYn8SBT73lVPZ`xHwsTa1ar? z23Zkr$#aFmS>^I&HxbAAtLXa@>Vribh0vTvpFd)L)N(-azN>5CP#yP1 zZAbwebww#D>j6f37!tDEWw8H(E=jgwV=|jca)|sul2##8Ww1c$^kAcRTA0Y&Ti+j8 z4Sx$PCcg(f>5D?p(Nh^5W9+J_y>Z*_Q-Hp%56sEUMp^_dhQDPr1s@VdAQ89>4Gr~h z^y}B#uU)&=lx-dxX}K(ez?uR$5^kL1_)qk*T zA#zT{>4%RVZEu!Nzh2ofI?5GHC1`f}hW*UYX;ahJ39PmW#gAvLdOq*MN9@FhiZNc_ z-`~G!+qSn^{&#qJd21uYHx9Msf3HtEmDs>?`0(d$0dnB&W9SC1)-io9#xWl6j|~sX z@qQ-bjg-aEW7E1a|@65Z;ptFNC>a{Rn8iIwbX|(;p;J1L=XL! zn2WrY3}w~TXI7S%QY{CST^h;A$)8jr_=1MI8&MlNQ5@5vm94)dEua&z!Ot{~>8H+Qx{~d?~uE+@Dp;hAIWyWHHo4iL9>_ z{p{YowNpU$0L@ByU(>_6cXF!7*&Ly4cU}<&#Jf7czX}K9?x%BGlCFlc#LKOI*VMJN zwB8ssUoyzYl1hi2%x?NT-c@QgP=BaCMN7-zq7FdsCL!yQSB;xZz`q!PR0+2-u* zteB`wZftC9di%E6wQGBC-@g4QD98gjGep#x33Sr?yQCY5RBDi+y54G17V(d^Yabii zCTxa~a59*zzWR8owWOr-nZ_D6wzd({fjp)b780jVui@e4HCvju3^{JL)_M6CYh+ZE z>qAkdlQwsd6{$9F-fU`Z-Kej2{QwRdO2Y?$0ZY3OPtPsiG7KLg7^86R;*^uo|vIwhU!*kk=;N626ZpptL%B|DMT0VtSl6+P*ptT z)Sw5Qa0WeSXLt9yj{X}J$Z=Vwo%gh3&jX1^IxWo`v}AGL{QAlrJjr?*4(0m~A8u4v zR|ilaNmBNFNWuIAk9Ag7wiH`t)?G%qTgYM)EvI@-d>eMZ_SF?$Y^sLeQca;ZlQ4a4 zZLN?nIE)QAGUBLYHF5I$<`xz{R#uV&(AZ4%Q5v`9xu@$_vv6{5Q+sPfWZ?Ua0OkBb zmIL>r&iFP)*z$Xg1X zwPJG~@87$B|2jO09luz!G$Va%uc!wr0(mzPjiw*k_+0KEp_(<}_kstgQGi zDJZPuY%pre+XZm5Q&T`xl-Y4%rWiY2^ZJ^2=z?7gm?ML4Zw`S`Q8eP@;n@Mo>S>$h z)PdXcDOe!Hk&$T<0Oy|l`z3m-O>mgS9&Tf-K|LUFgr=sZsimc>iwh|cO<`d^=n(cG zx22}0Hl^$PntJ2#>^*jj8hO)2Dymjr&F)i01yQo^%j_k9AKs4m(102r-@jiY8+P*j z$A=VVI6%d+w+?)I5*X+X8fVMWD~0$=2NY8@8Gn9y_7J~}hlhsDEPj;omnYS*%gsSMn*>b2ztPQDNTx#OU*aC%ltq}dCK^H zX+VdY3b+!=q+@9433ltpbfeZ8kVzebgP!M~u)i-a-^|a?k3ubV`!)~Y=l!`k8?5P- z*lK*rYAM8ktFiLw)nhuPzGD?2P+kcE-*kaQcLk?K(xwu9_61;PtIFASXRU1S@~Pg= z&b@C&^_`7w-9oNC+CSF$(XR2Ltn4$Eefy$O-7jFBRuaqxzaAM$q6-WRtOLAb&*Soz z+6Rz!0SD;W%Z8hl3Da}qIyXjIvM;%k(cB+I;jZiuUe-Wa)ioUXo>?8oci`OP4dnDM zzYN9#?$v>~c-hjT9y&lxLvxOS-{=u?D64uRK5QL!!27L=U$0GVq~zn@b@I*~k{fM# zwwJWEBZtB$m`<`?e17!wZEI`V<#}>Op{Z<3uu7bcXmIPWThT;C3iAX`ya5FE*x%oO ztT74*NovXNq=KB>9<}c{j(wJrfj{ggSC&UtES$7f(Dqx{jXF+ry8}>j+S=I-C?*2& zNVOUg4Z}rIQPCSHQ^ihSO|7h+iiwLyC#hxbTo7uwnL+dw(KxUd^eO^sZ;UcKjNO%= zHReR;6#d114M{u_Ze6NQ>3u^awL=FFO5LoF^OLc3aBz6Jk%EctO(9yiW+Ak0bs$8^ z6QUB)0mZ9l-%iVSoa=nJp;5@}$9)+soik_7+yDbo_iM7(G8t=ovHijdN(fG@J$iUl1<1dF^8?F{^yIrOv&sPgk*;;SL6Uu$G z@+s=skzaC7pFW*th=ZaGZePJbzgh(w%XgzrB35e-hanL_f-h>u@9EQnj==Aip0F!< z&1@NenkR7X@k=IQyG^4Ud-j|{^^AMZhjxAsIn&9@S;mTr0q^<3xr-ll;%IQ?sZdZ* z+`yY{XgqxQa6rM*j9Pg~iB#Okcay?f_d`VvOzh6h%`F@orRO(dD=seXS31GLalyu| zW0dqA(ar(|b1Cx-`)(mKjM^bN*Ma=uyx#VKFI(t zd)}-dH!vu&^71N7%*^a`DgYp3L%+a~S2)>QeF0frjE|9#F&Zq3i{bglO(dpfjdmwa zoal!ZQfoi92)a_L`C)b!iRrk+hC4Wg%O482Y})kbM^~3+a&SPvenjLJ=R%O@YLEAy zJ1;Hm&{^XYe<}JU0(sD3G8`G;2A=pa=sY`Y(ZraM1L zJ$nZlZt4mr97qUW+t;pLyES=mWW)z0oIuQCzmU&5YopF=XykJRVCllzP*wo+?(D4! z6)$vJ+L~;5>z4Oss)Kt_ioq+S{gU+D*$KsCLnF--Kfm#om1S^u1R_VYeKFKfQBldt z&E3+=p%{0EXv(ceTHb@ksR1XOKTt6~Gb4r05eyUs2gk1!;jF9g*S?I6<*3^tJRQEW zxKU70P^=jxq63^(+?Dj0wrL~-N*Wqh@MfDtuY>-{vK|d<{M*sx{i;dj6`djhJft4r~_Es}Mrz<#=**pTThEiRf4HE~-Ee!Vzq zhtxF(TIMyxmg9ngn}rXuvy&mg)aAwm2Q%1B_3aJz^zy3DeIOz+uzuaT7sjnQ8ya?r zI-N9b$=VxiZfg3j;t5A80J`F<%e60pNaWJ5Uj+S2V1y@?J>A_MU@m#HV&Z5u2A7tW z%)n$hOjZgAX{4`I(S^J8|1<>=-n%?oEwZo`07?q^%ThBP8i1R-`{~AH4cCb+w4C>q z6N@1Hp7!OvE#TD5bAz^Uo^5bw$P40S$8cu5@*7q) zHMOk_{9A!l?mc|?ux;@2L|fgLFWgAZ5krvUj_OzKZfa`k(-^e{<>!k)QRcT^S$6y! zF4`WK(ZHi!v?*fmN38c=etzYY&YT}_ZhYCm&CUHfBjZV>OxVfhxD3mPT7%c93J%i^ zDpJm&`DKumOu?r~KR>z#Fg>B3(20nix48wxf$Qy;;pk=dqNcEYM?*v~3;=n@&JTl} zrPFd=%8;7@$|Tx%`GJ8%9A31^M{SPpASv`80ZSF<S zyro>++%^#(`1RYjU+o#O$OLq|7(S3#%}5FHSb=cXfiqM_#WGkq~+#7c~jUtJ9ax3Er?E3O5FVH?gKc z!OF_&gE&{UPPu(BpW)M*7xR6!QQRme`GaMFN3X5Tu^#0N4nASc3C@jXP<%7w(T@Oc zdgl0O?*YlF860laMy|hJ6>=!}dxjzHw%x~HoTa!8>D+LPZye8 z$`32>XdR3cuo|14Ed|0Ow@YyhlNDW}hJ>}fg7Zq+I`lSDNn8mCFOX$?19ui7VArAr zX>I|IQDWGk6x28UsjZC(aW96J$Xm4#$YTy%plcek;zvYljCE2+$5nK3t^>w#`HCr4kQm4D7VgoHcK>! zM|I1#H@6@n{DOlMtr_K6!d(e*j7P7cPeTXE7bpHv<;74T8c9T=G5YOoqrLI{ZBkAD%?r;sUH6}}Yoy#OwEG(rcY^k-)%2=-Jo^@P^`z~@%O)>x zZ*r%_@iUj9Xtc=&^61@{sa6BG_#>b06Q27n%0hWh0W@J78=JTqzb3gxpd!B~Pol*H zWV3T}$S6v$?9kWO_hJ^++|FZ z%?1jl!@;??f06-7MOiZnQZS293;8twY0te8HNRGF&%w_A0qwb-IT4LuPvXVS$dZGF z0X9CuZ;nR$Wps3Wz27wyTU}m4Hh6vQqheoA;WT&-MWchPtQ)}vuv@M}Q9GTn#=x8x zd}#CD0F7L$`1;CEdrzETfbJV?R0S~5x6VX-y8p|WzM@97ZA76PcM2Ov3IuwfPJ$0* zPxEKLeP^f({oL!Ga%ph}fGW-TAQo00dn; zJv~he(6@dVEzLHxoki+@=lp%AeNBe|RF!Lqytn*9A?$nBCm9jc&t@nemmtjQhMZP@T5qfwKC-~ajZxNozK zU|r-B6b~ugq!jjj^5jWmxZtf@w+OMPa}hg!)zC2UvgrHw@6!T{iX>bH-SRg2fOw-} zS3H{aloJPZ-vaMbRngJEi-casKZ}IxcE-0fjBQ6`yy^M2)6ua7e}8?A6kXod#k?0NC~e>CuLu15%yCpFUOAmdWSb3^L&UZJZaM521@H?FEjm1r+r{ zLQ|(gZ^eNL%0N7$s6xZsR3cLx{C82(=ogcWE zkJZ((we(nk9Tn(ewZV9K%ArK8ffkq~Z_poL%fLr^4APVVhp&Swpo@oa5~q>- zwsw%C{PFAt5@6r7K(Mg!HRXj6UDd6QPXiOMTSkfc^=6?g1IsE#1Unj$i4SOc+NbewgIaS3q2-I zDe-9=A42wlCoNY+kMwll0GPmMm2u;N1lF?o`9y^}MO-n2zy#y;d^hX2SKz-kF)=ZD z%={P}=P5K(}&%Y9UFd6boUXr|Z^svQ(v~Hdx1_(Y z8e$v?ux6TIt-rga8T!14C68@^l7sa?9X1ElhyV0*M+N_{=;A)%r2=!3L*-QC@x zUZ}+HTXNg#7&sufA#9uKCqWd?NMVCx^bl1JsYdN*Q%VRhirG(bD##zyR|opOv~2XL zr=n`(YHFR`3z&C{I9%?OxdW-_kY?8|zhHxxF);}>?mRno?9k-}>7GDw#tJ=WU(q#j zEfbd5!Gi}6k_pS^WI3;hpl#4Ie-O6JaXTqRKI*}k+>2Cq^}z-@Cn`br=Vx!Qv{O7t zP)-VxOGZ~x!N2w$;G|N5qF*IUk^LIt-NJI+8(7bCKbt-Ecgwc*Ukw}yi}+hGur`B9 znO@52U{d?QG8v74D@ENqrm8`5+-WgOPNwoSi%x2HK4DhiS4dVDw6U{GsHvPJwCkoq zE;hDzXhswVq^t=!fi$>8XtO%=?P_ik^#X@0wM;h~lgR;?Bn<=BfqhR43<#j65lVG{ zPPwxJHUE64%yJT#12Mr`VLGu&|9OcvQYaiR#8^wfe%(Q%Th=2zZf6c!ROr{&nnpFm zfIJK|%^|6>Ycw-%(jYf_R31Nm{3@J*8yYBoN$XV@=A#3F2H{c3=9skc4uCkjrc2y$ zq?!Z=F8oWGEwQ;L290X39LDE}4kXq;Tc zJ$XaVFgBwhg*%cDbiq{-?LpL6C6@!E7rO(ZfZ3H?Wi+L`pY_64nIy(KPieb^e)e5^ zyOyhQSoQ9(E);OKoPyNom>9y=2!jAWqykqkt9$qCA!%!CgQoM)-=E6J$mm6_fyF#8 zKuhzt+0k~DYY(4}q8Ss*hSTjLv1;ho;$Xxz8iA1FF&o*#cdC2cP+s0i8X@ii;-GDd zSQ}%TzvdLuupSZ2@Hf=uK9Gu{oDTs{cQeW<^w|-$gTc0ldwH0PTm~+G&`-ejKw4)1 zCVnor&HrcomGpzJl9Fgrx_WvJ1|%ZydxpiUOYQPVIsI(l>KSXsdTW%=+ZJ1bo8 z->1vB!b-}++t%CyM0S6Jyu^V62g=0a_718nCqz38S(ckZmJOaDr=1mk7XN-&v`!I|8 zfUG5?r?T>LZUebwbRL2puNKm>t%iestLosbkoorQgYfWh?LjJcHiZ~3c1wa~zCAKBLS{V?a8`7_&EfP^4113V ziBXlP!ryt!_KcT1Ea&}yV3$dz=z6m^Yw&-6{?t-gF{5;B%{Z6TOTgXJcGL4%iZ~B`+KvX zJ$fXkq!Ym*(ELF$`oVYd*-!~e0&(?;OJNjn{uTeRv{}VS{d)Q=8poty1<`p; z9Z9FQHFr>=0*97T@JHHG;AC~c>PqQq{?nqMc<)wo+Ik=?|H|pncC9(ZJsJ>I6xlL$ z%XdW8`|sZj{?V^eDOtUlZMt5!+@7@PLGXpO<|33&s#Bkn(Xiu;CIi+GFfI~g#vGi! z_uCp9v_F6Ou63Q|V|vVPY1(+4e{UETitS8IP34S+pLv%JRzjK39d(UNvDDcb>KXDj z7Zjq4ECVN;C#Vg2=Hd^w-UTmwI^*z9RSGuye1S|u;rtNdQ+9$lplnpVU`uhVH~i3Q zhf$XIPr)E=9nqx8$yl6KVFmyZ1D~U7j+Dq-vFD7H)!Uj=L9wy1?=$MJm)j#~KSFf6 z*!n>J`6QPigU~x&&HyJL4Rv*D4J}$iPagQ1-{pVtg-?KoTuedHP z_^Jm2S^!n^!-B1h9xqpR{1SR{MD43?b#_onCg8^V=H~1sX?b}{7*)0=P*G92z)H~^ zQg$kB_l4}Qq!pT@mHn!+TwKw{AEGJD2a2~ponSKfcbNZ^Ka$`4BqYQO?tli-~7QMETSVvIXo5C61Po)_eQwgwH_ zCJWeT1WekFS#rF54HmxH>(Ijn2}ASC(YhUj!{HgQFdQM6+hcJ)WnCbg9sq36DQMap}k^ba~v&@JDfubnPTkQf3>|yPgjWW@1@F59utoF{cI94t?&sS zhNKkJI1e%K9qN=<-NQ{z%pTki4TULpF}IVh#su^Moq-Lj9jV({QI?Ny=)E@}xa9Mm zA-P6^X(p`psoBWBEFvOIM^xX`op4%m{PSyzW4; z|1Vq;`HcLZUETQ?`S!CchYp?N?*(^!NFgS!hLWIGBU&CGxUiL;#LB{gy5dQZ|J}p3 zCXjIv1<~(%n-_&`#z>$O3Q@dON>Zf(sVfQft_JMb-2D89FJHdA(1b~+XwB6pZXq`8 z0;l5k*IuIsW$AiiuMQC%$LPt$#Kex?`u0ZK9CT|5q3Ve+3i9w=;{TGaFAF}S|ILW! zn5wJ<7jMDexU=@t1JZY^Nl4;A4W9A-Z8(>9(w~?6l4CgtE4k>q=H@FYrJmc$LH_q; z6dW=$c?bVnZK}>0*W6Tfmg-5gMT7-7u7+Hg7;A6`|3s!YJUmRfbLWH1b|!Q5s%-*E9q8})qhg<_dxiW14c*kXk!v}@`5eWD&>*s4XB1JsA$2x;@zXQI14`3?3WpheM1_{;#>Y7x+DC+2BC>-z1-H z`}AoG`c$DLwcSoJERoN4Ik)Zo{|lJs5F%MlocLaUi%w!{T~{y2k<(D@bF@h@-B?%NM(+H@FRp(<1uP0-ryp>l`gc zhQN%(C4Sl+JJxb=bS>R{P?o{eF&*Z1nCk!ZIY6i&x48^MEW+TPohTOJ0>AmM3BCMA zfdgn(U{lrO?X3=1iJ>B_;$3r5Y( z$Dp=O&dfZm3=y_hc9l8&tjyd2jznEuUBvp526$pX-vhxIw>pT%OR3K-HY)yHch5Fp zEJD#EYhC<~HPPcmV@e=tSl$bdcPrcBzL-ZkCj4kMX&&DAuavX>!ttfqz_PNlU<3N6o51dTx<1mD z?+LFPabV#sMYZI>WAa#E#P(5x-~>J2Be7F!tvHxEnCw27p zvJ%Di@XToAt1B+Q*&Z1gnZCx9aG51UR~s0%9r&Og@Hp~30U~@4e?EU{xb^B5m0kK5 z^tn&uH#o2K%weY5x&Itbe>jfsmf;&@nU4U{1@!&PtakB&qTRaB8UX(_%0{OkjnY zfq^5yu<3QghtNmd?hg4dgLuI@8(&lDO!y$;VlJf!AQA~1W(!IkG_J7^g<6QjA$khZNloTEq7(e;@lqITXr`6nnn}uNx3|=a?LfD(5x^jjV3vi1=ChrxJ3p+4(p>g+ zGdX!ftngkaztnbG8mZc@+7O-sJ<6(2pg%%*T#8^=O&~0K|D?j=)}4h^B`xh`l#Hi^ zciM%Fv7F(g&1<8W7cWkYzP}G9sp2|(_Ng}G+WB99=S7Isy1ZAeT)7PSiLCYVLBC!) z5|{~y!)cAqFKw6KmqKsC&X5rPCaKoos*a8V!S~{@B-H!O!)?kH3_MAIO>ke9^HVo= zi#n zC1Kcyjks;lmX~cb0*1LLkXN62(8aBc8m$%kLiP?4Vg|yq;QiLsa+|;VUnh9&VXXpn z1GWSh-o*+xB|ZQL`SI&lWqww>wDHNWwA@h0yL);Dls+l~{y>qUs&JfbwH71wpE3cj z`~djh$QV&@+;RR586zc0#H_fZj6@^hcX$*Unsh#?&>UP~CD_LJ8uuG$DJ5s>pLBF|TreefhCdcAeCX|GAHNh+=^hwh56-rojQQbs(qV2p{2t1ARg(c6 zDl+{0cy?dDWNU991w&(6HgI18&#T)ITxi2g=dA%Q=`f@6W9iYjy8~za%?u2Y<^0G; ziP+o-`>lKy!wa~L(?&mGENMk3)due8ENEe=zF!QE5lX~+;R?KrGUu&P)9W>Wbjo?m zEG&FWy`n4N$>;lHVQBUH(7H;sQyzNwPbhhv6TqF8OEaJ{f1-k8)7Gtu5&O&{Nz3QM z)-IwQCHsjI>&~lR)%Pb9FqT;$Hv${fdqT|_Dd9nXNJem;*_aURg61k0u@7$f$CX7T zCG2gbm>HW&p*qrV2^4knXMhC7z9I{WhiePxerze06<>z^<+osug5X&*#vd4t6c?dj z5EU6oUD&pasgEp+{>Mhi4!Vbu*+43 zXTu%19?)8{f8S2&=h0@Z}BbbBNo>THC;(v&r4ur2=t zoRkNG)zYt%gV46nEX3-^sbwY`fg7hly5*F2p+H2(u(KgDwF-dwc(IjW1yia4rW?iBzgDZf6fB%J_Qc}=)764(u|}DeHI3I9#`sJzpjl+hqHpg24b9p z4c4{$V5zzw<_k4)uLmraih7SW=YAS7^929#qsNaUO;xyJ01c4hlw|bzV$glP!0}DX zhJ_O&3Zx*p6(bU9J$-$Nj3WKbAT?3}FaHDf4b4jqio!nzkZT*na0eDX*h;ODM7tFss_Y zy=wFo{%@TUFK#;ut~zuUuq?x2BBOjE9!>^m}(n?z}2+Wx9gt_a9}D< z2N}5~KL)fgWXEptG8fL9Ek7k>g_gCDdc>h&-cQ5ANPvh@+9iYmrFYnQ50G>DjSw9( zZhVoN%P_+Tz%i4y-Ixfd%?%Sl8KDG`fE0EWHzZ_XfG%O0{3rZ(gyo4X7_bW%tdn6I z-4{ZQ2S$!STXfvC06PKjh^fTi zpxanlA3HaOI#sm{+l^GBBWiSK<2`IXdQLCpU}<7h?E`7Nyu7@W@c1u;2Xp`qg3kz|+BMKHU31(mdfv7xc?amotKTq|XzYF}nN9Eba_Yp~IQ~i$sjQ{wEP)Sg7 zNC*d$X)Cka89zYw;zdc^7ei1bxS>KeCCK?%a4_+pL~(_9oHi zpL_s&h<=JKpc;Vn0rA-uM9>lDOatruTpLjP~2xTO7d)IL^Af#Q0KcP6qe4 zx+|wn-H{O>J1Zjt0#KMR>U#gH&xvqVA%1KK5;XwNstC&Azba{SD zLzWoeB3x5h3?H{Louo7G`RqqbK@!uAX{@Qj)xzg8{1l zDVQtaT!!^TWvB~k?>$KTdx4sOwMvk`yoJ2x3xSf+8eYz|I$}37L@>7zrRw>1G{_G{ zz(7PZ5s5ND4C{dWab*fe>V@jq0Z|RwszgaP#8MH)M4W#yfO zJ?iswZsLL=Nz{NEbPIScwV8D)9sRGZpey4M9)cDjo~YE9nRc08ja^n&){BmNt?1H} zznl{cF)%h!wb>0G*}98o9Uc=yWOmnb4M*@zh?F6F(J>rq0195IJ>Z2(3;hF;qVn?dJ9~OIu(GnE-(-Pz z3#k}=!Zz3rHlKSuH6X7A&`JoH$bPu7hmK(5n4cjIu@ppxCJ77UR0S`gn5_OQW$$~0 zFdD!gDAPoreEvKc#@PbCc{ERqkDmsWkNolC%Q7slEA$69hHcwmXK()zR4NpT<-w^Q zU{m=2*5L{8!|%}08i>+zTpyr7Y>=Q$tl6z}(1y+E?>4Na*&)F82Ckv&#=T4G!*3(W?cF@zzq2y>+tJ%FGf@d*711K;)isp$J)8zmuuzmiye?4)FK znqFsL-zMB@fbC9&0LUyUG!O>f~hCL2}3<%&I1iP-m% z95^=IVZzd?7Po3Cq?FR)Q4by3OpwU4FQ_lHeaCe$#PT37tE5Em zb@V^#Kq)f=)3MK5f7bx6slk%Ifa^2s_D>H@!|tCy376DPNA0vaY<{YCF&S|MfNGL* zY$=f{U~1aXU~OqBDJ{JfUU%IZq4_j8yK!?Dac_cuy?_83c6f?daR4#EnEXY@)5F7S zJ}kM`U^^3&CX4Z5v3WDhQsT$&xwsG$5TVTBkN`0@8#T=fKW^wor6(xkZqORRkco}* z;f*?mhi?@nPr+UH+O$&)#?-5*5q2s5K|vM%4(@S9hqMY#!f@$={_h7^j2c6492NCK zCq^jz0>y|eNTE7j*@}b#?}e^8Y~FPX)YQM|V{}Cq9n&=C(3Yim^25TZn353=#n3I)t6^IEn zI$|JWC0Qj!^PuSXmksA-BI{F{HIS1z)wU?Bo>S!_|Fh`Md=_Z zyiVis)w;5YoSd(}%lj6R5Mgct^(x&;M(LM8Knu{kgoC=To%!z|`W$Mz*naG9l5PG1 zZdfBm5z-Fy2Z-Rt5nNfI%Kz-yvxfi_^y((?vF$t|eY4!2$aI8*0zGtKrQG(hDT#bS zbqBeRN%-BweHaALK$(d#?q$}DIUS7~>N)^%Rfa7`hKI#=*5Xp4KmQ*A-Z0m~C>4K6 zwhGCS`}$`(h0JUG;K036*Iq!ROlVBT37Z*d^#s)!uZdO!j8qeBcp~$C`x+ib!JtQ^ zB8-19gR4yV$|(as_Vlv)&w+uPPh*29VC%w|uo!kqy0tZpN#-)de0uO66F;OQ6(@yaqNY85kA;+ypb_X515osgL!-bV1O6qGg zfW$pEPlC{^mHz3iV$KWy_Ccf&*BHo7S8GS2IE~}7ByBK>2c1)Hp*4XOo%ZF+m+v4E zzs%oW`zZqW0$86VMkbUD5}^MyoCswZDic=@5hfY=ua1aY{~ZyS)491LqH)(>WU_%GXfxGXG*!k}{Rr`~u&ss!86bo5mU!8T<`Z)a(tN zz6HJHqqr#HO|dRY``B7d?;X1WHtu5DU`u!PPN(hjjn^LpnvXEYZ@|=v;E=F>^_X4K z&)Z4O_RfXj!uni-PQMCf;Ta|_rqaQERpURooU==FcKg!vu_tHu1pU4?3+a6P9Vtao zsmM$!Q{V~1wpFs|FDHicfR@ymqX{41CE&m{V~Chxei{#lwGe5dLM3d-b@RVZ?y`Y%+Lpwwl7w; z7lF6!g2&iXbY)U>)Q@&INuEyGqrKyq&I_5u#cEj#Bf0jk_Kl&&{HWka@iK8<_?`+> zY%`Qv`UCx!51i3cWsARWR&2kf^!q}}J>vBA^gn_OlMnT^0E}|~y!luFGUMFW%mNx1 zWLm?%*VhO1wZw+m-E`<;Xm>j?n#UW4`vrf$Cvn?ZPfw2y{cNb|$0sV9yWmXHBd%2x zE{MOk{Nzk*|K=GpM3&CaG>#OoNG|B8igW zi%?Xk+ZTHTx)4@Az;T2JKpRU&+>t0z!YpKAARR6uoSgN;BMWe$>m&2BDNy2m9xE-= zibJtQE)*hkzc0$f4XNX3ze|DtFVGtzubMR|sT4men2LVRtt0iUS0<3>K*8cqE^FJW z|Bt=5jH+_$8bCL4#A5&^NZXWvAl-_9($bAecQ+fhqNp^2AdNIAAYBqFp&;FjAYIZ8 zcRqWg?|aU7f877~ea1LvAUrYGT(fIk4bzmDr>dTWQB0bybNSYD`CVd?l9C@GQgdHP z=^Vr~{DD)&(P%U>i!35CG69;yc=`AgveNox1UG+fY;{#oV?Vn2GZ@)Bh^^eRv$G4~ z9}l5d7y*wCG~uX_KQwAyQDrLAf+;6pAlyWzi*0N+c~C>x+#7Jr0K*a`sh9KGWPFgB zb}*CA>kX&5`jd`iLr5SkrpcliVxVN`Nme+!vAo;Jnb^D8=|2^fm21HBr-2f0G>j&z z1)o$GvcB1R-(G#4Sbq848m9KuAfqRdL5-RYJ^E=CQC@btQ?Yx-2-XK;x)fLfAM3J0 zcTCZ8Bj2b$-~5Zi$4QVGt0O5wyT*`ezZ$d%F;HX_XylnWWXe78*j)L zmbrRB0oZ*tH8SY0^F}5!f)>yPS&WbqH%y8g{kYud1O9#u^rO_F`NBh*upEZ$D`*>J z=BF5x=9|HIGuT&T@>>f``+<`E1wl!0zWo(s1vp@E33gth+b>TVUl`sezB?h+XizbPpx0oTYQ4=gcw+bFU;WT{{#kM`R(`9WDjEr^8C1e#r= z0Q>r6Lk=!3WMrx?yl25H0cv(m!|1|=JuXXNZdSdof#+`;NJXL7dXSll8%81h#G`KlqpQ7B>J_9CJp2W94)+sMlZV_e!5jzl--AL{P6)!t7*fk}}Mgsbm_68QzNwu9GYFd3de5eAUB4LKVFn@;IBELXg z5cz0Ah5hNz|Jd&Q`?R0`{pJsH;D`TV3#qLj+3~Ota^^A9HfpkQtj^ z-v5P>ukjGWt%m3~@%AP(Xd?ra^;7@G#3%g7(Mn!7g2@lY#&4e_8bd7JQKV#7L&q%beHl=Fu88kP0F zGpJg!bi6o95GHZYp;7N5gp!@Ro0>opg0aUeA{x>MP7#bKUi=VCOu>1bxpX#%P4O?( z3P-sm3MKH#kqG-f6v}uRjgPt;xj+$u44vg3*;@u}9`cqPRrgj0aQ)BAUHX4==|33x zpA`BJF8(Kz{~H(o!^Z!x@f!pGzm^hMeT|B9G&Y%eQJcB^N-__t#f|gam99oxPkIL$SPj2*I=!>dc|X)ax#_lK8^!5nVksiD(CTO>TE5O};tb^Sobm(hiRF9Q$F(h=-!}bFF7=irsdG^ZgbBnzH;mJqM0d22^`#H7xd) z3@k>6b=8tG^V}@A>ClU02Kxe|ty{a->EyCm;N)JtrkaoTV0SpBDqy}bypdrm`!Y+D zgGY>rs@qd(jfldLqjpaAx=*^Ft3s?PU~1#rtCEeucN8Nu`@``?KcnuaH66uK)-QL5 zMts!DA(o7uQ%x#ewaEevErUTm#%E;x>uFfv~bt(MlZ?PN`y776Pq*{6?%Uhhp+*@U6kV=VSy{1rGoiuiT z?ej)tit?SAPmS#}MgrYrg#raDZ@yG47y$)k@n`cdZ9XMPtbLzh>FeSCHrZ@h2mq92 z8c;9TL@c>ui?>(T-fYtN94FeRHc?T~*s1;^`A9{f$xADDHZ$d&EC0^6f1{?Lg{zrb zo_%5k(Se0yMF(~q#@EGEQeqI)CkUafaGs5tf;k=UCO{u1-~(qgR+xEKt7qz3!*?boE+( zUhV8vd;N@u(rDf5nuVqBIdFJE)zToJKGB<3devfUFTT62e{imNS$W|_N|>c&e$1FX z;goOb)oAN`O&at9$E#KI%{?fu+x|@kj}IHgsFgDnaOP1jb1$pRz0hPHAl+XjP*V-? z-sm_^abViIyh7bT2@~uN^ebhTVty^~?d^`O(kq{VWz;CvWZW~>Y|Skw--%Uo6=&w0 zGo}aQ7cTKUo0+{kHO6K$FZ@cOXZ;TKc6G?Qu zC04FSsFBZHRZ2kjj@ysXGoy*0UJEE8wzm~!&j-fh=J^7zPVViHGiNBWxTe33)oDQ< z*3Lnpc5r-6wc;IpFW+FP1&903qpa{BR4oJ)NQxL$jwAh|gvN7&sn&9AAe?Notx9{n+{UwcX4f!=ot)hug{GtQKjIq1}Xa@tsx&VI1!ztQMd zaf;NRCP@DE0m5`Hp-xyuLCdBNKN9hSHbx}k2Z{5-`ej)N2o@n{421T z2+Y%b*_BjGCMOf-s5hp@o#$UVk;%XST;{JSxVN;Zzt~o>apweOGs`E0W-y~_uV!e~ z)O_eu-tQ0%R_wWSwJ{z)2E3{vV!E>~9$ICq6LX68#B8kIpH0*Y<7=h`Nsr7G#~ysp zXHm)oX|q#MfCz~{?}WXZ5EHWr(^7^ejh7Iv;(_U2G#+b)9wd-XpXc16IE9=n0o~9J zNOThUBSdg)Apn?kgu!c6JdL8awg2z1&SqZJx}e%-)u6K-$@`vD#1-XfKdqH5Eq$*> zmh3MhXZOU(-D7rE6RMXX{V5{k9cJoK6X33<(aKHXSXhN#?z*OU4u{9)uqo7u6$vDi z2SqaCN=nF)4A@B2_S(6j%>^fjuZ=)`f?pPT&J<3$vXjz9qGib06+$~dh(|L^=e^-X z0FJHIWs9TS%1IW6k{qb0*5NglwcDcZ2Ej4{tc^l*iOfwsgU#eVob&WKzHYOo#sMH7 zKNdalAI>Q8+GxlXr&{Jl;5qe;K$$7_b%B@D>a!HleQ$5(CbbU+;_L+uXSHiR_DWYD z81Ae_ovS9be-YL>>kH~=^GywIA*d}uyayMSr)Opo;NYl%50_JOQ-0-9z7~I;JYy~ICD4x)z_~dd{bz+B_;kryy>_KCoS}YG$3Xf~SnIPG)xi(=fGjsjLH<{tU z3>ZePZ(@rau)~VpT5+063PVO>r#0ZCwbI^p+wq}N*e!U!yo!Gm`z&+&{mul>fSoSS ztK-Xe~bp4u#E*M^X5cN0593L{p_WfHUC8qK&zsy*Z>(QKqu_d18LUhmZ!> zu~w_$2mHBirl8!ssr)idowB|?hT+~{2_E@!My#s(j96&#=a~Dmw90o23O5=;Pa%?4 z($(;&3N_3}c?O>o&I%lUB*LODC@D=};rXO9(OWa5ZsIcamcBXVtkk&3l(cCA4k}^i zzY(aANIeo}Eu8Q>&w2^Su4H2+MTiP=a(+-bjfiRpMOQ<_`|HL2!<1{l&+~4(lN!J<-sx5XIaCr#`$u_yxvZo+Re~CG0kSGxjBvu+&1) z(dg4NGB0j6a$gqQ?rEwitk|7{vQUwJI1_B3aXUD6=gNG={$8R5K5h**x({Wi2swth zEY15@SL!Z%c@T4~XUr}3YVU>&jY966fKl*k3hXh0JMEGHGr?#U`OF`i&iP!VK%Kwhnq_MfYmKLN+4bCx?0%&^ z7%FyTSW__m<|k2ln%_93!g~^hO z>$41i)K~&_7GPYQ+WCt6{<=rSWVR3-qEidCE+zaa5E4g@1&Xir8r7Pj!n6e|KW~3; zX|o-+Y3fsMu=c7%wIY}PnTbo<6Ll1+klCw9ott~-4*`H>zV<$PuR8&Sw%!?+U+tNp zOK`{&?ji^&1yd9`s!4DuD4+_)G7jz;A3ni!37oqxID zzFu0(PfE!mF|eUDs}E+YZx(+se*s5c`F1YYtD|EP(Tim&Tva-|jX#Ti=o*SaA*c)9 zu$`B5)yEFL_?s%~&ln5m0)`@anSXfKvE*AYidq!-zW6$oh!`$+$5%_7!K0_#;U;@|E2@~6eP6{5;# zv886q<3}r0Z$;R<9zNa<_3r708_ZjbTkiZnAXT8%?VvNb@o?*kSc_S4<#aFjiaj%+PMN zmyv*;z;arW#^}O$ray&{gTcvhOm@i4v1n->JVm^l z!&$z!QnvvE@yPetJj~yxnob7Ue|VHaXP1`NeKpPP=eE?5VK+erXw1 zR}*wPYy60r8H}i~7Cj1e_c`i@Fb$jq^PV|i$gWKq(u?8UZb;IS#eLDIR`JX)Q)5Sz zcHTqT_X918&BYCK(X58|v`ivfa>zr_`g4s57H*7pI2We75k3vHh0_*kdjxpjH6cD; zGv8`HQDwmO-m|eA&krwl*(z79YY&_hQj;g$U%4&qHom7*6-MoHnVg7H%6{)r>AdpU zje_FaO|FIhZbO@99_2ZL?!S6#ESfa(tYvqM9h^I%Y2(^9oEH>7;4n;nV{yf^F#ezR;}2MZC>T1 zeid~pOt2Y$tGE#2T*OJenmesA_}WJ;tE)z*!JTo9y^v;cW4U8>(RF{x$H+{Y<*%r4 zqRP$0uHCxz9+K00=-M)tOus1RN_ZMBIg&$_DD-zIODmbxdoFlfEu_`M!B(-q~IH{^*{YKH7wWu)gf^;$6r=e%G+~#Tz~`sB&7O zIO{fVT1eo&bRNDH&2ABV1H*RD#ymBOCE{J0rEf({ZhYS|=e)(s{oUKrCiZ8y8R=H^ zZL7;e=2c=%7xv8@XD$7@I_H=-cD(S9=q?Y2o@G3cH2z|!^Kk*;T$b8lwOLSN&^|tI zF^inlm0$dpg}xZy%A2pIm7F(B(y(7Q8|`5_YtB>Pf7RG>(9}%eeAfE`GTD#WS7Y3C zCCyB^1LvRa)8}t9T*QmgV|wZJ61E95s;%Q}+4CjKl3_#Jy~s*;*33*Y$$x|oMOx6U zIO+VnvxQW!&-tC>S+uk?TH)A%zkwPclbb(;y4wi_M%;cI5CazJi_wbS17>7FW=1M|q=3r1^6?j2*qAiIlX#PxmpQy_yZPdr2F1w!=5X4# zF8Ns#jkl80qK+sThk-0jQ+Xkc?6OHy^6mdiHfq);ll_HE6WR_cwAmos4)yLdMN+`wH~yN_UG20|S3;UnNI1J~)YFgeS|kK1+Pr(rOUb^qiJx zSgWz~{wB7^bt!h1*SNSdaj-wH5I`h$NR~T@2{nTn#|S1us=gj$4kx3GLJNwl`5t7l z?^L*p?fP^D0>qij z?;~+t4Jk?ib{R_c3(D+qoY_XyCPx^M!r-%j)#it7r`& z9VHq+QM*+wkjX8!c6Q^BoV7$0yEv*ky*l6UJE&^1yWas=Rt9V(iZgDn?Y_?8xbe-9 z)-wPrk$tWfcgoGGno~t*JIhMi{ak9Ph`)5rm;AIR!3vAZVBxekG0MYg_CtIY{hjOz z&)c@CqDL^7d+b|pe;$x!=_4OL#XbAIzU<`kMFF9qj}yY*(Wb6Dc2k`j+d><1 zzJk_r_eKx!Ar5g7z(;>kcKs-FMC3FFn0cA?qlYS+%j6^PCXzprGX8aaoH;m^eyZ_0 zi=rjV^v-lfwf#~mA`so&dQS0`?krl$yr|e(akd_b!xMGXcuDtuRN@{L=FILn!^L|D z_qx2h(&cqb&HvlP@?yXDob~=rp{_Yv*N!sBiY-n@G>XqawVxgRNOPHDlz65!0!nH2 zAN!~FIbM*VVdWM(L3Td6*iF%rNf4#!{FFIwpy$Ioo^;Onm#;O}Yd?I#A9>RDy!NVL zfcFm(1`jRWAYGD@c15F zMt`BUUxO>r$B8J2m<*;4XxL;7Z3@kl^6!nLZ*43D*j0(#^tcJbfsdZYQV{AD1ZeeV&aC()E>H${opW}L3sFuPR6LF)z-a5jft4k z8Ak#>D!1!ri1s@|IJaoMI$~oztc#{VjC-r<@nXeZeMpf>ov~;D#i{4dq5|Bttw*m7 z;1w}OIuusv2$sJeUhd&rL_64t?T)GW*{ z0}6tIzG)6SE^$YWLrIn=-3${n!G{eqaS-e963Djc+dFT4TVINdi{E{FCmT@|)EQ~p z*12IHrQ+kS6GR3ire$2V@Oad79|F$Zu*rKC^XVIPO2G$&enOez5Z0OPpRWtclJY@&-NoaiTj4>{&2y z6>Km!Gv+^&ec!+Kia>g4J^x)AQ+D>?!doy7L(87o{{;dA8tGj8Z}Vn`0o&DYX zhqs#egto^%*}KhrI@0!d)ngLfP#AEc&)}83M3X?F{ayC1w}!EVjzoAhIXw#$?ne%z zYJNHrITh#UpGhd|f*B2AM3m@X?{&7@3uVk_1Zc_jr0LPyKc2Te#t&F6H%QP(9^wgH z-&GSDNE#{{wQMb4e%@j2qI-E}C}tvtY7Ncp^7C$Q_j${|HW+m_O?X!-8IS05mFT++ zr!6)%%cu`cw$koR7`74bR+>!7zqwceH6#kl+XSc^92J%ys3M~&P`wXP=O2j4L`@Pu z)wF974eo+7`C_p%}BoWzvU zM2cNO^(FBxg)JX(mDa8pt;Br4n=DQZ&+1n~RhZgDOGEq8X(xtWyT(wjc^ui>3R-1f zp^SpLtyFxSG`?_HcZk=XPOt(+%8{;|@D~#&ADAGRb$BwwW2DrTk(|9nQX617sIgg^ zQo9|+`aV`uw$^`jp9>@2C9l4)v@J|5P!Tk^l&&vfTq)Kw#ssxcv0tKqFeFv(0q#70|R;EgR99KrY z34xi!IxG_rU>;ImYP=-FiK1M5B)%m3+(SXa*jzWLd~Np9 zfTL5;;I^k$iCYsJdgQSR(Z2t~@J2U}1)-03_lrVX6>3SRI!Kf4s$=xGe$c2UYkkQH z4Q3F)O1&HDROe4?@!2PLot3Du-``#SVk+oh(mfPDU791s*B0!uwL#?eHH3X02h0O@ z0t}u(;>=cTRz*n(uQQF~lDM{NqQ1n`l0f}Rua7*hN96v?ONP0>9L!QIImVkDa@Sp^oj!cBz(E&x9={TG zGY3W|+d-p^bVWHFA&&*oc_Nz2nNY6ug@!e4ABw+aJH{t^YcE!vxmDqe#d6Wuf^yr` zSkIRy0cAyZE0+DHXpRLjnslFrx5ni)Y>_lYz2LdxGW0`qEBLu`>yOp2uEOd|`;{Jv2%?rb4(O>cv=mnhllPrqw`s7Jv^+dO}$tbYWEa;?`6J! zpN!sSCf`LjRnL>kri64#hFLdqQtYAc6;^lE=4^jH-d2v@-7nN_%8{fmTNz8v$d zqeIJhsQkE?GYiIua~rLTd;-Rn3yY#EDL13>wJox_gKDNVppdr5l~FvF_qBXP`GioF zA&t(xSoF@Uj_Z$hIJx2RoIs$3zCH(G4?a`|ew{8}=(V@$-p=&zySzJK*|;p!p_Aw8 z*jvcb_~l4A@xR2F;Zi9o&n#wN=~Uc(4f8H7omls{j2gUQV)tL3Q=T+C!#`tfq1HYL zY6r_ln$~A~f{}>%H=$T3C;|@jr{Y`l78-)qRf(yUM$-1tcmY>=b=QY0&_uXcJykN} z{%B=gfRwgk@s5N}MT#9+?&3IC1&`MHTGx8{`0%K>!d9yevC9yQ8cDKSnJf-j)5>z` zc-Ly*RfY~(KlH*NcZh3;=orfP+XCe;8&bDTVF_CQfF*6q-o!$iE`{~v5YF&|=x`sF zV(z5N&vSL4qMlT5x6igVK}UKjJSAtyu_>m^&?Qmf{h^qk!t&LODO&f*oL2oCBJM*d zRPs1f7=rv8dcb$$IsWkdlR&1>b~>09JGam7KQ~G8MHP`k?T5byFwq{%Km4&hkfY?dptC6Eppmu?j<6XZ)_fvw#YK3U`qS8m58G+l%Xy{V9@kDw7nXA z9yK_9vmpJ{3my!wlJqHjTRh41-bHVYx87w{&^yy{*1Eg%#$-_rC(2TH zNP=tR$7X9`tmOWp!qDAy0qg4mwzGN?^huHqv0?5%^GQ<*%N}}cg_~+eDk~S{oNyHYqn9+aOz;eY=M?FgOQt4J~V z5_t@0{J|^=lvjp*(s6E|G#hhWB5VJv5AG?|zr1f@h;PNU)HD@Pu@aEAk!#8CaAja| zOuUuKWBYE&*w(wY*I{#H>mo>GMU6bS!mhylGn4tgv@stAW;sIIlM6-s{=k14*31Zj zWXR&jdHbxH-7Tc7A1hF1boRHtnWAbO3*vroFYtZqiwVYDRbsNl|7FF;!@oE79Plt+ zfu^Stur{d`JOj%}?XsyNYLi^B+o)b$sR|mMdU?6FtuV&@VcvSyr)EyMHG<){_?4$3 z!w+!(z6Y_LklvVuu8QU81u5+>%CU=HTpu4Uk;ggcT5?i}Xi#8AI}~%H{22RsP#@cb zl4<>;?(R={P)QYPdNee;-+))iMYC>`aP4n?TG0_)mvh#gEMQ_3=W#n!RP}3vcEO#!%*sZ$ zRtSmuq}F$9`GkTp>TM(#?mt)gWsqy+%ZUT?&-o^H30n3_3thxiyde-#Fa9RD4^_BR zFtKg{-Jr~Ii1oSobBms@=UCZEKP0A){iG|*#Ve}nQDauv+OGAV-IzcK-@ZkMyi0MY z=`B-QW79zrxcecZiGCtUKNwa5FN1Tr_La!9<_H4$W>$_ge%}e87lhcjKem%kuRm}fLSouX9BN-jtb}FS4AuPF- zuo{j$;t&B8f06%VkGJ>BWpQu3L5(P>4{s}>@9>e_(on1guVLBmqLXw+e z)eY6E2$Rq=Mg5%w!?%S}UWm-Vv%=R)j_5P7l}d}m-ZR8UHW#iBZ3t_8=NsB=9L)0g zaa`x_3}ll%=3%Z&D`~|>^sCA-#abCkn?nXrs z!CM|MQeWWAd^^;b#)+Dt81IqELh|u&ar0q;T`Q~*Kr~WYR#rwvQWGQq;ShW94e=MZi%dg{pmLJYR4VEUj4txI{fU zJ2R1rNKVv&P_RX8aj(J6M#p5v%%VqaS+TtK4CtSiX~^c5EsDoN^I(MORF}?rNmmjy zWI5zDc^3P;xom2TZ-w2}L`w1ksWi>u)=lK?1@Y(`nV;}G!ZVWJGSL%b^Fr`zhX@EY zlBsKHNmuO6R19uM1fXYir=X`;XrhT14vg8_9opX=>~fnFp^<<=g%dk!!aNG1eU~gm zUaH(5u(1j0Q$=ZBw=x!ChnIc0I_G&`nth+Ih_*uw@4(rey#ZUxHwmdD8K3I-bq}rq zyEeMm)pr$J?~Ea~8R@;d9B5ih1j}y#Q@OZQDcpd*&Vld31ob zbhY}>%zP!DNX3F|R8e=+xBsl{E%6f#JFGdpGnIDshx%&-}0D%om$x4I?nPjaPJrKzLgczf>SMD zE5*=8%_onnr!WuO4$3)_Xdn_V3)9NFSL_`J>{YhvRLWloLWxSsdii?U6f}GC&&)tK zcMOv9wHx*0O0K1LeZLOVHU^_DO6LmlN=jU0x=>8y<-x8l$nG1A9|BnvMLEVf?%@+n zMG=okqKrGU&K+ix>o*;97k=RlKg>cjKU~}@1enJRZabqivK}kq9_-Vuf>6ORrQ$xO zLa<*Z3!Q=;Cr~LN2->0rw^{-$oHLN@uglQ(V3^>_TVjN`Ikh04J(W|>ELlIs21h8- zp?7C=WFgr6b@1#?OMpB3?qtB;|=8+iHF8G3)wKlfr% zU?45B`wt-)(HLFL?P1TmdhVYZ!{{rtu|>^86JZ`~R?Cnp5bzX~L+AmpkzyW}M$%P; z2?`zUhczQlEpF@Nii!=}P%Kweb0c|)%24)`VjOuoVcQ>y0nKfk-*fE_L{Fs=hy3RsIlx;U}_hL%pDUf0|8mueD{)6Rk%B1k}?usVsb1R7)8V)v$Eli{dXz5%N*gvKz0-*ZTJoz&3c z>F-*A`GF}?k44fpf%X1i!Od^7$@MH1ZcilMN?*j62b*wF{c^D(2VziQuqrO_hl)hvrFUhwfo0vt^dA;zrSeor@8p*-| z2aPRHp$$(vXc=9Bj#okSa^#Q{Qi9?FJ?CxEeJ?LTj|?+|nae_DQ__|aDqw85)bb4m zA+CctArZcY&vI7Px>NxkcXP!{7DP7Y5MUUOX%O(|02IPEdXJ1w6J(+qhfv?oURra* z5nh}!D2%%>h)8C^rK_~HbZ|AZH3>yOj`;!P@VKXp>S7#cCYW8t8furU5Fvocm}K!Y zH6ms$Y|BfXO0zp>y@h+z1AazWBWif;5*Qts|l{BnfUl#K|X~)g1ngTU8E7-ulV##MS;8~alb3G- zBFtcrm=B?q{obmQYxKEfS!*h`k{UVOAQorX3A@0dhR)|wnh9;AHYcY=={`};%LK)av ztBFj6FOa39<5x?@A50dqJAUADRJie_=zviU);4wMT4M5drn)F<-4kHJGL z&AfCh>kn-?@)J$shYo6#e}Cw^nP|OdPb*ta_*Hr=&f@|)`@y$Aiv0&k_ zfZe9LW@XaZC!PQoPy~lLisS*364|;gAo#v$XLHCqLjIiffyAwJ0`5iq)%Kcs`1-X0 z6y^0(B=4i9$4;zwo-Oco&_+%TaV)(k*dJia$DRgpac!)sKwz zpfp4O`RX^FOZQs{7_f`DfY8hYg2u_wA2wrSL~ETZawQS}LaZ7m=fm#9rTq`a6j^A+ z=uMFf>331xjIuzI@PNp+R}o^SyXH7}-n_!XqwXXA?D$jBcPTb%6d1+`6pU@|!8b?>ppLghLYrW&{Ke!JovrwPd!vc;ud^%(@ zTBnsLU;p_W4)O$hxxq`hEsByt>70^KS%STMYmiFq8ySS>9X>Iu3Y%*d^VF#?g*GC) z(@d-S?%lo3-Bfj6d3$T*i*WtkFLgnN-c^T|W9gcEHLrOOg&p#RKMJ#yd5+lhNxjZX zNKf!MU|%c|os=@&OtqrG=mJe_ngh20r}xXR#}yT?Lhb@#W4I3ZC^`G7V%}qoiw)Kd z=A(6Ny^j(4y4}J{XBpIEl%7PR6lp~4h7c4y5dp3U>hEMmtxBTfTykXZqk5Ux9MgW5 zXXY8zB3{u8(V4i9vxJq`FeyK-VIMgVCvmCFsu!-S@^sWU-dBEA$c~NttsGtdP)ZO! z!(^KF1z`%f5)fWHDV6uQJ5BWX)1$_r_a&Kc_BtaVJ!;{3aUrWsPtJ+F_Z{|ToYFv@ zJ!d|whT!s6o%*3L94^Hd01kIWj)25>KK~K`owuK~aL(7HC%gam1BPj?a+(%lX`x`G zT~jSZJWIIJ4RDkIw0Y=Z%XC^aVI}-lSYd_88|2^jvnM{`nEm%Q^1+A;QsdYs-X8$cH zjhQZ-Ge^CFox=ZslOt-JT?0O}r8G*CBI%relqoqr!1*aJG{D=TxW3aJbp}EE=^{I< zrVvz@9P63Y2>mx+4#~F=Sm-J#R1}+|h#WK#S@0l_=+M_el%}M3I`f~GBi$)PG}`g6s){l`v9kyI)qP8ignZqAgh53N0N7aT2h(2MOh+u=%r{~@vW}D zl*AK*zk+bP)Z6fj&MDf3*)*}k98eh}5d7+{J14*v&!3WgeZw|*~g z&4?579yBk)fLzi#=^)DT6ui+>ptZX5`y6>uXfcrUdX${fbf2zwv#;g?Q%;VTpc^XvHfM{@_ z0MTgZ`LAWRFWo8m7uj4gzCm?v?o~pELMia(>sifHBM4b-8B>RZ4g{npP$^OE-o%1~ z!bxu7lGej#Kb#1~qJ|{=UY*OKFe1d2{lHU}gvDkaV6$BaNBlU=k8n7(6tJP~am{0k z26`6&s)Wk=fat>cGS9!4$fbSM$>m>L zA86!<|P>_H{Jcs2_ED1FwK?L- zgfJFr`~o8Ei_NbAL`4U>8D}uiAtb3Gk?LpiACkwBBSQlEA2R-~N(tr=um>W_HYrr5 z?`kqfpM-bEiGNU52_^}rO6%`p4UB}}AeR_o{$S!ik9~^oP$=&IG^joj`lFE%{&Ld$ z`SaHhuT-1I-iZ251nQK`z9inh%Cd7gwjrj$_0reTAG zl1#h9EVN*m&iXO7g|d=k?LJ|eXwM~*a6$wc-+wa+QLI?$PZAFT1$Cg^PLNPo$3{@H z!PBI@#Vk$adWRv`} zT&xbiz|=_M@FSB)^Oll^-Zij3GqO_3AiO=9Iz5OvHHhn0+wQW+rFaH<_{3;BltwrJ`-VDom1r{+}*#) z6GSY|c;E43w7fo)3%5;zTa?pYC68+!1BUD z^EKyFvs#`oaF_|FUTPuebsX)r^3gFDHYwKQPfd^hHte#oej*}nNzLM0y}A}p)XDwF z$Z(MygEWf4F)fu6L>a*Kh8Sx&{1y3Z;8aT{kGcSd#tGE~dC6h6-b%zUIq3t2Ko2?@ z5xDkLkb+IH4q8$l|CigC7gN(mhtIdg^bWA)D5t$g@F4kD zE0fi)#e}IC4>!Sq{h!$@P0ZyNcE6gk+_T*OB-!?CA|sRu0SYb#oazEs^RV3~wjj2M zQL@wV?+s8z5a|JWHUbF>QFM6`YHjiI%e7r?6&1^-Qy%@>-HhdHo?&zMAbDcH6{a%J zB6na@v}1!rs63|LN^{^?&MP9}6yL8i{Wgq21cE_DHJ3WQGlrIpwcp@M3Moe$G40Om zZ+WyD?(Kb}$~@TSX{>J(NP_=FE6>MYS+?5i#46B{Ciy7@9WGN;A)$Q+>4{VveD(Sg z71mu`t+u8!f68foVZFyo)T%MDpPWp{rl~%=al>QHU~YpP8|7R1>{7C7x%bxY0Pd49 zIN|jDh=bPqcO|Z zB4s0?@Rv%;yzU{N8iHY7x4p-P5@FceQK%mW!ockT>GgBqlB5$teqD_$!TZ3S<=4!l z1`i2$H^%GWZl?#Nv+)g%{zk&yi1mu2@)kaDdNvdPZG*f5Y<-dsLa6TpVWs_F%;t;8 zK5k7?hJ^L$rzcP#))ZWM2U39GuTij|mE{g_YsU|N!w4b_QIN>sOpQn?xSEmZH)2N< z=iRq2_j*c)=#UKLFWJC2nTZz<-pXE&lP%1DzbwQnvOB!Ydi}PV_(AL*N6~JrnoNJ< z_Pr3>#@S6Rw}UuO2hehvIgjU`Az@>{I;P!GgYwR+E8)n8;M)3)k72g%zpV27syHZK z<-flgMmAf7uQ%4bWH>g;3v2qFeB6@r%1|ljw~a_8(y5L zxU?_zeIEe?9U5_@dTcFGSqkpKUZ0ds=N>^BiTG?*>VJ6Ir`pkOe)nlkC}HJ6BnPYx zn{BCakNP%K+!Gl014TT4mTB~=9cRp~i**u*!ekIYnkARxiuz*|ug;~awRz((|L6XN zv*yE`${h9-IUR)&l?Q%>stNU3z)TKa5x?Vsb+`h-V${jIAJn?3S`L?vBW4Zoy{6); zqW>a+Lhy~m8`LJeaDpA9{Rb#>MhQghUb(F%+0XXd8Nu34(a91q;#{Wc2jPt7CZGtE zXb*~CN2Fj2!TxUw!_!*}XD}9Th`<>~urB0Q@T10~!-y%2VuSmN|4F(M2pK8+%qTr4#WYUXz4h_ZOmEq-Xl5&=c&EyoHdb~ zf3OfYcrMtg5chVF*x&vB~?+y^R^aYUCFr~=4`1A96&B(JyOe3I)NVcy`t zQ2%SmII(_P8<7Y6T)4=7<+vTuH0#eF_EIA64vZQsXT_x&UCaVs$6VOU=KeRL2ek+( zP9i46`~yp>fmCPPQXCw=p+0}|L?IrxssKmi1i^4CHq#trjPRfVgkm@h{|_pC5mXwj zwqJMbs|)XvQT_V$#7pEGku6+wEQL*ZAMlH~3;#)<6;qVxJ!P5-~Ll(kJW?| zr2pYo^#n^q;|_b1%ilaV_ahJo&Tra*1=l+rW=tXDILw?7tps0t1PXDOO@+M5Lf&xHZ*F9ipe{{cE^?b3U1kVbfwRsgs%_+zd!p3k?QaqD?OJ#r4XR4gmKa>#>)^rk zDD9Gt(_K)fv!Qq3i~wcK$RUkdcltF&+FG$aTH59_LxHmojy0<>u#`5i2RJBp#0yX& zwQF$2BeuOT;$iDI*4(@z!jtlG%rOSdy1QmbO{azIw;TpEQgI|&WxPEwJ!BgveE%q> zN(EB0Icra$CsQZ7r}=^pR}QUCS@Pd6LC7!;V?L%v$KB_`3hV8gD)bs?kkX|IH(itOXhF^C1gpSu1!Y&)(vTp%D*f?ym+{Www|P-Y6WGE-tOYX^ zvn=C5+T*vT{-}`m7^m&LZ2TYBXWB*}4{&@^*OHDH^&B5(P`5mfEbsvJC+~T}TEec| za>l^k+4|~7>;r}|YX`v!P$bB8gY-ZRQ5)U0Dfcqd2-h8!A4WudFP6>!pNHq<{#ddWA#)f^a}q;X*)hr9jJ+8Z7lyF8u=;mC(Oy*l z$hwDw2wRBl2~A#E_zFq;sk#C9yoiK&jok-Qw~T6W zOTj%A#D3n%+wNPCNjN?QCYlcJHS)6%MrhJ-gTLfhu`c`ut~i{CIK=d2fHkOKo`6B0 zgn$s$#A-Fg4=@PZURo_tf8A$TM|IYKH@feDj$IG~D=zh}hJ4sHPVxNnAG#dBnwp-P zGDD;^p9o*v$4&e2@%n$E_R%nXD~EWxK9TwmY8Lx;*F5|>(=uA6GsMlvldy$<%$X}c zMJ1N|zmFiV6o&gQeO+L0$c9`05H-#)0iwR!b=`_Hvl?@b!M4Akl?S^6QTnMCDv@50 z>v*V;e(4W=9$0$IGC^JzhZ}1+t_bopeMnkH_%7pR`;19PTui&3Qs9?=LH?RK4x=9z zq7o->@G$gd8GbkL6A0X8FMgxU)jcKSt!xDN|5zpjF_#GMA*e(Ec<=j2{UfrWarQyf z4qfRFfpNP-((g{V<2D&*EzvQ^f0Y!r)$}aL_^Ca8;y&IYj)>HeOlSD#BEZ{` z4Klcb|C;T1gC&Yt3;FzqQDnC`e%`XZX$F}qd@|ez4)|Cdw9GMQrqb4P-|GY44)S<0 zU5-YKuLp+LBWHhAv!&8<)Fvy6{*KH3e(D6jXo((PLpEV|0o#`k`abJOR5edVD2`dA z;P6es-T$Lmwc-@@5JYto3~xUB^NmS@5D3Q!Akj1gR8Y>5I1Y*;^|fnwED`?f;^sGi ziSG#F)J2?0>*`3q2rGXGE4TP>^9&OYxMjY|F3w@rSGO|~+K9xz^X>}8}&o8&(b?Jb0g&n?)(QDZAqEhNtT2l5L~l{c${7 zl4FFfbOV&7@~eNMxxdMK;jGbKVFOL&Qv!31@Q2-O?L7_`bwO<5&Imvhh{IENVP}yN zDeO-ElN@t23&Oa4^6}o>C+sa?(;`c{!`lZ>R5msf(pfeG&~+C)f5#-T=DV=kV>az2 zgHiH4bNw8KI%_O^0$Y-&emX{w*t#)jiT+DSX-yqE_9AcWA-xS}`YpUVGB2jE$BkI5 z-CPMn;@^Kt91hHOd)x<1+#!X7Fwb%^b_1&(fCjmM${$jhHT)B!t&fJ&ZeHQh z!9NW$T!Xh4-j0>wz~2`BNXq!gB<>6U5y;+l4S-Sg6X$25b-Qi;&#g>Y%tkAy{ zT%|%HVI|07&s%-U2ImWADQV#wM*e=u$O?%6DgHndTw{}?&%Hq>!~-0cn2Q+SvnS>- zOCI_2Y?7vroH@~c#fYhh4-{p%dx`&r7{IO?D#w*ZKG- zs@I(HN%+Yn>+jYb84Xcnpw~TpV_f=Cdtv+&_02#Gz3-Vv?U-8>94{{r65f6zdMD{3 zT|@JV+uGp5bARV3muOqdwcZ)+^{rib_qz)nu3Du{>J3x-#hK8GN`U%$S7$qV$#|tM zIq=dILKJDYS$LB@g1YbCc*AR}0>RT~e{*g-Vh{yFmj|EUO|p-3GqE1FTV>`~!)D0g z_BT|{!rStXl0(ctNyYv_v;ZPX@|eRu^-0yyiM1BIJ`~BsaRU^t@cz$NwyWTrMzcD6 zfydzzhG;ShMMjpdB`hfx&hDZwFUI<+AS0yPZ0ZR-ff)=U$YUA1WqVcZ|6%L91F>$u z|KCzP4S7NXg)$1+dxTQ5%WRk#A$z23Ev2$|W?7-KGAoq5g)&1{8Ie&o-*dh1ThH@+ ze!u&Vr_bkhzpwW-&Uu~JIoEZaqpmkd;)*|moyWaeRoCvHq4hDtg_#E4J~U$O(K4jW z@b~$1++r8vlTFmM`bl4e7vX3R7!!ve^znS&*IKdxepYK8_N=Z}88P(xAjt%4c6JRH zU(JHY+t8UD_?*XsE^^D=Q=#?WKHCcGDfDPR;Y<|5olKdHnuzX*`Gg`W*|gpEL`PBv zA2scmWqI4pcIRypU7h0Sp&eHFlM}#~AcDcR+dQ74?91T*P%!v-yCRL{Z|!hS)uns4 z%S!b^U4GcfThwL7`)T0M^Zt?v9tu0XcQzyyn+!V>bjtfO@fpvfe)^%E*T!-H|Gd|O z$X{nF%0D4v^-(`$q)*({7{?b{;T(OOL)YVA1=>pap8QtbL)NrWRuJ)kiRCe6Vh!P# z&35|2H)Y904A|_%T^>dYI5PNZ_vjxwvAF~!?e4uGYx4{qDkg4>4~>4K@K__pZ^|BFD5u8ulJ-MXUVw zGUSD>F&kVnP;Am15Ev7$EJI-^_-rmkK0wCU<90h?Jqvp8=!`_JR|v_!Gg`>3q~A?Q zE0a&x;P<^pkZdNMP03ERlDZ*$FZ8fQkK(N#;dBS!?+IQGE-iZT$<`P*PssTHEO|&A zKodV;S>nUnNmiiO9qPmd5lrx47t^>Eq?!7-m+0sG(d%hJx;(x2s-r@woYtgvE`kJj zLV68BzKZ*;*L^n~QGy=T6xQ(7ECB?1G$s41vk0BvcXR9w?s<6)lYCJRJD_;|!DdD< z!V{cHuKd5y~p8#fadJI}=vJWlgxj&b4jm0A!-!i#j(qEOkU zX>tn@3Pcn1M!nvc#whU;O;Z$(%Dz$s;v+fiT1ZU=&xijbR-mSOT7w#+58aRH-G97E z*$9K@cI}-Etv}lg!$^V&&FpDK(L`*%8ALICo}z5T6p;46!t(K(cB&N_s{lJJzU;eg zO&i^dNcK*!P?}%3R;6jg_K9_qaX-i12I@ox5w!U8byxo`y018yH#v6#nHLXM{c9J- z0qAgOps6)HJFwoE!OI-{~!6>eWTC{Yw{%x$Udr8~Dh?e(C1M64;># z&LdRR1x_hXS3))xV<>`zlER@xaFRo`%@52@Ok9Ez?}PdETNfEUY_8Xtw#l-Y(lEcg zmGky$z3wYZXw1;LDvq}!z5Q-l1FU$pIp8+_5-d=Jv`j_~Pb@W=Q$GmB-2!xMidcQh zzj6oYy*5`nXkW3%9!hXmXKpNKR&PHV!&|OM;(3|<<*i3#TDz!^GCEp3Za@<(cz!on z0H+g3$Q#0M_1Vzw4|zz`TLCib{TMF=x|2NEX&m79O=_WNro(Hk!@f;LDwDNwJLPhW;>y14!siFLwqP0wB z+|lZ=R0kARymn4DHH;MFdYu~jI5Q)?;!xS0EdpuW|F&8(sb4%-e$3q7|CXr<&R;_% zjxW@%nNYe>3jN>3FoUJALbwBwqItONLs;vCphBB2cQk`wjLL<&m_{TF-(M*4yc6_?Vzi5Jww(Xd!rE*^>A~tlH+0>X+v4NKSGF{y zhJJ1HCG*Z*n(U%czZ>euiIiooC<`Xdn-+kcQ^<&e7qo?Rj?gSJ|1Appb?r{ZKuI5z zk4a>99SYUljIpnxwf}l=zwqoj#;PMIZyQZ-+DaRR+dfQJ|BWekhY&QuE79uhtmS(y zO6f%07}ci10XdZUhHf^`REd;i&%AUUni2I}xZx$jU9vbR*G&3THhErLrBxt8De(fE z>Abq{yYM324rs1yQgAJI=Qw~S*T1#kdnn3r0_pm56MVd>&q?y3;wu%!*C$Y2Z8$jW zkJ8lX!lC;akYOHG(XV%1`i&(Ss^JN0xIY>zw}j;>T3pW|iDVpKAq(4-*d!7zrN@b` z3 z#19L<66w&C&`a;nP&+k_%zmuy(p2{e<$PLkwO)P70_K6~mSlp~*dC2rPc{FGIW4qa z%c)*;3%!o#e(<5fQA6k)`XrQu+UeSit_b02CgJG2ZI#vqJxF?ilB0=EznvR=H|=4o z-dN=JWkSEhd3#yFvE&Ym;Fp;@yC$V}Mun<94pn-}0X*&(GVyE7y8(@aFAd6$6|+R> z5@TQvLgr|0@ceL4{^0qEQKUyGf8eE`Kc^{wzzvU?u4Yf+xVe~b?FlmcoD0%LHn4wKg(3x@Tkpu4&o2 zPZ~2mg1Xx(^XsT!Pk`6zP&TCho1TpO#(+Q?>nhq)Y zl9p|X)dSM*Fgm`lNQLYFI8{hWf5TNU+sag_UuoUO=nha73HiaFcbn!K%%lWR7rKq5 zW_-_8!14IGyG^87oQe56BZC#lyeay^*+l~jM=Ad4e5LD(RwieEK{c%Eh|<-Ov^Z*}XE9ga zzc;*1GC(#SdDka*476-Omkf8=x&U>!xJ=R?x*ylO@gMscnAZ%|)$%e+=aYH-pz@*W zuNWx2bs@&N+aj;J;llnh7DWrlf5uxYRySO3DH{FiwbIi+_QtzJ-k+`hQIfcvC&Fa- zT!%>NrIo?`r59J0l?;|!<(ee=SM(vlsb9?g?*;0YWA~}>VlnkGNq#Te!g5X~H&B#W zUqBBwJaJD$oZz3x6`ENcsN(5`QX}S7zx{cS$7;Bj$Mxf*YX+qw;W~r2$QjIsdu6;3 zh7+s=Vt?!%r+gbXX%^5$#YVOas(8hY!+%2Cc*7m~Zq`30$Pe1d9JDJV@rzl33UrUr z{ky#C7kY2ydOQfV~K9~$cW;x?5<5FhSL$_(K@B1;>sW3)}hZY7k(1pJc)WC4&(o zij&|qtn@?CFLKA@ByrQp%`Mr>Z}Rl8vRA!eVDmB=UB5r|i`#%Ac&|Lx;7-T2`PJOt zs3ab!7d4bk52$AJlJqIR0>ugi!=b$5Ij`lmA#c*%50HLZM{GCcOzN=sxK+=w$bB9N zj$A8vG2Q?2Vloun>vYFwlp~giDuRq=&1b+Rot5Ro_YbyyU;5^@0ryr@Kh8COxDV-r z3uo&%@f^({%*}4AfGCI11jfL9WxB(vh3D3Tw0OhhgQ%lOQXnOyQ*2J(G;qB*}yXBaac6Q0FyiPsw@*~~8 z+4Y@ixh80eQQ^PUNV65bL|Th{{hV>d|GVYI;@-L zLc!y?bsS}(%*&hx%YvXl@NzjMy)~|UxEE=ynE@nQ66#xUI~U?4b42$aagxAfD4*V5QUW%$Dan7SNx&f1 z!?E9Ep>ixWo&hc_d3|(dZ&AR}_&o?jmz8Txvi~WFzldCrv&<=ah2%Smwx0BISP4m_ z@Sn&Bt-FMO6HS8JHpCEnj&@+8H~pG=Ej-YH9-cN8Yai%Als5zciNU$^`* z0qISn6%K(#%=GXm5qHdkim5l(=i(X99=fi15SDgkXX($K*>JV2O5g3rUJ!gURLPG4 z)DX|>d%Z(%CM?sPwPg8IX4T7rzTyE#yu2M0+pa*@q{yUeo!mE8`p+#}wF%St8A0Lb zm$C8gq5SKjbWLX}n8p^Yx{8H_ZLBuV8BToWII=HKPmV9&=F(!v^|{{O8OI; z%muH#*@|7(*1mt@{No=z6Y+&5JvO;Z6P6`&AY!U5AENxm z5!EQ~Yc_~X)k*S0G$5K*sAe9dhMsE_sYU}@Oa=A?tinra6tAWU;!AH9d;N2}6nW^2 zwV95w1IjJ^qTD0pbH?d$3&q6sQ%O6?v$`6ccs;EBc~ z8nH7u5$}$Z-5Fa8^MYEZ)ukINrPa}W^C>O?UkdGwSNkAIQ+pEyE2rs2J0N_&ye67e z*$qhfzY>Ci$SDwu79{EA_;>in#G<6}jiaNZK$>yMoN}?k4eckrp>M$lTsic& zYuzpZYbgCBT!Iy$%h;xQG@{!0#&C%@Uz8o1SQcSrFbDF%lB6=iWSf}NMR#<8Ottu5Yo>+1*}sHh98-{-zM_@&_NweZ?`%}1>z`t#95tt2RDWQC#OG_y=U1PXHm z`>%ch2cS7=H)+|60Yh z7PBYFR}CJOxSy$Lk+IOxesPf@HD&E z0BWr(t)dIPk2!AJERTIFzTWnX!z0ioruO%cJ-cP3K#&7#DBt?}kX(^&Cy0Dm15kA> z))Zyx(^1Mn|6!!B0mwd=NM(==5bS{il(KACx%)KZRq-{sPcmoswoYoQvn*z)pfW+P^}s`P{*Wn&b2kN&y1uGjofsf>86QC{ zN>U0Xkuy(>LJ5aBHK7(2a9O#Y3`jKS(lGo(>?kD<912?pK{t`NzF zz%kl4#P(6d6598i4Y4%n&$reYk}ZQoY3HG?#k=1JNXw+Bw(;CN`C|g&5Y<*YZuxU0 ze?kmHm)irkl1WNW%k($9FPWf6=KAIg1My@9;(M1azjOWdwt5w!92XLWjt{TxS2v44 z=-9xQmuU;t8fG%-oi4FAs@{3eLR#kHzNjm_C*p|3dO=xVgEBWBun8X~c?ofOqM*5<1WYrpgwZQ!R!S^lzryv0n|>*Z5$0S61!^zx zgkXrE>pDcUauKFXBtl7vX14}NH+1#*T%lJelsL8 zP#OXm6jVoDm0&(9{)7V%u@)bVG~OiB8xV8=X@R29U%oHBF$V)Y$B+wUZfP~Qe9=_Q z)wmX-cUtOB0dlB0p5Du;u;wIgbD-TCt!ou{fX{}wu}q++?xbZXOaK8Yxuz2$BKr}b zUJKyER@+ea0hfSFupGNMZrN}occeX>uPV}&a^t>E!~9iTo_62V4hlq?Q0K#wZ7^X# z@umMvHAI^pu_}dwyN0;+tJ3vlxh4-NZCo|l7)|u-AYNuY+^hGy(bm(k&-i!0*9KuQ znHpNjwj>OuvtLmJjQzq%h|&gsj8(62TG$ZtB;99zv{EaZ196vhACAal0PRmZ|p-+W*wqU!X?OgG|KFA zNePtl#zSa$0m7H;E2CPK(Rkitex@7wvZ>1flE^=7a&}oN-9i<8BOc(Nyyf zecDGA&9&)Y1#N@9BydT5@y!(?b--2N2Y5aH)T*LSe@CK(2pT88t@JIFba%wV=liZVi_Db5GJ@GFS{&x;vm| zR=A{L>gHL18Ai*1F0YNXAs65?2)Y5C($bHR`L@L*sxib%1#r{_<&zXDN9m$n>#|)3 zu38z4%Z@5~9Mii{XbfM$2kjFwxuLvVMxWBP-ne@}TzTd!WT(&&>tI~}%2@UJr4GoT zM*MR7%}*KnLSc?!gHP`>JiPFBaPOS3@H@!T^hoh2MLS2bbk@W9D^0pmuIvVPbdz++ zlh;K~4WSci^Y>{IJhY7Xqg*B1go0y%uE7WGgUb94KYoeI)^je}GN5R2@X-*YLYSu( zZ$1j)oWkK?rE38$^*Vi2ZV=~#ZwsK(#q;#^-(KHhZ}e46mjb;ggrpR4=lyp6LgmBL zQsd|#++_R19z~x-N@n~7(zX}B2-QyY6~@e3zYB4XW(01h_r|XWdo$Fs433M?drMTF zAS?y$pU3_TFL=wUovE+q)&M0H#tVOUTOM`YuzXd-rVsP~nIYHp*SHILkYg6axkT3& zhlU;tG?_d7z1VG;>1XUO#)g#FCBS2)r=J1YECT1s)Yz-#kf_J)r|$#XFQ#`C(;CBl z>JV*}9>#tsfjjP(Brf}Jc#q8j9{{mb4Yvje_77F^c-p&9ImRowPNP&n_Ty=(RYL)Y zfI$wIzKg|97OidtW35U&e(eWw(YSqWxNIVF%bW!HwU8zyrI z7S0S0M1v4K`yGjjsNnfq^q1-`Q~`J zqp!aJmbf}OLZ1#?z!mDHzgp;%UyEx6^@&8(n-wIR7Qa3x_tN|!z4G{xN#PVE;Dpx`(j^FXQF z_aMCA=hPIxu@oOb>G55*ZTYX4h&7=_S&65pMIwiGVC*}u+^>Wr=KxTT0R#mqCdnDr76VIB+L=QS^M0(dgC;4i{28VcB3X zPY>H)mfT5yn^LOFZ4DzzaB=Ydoh%jEvSq;8?+c>t@IjkgE$pbnDAH`-s&KUOM#)^P zO8^Qi4MH-Z$VK;z3z`1tuc+|2Z$I+|)FGIGO0bhD>wS=d<{YXwZ$Ddm^xWFJTdP{x zj)4MaxMky!g`D@PPcKyMvhu+Lg;jpZN-vd~5+^a6Fo{iIrhpwPrcdLaGKL_er#=*I zN+~uRcoA6f3;lP+ALl|xAx7m7n*(&~_qK<&PQK2q<$h_;9YL!=e>8`aMZ@w;0RkS9`^ z1ZDd%f`nD;y@scdNT{)jG>!1zj7FOw{aCN^A#1vT?pJ8WBKLk&Ul~^WG8jjIA{>O9 zxjB86%E$>ss`l$SsUZh0yIE>QdE|tdb-;<=4>VN8Si`yX#6#vF zByb$uIFU+`(xt{llw#~6cwov+J6SnQ7hk8h(tmSUnuK`_e7*DVby=nTkM*>m3oZ0T zlEeP@GL*4`I<8Ip!FM%|j(^JZypGh%{^ObbmE^FAQV5~q;Qk@NxB!v2Unypubi8GQ z$lGU`uw2Ay7F#1qXdqKq079u(#pCIV-5n+S5L=N1snQUu&M~bY91c0>kK({Huo)!@ z3G>Cm7VedBBC_(}q|wlyfSJRF$*r|;<_>%{d=4ad0HLjH`PVi#&6TCu5qlIBhrkj& zs`aC5U%59M*<%!P1=s!&(iE0@WszL zm`GlGvn6=$ITdNz?w}Z=Jwh7|_PZq}vqUGe%DcIlm7qAA!DK3UQK92djsX5L?0JC>I^vt90se|s zl1TSR4(q2XU+1t+o2dFcwAU?oZdc%)*LTy(zJ0u|sOOw-(WC3W@>C_;W#y+?Nr~0W zGf|UI4?B$u&ZvYD_Fb@-=oA19`qS1sF;RkNueHX!8YZhlW7dH7S{NC)JETb8eVGlp z(ICRudmz5#Ysq4(HD%QgN~@TKh3S3AMGIoB8G4IT{b?k$KqLLA>2{AdLq9MNG< zd-m|85ima;brk#88m|iT88_Epi$Dh!d3QQ^e`b{qXsWQw@QjSL?tFb>eX&iXdT)Vb zU})-(1O7uk(~?v?8$UnUPwm|8FD?4(TQob;4ES8;hix_tt5etd_=RLZ8CL7shKVml zgzyG@E8`_k(j5_VR!D5^Qy9FIo;5Rb1HR0VCSpDb2BhOxMT-tEA?EN(`q~Ve&T{0eEb~MX?DlkTFR}W5!LrQlEn1JAnI&c)L>e82%0e0XJ68f zs7)-Kc@ywjkGQ>|jNf%qe!R0wL``eYor-CGN7~?acr@*T6YY(%fLs!^L%A%wqoss{ z?+X8hP8_+2jU@yS@lPb4!6WKe@<}_m2lTqBNY{r2t=Jg-g(qo=Dg?0%(B*%nuhf|M zB<=RTMvAl65rk(k4Ls8kb@Dv9wiZ$ZF-U!AO8&Fv48D7Ln9SV3p;&W}dd$^^J0gqd zd8MG4!ZftBB<_1_4D+*yBVE|C#2;+pvb}+gwTyuuqLjgL~WP@FO5-jqHrqeE}HW{f) zL)pdR_TqN;G>+LIr!`>_juEwJ!mA9?l|!I4q zT;`61&~_eu@sOj)kvpO}4jm%<@?FQMJoz3oJleu&{8fDd((xS&B#1@=6RucliaM=L z6lE5rM+qe`r! zY90l$3~|1%W16CE;qlC&R-tY1yEVQhwvqA7dGgkgOc?X8opihD;sA&;i|!lW77Q>pqpTGIUOQE`H|c z=%G0Vuh}c-d^Z+0#Q5W~n{#M2VdzWfkbB^xQ_I2W97chiq9Sxc8cOM>O15^%PsJb4 z`l?=f7}}q|Pcm?j<^XSyiA|(JC$e{|${YRrrynkOjJ?{%xbaD%l(BhZB4f}?+U$Ca zXM5Y=BI$x3>l>bHS*I|p<`Ib@<_*S*vCz>{?lO2$@p>Vnp6BE@jc zfiDR8b1;=m22dk9XtC_cJxT!F0R5HN#qW9jzIWo@O0JJKBn}mlF2p)qhiOSYNwjF7 zqMEhz-ql^oedthRdPPtl6+O37Q6{wJy<|#l|LfwlVoiOz%H9?~H1kES&82-acik+e zmfok_T)Lm>-`wxC;q-6|=G}nM(=Z)kCT(&MZ$MjV!+xBNp&!$O9--R{hF4o5D5F9C zBOAxVS=clfs+yMK4_lxMVD9tmYMfc~>q(jQgzgCtRxORoBCt~|qCU`sK`WHm1x`!= z3~)eG-~E)2ywcC0qE2fcs_pNE(_BdU%bM-_nRSeYJ{P6E>o1SKQPIEFQ;_l-HONU6 z18JZ#aPX}$G}!8el4E*$#m=V{KJ~f;hCk|;t5CFDPiE*NyMUH&*nIBy*YXi3{;BW2 zCod&ZO0~d%I1r(}VY{{(t8G(_sXRZ5a=5Z437b3LvP3hyY#gIdb>`vh?DG-=7SDz% zdBLMj$UtE!*N}bb4^cW7&eq7T^mezRRe=+3WO1Xt>|V4b{%nWakbMPjL>aOb=Arq3 zG|NQ8TFaav-#;wQJ=!*xD5$%P=K`GfJqYoQLFUmNj}sp}_^027$njLhv!}2r`if>i zL|q`l^SIcYQ?l^+a8b;v3(3;FFH?f`7-bSCZ{U$ppQ$tORgGWCaUgDw36f9kpj`_r z?F#h_dd~S*aoW(6Eifb0aH* zYsH~41|PReAT-8goS!^s8n%b2xJ8&pse^yc<{{W$pe1f+yEcg;`aPsTd*<{f@ukToQncTRm{lss|G;H-M3A~H2ID7?GHiztNIp4( z<*>)4NI;ow!n)xO2FOm_RwoQei06o4GwBZ%1_6S`ZY1Kv30(o}awsLPMApf4P+FB$(lmf8Jlgl->3!&HILG;)M)A z)QDYwTsNf3hT3Jlg;3uh~WE87%&Ay$<*7DsTk$Y zR`kl_+s|ElAkJBKnz-oeWe|cCneVd3ro#VaSbV`tc*3*yz}Y=}9A$4X!z+hzPPeJ~ zRQA9Cm-5owZ}jwLMTuP157{*bxG{MjvHcciBk#{zzRd5^#Mr*@iZ}@1!usUeQ`(6} z5-h=vFjdMlmy#(R{OOnHg|Py&;Lo+~WR2WE1rS(&4@lwX-p38WCKr1e$gd4wISe0O z2J%EpuoEEa$a@;n)mXbo=G`Mu`#TgmzxESe1Uw$_q5WoBndrj@k@R)wP&<>zGjJ90 zzGErrNXkQER45c|+P;6HYYc&BWcm+aHgF^4G=Xo4(TUK+)egf=>{x<=2A|Oml3MN3 z{2MNGxv^Qq#h6&yP2pGMz1IUlAWs-@@B|z&viWX<3`?*1Q<6W@%zoHRON*MqL3k## z+M3K;M?7w0Q=d~yUyY}i#3h%PB017ID_$3=Wj}X^1}X= z@47s_w~pXPxF;9!QCRvdblQ9UZ_?L1LIxbX{zs0C-bLO(V646DSQL;*?^dF#bj4)v zo;%yw#LiMEWAvC!GfQI#tFW%Hy&h5~7b;TNVNi}tr;3+9+dx532>Rv;APYoYWT&{T zCDg@aM$Ood!N|vA+wG7gchWgbVsO6;Q@%^k-$Z-%M!+*(W3;r9>FMc4yfwz8Kl6*g zJcrziGTG?_%z(Mk2Oe#qcRkP(L8s)(pcggj!>|iAS7gBK4u7o%&UfX+Krt>1g(V;IF*)fn&$Y7(;dRguEunzLZJKM%CwW zy)Uvzzc0r^{%4YtjynM5RuPo9>G=NXiNcekN>+uhtq`UgI>YYV{>Zae@bL6-P3dO< zI3mE-wf&XBVZ?iKNS8X^3lhJ*j7qwZ0~Aet3eB&fC%!r)8bWFh&rJP+*c1engvI66 z0zT{Kyr=Q*TU>F4&Ks4RQb*$hmh}6UT~ zQIxeYg!V!vD=l0A742LFQ1*tc z2L=8{I=AB2PO2d7&;;6;)ga@Frmsb3FquSL|7BfOmDGjQzV({d1-QH>Dbxd*b6$^| zUHl080lpMN6>>kfNd@?4;Y7^=Z6y+cB*6{DR!Q0f z9zeRyLb`2KDJh!1c>n)1YQ>r&M^Zc2)Gs&dyf9(x#yQ`$sJ0SxL~wDV>&^6{=#==z z&~%sHuWLFvy>EJB6McL#?D3KI|Q_b)rN{jQAs;d?B1 z1$%rC9i2K8&Z=WG-Z*~QI=Y|n;a!@&mU04pU0od^XBj%XzjS5Z$m9IsCKW$T{*&9t zdpP$A&yu~YxIABh+zxm>e0r$3@0nTEA!old5ubH`{#|bO9926^&KL<|M?+$#Nu>Ab zs^hUEOlFyhOkS$osLbTovOI-79e_3QGe9kf(CX%0gKjMf+8v!7F^)I4@KTg1m}Zc4 z-WTxx(*2GQUcC9Ym`v-XIBc?xBhc!jXcrP34AT!WEC&h0%J$)HN`Bz^bt^6kQx3YI z-eocRYp85*{9AMw4t_xsNXiob$-Oqfg(i{^@$ueY^vmK4kI)VD=hNmGsI2$Uq%!90 zsy;3gN;Y7UBLsce7NLy(0wU@0H?%N9W_T4_QGZNkh`z%l@6*x2KV=M?@25?@Qls4! z)3&ir!iF6Ud)KPKxKDR^7{59RH5!`cmC7PMybzvW#^)248`R2oWMi`K0~lG{e<0J04cL@F7jW287%%qotgDik7mBd6mk6 z&W9%JBgv%GtznttQ@O1F@vRYHyEm<2oxW!!XC6QU?ttAO=x>h_~O){~uogI{u$WoAW!US=#y#eA2g;H9O>JHSgKS~S_Nx|}`G zdLh#qZ-STo;en8V?PUk3%wGJBe-k&TO+kSGW^+uGKQ;cgs5xII$DBH5S0@4EQipL3 zUigo!eL7utf92!XGap5H1R#-}9cX^#k1Pz{&k-`(`JjQ*|>jpivH2e2~I)lgYFeyhDrVzD!F z=9nsn8%5bVXW@LCCE7CrqtIls)vlF~( zHd!9U`Ok{(Az%>WsM-Mdi$!W$*Y|mGUexk@BzA-rLI* zt|q#+2K);Dr!#!k6{If!6pWd+DX1TBnm`;A!+4(hAiyM|8FZz@LVm|h!!33!axfx3 zlAC{16AXYnBR(hkIYnWI)n$&KltLhgc}Em#$;z_**R%lRYkGBuY+yL2tzn}2wo(%x z`Y9GDRYMZooOM7EnWtTU@bFY3G75&2MEP=>v*f2mD;u>tH&h4Y=eDuviCZf~&= zW^#Ec3HpX5zL48Aj+R6y&8n>Zia=FH95+@N@Q!lrk1-)3>VRJE&L!ll7cKuF$Nk!a zAxX?3AO0p%j-Ll2q|%Y&jg?Jr;@`F)A22V95=ZG-nP&=(t8brB)}cMU!GnHFy zG&WhG z%ky7-FnCCMpHB3L5GGNu8xXAd^Xt8g`*g&`x)8+y8K4Io?&>yd@(QA<*lLJ>_qOVP zR)aP@Y-i{5*8+!*2U$(-l5jpABjFi?HT(nR-uo|7M!FwRIH?{JyM(v#lLlD?TfC>c#BN9EpQ%%>@VBWLN0hKU1rH z5WHSFd#U(Jxvt)ul;d6X_}H-B&pLURCWnJPdqa1t3x17gC#bcTe3lynyntwY^an!R z9mT1=V|Tcee=LlX?whK~HjIxg2EL>te1r141my+)v$QA@Sv@M7(rzPeFXkLZ4HKb|bs!!cKhnOcboW9D#F6 zU(u*}Z^`7~NVPE>h+eqkhw^=K?*h#{QHO)dl+@m-qhCq=pz9hr5qLkbg9Dl++g2u3 zFgfw=3q5HCtL|@}yeY3Gm=4V17K(ZQgYPOOVuB={a-U)}DBph`*S_z6cPy)IYuqc( zg%4vUJcJfS%Xsz}aO6@e1Q{o13V5h_tjCc;R2j{o-R_?=$in`y7fK~!njHJH)C42s zl{eJPCwEQAYb?ADxHFb3LLz$N5f^2Z5<6c;4>z(x? zj>3C7id(B@Pc3xdkFu9;4U%1pzQv+~^{IauEK?iU3bP$!Ag5?Pxr6hd-%&RLb{RhD zpIOS!MeYUA!)1}?$$C!Go0e^{8NL3JxzUG(q*hyCW+W|MLIArGt(2N}vXfLzq zT;yttxq8n;^2#_Z8|LN{d$mu7?gmyp7&DAN!}MupOlk=rNsi7;{ea-##*S#01H*bp zE9@T3WU(V6P9)BhKb3Y{ydBhAvy~S+%4TSh6_b|W1~va-Xfu?I*YQXf-Ph7anIJC(mjVw?LM2g z(oU;Xz~0o@a_`YY>;9u`)vxzjK2s*7bz>U&h|GgAn!^ij47r3~%q@5yp zxYBE6*{w*oU+1#5AwG9lpX?sv*)D~MRu_$8&EP{j#`|p~&xz57*p6Qej<*n7Fx^~r zk=X96+JK3=D@f0p6L9~HbX8qnQ1iH1YNoUJT7XXaWv>3KLv>W!EHG!#cCIURI9&kt ze7Sr$H-snIo+V8EHi>KmcWj!p=P(BsC#@INPoJeT%U`4op8lG9bo`LSDdL(=5KdaT zovPJG;~$Q`>-hX)QA*$t7Z5bJm1pZd(kghz7cgbI#08T|?YfF+$Nt*ily~RVKj0A;dXOGVv&9^j=@q(D=QroZ4aIgOvg%2YmSN zeExmXjOgf2DM2=IXyuPo`ik7A^ZKEJjB2;kS1-mu#zB6 z#q692W4V^@5V~X{o9kdDOr8#rc@#K{N_NQYtG~n*BVaB0*TwK%Ad9O`}V+vnM>0|&Yg^T#loTn${`ym6=K z+|P4wmpYCd=iGKF_#NB#FGri7i%=CfMc0QnX{ug5Petwh<@83T5DsEsZql(-P_ow z93KHPSm;_Q1RX{XgP5ILsEw$a37+1@Wi=Xkg>S)hb2$YRn$a&dC#2Nsv}n$Yy78?8 zcm1jjEw5*c^jPU$;$QuC-Wy=z!&XB}V&q0-vJWO$08Ju zDxJ0Y`Tit20jC{?4 zizSUIv#opv^?#}NecPu49w(SL-YZ-2R@=`aKz_*5CKjrA_~g!WHgYZC%|3P~n0FDd zP5)sU-gnR4t_h+R?tOywGWuFp&p0bpH`VVN|8Pd2%KgNFfsQK+oss#$Rh8lYD4?*i z)UwxFJ;+5$?DjI^_X8XuP;miF$UT2#8APuFSxxQ6R#$zU>nkr_IL<>`@ST$;;cYY5 zZ#FD-dhR4H@<{8bCGeud*O$4dDZFkkf#g5*JbkHt6*80wBn7ZLKqi3a&^-_H%E=z{gt8I zui1xWV`wv|LM7`T6Mp5ogWLz$V)7eF9`ZcFEbkJp1ME`OKpCa>g5{=M4W3Qr)``*- zzpu_-@nd@#>7U^X!w&twTwp3Y|0kGLk=@iJ?*N1==h)p;gk8vZ}N$o8l`#D}?mZ*0^pKx~)lS@RE49iH}Lu~z@XXKm@U{z35 zep+(PQY$0xj$-%g9Fq_Ar?mI`vgdX*L<8!xj7D#w{yxyZ=Bz!6$#W@AX)NXzTkKk9 zXPAkhyfV|Nr2j<9!E>fM?SK6Jj*Bm11XBN=wRvTeU3kR8*k$Z)1TxXYDgPsQX3MO@ zN>?ln@+|3>oidfZTH{K4TCiz?upA-~kAmshBp6qR?^0w`I-Biu8QQMV%#bHcB1*&S zG%|aMT0d@25=#r0GoX<*-2yd{`^bB=^RmUq-mJwDscx&GM3F5ELxDRX;>CO2#yalo zzalZju4m+27L5>9s&PwrrE$nZO{w~=`Nv&*P0W;Uy0p}F{#D2wtMm_;@?oODF2UfN zsi(0Vh+GyhHA9ggDFR1~-qc1SpJVMm*fnSAVpnyE;VzdJS9nJ*sCjF>?7oLphJNpW zab_}W{aYAk#`;LDhLtAwMAE&m5{)uVC5a@e(wJPuw@C$AE-1!7F@f`VPRLTSS6fafAB1vMXUYHcoo@B!@4x;4$KQrhA zO!4;tr+bOr9_i(+GgpVNny;-sQ^=&=q2Bv#-$SmKn~d6Uc``|9>@B+<$M(xNpYi`t z#!`sH;KEX}6v7eF4kE2u6(G6EGC}Qqw8Uy9Te$M*n-8L|E~`0wPW$^Qw(_;GQu~Vu zkVUy6DR*jk4C29!i+n>$LOy;reS-c;>JP(?bu?`q@D={P^Xw46N^NM`T`^Iuns&qW z*!VL=xJkz}!k8qHVp)BCjJEB`7g_rbUNSUu+47U+@HC)6y=B+yocR|WVmfztCz0dj z!MBNoX3K0NN_r5IQ2M6Has6VgL#hBtr=ZFS*DSRg)9IhyFRKb&r%=8b9lUz{W$cCL z1qS)@nU_VXXFc$}hCtQc@eS4>c(-@|X3%r{5x?#0l6$G|L3Hk#Ql1|ip3N1(?wb>p zLDx#`<6Q!c3lu+K6zp!L_{{)eaEjmdvY?x%V!@vro$_#f@ytT8z~TpO3-sSQ?b^p* z^rPSV`<+T=BX{7D#j--8w3T-qg`tCcR3er`#%Y+{ZSyQ}!9*uswO~O<{BvE7dn0?D z)Wok-C+mQje+yFiX2u-;vzB-k*`k4m)__C6ibdJt?NL3Tc`gYr$p$W-GI%>(78>nk zFb>XiUGt7HH(PN?{-LHN=#*9@aa>`?wk?-0g=d;3FNL$w;zn-ZsEHYLgBSuT<72kW zdas@wc~?CY5y*hPn&P9}^9FlDLK@9~(XFR@5sFSuq(Nqv1VnU3{ZI zPCWM7bZ+kJD>r_;_!LhmlqOAg!6fD_kBGo?%2J~ush_hWby**i@JW#2aO9Logu+d5 zc&+*p@psmOqO3~2A9{3wOq@+PGn5kwFj->V`S30*qOQ$UQ+fKj_9C< z4@pxsI7Rwo|Mq2ly>>A=dC276mSU%|26jD>)1+CJRw^*&RAxn@9b<1ky2n7#cuSVo zw&U8uCO&URp8w~e%9BYlLYx+xdtoSL@h=)z~TusVcZV+#>s7@?FGP@Ve)Z>m(6_3kF+|(*Nem2#8?Qi6V2wAf>#`~McN8>-S zsrjz=YhJl7P^}q>_4Y{w{uw}FRP;w(G-0JX2@$=Y=j;cbQym9($m6jqPOSTySi+Z! z`q$EGcxaM@Ss{LWI*YHbZ^crjMyMm2mD{`I!r6g~c?ph{8g`x7Ov zWgL{WGDcSVU+1*9{*on`K6gw064=Hh7rqOyOM&*-fI>AO(aWXgp|vRG(z}*LHp-8pa_c~qckG&)g1V~Qd6!G;>_g8_w56U~_srB6wXd4BzR=9xVwS0sY^fbll*Nyk z3H<#iqlEcIiM+B))Zs?1CT;Cwk&~t**Z_Ts#rQ>~0Pz)LeiaSJM~;F5B96Vyc~8Bc zp5NhKMZz`|(Jc!7V4_`h90ix1>0Xo+JHG(i;+*E=U9JQIZ@FMCezC5ufy5Rq~dh4*Lx-V>aKv7Ahq(P+=L_kVfq`SMj zyITb5kVd*YrMp2ux*Mct=x*LUKJV}P-s|I^VYq-fd+!zZeXn)SI+$|zs+Lb{w5sMg z4c@>g!;lK@#)fW3(2(QH=sLaKW4n=X+-t_Xy9_d0tj)7>vH$iOyBTlz-JhvKb|kj} zO4PIdYD16bE-J>}3f^1!q2D8kq@K%;5;n{3NA#DHe%WgD&(hif9FWrU>^QXobl zvG-}I^yYk`FoUVsN99Y-m1?4VOv%WnvU#1hktkJHHMUk6*d{KeZg=@#2luplhjc!0 z1%hkHvA9O&PJD5QYfaNe{)lQ?iDfyIuKj4P4;QNrhKadW%U*J|mYf-hQ%mm_smM)C zR7G1#H5kRou99$R`iAXXV-qmOnJ00>3xEr>f6e&2AYmwZnD__n364ng93>ky1pEK5 zC6W&_hBhG~)ael7Sa0hggMAM`76BlZ(RWx^?<*LK=0Yn$o;m;Bgq!tr> zHCpIhSc#EI1xQSGJ#>iA@cm!@`8_%o#bs#BF#8V<5BW=<7X*>!Oz5y!OU3#J9HHDx zS6}QXxTleFPvp}tmn&Jfde~wqv2q9b6$~%hw>h00h%9?n$%Pni(9HWdwzF5be7V>! z7~h+h-qz8aKAiSN(C@IPuRQ)(omu?3jMqDL$z|1p)$}YKnrqd(RfFfy(Coc1AZ(?? zAg3wZ3gx&yGcc?y)!-55_1+qYImj~I^wLSpy*CyQ^E!;DLGLQI6d_{BCZbnMmu|7k z*~HtbtNJoCIf^$La4=J1**j;kc%L{~d6q*oW#Veu(n;ItaE8`(TJL@ilfEH(zw9Jr z<lB8e9b%%mjl#eltvthXYE64`WK;<@w=&!wdcJ!0T?{HUD}6 z1W@xPzZFMD_)PA!MpYFwO&nVyBJd;dC#Gv5jO)ypY)M||iBmy3C4ozBshgd4_7+W& zg{e1KIthI~XwVDdxjf$3J$?>%tmq^0-|?BdM*r~%rIXE|T-ux{8|I9%1#g)Fv15mg z;3xz7-l$e$tFe}Gl5moPUTFmw6Ol{AS@4oi0*})cDYxn@*XA#mj^uLDsurf=>!ETW zhi>Dkn>)R^Qm38@VmFcc$iWn#uH?JM1*=!N%u z#Wk;tb1568tZpB*syuo zYDgWwXz*?kq;Fg$>hIS%eeKLS(o5CKm?7hY(U!uJjaj`#7Q0H0!e-o0yv`r?=hy&r z!Ho@Dblaj&1J8h)$WYX6@VfeAn_>a8Uso9>ww(06fs(Ml%stp4AFN687B<@<9pUt< z=YPZq+ag#AC*zjoF4yN0 zP#+Cx$;HdxPwArvRNT?;TbT-aDT&~H_*MJJh(SjrInOCMrJ>J(z9zJXogBgWHYZcm znTPl8Z)#$k*4=oS)`%}zvl>E?^|8(58m{DZpS&>j&tfLl`#uzZN83UB>+R)Yk@|OE zz$boH1`tm}s3Aa{$CxGfaD1XKw-jNoY!5$mA2)=0f+W0v4NG2C_nh6*iPTJOMtdGa zQ!P4>Lx9S2+7dQUrRQ{ic!t5|!0xq-Yl%EaXMbB>zWo!b#O;(+8?se%>t>0V7JznPSG`T}Yuf9IRs4GnoH&T|$ zy*hJbrsf8ZOj`AEWHo(LW8CSW^kuW_(&~O+#p5Jd-;YvB!b!F3x@l6B#e#5S##w#g z5MZ6xog3wu$9Wo{SshMXRBilO+kNGS*YOl8343b%f9gf~e~l#choU{~zj}tsXAsR= zE?@0_S~7A?Y{wlip8a5lGTOC?!g&_Ab1wn@#_B4fH~f=RG5?vS+qzDc)hFvx{obzA z+tY%q>kD3W@9?L8$7=K~=bVZqL9C8!IrBfm`B#`6H-OW5*>h^hiRy0{qW{^}yK!pl zuK^3qMM|K`dA3l&x>p91`NWYx`O+ZZG+43nEXaI7m}RA5wZ@YA)H*_;koS6;gys39 z^Nx&X{Qjb5UW9hz7kCo;h{ms}yOr0VR7LGT$1PgQC@KFG%HddEDt<GP?l`fliG>#{^sWSOV566-i*H`9bGgBpWv z=d)&>RMna3PBE9IicGe-^01Ogm$6hH>u-YNE#EN0z;4eA&W{D~DxD75KM@hAuRrV! z#;x1*JSRs)i|K$of8adcFE>z2fQ2Tvvh{@Xd-RT$1p#2;AGWtc@_$v#kLoYA+&u;t zf23eo37j|ndeA;kAtpLwxXG>hQ4yRAjN$o8L=9L~#ViFWm_3`D>0;~@#{NpV<4m7S zdI4KpO(0!RE`wihBU?(|bPDhAaRm@up6``S4`CZSWLKzH9y3*2X=N7_BXxjRfxRbaxMJ{(9hl1>K zj*p6l`4%p;<2w^G`9T@_Qg5O=uJf;G8Q&ycW+(87mcUJ`+Ff=>Ay7hX>rKqLexGA#HJLEliVf2Y zUp}Z5RtG|t=o?+=5T4YIdjzSh@q;#7JMt5>=DS~l*QZ6w1+O^y$5u`bs_=TQ?$G7g zX5E*T#!0Skxo>*8r(3+dGOWDTT<6NuMWRjy7l8y2K-AzlyRDV4On<}W%v2cnVk{Bm;#vbB7OKCW2t(E*FcwCxN zJ*PFE8^BWoZcijI1HBn7HG92tKx5%^l&`%%!sDD6K6(F{ zM(-T?HO5tvqMl!*6cfsB?9=CXF6ekd9?)xXdo*(Y)JQGFlmo+nnJ|3ohisfVXA;#An%mMu{L0u z+4nMp`gCdD$;^IohALiH%LMK0TFn*}dT-myw)O_8<}2fQ>V>X59nJWq(@IOXl`LiR$z(*9 zh?AQs2Y?FBv>!1@Hh?4l|5)XlAzAdcm*&4XZn7G7;w<&06w(I&s@AJ<(GJh0guTd= z9mI7)p&oCZ`M7zAv3pqSKjZ~R0Nh@6u5~i6$W6APxRlq|uxa#G`UY8wSEBJ=H$k?o zR`_FMfb4)MaM0{l@WG=(1!0QVba$#ozoan#Kn|4f%(q@baf^&1%!W!#_a^&lczXAl zu%x%o_oz>2VF`$E@;%c{eM14n6YE(sh*T%yrOCpCBkuxDXMzj=w^=0B>wU?s9c!gw zC1B(aE--tuy`WI{#d{NtW!E~ni@kz0yB?fys?)Ajs_8`JyuTTD=%Buv*U0N)sOCi$ z3P^+W!`Zs*UeTV6q<9&e#Q;aY-jW<}So)@ShS7CevAqAY{OY2tcV`;!fIB^{>FkSg zVj~&PNV>CTy}`l&N+mx^jw=6y0$SJKYjMG7j48*R)1N$a^n=q#s3E7pv6Z;b@KJ=< zu4hu*do1rscDz}qw{MZU6Sb4q`Z>I-_qzNJ$WXO!y_(Df`wk5RBnC?WcHawl9^nqB zTiVSJKh9J3C%l`kJd~Fs4i@Fvb~b2@wqTpUkfJD=G}ZZO0P{ZbW8ZA1OJz9oS>Bzn zXIYaz38j=+JU(S)ar}OkX5I36@dGoK*ci2UtMoyW-cdqX0HS~Y07_M1@n`m*%#mu5 zA_;B>mh>j(jBOP?SB;@G4?m9T%9=gyj zC5=y=SH8WGUrUW1946E_p%gbV+v9p*Jtr%MO^gdCPR?P=9(;q zT1pli+VaB*=3>oVSHhRYra$RCcTh#QEnIONH2k@Xs6H;KOL0N$e~G`1IUy7@={BZu z^(F-(TUSKWX3sxfiKKF;HQOg0;k|<*dG1`ZxNVxi{03XeNvyViIXp-!SHDeM*E_qb zP61k_@M$+}TH;0paGF%krQ9vEIfZ3RC3|I+RTGVZ(c)yi1DNnJ@X<7Y=jMc@V&y(h@!W=aoPHmQwX8DF;UJ{d$8`ckwIVPoqwlJTsfZeZ2j}GJQJzv_`lFvq>~OzFBCb$m%4$ zjB$h>W_7_;-jnPCO}Mv4>8eGJ)-C&8z+=KcPy z2iCJ57H~_;edl?;@2SSyI#S(pr=H4_t4>w#0cv=j_bf$cgi8^VGXzud4=yqhWLAV{ zX94GI+W`^Eu(j#p5lKAy5$V+8)UhKVwFy1nvzEE|$~kQ5X{>Vgl#r@{7VF}Me-qs`Q}TgJ3wpbsKHey0*yQ;0e8{&7ER95DK(^)+%PH{ z{=!7J)7?=eWzfdyIYS3CvVz~W_W$&|M)8MpJqHY@<=!LT^e-)^!5XtPe!#aK&*OeN z2}sQcySR6#B4nd3Us&jx%?`rgr#<+4fVia?T*t$4BX_ja9DX3>>1^YL`QXAAWhbIk znsMUfLk1>#d9v1;g^IPB3n4fV7~k^*f%t7IzQ^7lTGC|vicIF^ad|$yBfr17?71q8 zAX43fgy$|fUsnqY>pBa2N;|Q@oj$Btt7a+xcBHxx*j!q(d)mvvKP2|5LJaA#hDd5` zWipkhmA&=wn?E5G@rxGk20=|VnG|&!g>)O*Pc*VtyHp~E2Z#KFkj*Z6^i6SjC z8B;#sWnN9h&OHq=4p;Z$BIRbbwg0XTNHfSX6D@O6;EJSboAxqSz4Nfaj({_pnBq(i zZ^_rAHwwE_B~W9k{d^K)uVMWym|B9{y-E=v)(N5@S{;!S<8`5^0v$a z;&mb5lM_=!qd!}IAL_G$1BB<|4O(%y+F8om8kV9vS#_SjFVPCxssP$j15Hk-MxjGG zfF$s`HHp<)@UWU;e+NAhZZ_J@K$!fp>^^>VJ-ewdZw0*@#hwi3${p8D9BaMxDkHt> z5{i8(VclS2KKylmR*aR5Zs*lV*XDJ$>+fyS?-eacNI5u_%cCG-$d_{G~!9pTGnKc=DiF+C3f|eppbwI1%N(tOimS@x8%EN-!{|e-~&ZBulfY# z4C-jFVfmI#Qod0-Wt8kJY7nTc-$X+p4u6*AQ(yOLI!j*)iwe& zmceP)={!l^d&|({P;tpjdB?4jJV&rU7arSU!mJ9WP!w}}#gNn@Q~AZ8UMV{v`Sc&_ zM5T-v(vN?6q|~OXShreKl;o}f{04%g7COltVIU&=oFv?w$x#->>%m zPjrB5K0nm8DjJ9%9FtDt*o1oeA^Ml9@R-l_em&XcD%@FuB<~jBi?j^2%RHYM(_P+Lo1)a3MpLjD4&bEl-oGckp93(RTWK^Kw6wkDBu`g$Rc+9btpMb9a;FAq$6Qf^g-Xn~f}Hl)Co@1ifJXG-qTs{rm}nDkCwPMrY|Kc;wUp;&_#(&b z6x;rt@smez4B&Z!4g>9xJYHL=l~TSif*67Jnv?n_)L4}abJ zel7*Vt0tfx=vZ7Y3}`keO@W#UFd`9e@1rktiLpgMENi*g5?gF^zeWBH9AW#8D1Ha< zVx?C)+tkuZu-<59WK#2;Nlx#2{^rO6HhjRL##j9dB)>Vy!vos9e3AE3)xtSrYN5rH z@%|Fq&iXab(wp-*tAKXba(Ae!*Bwd8Y|57TONs{sN(pz8(XgAMM=dn?S#CSP1t`G6WzboLLC0G4w5 z1_{w0WD$USXW&q~vBM2kGOX&x1vUx4n*H-fVsPbfjFxu4COB?}!#z7yB)wQ|J=SYt z^6}W4ODPBN7=iEXuL088F>qhbAJzdow2^ZKuTfby*|eZ&aRt}{2e{ZPl{eIn2mJ*D z4B5M(=~I8`MgYS(>p{hP%Y-um$^;Ep-vh&)LOm^fadkB{DmArRbi;wSZIE1|?Y6*$U z_I1>3xLOtSygP$gkaaRk-Wm12^SqJ9MG>Z6T4@3zw>Qs3_JjMmACN;G-3I;Z=j@@O z`^)NOKqfMSq71~u#1o8xU@ z1|F%Y;C!(nI_)0*v?_=33^j_i*kGHd6(d+;Drd1ud+U{jK{ zN!}T|DNR1zMZ7X?%PRpdLC^Toha;tUrFG9`mphJTSU+W-))QhUATd$TyG>58q=%+w zjD34w@>4zkSNyJw*5U+wMhU2=VjsM{y$=(29Nq_y7L>9)HaB{k&em$-<8`u7V0uTC ze0XH8v@Ktz#&UZh(4ip69}iCyIqsjC?3k*vDU|W(5*f_`4my&5Ao^#}FS&pAo?&s- zhl=>W_PkasQcy}L0W}gRL0|#>@ia+ye9XG(-oh8n3XiEOly?oCvegdH-?A}ft6u$F zBZaw`m+@S}G_miC-_iaVi&(PD;IZqqs+K&eznf>NgbOFN)@j!QkUZcoSxFS_%~@p4>Q3LWhRC!*C!d*1$G1^w14qZZI z)*RE_5b1>elKYvQ=SH=8ug4;@BuM@=ytK@wUiJ@59PoQp!lli?e;-rUu2sULPtCCA zvJr`pJg&?ED3;A4A#3@7i`(?%&kt9@S+_f+le5afeXFJ<3+rZw3@b3+W3@FYw*Vf} z>I(&X)!bOf+4xU_?H&4}erDwoZyEZ>#N$q&^Lh#8&GlO6riN!oVond!j>+K7p0ZyM&tK6(><$G zu(b|uzjt3RI2N74_NdQ(xA#$JYFAjqd7Z|gIy@}7dETscO3|xEDf}Q2b7RV&xLfsA zh6^bH4_1k}0E$;tHwbF3CKzoRfh>%uS)Q-*lYA({;4wO&-&09mHI^=B`O%c3z2n@>ZfpF$mb!{wu`x*Xd( z^gzN-w!=PeEYrwb=J7V05E}G~CO|V;p4MV9>s$mm4BR?2b<#VJgZ3B>=(gzJP631N zBr-xmGi?vmxZ4gg6Hi)4Q~kswoHtMXKvE5EG)!#hfF8HGC*gVAIhvpC7sXMz6NG~> z2K#luwc1}nc7NGpYDw`ZSv*QQHJZLB%KVWW!|+~)|X|*B=nj1 zzY3ZR=6cJSxDkzwjsJ=@NUH}m*dQ`50vWBR=>f+mB6V|iiAWYC5l{oel}_k?_9TXY z@YcFLl(@uGlw21mc&)P_RYN%x7Zlw#MCr(>d(6g&N7uu(A(h%^3bwpwq3`Y zGLQk>mV0vC#=BAB`d;MnernZ~a+KAg+rn5YFP3;+&04u4D1MSyL9DiSr-Ab2?9zMQ z2f%2_Vwj{nsBn?7!_Jgqakn|ytVX&+jNx_`a6WB*u!E6e0#l@jlX?4Mfq@W~kplq9ew!W&b zUc5^yGMye!j#X<28wZIKHts!BroQZYl-~i`G#s-F)Q1&n3yojp!rKhr)57oh>17s4 zvw%(Vf?(@NB2O#E4a7?4`-2nXX00CK`k?>y0=(7P_5>gWdpfQN#2|Q4C6$-){z4s; z`pFt|HQ>NY+pE=C;z+B5__j9Hs%*U39qMrOm!M(863_HpJn<6VrP0Srpk4Tjh%U#K zA{Gmg^;_qkSHthKnLIIn<`zibS`BAo^F?=u8S%EV0jVtODbd*m(G;4o+~A__-Qkg$ zCC}K$WTwGC0~0{QyY)Wb=j1Bm$)4+?5 zXCF>J`IF4fWSqKHe?W9}PFBPTlMY3FxJuGfy;d9_3u*)peY2le7NoeKwcdSpwW1BV z%*}sdRZH~kReI^9k9KqAy!op$8QaEH`;R^0AMlp0R}+SB?$1Am6|Y_TV7%cnm7b08 zsV3W{>Gd@~8Gfc!Vrsjhqln70tj@CT>2B=)ZfTas260TYm+)}B)$3rKhYfdHuP=m1 zXE!!~EbZItOFT#mT_F!HL_=-aA0V~kPo&-)(Nc8cD+i*zNgTHGMDw0z?&*cydBJ6$ zrE|9Pc;;wf)~z~qR*lJ47F;SJl=^E3rxaW*7keo)i_$-ul<1Nfr41&{J)~S{1$70Z zhZQTGNzGqWALxj`B!3z({{2AQjFF8qH!tyElicOFvw1s)ecLr1tei(Xpi@vp34+m_ zCjkFqHoynZjujBVdHlsNwDN+ZII=qm2n;zkbhJJKP@A@Tf0Ck@l*qT^7XM2qT$sDS!De z=ka)Jqv!8Qb8oYf)r@x&!Sh>pww5{Vu!YA-7Py(=6W6VCJ~+Kn@44QWSa*)$u_YIl za=fUgX1yRg==;#>BEi)%tG#F~=-&}c2sc9WMN2d4eE7u0 z{QYS%(WuhZ#~J6w1(z!rKM!5-?zY_(&U>%18uGKc?VPYnmn(~zusI*H&+t9&6g#~A zMV9KOoN|0;>$U&vDkU4T@`|7+v#rn?*3rm0@a^Med^WAQN$+R_Yqn70(Vmal`-j#P zPsA{&8VT0{io(=Lc+dFymu2`*ZF7NU&fpj{Y+K zHVbTneWm_kfON=VFa7f;4V>#fwJd028-yRo(%}mb_^1P6z{JFqeeo>z_0WBsuI9(r z$m-9h*TN1WuFq6fspyWec72y3{Bghf3RMY4h*U~Vg|@Z7SD}G;SGS^ov#ZVjj%*hD z6;sye*20XYl#BK%G`OCBXYe56@6iK}3wqO@U4yL3s2@14wDZ|LyS2_m+)Eqh@6vmm zjhdGc5taxmowq0+2?y@(Ifd4aZD8s5lZ_r2_arn{Y#tn7su~A)EcL}z)$n!AhlT5F zR@Fxd&!6`Ft+fs*WaME-L)r+t>>EfLff|ku?a&J|7?j5sW>!2J_Ehrg{qP6XK{*h7 zz5QKR|AR3-JNy{^BHKYMJ&wVD0HTBV)t@zBSdmjywI4d4p@dwwceZy&bw<8XXzsXD zw)~RmlC7(5fqSyyK$}i_%mgJlF;2>XU9)a$FNIG&HsLm_umF3IM6>Q8E|yyj+9BZ1 zUWgRYqWx8P`M~wID~2Ir4~g%yT^(jUGV6Pi_^&RFqx$Oc17UZ)Nw(>QNTV;g<;W#P zp26n5#xvAzHy1tpblxod7y)Mi%cQaRPzpB5KXhR-#JBrA>uh`5?r*9hXY-Q>|3q&~ zo^KCoG3e3Z{N`|DIn7!RqeOJQqrZ1^-QnNJqyVS73MAm$2W z#aD6A5N=Lvb( z6`~u<{KH`8{?abdfv|X4d84)^nyX7eh-xDrWQ?p^6dV$3WU!4f;~PCK{YDZJ$j|?; z6b0RJYhz|L~ zFQ@9s*}^VEvTgMPjiM(YvC}o0x$0#8)Xb;~TmL1S`r+ouguP<&dkkd$Po59}%1rCKADiLA3XL zf4?fk2u2hQOP$$U|4viDiuwd))_jf>6ZmoFKBZ}C!u_h+&n=Wt();c{cRt2D8A|GGoH>!N@D zwbE0k_~Qn2!KX!PGV{a4TuAXU5(ev06&ynOI7_eo?TKHd7Tl8fUODtwHq&=C*l1*G zhewf^3nnkF#Cw{mAgH|bbyc)ZNkYg{+N*7OE2s>ig)}Z&S)d)R-yZPJMvw@@5Fih? z`wTn=)iYlc60pK2*`$R-6%Q^vm06sxJ=1Vps!KZA#OuacZVM-|!6rmHTa~h+y)8iA zfvl8Xsg@Hm-^0+ZaA_d{tVMi}_+IF+nH^0~>K}Ico*WI8j2|uSF&z#*Iw@aUJvr>5 z&-=S1>K2N!wpAP@pn8g*WDsw-?A{-+<)Too5`!1eXn=x6XKoU2*t$-X#20e&(qOHg zw)Zu6|AKL&Vi}*EALbF(rYYy6AAWIO4!unhs+(Sr^g92(kB@ey>Ir@oyXIRure~B4 z9NbVY-`&KSmJ?NbEz`G}$G*m)h1k!8!YxXKV@MC~c9F|yRT#9KL&3W$wC7~jq!YGA z5ut<=Ytng2wyzV2vz0UuzTy`lOiM|3r?q|{t+RcGYyh!Qw5Kk7M4Y_iP=7RZE*BbH zxq6Ydi)y0n&y*w^!YJzG;WGWccvdU;VYl?NsVC7NH}uRBHwiK1fWdr0&7wzOt8LO7 z#re`J=f7t;TKen@eYT1EXXtKgbb31IMt$xe{%~#@{;h?5qQVSSkVE{cilD;yzWLh$ ziy1Cej{n8{)F0dr!C3l}Yq7B54i@hl(i@tmZ1fZAL`9rWViRLW6n}1UO06k|Nxm?E1&p_UXE8P3^cqJHL3; zw>B)ZnnqGh)H-HVq-^m_{8pu7llgMQ4tE?(bX=*37vL4C4UAnAb~mP8*iWU&vs}!O z{XP|MY`c2-nCqnPo{z*>N$E5l;7%n-T(1sIDWq-jr1Eg1g$Bf=BWW*JdpVrKbTsu`xWY~S-MJ!b*8I+wrp3Uf$3!3X z-v?GekEX4~Rl=nBil5Lu=4+E4mTLdLhF!j4LxM7plrD=b67o^s&g|10I__8@FjI^G zs&@0_nY_)f)VLVF7mwGeW_~2;z{aJ*gJUS@i}*qS-feQ9NAu8-2|5Tdw=Hi#l6}cN zmh~R^Pj9{p?XftK?RaYqQbQxfx54!8zl=u-kp$npEjdC-go$jbO3{yWg$#t$e_&e+ zx>XTqAC&c=!T^G5Tqn;`LN8JK{s$lR{^;c0jP`8k?Jpr>Yv^Y?Kjiu&Rs(^g*Uu2| z4|lwpe%lk-HKb%*%u}DH{yWjp5#9gb7KFKmb7bT36Xp0fmzTeK_B(8SQ6W?23JD+I zd^uiomoMUn5kC%TZz-fodE(t*gjITblIz9P8;~iDLNj_<_(*%d%zu2tUkpN(C%95r z8D$I5f@p}!q7~cHvSPTmHQ)}e*omBtk+}Npr=cPXjP$5Z^23N>I;tM>OEW&!!Dfhy zVY-7xhnAyK2|*$5F;qRz7P#kvYB37RE0w--cJ1>a`m~e4k9Z;}Nu1!3S$V4+ni`AN z^^SnX(J_^S)AL~g;dU{x_w=+7+JMQGn_sxt%5`sp_XNJC3zc*X=jN;$kB^OP>|S~7 zkz_w~x6nL+(Ei?;E)gtiZ`#HGGZ4O0Ygs2s#BBe9nL(R38n`J)vb0h(zx(Wq4bza%1VHoN8lY#l!%rj_e6#hhvlyrzMeV?dfOt0p7-|>trDn5SV4EKLo zYmHuf6)*hoj+tx*F7L_5x6`f889}YCzW!<*eTI;7yFg?JtNr(o%u{D8ZpE!|1|}Op z(JqbJNF#0x#oGQEqGRf!2+=P-sVi3C6aof&VXWVL{DSq5&K8avm1Mg-rjHl=bFGxO z(LdTQ{4ds-H}(qd+uwz51vS;Jw|o5X38-+;tImvXqPuMyjp!(U9n<&Q(46QOHm7at3;gRU?urGhDr5|29WC-A|(bMVlj1#*tg5 zH`OK%#4T<*q+X2rkL~_idd*U!hl_o|5>AQv)sFK*@7o|gr1(9ntdAeDxdN8#*3_=M zItrJzuK>cUWc$a#e_pXDoaUsHU{TmUqM%E-r+H4 z_|(Ofdu^q);rir!_-fJJ}FEs_lkqW}6D%I0BG!XMEa}Ck1$5=ui zZ3JaiVi_EQM6vqW5e<)6Y_xN*T&!^Y(t0z*|9IliItS#+ph2AMonrqb@Q<6qlyH}5 z#q=otg{jY?<0gc|N?eRt{qQLXL6!04JIxc35+g`Cv4DXz%NVu5t|p{?0%8+r!w``oDDD^|&?&&}6TsPC6DZ&Z3wV+y zd3uxmu=D#{4TUDnr@|K;=+X5*3>-bwyZr`&7cTyy`9W1x_QkD+nv#Sg!f}e~!Hs*n z^0!wy4w-`oH;PeVPt9!}pqh11`lJdkZQO7+$BvCBVrFU;M#2O`?)yZy8%g{#9{EZW zUY-Rn7v|}WLSNkBqj>2deyy()W`A6_3hVtPMrqTY6M;X^2S3c_qnC{3e?Eqt3=Rdy z0er?;Eq0qw9*6rCmtVr}3sb-eZnu#E(uz!XaCC;ah7H@Jp_mS{k-$WKV;0$s7bmU@ zpqf8jBByfJl2#;AsnwGzlkTVY%ZQy8QrQ6K?U>&={=*27%j=Yvq{;O*4#Zw3`=p3zxyK$t_PS1gdQeZp+`6+3cHhzdFkBYImDyHTFm8%A~(;)wTy z-JN*rD~Oq-xEYAejpN;1g+K)zz;am0S!Wx`D1c+HYhXmO-x)|W_>+@rKKgq zPlq#jCM1@^Nl-VJu5c0>?p!*#BW#e(f)IZClG8|k=Z6!rX|k{&0_Uh3?w8Z8;%sx`NB!F^^Fbqj6(Q4 zRR%}s#OqyC8&eaLHZZ-~H-hK-nYPyzB@_m0u89Z?Y+I`R6 z$XC&WZ>{*AKKdHlnUBe~)`!y8vdZ-lzPz)|O-;Se+srgv?%kj89nEILBVQPGg$z)w z4AnZhpd+S6z4U3-;zS284M>(`q92%ny6W6|L*jI>w8sLZ@nk7#@NL+`RoX*)mFYNx z>#;$xTD4iA8!@q%xVSBt$VmR~9WoeWNnc?!n26x(jgVeiieWxg+>Xw+@HIP|VgZa^ zeM?72@{JT*mZ8Bx?+s6jd(ArXcSCu(!{Ib(zT%PtflS$=9&{#QosCKCjOpLCUx%~D zSDNRIR~k&0iu@>q@sBpcjP*~-w$_pn3Z;NB)46pq)b72X93*S2-K<@^M5k5BgYf;8~$LLXB!rd%r_ z%6r4!v0c45oSU1e)BOd0ie;^fQsKk9?s}N}iD^h-VoQvPIt+}IXt4d%?|r72zsO*> zj7OIP)zLpNE%z%WORx?@2*?k6!i@RLWY=2p4A;61v0qpnH@(s>dTI0UEpq0f>kU^q zL*ue-X>^B#8i0&0>%29Pf!yCo9`q^+4rW|lvZNpIlU})!sX1jwfQqkpVBmU@kfS#O_bN)Fun$(AQ)M4%m zVlYXUv8oEKbk5M+oED5Q4Vu<+M+b9n+m1H|GUOOrACGrkd^uf_oO;P099p)px`)S9>L4jW*nt-d8OU+E;-Vx~gt#4& zYVQe2cnwf_fEJ;o!A!{ZN20fM>~NelM2J?A)3;-s1qsHHEwE!>8HUZsPX+#kPB9_+OQo)jB0H^9y72b8l@PKYDTPX+ z@C#KTRnw)+xMo^52cXnGNg)JOQXuin#Kbv0y{T`Fy@sgzw|G@&@pyV>1<8#x7rpf^ z6-f`p9MHfe>?kqby>~;u-}+TichMAisi%z#ohP=bUr30>4FfxsFQvXhXgRqiJuT7Y zQ}}ZCgJsu!Kh>uO%@>am2pC_6N|ozMWRfIehrFL&;2?4DPl6)^enmQ)#>J6B#oytT zZ^kk^>F?_uf2SIk2bW)ZmFoK+dh+?|V>j0Ypni_&cx!h`E!V{&1y9HVyivcxZPkP* zcp8l{fWWQiZ2BmCvKj#r%7Jc&ZGoSL;~yh}4OuxB75zj{{gN|$QeRqit>CETzQ=f< z+nU0QgA$1|f<;GKl{}Gih&TX^?cp*(B!skkl6#HnJFevRE(cS)*_VW)iJ1i1A|YMD z;X2XLBcnR5_ac%gY```U`Cixnfn3;J{l?PS&V!0>%+D&G==+9bz8UoJI?qlJW9f2OWdhTF73Q4M^mlj1~S6C>{doVaygeA)3U~toXo1fB1xh{R!J^b~MJC z)GpK7;ejsP=&15Fl}9N3grhS{_APoA{_q`-R4D^(&}^y8&rPfe$ziN!%j>M<2_%^Asa-V`OeSDdBBw)BPbh!Z_X{#+KMrO^J7nkcF~)S&lH_od7Che{Dbm9;v&aOxUijyCUBeGH z;Kkz2v>bzo0(+Mi6;mDO=_h`WdxtKUN8GFb;pm~R0?apZ#VqDiD-EzxA_s`MwYKLO zE|qj@DBNY^HSB`4FG$b`iHIsJW

-J5+XKX=>W;d9fI91_PxewxzF&L(m|BC9VeM z=dfuqVS8S_dZi+atz@Q#<=&rXgc8G{9jAZZ%Jy;^D->sYVNh0!wN0FgNJvJYnefWJ zkrWAH*4_DZ5KH-(@3T}BI{Q%#!bO2%5eSjQ*zz4uEoe81h1E_I(y&9W*jv(;+ZFyi z6Jlh26elT4P@eMY89sq|_wN~>B1ZEGnowzs&dc?3p80=rnBR|N3rzB0+^_smGf1u) z6zKqmeXSR1qn42ShxU9alLOUROeTRWgD5YArqMlRHKu3fga#Ns+6?QERofeP;+J9J zMCF!lRY*IdFEzMc+qTtYVejFmY~K*KB}b0()TV58o}e(tiv4@XO%DWGRn^giSQZ;N zdO|(UKc?HNV}Yd^E&|F_gG=@)Pxyn{b@~5AovuFoL>c@`ojJ2K$MP-u5S0& zK)Kz9nCdy%+sVnv1Rl?ZWnXXUi`4)!y`E5l{DJ}iae&MF=#3P5qP)Ry#C$^)pl^u= zQ9`Lu?bs9AE9i#eEQFfbMi*#6{t~g-|BnOmQ=oiMV~OW~>mx}25u!36txoxZs0xw6 zM(|y++tC(l@|F^2*Apx=Ae;z#`OE7B-brAvRW?-01@hFQ?JJ>;1|?l-64_~F;6sSF zG2kKz<~w}jra%!}EzdK>1=p>VU&fE^8yD-=!Z{D;%**=Rk~79;W&*#X;$@bX%be@u z;^64Ce?u~{u!y-+0W09Qyw6`L6Cke@sa)Es0SmyW!0scgMsbSd>%_tTOAER20I3Ii{YM`wT5KR1mcEDpM4isLj4+f*XUoN<;h4I|!r15xi++X(c z>fN00Vc4sQ|+njWD zb?eTi)Q{SqlC6Lrm{?m2tE&@*lX3@NEPIo&EqgHSI^BG|nXS-&>UDpTc9R7I*TA$`g9=)h7A?mBZo*dZ=1;DEAxh3eo)jc8S&gS5CU`!EX4E|5Ga_h^7g# zkm7^ht%7O~`e(87pFa`Wg4i_Y)$3MccyRrlB3jt*lhm_ zEQS2>L(Ayd3DB96KYRYXH(NB?W-G;6Z#-A>63j&Z5gGY^xOxk)s=BQWbRzIo_wsy)?>lT*Yt1>w z9OE7Dc*k5b4qk+Q*cy5+EO3?MgV*l|E^$?RJ56~ETTn|97q}nTef;>*VByE7^69si zK79Om-lqYT*6Tk%|AJk&@+w!|@twzyA0yW!bRLIy+|Ra9=YFuKs@e=FJA9FwsQ|4WGx) zo>9`dZ%O7`z80dLbXlSmfj_%&=@PX~63n^tj4wrj>#n(J=_FnxJ^b3o=;)wTULbV} zI-eBG%qAB(mKY;6cUsUri|}Am*ysi5TVsD{6Avtih|A;546t zJ%pL|A>w}d<7)o8o;&*CpNT4sfm)viY$6fwp&|9KF&xQyZR;9eInD~Hom#LQyK2~s zdSfLeCDU*4=!k2qq1ta?(r31{g;Rmq7~U@2eOMJ_+6~@oPMRx=qs-yC(HXzQUu>&nc@~`OD z<>Pm1tY6S%F$j1Vg51OZ0`LorzM6%GPzk9LwL3uweA(eeAYF)H@~Rjyu>kh`QhV}*h^(s8*W_xT=mg>3h{taO|+5C#5nY6 z3L##n$Lu0b3j!}%G?NYIJ)VY>mN2sPQWA*9DY;Jvew>fIyTgp*#Ct=Q1pc)>ehV3S z=F-L>qN{`~IEWy7nM_m=7#L;PU$h z#r7EabS$3?NcS8D1_ucakwE%5Ma^&Vmfp>0DRbp0DUv^=*>-@rB2(Dr6}8Bc!?_P5 zuUKz;ncTn37J-;wCjTTODUP_0dWe!O-#p6*k5F&unbQJB!pTfiE`VFsb^O9@aa*5+ zkID7ttKO)2lSw>QZto4?Gu3=6x-9$o>~qWy!MCuff|*{F-KL-3$#Gqd2q|%jOV;w|`L3 zcKO7Njlu5fprQ1kZDdHZm*vC@n( z+;c;AdFJXrXGjo*!fhnR8Ev^jYP<5T8EY)z6L~0D1EcVe(D@oFu`i+GKm7?#D@JFm ze)wPL4I?>^#ao>EVwvC|NFl9pgt=CD%j?&l{eB*29j2}NpAPwFtegCgPVjwqfTzo zSKMyLKHM|ix_0)T&7y0X_lPa^L!sx1tE#H1^SBlFHJe}ehB3P_!@5qiJFeZ5mlqZm zFsnKF$FA~%|J-32LI(7hw`jO*OJ(%WAQ^;e5@PuQ>a?-qWsDrNKB89|gWKf{?)4h* zafmASog=Q14)G&j`uF7H7tAibmS!6*&dygOo3-)FnWCy0 z#~t&`$LpiT2HeK1P%hT($qaia*OtJLWoUKOpPkPF3xPDybKOOqeO zf3<&%(tQ3pl~zOk@n2A~=nve&;$=x3+qN^}c`$oVu|Y;2W%E+SZ~4T@QTU;_alv>| zy2fG*4Pt1%e4(*dl%5_zRH?SoFM4q?SN+U*^!wPlW{GL|Fdz2r?H+Rri$b%0)_lvn z%GFzS^iIhhR^#O)4h{~U;+$Yr+(pzU(WXo>kFwx=;Igh?TlR|W`md?Ttl|?m56~1L ziuJlnFAfW3=DCDQ@%v}Lnk?(v&X|6Y`Ft{x*2B2@pV=e8BQ<3Ae}oHg=B&o_s#v83 zIh|%q2q;l)trRXtCB^wVStY!m(ibCylCh?K?k{hIPCP3=Wgi!?IG=7J#R%j{yfd}& z%ZD>jf|MBO515@+S+YmhP=FSKA}^LZQ=&WPj!q0+6T`GY8mYGlC;jc4ABa&YcpMJ@w0sJ-ocFZ^d<<^j5&H*HHiIusrA$mg8Ni(DK4 z2a(4ZYUA{|)nb+7;p>0nK7Us7$=*9$_I1hqN%tkHyZgS~yAr8eZ+q;+L^+>nMbJiQ zyq#dk_9*iQIBtVpqDH1a{6(yUled3+T(|hy_}U(eTvWT=IDDV3*`M4lKPm1Oi(Du_ z{R@E4`P$v*^Dnis8aSCTo&J4NnB?}*XBPM!_$+LMD&~=S9{BRiNECfQp81B z|5B>0oyr>Et>!Z(dkwCYnv2*U2n1hyQB)7sj@|%?5@<>dbv<#~hTnRF58{mudr&s$)d52>)O>4NfFlC{L!ZR zc=tL@ra7f*(s?W&SL>%?&D>0<`)qT`R8l=PAQ+g+7run(e8u^qrkz!mk`J5h*XThW zF!SBTN3N2_tQT0-?pAR=x>oTz;o#N9h6HUYkxwXgaVKV~(aNnKt)xlx6oFH|Df|D5 z+y3tfk)Us?rmAYNIa#AO7VoxEQABf8z1_84S(BWM`t<1&c=X5xjL$A&4HKNhYmRnP z`L&1HZR<&1r-Ja;{-&BBlWGqsODSM{O@8BvLWuV>t`n2_eDaX{>cKeO?nU%!KJl*x zvTAh&6W>4vE2D?7q!&;t$q$FT0dWx!W%-9Zwc@$3U+O1LkGU68O{_Gd{2tnZga!*5e#b-kGtHT5Ms`{PbQKH~ z&kC{edXEfUjjxK88?k<;x2zvN%0ZwyO|F&XgE;HCV2N(bQk_-ITMPXIEV2+<&y``D zwEj%)+r0Q;x-o1ORL`vi(R|fA{Q;R~E6wk*?_oBc5(EOU9~=(=S(w#nbAG9Hfy#mz}_y1+}rw^2^x~TMZGodc9?sE|Qfke{r7?|3}=`uQ#iS z2T7HDSA!lUqI+g(nn!j(^T6ge#G-t$zO=v3=B)9RCN7V@TLf$km_UTHFW7xVTRW*A zqWhIVKz%s0=)Ggo{`OMRll!37Nj#gaPd>V<^HnC!_U!GecyS@Zx7?WUbCC)@V@oe* z(|@mw*p^`FQ>di?f_X`>enV(Oo1soNqjhx5c-nf3+-UcEpX9!oz#UUHfI;u^D3%Of zDPK!GZ9ftknXG&XGEV<6!{}gr)Unk+(|Gz1_GpP8Z}|+bcXV_-Qc#Fm7%?+5^A8J? zdHB$`jZgdgtA@U>axVo>4G4Bdf5q@T_->?_BsKw32!K8>g#S4}mp_dnItS5DuJiov ziTuoGVRQ8KV!5H+ov7fDHkpG@m>YHHrf9PzWunVFa_sF5(N&$T(`;Uo^C~Y16SQzX z;fv9-iH-(;S75sp_py{gp4dC5>oL|e-PTFeRVyjIx3nf9{#%{r-tZn>kI#;>hx{_* zRIhg=R9kN<6omaEVvg$SSLrlA5QJ#?hC#W+Z)nk|bLP-<%v|-HRbpi5ZMKZ*nf<-# zH7s)b(BM)4IW(Zs&Ep<|c7| zBVuSxUFuO9g=07Eo2R7*{=;nwpd_-6n!o>z^n(Ha^l!zWYR<_+fFFp0j*R{)VR<_< z3&oGBOufK=od7S3sNtV zg`Avq4P~mf`+sNnk@~4CN=^ zOFuyVW-%rb$_0Wo^xu1t20htm{UGV*KyM}<77#$ZXPre7b9k=Bkhx4qsTTLi$%kRt1 ze;RdYvaMP!>CE%qIY=`q+|B17a_jc*4$M|_-!Z>wjFX|Kn z#NRe_F!u$uwK8=XOX%k8OW~S-!l#7dMPPA5=Jr{|pqXk+B8l$`rIN|9$6N!|IC{}> zz)iN+7DUMGKZB5pDyTNMMvidkBCQatVk*lC_>$0>{;S%hat8(6#TPPj;rsYcpKeUO z8xum9Zv0TI=*&$t0EAfKLoZRlzS6B)JTNAUE`^6Mg|T=sk$+r*anya(RnI)WLXqI5 z)cN#ae}TD8*e%m<2CI5jm(T1~poV(X*~SP$W&pb65GK$AGKrgEcT#^juSW3r7cFm1 z$BJTRY!ceUeqW{yT5N@OchzgI5MTc zjfd{@F6H-Ueju}G8Icm6{eufS07+=%YIA#+_(GZwDL}uBjCiU(wXrLVw|ud2!y}A+ z&-2+LX3Bf|e-s~Y$9`#>GvX_NAmIj`*RgHb7+2*oV>Qq%MYLy)m$;ho=-sDnkAR-o zYG(>-cXZF9A;e=Rzf@T%LR7yoQiu(hHF^OvR%VS5q#{Qz zfZIx{TUuO9O-^P&iKa?u*LjM@#>E{SPneg^#@lyYlnC>GM9AfCivlxKO0MEDJuAII z4Klx-BTrpU{vTAMNX%_@#Itho5T?;%)#5c`M?}p4i4d3Btxqur5h<-A>7fNEMmA!i z0|1$%R-{qa>6TG!Zm@4Uon?iyij)iBK>?%(q?SwKT#bhwYB%!C)}0t{bs5(;4{)=` zMZ7I5i<*T_s4%sVD^0;MpDBHXmrQ0mPXI{8AmNA3rehTv{I0vYGY!td6M@Nb-f#=v9romySh_b!i3#`#(!Q&U z3db}3CnKslK}@A5iZ?Q(W4T3{NbRMiVdPN;PS4WX_Fq851He4YLGaz`x}0;q3n2ne z2j5x|MRue25?jjp`%`t6pfW%8 zVBkgNvkYmgw**KFSm!gQx%i*5H2HaXi_%E8_S(5$Xb|PnR64ddGiz zv|`?Bv0y}3w7EaH)+r6I*59Unyrrf@w)gQ~gLw}F&rkoHjC8}_psCooGCtC~AO$ts z634w@F6Q@?pf-HBT2go$IJCF07;1i1@tm3Gv6xbSwg;5WF(j{=Lpctf$R*)Ckb*0O)YyqHiBiFRCP!Ee;tJE8U zm2}dh5hu`)BXBLbI!kd-D^1;J-1#=^m-j{+?WPyrLhBhGET9N3(X$;Y@RvWxn<;NV z<7&RO*xNem8x1r4tu`TA_pClgzKJu=*uUtV12pbrAS-y2Hz54hVqt*P8IthSZ{oFL zAgpC;4X3s($)mL@JCahyzTL{=I}@+OlaaUWqsD0$z=mw{%u7B>)S(6a6bt#anCg!}AkUD>XO++7QgGiZY9 zE@Gb0$r=vD`;#`e+9t*9Z{K{MOoT8OQ@hMqjg&}OvOQh9(?G-DXjC)=2^T;&0BQB> zj&7Gfs%D*+iggGSECVd>Y-%aSN0%$ev~}lp>s!C5c>^oQpOovumGMY>0Z7XS5;1v~ zc+KFp51;_fs@uJvF}B{?>Qf3K3h9mjA8OChI_5@tH9qo+Pw)>2ifoy{z74 z)FcCibu*k5_+Lc&4Q(1U6P$qL1bN!V`c1x7vTX_79KW_RJXoCcr;WZ&WZB;B6YA=j zV}PP1*HOO{G+mxGk0v6WbX|{wu9c_If9uSz|7QIP+N93lhpa^C?duVN+c%kUhLeEu z{g?dfzV3bKe0H)gYUPEQ@vFhTKs3}uBp%F`g|Z9m44qHieyX z-EZn?-@XwDB`8GA3DXc>3z06b{*p3QVb9hYLe18R_M!ChRRbSY%#~Q7$`3SF_v0ssKj1w6MeD(9txXUs_Ut8Vfy%5AI2!0)J}L6b==8WntevlP zV43pJ!el?od)+q7>(*)^$YScTFUcHyrAJBtZ9IgjbVl??=bvD!VgzXsy2O1c>?owm zifxDLOrtBUUQm#=v@Dg<)=^ZM@h7m<=PR}6*<>unkiMIX&v8L#_cF`;@f)Sdp3p-+ zyog5m0?K=m^d%2#SL`Ya=1j3G<2jjqsX_RtD(`(LOEa~sZ(+j!ohHvm;oE)X@{0j8 z(!GQ7Hw8)^9gQ^1uwUVFL^OuP4@dRdCy~t@a1r{u%A@;(JYuh?Jw|QG9FUbiNk>gf zh|n`;IoC-l+nhlEm9KiBA|w9IhYu%jFT8yDvcvT_IQVk@7!eIIKLf8SuIq%diptAN zr#P;+j#=5*=Gw!V=*DOSYz#C(d`i;01+A7;QzG0%(E1tFpbvmex-Q%$^d-n#mF?DhJz)+q8S}BHI{j}yUbq6> zDILYdOjS`zZxzNT*c?b|m~3kyW#@Y9%Ap7jcRhks`0=E9*0H!_lvg)iOYQ-)GTwg3G2aTkNV zUiamT)DXNj>}lP+=Y#@X)7ZhKq2W;IQ&a#A;Ew5~zBEw{dQFecyCVC)v5vQ^Nd5gK zu~9!MDc5-<_#jCJFIp@kZ6x*4E8F(R6G(d=ehyFna7r5fH-O_#!%cIlJP`jIwBX@j zT)pmT(RQhLC52N4OtE)7RH)|gu3-W_0Q)4yLF63xmEN-WVo)~1{vH6NYbjCfpStR5k>$y5>>5YAI;&cm zrs!?B&)xX1Qn4RM%^F*_5>Y;aVA4yk(etQs zH&1e_r09zY()X_FGQ)C-K%w!UIm3{+Ze4sfUHO0=nK=0Rw@y8vu-~6_BLctQl9A*Y z`2IaED$&OSNBj%*X3b_`Ab$19-k39JmZ4bN8b%-15=3G2yXa+mM+fB&`o_+{(2(nd zRq^lS;kB3RKE0;zS_~!Sz9LH1DCk6Ge7a@U z>)lXSBYM_?t3SMe3gL~AFW>Oua|O!M(et_gj`e`*t)}bs zca|dsSo{;OuguQQ7J&K=c}8de@EcnfBTK%0;eL`AN}-hGX!FbIo?B5!=RzZt=Fw2I ze!jEZE3lSZyfqudm71Q;%8-8rC!?}bD1Xe7Z|uX4QS#j7fo_Ql?}rrv^8Xc2NC>PA zw^M8bW8X(Y3pjMi$@dxUf4n#2w6=Fpfi&hf1nm1G^$O%`AWnEwJDv$$w{yqoXU^5fHOC1vGvD35dYZre*l^ww&=isE}KSWRQ!Et}v$ zZ6Q1xt@M2bVS%7=SNuwuSood6;bFH4v5#2wU@&xLct#8s+|`bcFQGhFzD6TTwcla( z%RMQcXOp9&fgnEY^mNA;1Ls0_*0p~gR{sEdliz*GE-+3?+;0BHP=5Z0EPkmsy(25F zg~k+A!V@-gZMo>FDB+pqsM?sOgVPmizi zHP;#OIjW~X8^lWT;)haNIhIXZVsHie9FY$W#0EZ?^;#ypILgCUqEtwF#Q zJ`Uki%4cEuY7Z~PO4VW%xoH)y)za%g>acU(-@o(SC9*v)>E?$SuGauxW(qGWv`D?) zbVTsCmCR6WCcyuZNR-aga*w0EnIE_FrPS5Q^_*vL?(*|Dtve>+7l~4uy4`8td%>`= zGUiscKB4!sF0y*PZr?~@%JZ)^Vl#sp`XMDHcdJ3hxV-vzMuXk=D%9#7s-$`ErV(M& znk0MT-bc*ke>Y(y+kE(qatDDoWkG6~6F5Y0IO_$(bniZOy_f$n<$vGr9%nMkhnL@H z&oK8FrA0Pl>UC&?z;{5FYj4B|6np&Bb`@P0{)lEdkxiavAMIJC^_mjX(}zJ512Zct zJGt}2qZg8Nc|EP* zoqKU|0^?0NZS@4887|34~7S^YBU|p>ccd?xgMnVScgg&)v3qY2PeUsVS6S?!`{byNe}q89*WtB{Hj^*xG2#ZfiK(98gh%x0+K&Sd@_9)6bV)xBaT9 zgVje_h7=-cq2u~!;27Rqu|;b)0X(g>?9#-O>-|4Hx0RniZK{I-z}I^A4dng70}`n6 zi{mh<=&xKJHxpe~vjVSAh4>Vac&*e|oSh!EK{%#wqjP)ps&r7@N8g>O#gJzY#Ihq6 z`8Bh*^$#Auc5-S9rsSPHT+0umwyx&UgGMO-W#P-!=%cEoL^s1Q(LH}I_nAw!uy`$* zN@=Tq6WhB#Tz`;lMW2hZDP^#fI&&Cmf*-8Xp{%}lTaK687Ov%0EqW%xUvsMG>rJdJ zwHWrEg_UM~x~;MIyR=G^z15$DY4s@ys>j@Y>RS2z=W3}Z{FFtq!Bm5qbz}7szqEFY zFFOX;q@^)Qhm5{{+I{gd-ISm~!i%Y!ewQgp)1;qqUol{CpF*MjE*{~2h$hLYWHfw| zI((U0j8Qt|)?SrzS9vy(W0of>PS!06mqQ>vBR&sfYGo%?RklUiC~7eOWld zHM<&gGDUTx7fof>FjuEZaeABePijffUTj(!F*(mra%_pQ&N+5jkfp3*~4I=$-M^qlfIEF+O4XA{~xn%u8-J_F@@O}hHFmpK1yR-3)x zp4 z#q$GVm-#&h$HZ;?m zk8p4Rwi6xwC5_zB4WVOf&MI@1DfWgFvYB4xeoVDD(x9ikU%az8nisRzQ|*lLZ9&h= zbs7$i*0G!KhjRF}Sy@ksggWo57aqMk#cszg-Ee_FW)Q@hX6@xYKhBFes@<>Qs{Q*Z zzuC5pcG!Bj+qkfUHLkf$Y_AYA(k4a@9Z@>&OTtqD$WTFWS0PCpGsNfmdUvn|_cm&L z%H=Spm<}8a?e^lYoN^Ctu`1)^aX5K?&yR=$s9Z4m~tD zz~%t9#F0BQQz7dGO@y}S7K%2IT@x?G+baaqiH_cSYH9d0hDWVTW6dV+>sPsG^@&OS zgxwwpC|*mZ&Hwde850DGJ^p!Krh4w{t!?}l&h~betG}XGZqr|z&pvIuhb$<6(_;jqkR#IrIWt_@?D?TW`DHKgL||+SO3INcWZw+ zEi6?0c!tOpbZRZv{b-aoi*SEMX+b5f zPi{Vl>T{nJr>}~ITzj#;S?mVT%r1XsAzDALvW7&QAB9S;VWBnT4wFy&ygeF-iKeE@ zaiT;?kfv84)&u9h6V~ez6!ncO8rNRi7unYO)n@jg3`X$;;^D=QoeP*AKe4Njcvz3S zZ~sD{?$^~#vJC#(nrWK*$=e-llH|eHCAbuSjmJ=`MvjpU1ji0_M@SeQroy#5els9A za+q^-v)htkX~a0r(k>rDFT>{-S2kI*%#FtdYGwQT zwM9Ksg5Sris>Xq_LOo(M!!tk=QvIS;tc@5eJUhwMotxH$V=j-Qy$%-a1QjX_jeqJF z-72#`Cn0>p6bm^Vx#zF418T!OzM{Qtkt+nO&v*Vxwoj_9*i96w-4A8s<93X0OVb?4 ztcU>D*77o1mwaL(WNhNy4szRUtZDI+6-C?S6u(8sQ{+F@%J|LwOY15R-SnTC4t2vT z%uV%WGjceTpD?X#aJD6p=eDn7#=>Yx#)5y_kd*v-Zy9j|^(Pi9nWKCPfj0%=%8^be zPs@W<%}R62S3Dvf#jMCQGKhBc;j$eIbBkpR-35e@J(lEoxT4d22CJzGR`0Rfr>}d7 zf;0GG5cz`RDKwQZ1iU)!P|*@Y9lx`Ekk3a|BeO@7N*~>!}%NNArjLUV^NJQ zVQe(USu-0@OJ4ETt$Uu*3j7_`!aEWxu;-n+`c<|jNTJ7qth)8ZM4~A`y)nS zI^9V_FbCAoNtsuvmGci^%Ot4AM4{Mv{m8%c8bReN}e~aj(G}Yla)_cFGPM$;@7wWGM!rbH`VZ_ zH?Y=+*|+bJcVVNvcaW=>LWfyPPs)SaR{Dj853MAJKJ%Ki0u)iQJ%XRkd2G7rb1ro? z`oZ4L9?MWnN*t^3+K!t-CfX9Ny8Gd^)%ewWAul|;XuXf{QEV)CiT=-t(B52pCRByX z*K=2MPN_7ptsGv>_k|60`EG8?1HabVqYZ6`BA`e`qVCR-^)*fYV*tcKzd*P`Ej#-P0lrs$ca>GtvgqrPC5_xM0o_?_S zPZ!Z4N6Yfnqw1DV6g-`83F}cGi1tgqRXzs##?&z{5!O?FiPYgim0<4+!^5KZqO!5KP}udqit2TI z7CwXf$XbS(E4itXt~wzGwflEEvwbVX5w1Yn}(phu|qDMr5gb7^R3sK8>3QT7He zwBP^iK8j2_{<69U4JdpKaSEliSIH`jmv)1v?U6@J z>3b8QaI@Ia9~FlrIj)+!{q~+mV^evR9#bCsA?x4AIQ#7vXTC%#WLKUbhyx_?H;cDx zFtb6n{ZIG@Rbj3qYM2R7acQiIIYX~oru0q>*tIIsS3UPn&7SKx?iW`$p*C*3?7N2C!3%jLa;~6osV2=b64V`zK56JtB3&b_OR@acdO9AvgKGN+ z0~unUIx7A;ZZ+Vw2~VO!1ILE*bg3zHUn?0e9WC#&qv2%q>*0{r z6Qdf)iA*`q)k`!9FML!nJjS5O%Ictv1>Fs>^mF`Lj{b>x^}%8s{B(iCIzUB1kR{T7 z;hXBM7HEZd=8&`rpas3tuQ=?U2c?rcwQ$Uh#>7%?aaW*nmg+VV0{4Crg@3#Yrcx0CH5$?g2;A z3f&wuV2rXJp@TUZZSeneN{=>|d(-CNkrh3_>3dhRgz(40q7oguDAmY~Na$l35M07a zcHGE7%={adE_fxHTeA5>6}=)$>QBbbp?X%qoYHL;Kby1;X^D3qe zhCf%*uaHyO4IfQd6Ib*G(+J+_0xyz%Bm(V3=oLjTp-Pp@*Fe(Ul9iE2MI?S~GkC%Y z&1lyI?Ox2z0Wi26b-$6ko;9LF&P2nh`n$VBP3MRN#1`GV|1Z1ZM8!Y2?l53E4Y5%f zj4HMfK@8echw6hKQC#|Tesr#;<93}K0ihn-zxdmp`_Ym^Z+&Lv6bM>rn%)!0z5XM; zweNMdUkIuajR}+0fh?YvKR#-HfA!lttm^ejpTI`>+^mWC(X+vm$?e4b<|VQH3M_gG z#AQS{q4;EHe~&Y4+(1PiHlQjp zW61R}&1_;y4oQFjTV=!#dj(d$M9zkJ9UBdLBmryu4+*!?*vr>73`Z&m-9%hQ^F98z z%2`*3b?l#9rWGn#_2i#)HjU6>S$Fme_VS=wl z3d$E_EmBo)ea!|-Gw5NCcjlLUqNn#v>%i%+YsVLC8(arug~8v%-A^H=y||<$L~U6* zLbdQ4YozfPIFiaxR|*MFI**-R=RbvQhF$T3NLry;YOV$ka`!vT?g&h)VcCS^TG{Po zgYv&WZXf+2)Vgui5V}AdGX16ZeCUrE;9v{2d*j-i(MHG=gUf@6EIRvu{_yE5_)9pP zr5)%^7liaf=+3r3zl-r+cRAIp>7q|Iy~K0Mo>Ek8*191_kf6)Fj>^>bEDrRy+te)p1$)gbva_ zW+dm*8{a&IQyyN@xXg#!0@dFJc>2x-vb~{+30m+@HJ*Amod3L;ln$k#ESvIl`vc$5 zAX?g~I)ef$4Px-C+m?s}gK*jgbu$(EG^KdJNNC`qTMw3!rZ#KkqSylv!odn!NCuXK zp(AIGH|aorbr{(m>4uHA{vsM#={5IW;7wm{UCFH_l*qBqhtE*S5ut|HBTA(Du&$v{ zni)=OxUqdcL}J(QXlx{CZ0fOW2h}uMQXdAT>TvEKne?VUv|TS9ZiRMcI%JlQkC(*r z$J}mQ#a}yu z305Qlnqs&u>&Ns{DKa{mx&YfIYvAY{&pW*To8%V5qBqI!*HAiZYxeHKA-l2wr1s8x zYuDGE9o4n@iS4A6!+a0pxw*YJJ31=fxChNv&hB9AVNfD!fnct+S%#yw4vo$K(k`&T zs7^FY>Q;=Pz46BNIadMXxsZ*^sT(2#YXI4HkbSo(|F#iK(0mqg2kS&@v ziN1B6<3TooYG3aktZ6E|I;ubav+jmD8u_6}T&_ijSWB6hEa5gx`CogAH|@W?8w*~8 zYx3-Lziqhgba#1UgKl77b&bovB$}ga{Eii%ehfOyiw1OP-SaW|^fUkSg5KtBc+QZfnv<0ZuWp8| z(Nc>!SepPMFH94U^<=fk6#l>;xKoIr{bI9I?RLTlqzcNkMvxeW{0nBl@wKsuA9MuY zekBhyq(4IY(77(B2mtG1G*a+9AdCl`ivSWW5nd1Yofz)t_X$4%__#}_GBE$Lp=fZI zGbQ>UgYA!J(cwzj!{1J2W zFyK$!+^F!qwQj*TS!W_M?cfCw#f#qUPoa#C+j^-jc$}9?Li0fVkl40Tn*7Vjx<$6- z$Dei18G`MhWThlk9mgzr5CjIysp0AI0YVHR47DLsAQO4qKY%0)A!N47i2V(B z2Hru?v=mu2g28oHpdx}T@+w$8F-`QX;7Dj;`zeZ?V&>40!Zbs&Vs!9#frJFP)HPAp z*MA`1@j#+80*`70CCse1O)%V$^wDdN^{JMJg|r@3=!8Z`=Vd!l)?7VWMa7p`@}YWy z#*j=#!tDkNG&1Sn8AKvUOf1UgO6BR{+ML_e(Il?qM2O`vYO?ic=g(dhdM~63s}4T1 z9Z-^KVTsluHHo*CHr~YkThy;0+@c`7uDW?AwyWTI(=13LgPFoaiYC9p9WGbS|GpGC z@WT3cc9*lgrO~(L#E1J+{{BT4xZdPT*QMcCP`6~MP#bgxsPYenQN?sx?A;JkeI6rh zwf1-R+MTal-_G3h8zvLQxyXYGx4VSf)U_?i=2}C7AQUk{&65IpL8Wqas~k@(_&jyH zt?Gf#hT7*WxJyHJopSCjK%MSW%y6fA2Dwp>C$&E8uN|W21{bVbF-i~8RN0$vcTVOy z$=2))p71k1F{ML|#2o!+dLC6yuSy7`_&d+#x(xkhPXc)Sg#|VKg0pft6**TY?dc6w zf-}S|*$zE3X@NwH5+cF6Lp+?;(F_f(lqwktA&3PJ<>^+5{n5^%wt>}vF>pn(KO?2k zcekyzz6uX!K+HmjT2jHaoGt6-2=3hQj6gFhX(? z*2!7*%A?0AA+cd5HX32^y(N4s}lw0{uz+s-tHtRg_rvta1U5=LS@)ZUzu zCcNF=dvjIHM*vWHhO}X+btBnh4?F(FqkPM1ZtBZYPELYdbqgIBwDnnaL-&-<7;Uk> z4k`RE0u!Sz_-ZKz^ZiG|j9~t^NA5opACtA7UA}ZqVtrf@xz6Z=KGYV>H(SD7F2#TN zuEI$iZX1L!Kq`?W=wUy3xAzWhA=DIbq<|9=wgTQ(SbMB#&%v=7VMumb1+=eTo1W9L zgCx|1Xy7D*m+rGylKde-&Yh%#n@CJ7qkbBcFYepB`FdHD4jMnmvD&;b#CKlj)(UuJ z>>0iP_zQp}+EjViHX+4nE}VITIZSsl1BCSc20@-s7s3^tjf1uamVAXj)gH z_d@7+PzH0K!g*U2!-7LAl;=(ly1nSyXq|L`!eZSOM8-%Z+2@}Y@FK$1tRow9=6TX4 zA13%kHMp1Qz3N295XxG{muw~OoEs1U$&$eBJgoI|Pr!dmTs~UBIJVvcjQoF=k5D`daXdP7H=&$TW zdn8H^JZY45vL9e}K+@vuQr*vV_Q%F?d(&?PFfp(}9VHn}{rY8BfGbw7feC4~HK+)Cq^E0mz)Kb>E zhgG^k*s_)<@TZ{35M0;iA$SB7x8{Ff?49Bzj*jCP>j`($x+7+f~_A%}2@qvkJ_B>jsy)FZtd-?iW8%;anOAuRB*(cVdaaqLcUD zn{{WW0)Y69IwJnizc>#UYuA>3qL7jr9bNnRfM=@c*%{V!Al4+-ts%^zgNQrU|3R4a zO_a{unga^=9|;oIJQpTjds^p)Yby-XYkj(CZ6~}5xM>c$l0&;aHtg51>qNV!c+Vdr zJS-Fvt^o@C`3*5OZxQBARJ zAxGsoB<2)OLP~U(4AvJxY_GQV9U8_&_s4mqgRh0JRRpydx^KEo1py58(muPSqknzc z-ycDnr$?Lg`PF|P=iNgL>_yfGZVx3sxhMBsL^28o7Z03J3YCl=EO`LQ;44{|>`K=| zM}AE(Cl^PQ)i*_a6w37q%8C>YVNgyYN=0%=`VuOnOo$mOt1Ug<{B*w_feP}mcW;8b z@d$ z)fO^(m$lZi*mHmF-)_xD@2*uC1IJuTj}Q+}W&3cntKbEZIyvMB>%g6P-aD=t5|rOd z-EF}ub)7Op5T#1sdih?3;yiMap+mqelHmJb44niG51Ws0nxof731apThpfpeh3=xEdcSqudpD=WK z@g^Pie7F5WcLle^I_2r3>TGw#XAUUxSiI!HieY3zVTcD&8{~1pAA52BYnxz$lS|zi zc{+mapNA5a06h&ARC%ME1N(XJ(TaqBRF2;}0&i;YfZrn1$h#3rP-s;bgqp@vd=7lRR@6V zVh-Pc>VqjVr1Lna5L$hsbh2Nr#jC|CiBvsW8#m;R}O=&TVKgX2Vn`4{vwf0AY zg-}&MqT6o#OB+=qO0aD-n!qLXPb5qgYOh6}LwQfW1}lctXyMSnQW3h0;a#1-dk}6C zIflqEh~vAz|BnRkXii-!Bt3_MNE)XDGElf!T$VSUEQ^PNQJ=!x?7Nyt61G3Pp#tt@ zWvzTh(qHh;qz6W@${Q`fDZuRfhsc4QYkx1nh1FOk)4^(B_6NcOqiiBapd!PMIjU5s zLU^}?TcbUbZkx2ACD4FUE-SJs8o8PzGBmbQ$T3O(T@|hX?D~U`l9%L0vC7~7wBnMb zzqOJTwPm9ST#eTMy5Ywii`rVS9u_s=m#?WJwH3%=wa=zRg|WIn^Rhv1s1p|9>H}vMu5ZN;f7Mr$i^F}9g$QL5jp8KhC&JeF zgNomRH_E#HPf99FVL@wya{ll>+B|{sm%aI52_&-L^3otEb3?YDTW)!{vtkSBIicab zPwU|1Z2`SPwKH<=YqXx$RF=Rj7f~zue~bX?IRaq#NFMI+&lgF60~wx3cy-2(T~E-9 zHPTOkDiPQhf~NyWD74ux*n`?)Aduy7F|r)r&+tX>yj|%1JxB{_vg0-WJC1Hgi#%2X z=_j?5BmW_e$C+InQIjKZbjA=j7Pv+vyMQ1VjF_I`#&`wUgL)8`g#h0%XAAt^a0MWC zl=lnB6;=Nd*8fhZiXygdA*`qR$BO?Kk66)q<8@pV$LO|L(*L&1DW8s+F#Oa0Lvp&+ z6-rM%I)S^K-fw=xk{dyB9h7aDx(uu#91E|5PJO=dACJZ?%XGocm>kD#+jdi?9EJvg zpGYk(=7pn__6R(|+oQNg@GtgLNb@|p<$@AuBCP+q)0X|!?f`%K!{}S`1`rcj_mL*-r5! zT8pa6qj4*9G8C#0!USU^n_^!1dUj48Rr6!q4GwD;IVgLG7J`sLl>qA>yinF1#k0^5UsJ)*%u!_mir1qD_g z&uhxoX}0}t{9hzd2idiwO`ST`?yaSq5;_*;w3K_go3v0`>;X{20-`2zd;nqh6mYGJ zUp=%u_72E%ZeB8vgL>ChtiyBW1zZ7B@Ynm=ns&jMsBp6Wi_2C|4>Jzj_UPQ<|MeV& zruz%+=LT1%?Mkk6Ffedgk2U22gggYu*D>PV@Ov7upJ(?4wk%#={tKW|Cr5d?oe*8~ zDQC`ijt&pfZ*Als5stlEXWo+%<8jGC2}eGg!XE%S4E1h*y|nnxdr3-zVm;1L zhhaq7WkUZV>;FOV7pl^*n72sb{A01;W2 ziF*k8*|+n&XF6A&zto|pf0L#{OVu;4qqf{ssL?H4IMlJ?H`GTrbK;@Y}^*Mus( zzRR3+gzzSK0SJ0pJ3=`JRfbAFfK~*RJ4&=NPAF@-*lhInZ>pCsBbTrfp1S^+KAx_2 zL|o0%Eb13zt?Td9PrTS(_O_oG(WQLtth-PrI3s34NARL<{q>57(8u}_&A6shKkL>n zYm*JcCAU>1q&c72TJY5$^mwo^=A}HbS)*G7ZFyp z!%ebZR-Se%#M5WYM0)9IY{ORh5l*-2q@?u}wdP}*TdR|~;|uE-rZKguOO!!UWCJbY zq=Ysd7d*gYmgH7$ZhcNP;CP9Br{ZCH9ZHYBKvBu*)72S86@?-xxJ|4}4b0wZ%QY)| z>%M@Mk;#zVSu=qg9A4q4LZiUgcpM-Y?ZeR0<$>zOeK|C_qpvEcn12b=n?wP+PWt^B zG*+-O_U#>_8oBhVuR*U~J;Gr7h35STeoU{$Bf1x;~hCg~Z;UR7PIYrDKqa$#d zkz=BNpsWF>ik@Qlm&3$18XV=?PuhBTFm+M%_Fz*XLK~EqKAwf6uw$`%F+1D8B7Hgz zU|kJdcHV1NQS2irqJ#5qbccFzLspKNPn;vh{`@P3z3@G1#UqFv^uA?)O0EBXbd`=^ zc)6VQ3Ko(%15a#RwtNF!f?1-KD7WCsi`y`udgpdh#J#_Jb`h#o-+b*>@l{MZbhF`7 z)PBsQb`yar(N|+blgD|_?!~a@I|Fd@ti{2HRmyLkMElY}#moBObTv0K%%7ZpK?kgy zPTev%{t#%gyxgr*4d!#N=-0^9cXz zSvt=TNaZoZy;#os-%)PDcpfCY zZoKnTgFS*+vjJC4FKjB1_}2BreX@sGmES+q@DQ3AKPNug5$#U{uD&3J@XEkj5jWSP zLUCZ;utSs=i6NXN`lH+G!1v*rAf|756f;mej)xaeA~@>xg|AS=z13>wZ(=|JQ%ke6>re zziv1e&N_4$GbI60Pq&jcEq61ZZYTV`Bu+k&LJMp*AgQdc=yi5=GJJXvDl~yS_IU>Vq)j=0pK4xcY3vI_pg4NUfvo! zm0AIIl4j#!bm|Fq!<<%A?&{%`boY&)6HKj#v4)Q%<`=|?2o-VNkZxmGuudzg!Wf7U zm$FSlIn)O+5tLHyXIxv!kz-2P?nls-MVDbhYaW_ugtgmYUyjb4F_XM8-r90_kWKO9 zcWq|OpNJ0yT7+!5!|0`h0=Vg2z8>=%C+&JHG9I@kz53P9;W92Y$FV)nVUvb0yRCpb zc}BBheYdH7dzALgQKa~KpOUbs$C?KJS>MBSgaz&Y@U*8;Q>Hn+-chMlAI5X+d&%kT zmCB)#tv@9bYB&a~&2)ah#GCr_fuD`9Uhy<%U^`+8whg?kH9i~R#yBCx z@f$?Ng@%R(xUm}tuU-ZruOvZb{J_F8H?R~$-6~4Kjm)0FC4ygrQC9@yA;(lWt4|mH zCL@96y5rS8JGW&!p!&D6Y|zeyXr6+i&i^D0G3+6<4Yd<_H3s9Wrw>rxDKy&0HSXn zx6O99DcJmHwI7vCu1x2i1FoWaqda;<8u_0oahJ|H)MlQ0$ac2xc6#flL)hcrw)mI` z3$MM)Dc`!{gGh6jXdu)ZEj2eMl!u;@vwx)7qJshhq8M^M`u5!M4gQNy0UjJ^AjN#_ z&e4B}0n@<$nW8lGL8Y{t;a>x^bqvGPnsqoH_ljU>B7 zIO8)QzRH8Cazuqx#qTBI#+j0++~^0SorHIBXfa+cy#8&`ox*H5_3b12k8dz@aTNM; z{Vylo{oy`q8KX$9iSzuk?usNH^}9?r_xHwTxvn>-vr?fs*ajws3+V3_H5U`gWZl-9 zlYaF>Xo=5C&vU*X_4D8|n9Nzjvb&|v3UxavKY=OBkSBY{2C$i)X#)Co%A~_zK0S(> z`*sDMYu~|gUs^+P4fvfWpwZ}F`s|G0A6Hk9f~~li5Fwv%8@=K%>2EKs(S#WRkOZi+ z|7;h0qay>qcV3J+?E|=4QRD1PehJk+_mvvu;=`I-^C5rk<7>?7q6F6b@bTU$)0B9M z(qm7njz^IZx)`=7&>I)6<<=s_u*LI`U?PwQ038^>sEuL9Apj{;v{4L&)iXk9(JQU0 z37iR`^{!X;T3eYXu4+ku9oFM?ZE3o8#SP*~+8B~gQYdJ!{S2N5J45oIf%40)@0MT* z`2ihNxVYg|Mk!tfT!OomHR!Zq_kKE9ullwrvWLLC9IbRHaprncm|^?OLTixSU|^MSSa@{crNss%i3&+*pKe} z0c=9XclKI6P+7D|LsKDoHFi8()42JLrbOr$gz^3#9_N&;B8?uKjb+ekh>ouh%Yahe2P+fpJB$@Src*2-b?0*HSRwiIv8RfuV@}X z2RxjmenWyqw?eNGEK@U=YLFUa59WIBO zOWWaV_d{(l+pm}?$MF{Q-9vz^;1=J(WN1Q#SWta;L>(fOKdz7#PR{__Q0^oYq){hI zehZrCO{_m{u!dra`w9NPn(3hUDJcKkA$b>pJW*=_Ysz=#fz^whAs>DC@2oBC1(SzS zQ5m$n&(g0^5J5*oE)*#TgYMl)R1SrM!A8kI#5?*!p2mddFKfX}{8f#xCUb@~Dr~I& zdjvW{j@FBp1m|LfclchJMm-pwh{lHi&IDL!nk(O^CKNBgk)l#uq0;ZT8n)y2VN}UB z*c)YH!hsc2JQX}%_Z5z~3geb%lHGYhukI}+aJ3fJnq~yA-YA8KUq(GY>DqDVl0LOJ z1$~xequG@Qwh$AnKb4fG?-X6F>Kp_3psN$a6m09dJ@kKy3Nj+xVD zj`eigcR3&-h2)yyx5C!z--)HLPwy>PEYZzi&+2ne0=fwn_m(%^6<%m~I0ZF-WvETu zOgTv8_KRH8lh!o%{T)Somc?IwBo&Qpj-fP z0We3S6tkUZ;OXx0O!(!5G(;H28Rf@uE<99@3$E?S-Ef;S0H+DvQst72kw*c%{qLC> zU|~>{4kx~yYo>bu5B&fJZ}s2c(U|;DfhR8p`br(N{|v%=@T?AGRNhaNu2Ce2T4U^o zUyJ|qsoy2qiQX#xH1Lzx*)$dpGcAtW?{x@hDZg$q>HzAR8?A+$}6u z<-ohEM1%vuY_@1|V$T{r{(GXs3_E5u`o?+&+-~{KspWeEJ!Wq*;II1?l z@zeXw*u2;~E~p>gb}f_-1`JXR>+mmUN58ImDgemSVg;w`CPkBJ6i)!4BnRc)7b^kc#Wou5$oJP!3|y{#dUt#b`f7Gzr2 zMfdfv$eNCDR^&l?fBS3tI@K>EpQ;X{-vB|pt`z=&)s^!eRq=teK)-Xv?RyfhvoB}= zRLP|1X=ARPE->^9i8tC=-)!}EfT;jz5OMY#+%Fm2@81y)HvupjTnCS%Z*JZUOVP~{ z(v~vJx|^w0F=T5fh$%byJh}zX`UQX1|FefV8Qcy0=UgEG*^5JcvE!JrVCYHR9*kd+ zY=HGfRoZbdDf^+Gfnl^PCy)Vm9D}^Fr9A4PsvQi+EE_$5CumOD3M-e*0%OiLA-}f<~-?b=)y|ku0I3J+IoS7iSd)!(qk+7RQQy8aHZ!V){C|ClSZQ0HxdItPSKkI5dsWWYKIGal$*ov*Ov z2i6q$ADW_0_VD7t`PbsP*)eaOnb6z~$W%CrEoxmwejDS}`!{(XqQ7-%gc({pRI~-e zlUr-t77*%qeW5N~7oaDV$aMVdmsVJ>1MGq*%5Zq}RNNnI|7z7ayYAP6(S{oLUjEqy z#w2!^1Ui|)ezAW(0?lv(C&O=4N`aTGHV#h;<_o7C?UB8>4GQd08f0KZ zId+5VBb*{7{JZ7RAGP#8Yz#7cggDBDRImg&X2o%==L7?>==V?j=yhQGg@;gR_&<0r z>{3j%&iv0atNl#6Z|B(x9%9iUVk!juwksZ1A&;I2r784N(V{rOE;V=aj6pMrReGvt zrKSo^V^Ka=z7y#kFZb({mt1d7E@jtizpyw*8~@#up?tSPW{kp!)no5{MA5HzkV~V1;53 zmb6^@Y0$()#6rjbOg|MtcP0ej$Hh;(SV!1)8KPTgOF)a2upL8Uz7Y2J+aUj{xSJ=6 zHVwA>>m9CMP+tU{`ws0tY+CaTLpT_s|MKNA+Vdf5Y@R)5WL^eZ1cs7U2$~=M+-LoMcFW~lY$)8SHhtm7w_Nr?aSr~sSbxf=U7d8mA&uS6eGF53 zEX;v5DG`^<unY-tLYQzxi6=VG6 z5=UV5P3GWN=Y07;h{LXTeU2(8 z@-?V)t65gptLA35FdV%p_=M#Om)2dZNvxQo30+ro)#?Cpr*YPaXHDGD;}{|B>Z^Y% zCgelp4#6l#cr~QG?YqKEO6dDu{s`RJSAq}10ip-v)I4Ay4X$Ci#E4jd-m9m5iIMn)z?TZl#}J*pVLdfH-EYQqxghmh z3EP+b>)DfQ-PV)!&q@;&m?1btdoCcxX2c(GKUkF#d-E8vPh3b#PIS)mCxR|6PLe+0 zij9S3(L%xU#@H5a!i8t#)F+6U3W3LJojV0_M1w<#vbv2T>x0Z#f!uES+JPAqXQOHt z#UaNN41W0cG9t7f$AL^X{y@nnvpJRRHmRM}Y zaKIWxtW;#%lt&Om5?KK)3p?=yhTUew9~qWYhnf7768pIm8kEDvB-MHBKCBWVK4&$mqp^MW+VUHlfRX zqSl53MWx_s?ROCmR^7IfA;AUujk$nX)js{GhFyvL`=BQu;b-l9M)`xwJ@ejN;qN)do0nJ(sJoY z+*yZyIkK3H3{Lt!RsIgHJ!*=I$DqXMth5eRRs|;ub=lH80AJZMi4raaQu)%c&3&?s|sopze54;91AeHKW zDS<7FfFfd?Ltfo1D-wAR&wD$oE@BbeTvhV&{m-tG!mtXjdlC6k^L+en()s3X3rv8p z)l3w4oH?k*4OpUqB*y=1A0-Bm{fjF-wg3(dXEpZPcBj^xgi2ok*@MW4B@_eu`zTP{ z8=q3I^QM;?Q}t&r{Wx{4z_)HsGxi8}Cl|)cCfB4l-{!&0 z4A3RKy1KeN?ah8@)Sj6weL|xBGgh*bikgy#hi9s93shxBvqa#M1moeu#s2#6+KYF& z@4>`xI5w?Xk@@0TBJcj2TFEn3x*vBbE*2V)!}U;~Kkr zKhP^B*w5<1j|j$bmiyE$@VKf72Xra&sz(RYRmye=3vYZ)%`fcFa5AHMF;i@luw1=# zF0jrH*5rj8RJFvgfI5Ge9!&w5`8N|tVChUzGj?X5rW0UyVCQNb-DF^ow63C}&lDBt z_|*?2=CJT!k$rq=au;>)>_8x>-TS1t|}D~|K8d#VprR!%AU50Qul2=L*7+#ok9 zTmMuH$;b8?Rr#NVs{q)EL_Q{$ih)K=i>fUzl+VoocoTD{ z+ymGZ$e~9I!*l`2aROzSv1maP*a35*`rV8)LuN~p#j9Am{ zijn_0$j`_Ze_H$dhYFxo)#UCl;zGo123|T08#2SjKj|fX zdL@*UkfhiC_u%))21v=|YOiTO)!fQ5XTuao`&ZDAG;y=np~2jXDMM1k$jc#Nl6T1l z2zpZJVPk315*A!Gum22i&P?92(Crlp{dAug@!n zUU;z^H*Va_QYYmHTqt6h9M0LKo@cFgOpi6Sg0y67#DDwPePTjefRi42B&)}L2=nWRkDf|g z5<`4Os^fx(t2fk$$4Aao&roB-7ef1SRrNnOuC814pdD0)qx#gKg4qV171vbD1_qkdNw>bSK*&O@O63-F1Mc}%{QEwla(D69&~ zwI9(Fxra#gamA3COY&Uc*9p8cmgGBJtd04HbLEcWmysQ0i$fGD}NIXS;2}u@PRagY?x*A!8eL z8JT#+l4fvB%yb-ClOM%+aKMs7Q5qy4pt)^*T@^EPB@)FxT32sW{JZ-znlKL#Z)?!Z zZCw?bNi%yJN~Su6n1oP=BbZz*hyZ5pvVGR8e+5PKVuunozy1=pZT`ik8%|knaFc}T zT4C3-b@x?#_QE5a-B#VrKrCv(u-t-MJ9??mm*c!v*^mhUA#GO}m+oz$zb*GT0c(?p zlQ+rVFx_Gt+@$z=dTaK@5ONyOO_y6~qXv5cruufzZyyvKiyngu`uU-UX`&OvLZZ$$ zjwD#EK4B%<>spJQVWd-!K(WW?RDVDG4ZV#+6_GdIi z(QmmVh4FY5zK=eiB&CkUeF1p6Vi%R#AtV%)qFEvg+l02FR!*>>sPO4c!^4b7?#n~P zu#!?e>)=D;z~g8|Hdx%9WQDurZ%d8(n0|{@wwT;QH-> zPBH9dh~|=HehadCm}ue%*Gu-{yDFiiB}98ouoNR+%(&t@4obq;f;;pR(Q>JgCX)L> z8Cf((Hg?AbhGDx2q*AkAB+)6DGSx=eS%M!4fa6U2ztaMr%G&aMtJ!03rzq9q)^G4eY9gph8TBNAZT;Ayiv~WZs7Da{T|&{fu`We)5)CrP{)~xS zZ&{e1hq-o=0d9m|Z><~{4e1Nb8^0m$_68A4k)=-kC}_;18-z|cFKCBMzpJUKIf2){ zYe3+ksIsV$ExDtiM5g8}7C|0G4d;cAAeRI}t-20j?BMW{R%LHqe(@v(y0SvlZ66>u z2PYDE;?x#XgAL{o)8R1S((t@aBS*0YH|m>ZPs@{~)UQ{^)t=c7Z}R5ChU@aqq7$#m zCpKToBPDQ)jRMpLbxp2TD3H}&GOwL3g(UN(2!s)Hp^eTLkXFQtla>hZLIruAKI)C-w43e;xQZKsKKhVC-565yYsSU~tTuZYLfD^OmYYdG zguSXw#GhbM+6O_LS!XddG3c`a#^HR3Hgqu=w-WKwXYM1>=L$vg5<@_(eN|_ z1KhkMBU}lU1y%rQrbewSuurN8YTHNc5;wC>uT70D)#nrei`4?U?kW+N{e-ZyJtCoi z^rCVZY{hVUmK9y}_StpAMeokxr?Z)23c=TibN7cGB@uls@DhD_MnwLYASE~AGGPWc zuv}@NplaaaI>3#gK`0BrCkz&lX58#Ab}878o>b}4z? z2%40mQANGyJ?7sJSbW>dSO$tJ1+7H(3nnr-W?fkq@ut`H$$|a_$E^~SMU0z=p(^sttc+WwGUH~98(rX*T1Te_+9MTnqqK1 zxVbSK$VXWt?^L4ZD7=OPDhS??<}#yRqe}3u^dB~x%*1odPVLcv#zKJm+&mFYpVN6| z78fNz!VXC7HO?UuKYKJp0%yuPycBA9O<~;lQ;&sS+guC!?~*K4D|17*CW8=k zG=ivxSs5ZEqk8J%pZ0WEk@~$)_>4OaK?T^!8TMiJgVq6Fgts9tg~ouvDGgn&vx=dP zDM96gM!P3h)%IwaDmj)K$DAF4f=Mh=QgJN!zL6yqHY_PI!t*0onw+Z17sUw6nu`{Y zLYBka9E59ogA@xV__!aB2KYVzS_eV5!{MZL(>2sZ%s*FlWGFt| z6bZJ5Os*okYs?N&k^Cw50Y#sWx5sLBpQir*&*m`K);PpJa-`F*&I-64r`45Zh#Il+ zo^#Z9gVWh-*>cL@@jhf^WURU-9#1~pMZU+Z*aXG{R{>Cj1Z{KeuNM;5@fBVhTNx7< zp#hq>%~ewt5!4)@@*9*^DJ z6x05m&TL4QK3$?z-Ok~@NloO<%_MknpgbbX|?BS z4y2l<-$~FK4LVpB`eKSkm144aTH8j+SAx+-@kP#Yv?Ta;mV{F1IdPuNq;tpOgTMje zAgr_Z2~PSug5$A>?twa|EdHeC;HoJxVm`>r#gm)go6U&$h+^O+xFJnYd`1nIEn~;bksP82|A&$aNp$9NWWfmN2t<+(qqXDat2=B%^B@*a;qY7OTp)N|$ki_0TrGWq%S0q6#KVG1Z3a+|`5}}CD z#KN0;y@ZXVgp$sV%yjiF(0M)tft!H9#2+F%Demm7M9w3Pg>$A#exciINxV6_u{UFq z_KTU62V>DZzaa{M&{*nv`myf!=_m80q`NHc-|^$ohdSlY;IHyr0Uylzi!Hz>RiN?p zqT=v{jJpDtbpRCL$|QF3hwBMsn$JX8Qk(eC8JMW6-)QS~+MaDP+LajB!(g*fE4~|3 zk^1L0tffjOtRq~?(k#}_YKNO~>wv9GMNklPJ2aIcd4sv485a)3u||E4NMQ%baNNXm z`~w@jHsr`SRwVN=g_%hFZ1whrGE5y}27ak!ledOnAXYNQ-0+a(S`m(%1s+eK(^X{#LAatYg>)&+|hlK=EumAw_TJbczb7tLac96#N(R?t_HSr}H zpbAMf`D;fDW$2t;}aivL;c!EYA5`U=p&1{i6)u?gVExNpHEJk>^HYPglOrfjIWFoHc_<(<5@{u%ma`sq$w{fGdDLqWU`p=`#sH@hW9YJ%%-eTVHP$ zrOt4`zbCLWtO};Ax|+uCWH%4dzcOnCF#hnmh4H&3)tn*fS!aQwSEB$E`pUTCEj7FY z`W-?+d9CiL&em8}Rfxd&5@X|^z%5H$`j>G^$tS$(3mjtvsKMbM0inE>!94V}p7AZR zfsKpLc9-tev?s>OUuSk8Se^iFj}yW;R-kSJsG*%B#KJ?M*y9IUhULKTq(h1^KD2yd z>gwt`udMejKrsR3Ltc3L8=VQ|bt_2cWCh=ktAIxjs9Q$4BW9hNZ1_p1Apn$crb%J1 z5KnYEAHKd5sA(1QO-3+V_kKEZg?i(}2f536!))$CD!|r($B*9ii3KW~jSP!nr_sq4 z{Vl+zMWeE2_*Ey{jg?9fU$EH)d7sTP1UJx|Sv;Qioch4~tZdt%c=-_j6O!sJzqkSa z4b?>X{>$$3$a$UK_069T6eu$D6=k>!$;~5kqnkU zxTXs__3-vXlB~HZE1!=NLFvsBooCqVOADOs2;e4Gy*BOTNGZd>z~1bdUajV#E99GN z_?<{_-8g+Ufy8_(=*Cvg{@bJkjeiqjN^<_w-QuWla$tDkrMqE>f;}5ump=b!YHB(; zX2P+^GKnHdg)pdL)JLjIr~U*~YeXu{D)KYYv)bEiElKWn^TusLr5~4rU4YMe(R&+2mvYQ6CMzLdlS?E2?OC zirxu8_bMd6!2^%Z-OvL2LI+Pb2X6ba25c8@3;gJQUTD%^fwy-G5(PW&(;~tM5Z_#1 z=5YOietIjQR>+EBM7{rkGS%lO&EtN>OLtPzyN_O>pgnP~(%Ump+e7?jS(i$$+d?Aq zdlu+thIb6IAo2K1mJJZNr*I;iuL!!DVkxmS4DKDN*4j~TU4@$b(0c#2D-ua$z`Nw5 z6)eY#l`dLUyRH5XpNkCNqGoAt&&l8X;H2@2#EzQ!_vz2#EoP5d@7h!=P^|U`#R0~y zT`Yr!?Biwidd}eQLa-)}-UARu&K|+{z^b@HIp?~<7kv8`jwT!ddGMD|U*rYC#T~pc zB$^&(7XRwrf#lz;-W=)+_TjT;f$JLfSA-YV^X4j&y6BbP7$dlvH<$PdCOK+^+zY|E zdStLXxCZeEC1En`dJ6^m>rIocec1MukJmg3)kwGkw1g$c0%1F zn;PoH?8Wx=h4cyv0!cNG?uz5@N?l+FX_0f5JjKg(0c>~Y529RR$dF6$Dj3uuP_FR} zcS_~8Bg|crGkT6A=g74okTC7FlQFsRBsq~4K&*%rXrc?QZ^u{tqT2O@YFKaj2)l=* z&`_hS%aYSbFcQhrq$}X?&mwcD9wG45yuIPu_%1p$}H`o&E8|l%!$A` zI`cKab%)A0r!en6RP*b49uyO#;fA7%i;H`^0b1>+S4K0r$w~K0XoTeK-`GDiG%=?4 zv=eJT-UsOZ%L*}gz4nXfR)Q9?L^!g3u>LHn5zUZo~xF zW=s6lb>0m?rfRAe=tV#|Lr_uS&}bBx8$hr2T>^rMt=Z|z26C@i(D!3SnUNB*^J?>J z`7$sFAA-R+%L93 zjJ;Ypu#G4;E2-uzQ3OdOC6Pqt`6ycSbnuabezao`2g_c_ zYlE@JS!Yjul!`{SrLS=rf8;3%27CGo{jzM;$SWKIyoPdXvwyp&x0{OfzTEI_bY{o& zl;2@TghC37f!G=pkRN|T|0bCJok?JwTI=xXc|#zW{xkr(OOaRt0#+9K0TTl&gy04( zC?qqaph!4+xr*01blAUgE#CuJA3u=uQ$uiedPrv2KM#c%e0a4cDJcoXH9EXT8BjyR zdlz0Np{E^F&phzZShy|VJb=|o;ETG3UA3??S^3}xu`_14`ClzzdiOuzRPJQ|T3gN_ z68OPOrX}RFkkoFMB?$jb9BWV4e97{BL#4#k1!e501|A_->Ggs5RyAszBt~D zx~_e$E_K9sw!*_V(V}@guwjC%IEUqa@Y5}$`1p7mb{U`>-_&!9p8iJA|F5D%149+Ka2Rb|>dPryS8121Q z+>wYBnQ6w|Sb&QKj_6c{r0IRjEHXeC2NX!$@$v+;V)>+IcO|W6LxA)5?_V4}Lwr$W zefF|Ep9X;{sX+n>h378voeX-y`a2--6Q+kg_jf@%%FDQGP|orK_s&{r+Aw%*o0jt1CJD}> zs4Ay#yrA#_DvVf(>*g!@-!LgvgNEdU5sZqE8MWCVh!yY+C6F#L66D(@f;d)jAtq$m z=VdRXLlddaPhCsN~JO3;VF5;Y5+(yZg&w9VpPHeBVrkQ5T+jDO(0@AxB$VtJfH< zK+A6~=Je*r=t|V*acvn=bAQ>+J3NdIRXV+5RJts|N!AXmj#Y`3+~^17Km1hxm< zt%py3<08VmLsBl&J^;nCI}soyh@=rmyHz|~!0uWd%I$dW+u4Hz-;$Z6%Fzcg0$rZtFxEvp4<6Ptj zzl8SFN{%)VzvSxNI!TNb-FPaCSBB1*<%jL#z6S%B8VBXN@*KnFcz$4}X`^j692Q1x zI!1EFm$bH@)b}FlBOrU$j!{UO5`iA3?ry4G!1EfyE2KaiXkL$m_dExaO#h1+Jadgy zc3$myKdqE>7HP5p&T~flGW*Y83rl(36nVPleFG7fOw zLA?EFH61?TfZ;!HM+!*HqmmSyr@j}I#W70P{BaGe;-|xc5=f))T9cfP)BIHJ0g?u+sg0QCbv(s}O5EZYKcZ;> z+36~K;p{hx87qhc%7HIBbwbGA+|PFx%-xxwO>+rL{Xna|m~6jMxJ0?r(CwK`KCQ9R z;*3gL)rz3V7v&V+cUOEn_Gezh=%+$(b*>sa9XVSmMyL;}Y{zlLqdq*7$VEZ4B>-E9 z4bHf2J0)v+t9ZC|ue&D}nO{2Ee2YrGWqb)4A76mJ3s3$*{j|6P1zp0d0+-e#MGK(r zR6uF>O~?=|s-^;+E5Q-Nj{^VN9C*;X-9jQ(nd7_mFl4!w;j)V1Pu=;$51fdw)X;l7 zDO$kEr!w;(B}ce^2unMJ$jY!|XYThjNE`Y<1s>te&a=->dxQE;*}&Il+AtIE-n%zM z#qmlHT^b-2m_JBA*Q^o|)KK^uX-fp<|Kwc+xSPYw-Dmw`^@JuM)^ojQD{K0&fBFD7 zjnaflKxH4--sv!)he*usjK)>};YTsfB76%7Qb8VqAJkyAfQi_g$Za6DX z9>JFk$Q5xKG)2n?lT%V6as}cWU+F1E+T@_g^txT!7215pE@MLa4G~D-Q5&Rl9ImqO zSV_As%P47$LQ5C5?T$hFNq{fwTffXbc|@Y^Huw|Mtb>O|Y-bG3XW#S3hJ z(BLr`tbvyZ9x#BG0%81sp4ROtPJjQ6YA$|31qC`oa( znW+UD*u#?PU4-VtrRvOq8)kQER>7pZ`wyh!Cf)H&^}WZEXgevnJ>&9JqQ81Uq!f8_ z${#0JO!jTZ%O@f^FH}rCvK6OnXkg$8OESHAT{=p*=uGAG;}YOJFjrZ?`(jEp{vB4! zQ)}NHXjay_ofECNl9Q0%O#~8iMkDhy!IGhv+-3G1PgfkPCYaXk4Z#kc3_k=}=hUsf zOzjCI@Po=ETbt`t1*~H&21QcSA$rmpYxv1O}HzboLXhei8mUfo9KmtfhhnA_=(5E>M# zk2Xg2>k(bMx7-iArCeHDno|8x6Riz=)hX+Bz#C&UOI&veEFsaDq@9Uj*-Fm+t~JX!ec_^r#@$JF_T^G)=$yf?E+a)S_T9U( z(4B=mv!BT2O0mC^l)Czla8K)}_kKPFez%Hc$zOO4*x1YSezYS_%ypB-~}=ql0eoO{8RvEdB8blE6jgky{@L7hL3v{iJu5H$NEO;3Xf zxaKDUAo-mfJ4HWKGo>7nR;n#)Y6B8o)Qv_Vuijveki`eEkO zo$!m_gDL~Pl&N$|NY<^*-f~v=nk>XIe+@Ba{qDCPI~sHkLNq`yw0i*UF`$QM-F@)X zNm^cG1FLn=hgE#~INC@mgxzFWKRXV{$H%ig(w4SCPU86DN;#<1df=62#M*%}<7ouE zvY$q~8KHXfBuGc%`-Q>IFbdC6gY~PJ!-5!9O{u9ZmVN)d(a7Ndc0XpKX!{5}ee>t& z)X2>Z$iu*GNQMl!9=_ZOTfuZqN!(LbRz~-cUbLi=(4Cx=wC~ize(2y3?Cn$Z8F>ix z%sE*3JfQUM3r-X;P8bEe5fcd}BZxKEVrUSwkR?;p@-jaYxyEN)i_g%9CMeH+jrjRVf$7p-H&pxS?!-$TahD} zs4#zjRfET0x^0S%cR773N=oTN`D@>9zG)7h$lnw+?t$I?#s^i492FmIsIlG8zWArI z4k_lZ?`n^Ie%`Wyh?1j7CF-v>Z1_s&lFVvII!5uE7889h(2qF=2G1A+|6|ue)%Szt zpSI{4sZ3I8r}H=-%!@(NIREa=u3NvHpQ%|dS^;v09KGiDTKf>RU%qP53prc@>wF0K zbWC>@n~EE*=fJ++WE8Bo>40Yt+4fU0vZxaoIS5gqdg@dLTCvoSAsfNwMdwk;1BFB& z*~|-iB$Uwbdk6JF-~#-c%l-Y22w$%DL;j#WJMb0lotH>xJTHP42kNB0ZM#uXQE~sX zo=ml`?97lpF~)THH|>;>amp*>w2QrRnx~E0f*Oa{lYA)MPf$z-PHZ*abJ2eESR$Z8 z=0Jv?jCx}2*iVlxg_{bxf8W9iD5qJ~{K(WG@bNq?pWb$FE|e_Ch6*U7#Umhgbsu#m zVRHA78TXVJE&b8;<PfNzApi zwQ-gUG=aVO$Yme}RSxisw5VaA2e4pVg&c|wr-5NRb$O#Z6mo@fnA9{#w8xv4FRgZ+ z@ABm`B>xLkcL6$ZVbN~`ghSOnV&)~*%i58WZaxd|)pi>fg6oYRWy+1WJfm+0vZ_{11K;5(` zVI!lnmeW`+0Hv17LWcz{7&-O6W%$Am>20T1LN37M$*TX8TeqzttC-3f%T{@BBsq?azkX|#2IH-X;Jg8kK)q4F3V}1&ti^j~6s<1T0S7J0+q_V)S|2f#%Yu3%d_C&~s7* z9r%6n(2pEVmzz3#Zk+bB(I4-q{@Bw**T4tahgC7r;)T{$=op+Tk(89X$IY~RdB$Fv zHL}aUbqfZ4ON}8YY~g_A>pS7vWFJxA)C3~iAl-vI0wZX*l?PUPa?{e-aUPPa>wF+m zC>;VPVUP3LVAm%35b0gxNuN#C)wifvasXU*N=i;fcFz-mdcEdGfv~kgQu}U#EQkvu zG-RJ^1i;o;-@&})%|YM>+U{<4sCm67-nwlZ5CEJD03IX*sCB$K>!CoUDqj_|bzN&D zqi-who?7<TXQV zpn;FjH~gx7R4m25phfp+S;>qDo0!RulJ8TSqZ?PXw3j)U3hQ~h;qIlY#0}-l8~Cc+ z&G|7H!a;J)mFopLGf>q-NWf(~Vqg38Bejr74Iw*+wl1Kjw}nU@{-e`^-Jm%^-Vkuw zS#=3mLmR-EU|+Eqa{+V~a?~Z)xr@(nI~c43Eddr2i3t@bd;R5tYW#k}YX)HZR#|;v z@iI#>*Nz&6PVkt(iY$)M*rGCDkmEWq8|n1Fmj)Wd{&izCCMw zH-vdL45P zT8CaH%34BYiGLWqF?l5119N z>V+(W+|wT zFQgeZHg`vdg{^>WA%kksxt3GX_v(CkCAZ?fu%J$sPMd?w&(S`-@K}J#!uIT9+gqFD zO5cG+*gC$1=*9#hl6|%tmS4bNLjnXFw1TT-UbBK&a8aXkD_-8T`>M%RZD zO3TZ%kA7#L@E<X?30Ws|4DZLVBW3f z#G>q4b~$zCzFXLsKz{-p3I$qc*<)|I5jvzJg`F6)K?MeA86H~{MkLT{Mq`h+iA$%t zfs|5E*a#EIOKvY1^Cdj4ZLX%Bpjjwx+};|Sejp;Ym7|@gP!=2M@h0E<>BY~G(daN} z@33zjtwhr$Hlxqhn4J!2UZqpmwrE z9>MZ;yRolGyi>7ld1yN#PnLM^p7R%o4yO^<(48w$AijQ$R1-27jpv{odEe{W-JY-S36MC|PmwO5XnF{(jA8uVIwVhb+ehz6-j7ZTH74d-F~4 zvCVA*$gb9|fhUr^8J(&AE^)-D&P;;Fc@eLs%p z-nVPpSABcZcu2xiL7?TtZbCM)C1f@Kxg`M;5_X`&c1jdv3d$De!_Rme&zl7iKRqaa z=@rTl_SVqs`ctqgt;4pewgQ4q&JgAI*Nt*2x;=*%Xfv0htC)FjmuD|iuV{Y$8c>+ERL@u+M9pt;vSCnM!IoFV@6&XeE3 z$!3}yh9gJ?r~(=d_~B9&y+zc&l)`82?9!!URo!>1-T`*N~SYAI1AM8B*?2S#ASGXZF33Fn_JkG3G@KHq|sPv9=ev3)8byiG*3@U;Tt;Jru??o z;2k5YPi*_GSm^qAKR~|Qp+lENOdhb+u)sQmmJa>|gs$n`Swb`{V87lt)}TNr#K>HC zoB@1>-P@{TFLxpKOdO%vh5FFbEx-uFBela4IO{A3;rPwPG>2Oc(gg^4H~}Gv(Hn!B z)A&xF+FHZ%TN_K^?G91tgk58?`pk<>=kD5LgM)5I?~HrIc1|Lz_T=!JV9T=#A>twp zxBF2@Rj|KFKFW8r0&a3jzBM*uD|KZhzITl`r(z!;}W4uKlMq4CeXJ! zH+KiSD-l+wS2zHpyz*e|nGCwCNCF7ILRA<iVCG4(42P|W{sV%p|Iby(ColrU~iJ285hCR72 zYMgVTor=)m7bU3aMu7EF78dcv#d$IIa@`E*{LmMSF{UGNG`v6Ed2noDJK3*u*|6j zW@IN;Tn<`?y3D_EamTRs^DIh)g?^EEv;<`cFXdSN{!mE!WDX4%frd5~rB%yvxk;^g zShV9<%Klx5$z8=0OH+ZKa7=`$yHOXnY})_SrO?K(J+l`iN~{L-j+Pxy{cw0efkavg z+$(aQVOWahfS{Rt$W?mnd_AY4jV@!CYS;_!TmqWJjXP}*HCvafX3|hom?uSW7fY#6 zIQ>1GX{7HE0%4}=DX?btkkxjD61Bl+5Mut!#|v^8D7Hp_bpahmB!%QXc1&qpf}5Lr zJb7h4`CP_H2Xpgdq--~8oM7pW6zK+Zh-%Uj%3*0QHE5HRSx_iz?Oy=c!{2XS*{XBR z!pwbCPO~8j^#(nj-k{A9OC!uVo|{~*N)LH*TJa4HA+!Z+NHu);cAfdk!O1NJBZ zt_Exi(4?|?iw?zL)BiSTmtdMK091i?{_iR?Z}e)~HkB=pbS;~pcJ=rRrjwxRge+H} z7;0CNZuqtP>X_ptY=4q#-<|#D%|Wtei_m^jNelwVo*`=iC@~;{SZm}LJOHEmD<-1+ zXy~0oUx)2*x0oKfY?&T)`74V?fyyND@|M^Qh2058@)X!Txg8Fev$$h{!%1v zffUm%%%JHN+8G#-ZHowXh%f8{_6tU&t4+_mnf5)W^J20V3(g~!?_#xYqv#wOc-RL| z<}+XxQhl=nGzY#$F3>(YUU0`Q54guU8*i0g90TCg^@`Oq!%)uA+=8!SvK=h>Mm(ML z@<8cQ7ZUj1_^geI8kfet^ZOwl1jWfv)Q)62oHdVm`iEEWg##zRGF_a}(4xHIb;nR~ zQE1)J1w}-}aY=oZQ#Y=@{c(RhVP1Q7-l3!9Ns|MWRHEO8Sygi94}Q8`wUZ!#BCt5u zX1Lo|p2rRF4Pv0abo8`~i%Y>{)k_HcB-?g?L82V~s4@0kX&q8=ASeU12J|hLut^M+ zD4KytfiLHd);VbA!X<+}64uy8rES zO|90(_6c!2ut<+U0fqDVr*TLimLizw1=P0}Cr_+ceHUHR1u+IGSP5hi%t*@@e(T_w z*CXK4A_+_xHYP#p$C;}MzAQo3f)J4hc~j+_n-ZkV9Tdq8%*>K2mJp;p*L(29Zm=0+ z-OvvZwpj{??d<%5g2=#toIWsxN9hy^^-s_C1}knPjLP*7;rfD~HX!L{KO3d&cQy(h zGzFRkP_Yr)czwv^9V9&(Z`;4jMa2YQb@4`x01HT;OT!ko%n5F*dgiIEp`o!jt-WF+ z4w{4(Smgy+xK@KrfAuRS%#niT)By`%(})(YY=sV>j&A5daYsdCjA^mAh#AiQ6llGV zw)Kfsc~gc$vN38|h3sE{CG)}?2r~DP)N!b&R|>uK ztXor3dXm2#)o^Tx*V=)PrD^_-hE%nD|8Qdu^3#a}Ulh|Q=4Gp(ewDoTct?4FH{w*>EjUso?*ci?gUu4gucqKwu+ zP|X!8sgb!OP>ljgf3{?nmV;nw_5+(_HY&m4>Smi0Yp1iH8!IR%ut4xGw!4C5Fbjr+ z{dmZ1{z15T zY{BmQU~n1WFK)p8Q-2$gN_1RTcymI2cP+nr{dug`{{oS1{_{dJ=NPmYZ>U~19Jf>s z^>x3z0sh5AQdB3k&Mk!ZELL?bo=eZj@cOIJw39ANmFo<-&hp2XusDT#7aOH8DjL{c zR^QdN2T6djmkBFWD30>)fw=YBz;_X8&rNIgK-(9o?F#3OT8$wt8IdRX)aFZ-6%tGL zUuqRaBpy)LNR>S>s^3TCu^2c!82hY*+~%Td)Ay3wSt(K6zZ&f}Fr z2PIpyuu#7ihJZv5h(^XA3FYr2;W4N*2aR>fZBA@#&}i3H0$pamQQeXhLCpd-2vY79 z+{y*7ll|Oz%rc(Alh|92qS06u@0=?WYBb@2CziUyud>_uR2kJbIhGci6_Z2F?$@P7 zhN64d+7c6={}|#5D+fc3mVR+`-{Wd8j!_+x#5yr{pN#`8uNe7I08_ch%bwR~ymf04 zkTsH=N1!?;4uu(VX#u>Y^yE60?HD^?A5m>>?bG?}=iC}Qkt|*u`uI`4ilpd*uEqAb z>8kSVK0~z#8kaV>0!AW87mn?3_2p2NC$?Xj05Ks?J#oi{$9RU^wguIRqP-cr5Vb(r>ig(erOnUD#%C5l)ks}@ zX4q9D{kL~1?WX^xAoh@@bL>Z}bp++YUxd)>#>Pfr2#b0UHHlPDlAzmI4yARalm)ZX zePJVS@7}#@4@VCg$XG9{bg#`C-g=*AO?In$yQ02pPo4Zxucm@gn^-RhsR$kUs(LDW zTm(s*sEgf-YR{RbPrnuaIG9d^-E;~-j{zjn?t28e+3dk|8!kh9P_S#SK6bHE!)Gct#>*vohj104|u#5w%{s~r~NJ7@A2QJ_R zP(Fhir#_#j#o*wc%BlGdU{!ci%JJyj)S0z=Yxpt!M^IYRjzCD&xtv>t|c&G8?EM$fi$B|Q>l-a#hII-iMHe4s{Ciq1xae9>z z2YWUbKRdpO*u}l2&G+kCb4h(zEIogArKP%-yQ_(vQ1y5{6%oc|0$#_U<6xf zi(;NPvt?R{yKU$%=B-#Bnft6SNe_izSFCW1C)pLq&tZ``CMeQ)|MVt@>m5|t8icTb z!zc6o)if`z4HkT{4uT_S7dS=TF$0c0GVyT+h z`p;5X7>M4>EPKcV(8rf-&!5*f!jfaB`nJZ<(9jLd0#uQ@0n$3AhXw1&&=v7fsIhsu zK#lihWr3)eSP!I5k*beP3l9Bqzz=Oj&Xy%*Tp;`jk)L)>f40B%F&A`X0$3<~dDf>Y zjmvw;q`)6{#NW>{-_ft@CFJ@9*HSj#g3!esAgd*Sp%g5ffhe&YS22QrkQ8JbSZm7x zDv5P9JUkIcv1#*WX;^=lEkM960??520%Xkf09k_vHDZIqqoSg`)8PChWI4!W8843n z%((XC&rtJhCywraZtP2#MAoHA_wTUYYg!ta8_Rp89vq)SJ7`j1lRMwXOe{v zK&cf_S@(@@w=EHp)ufox#Pf_V?~WFAivRXoxq2WQP7#-16d534xRed`&*2N#))eFA z{(dU_;6lwYz4Ovk-(ovPEc)^`E4I_UtelunJR--vddnwDtvfi@A)gzh^2je$?J)Ss zB71^x`eiCslC?bclvmHlZm6kKvlajyCWU$_D{BbB@dx->sT-wNC6v{nuJ#n;D*Q26 zE9X(sC(3%T;Pp`lV$LQl`qp%7cpPQRb9^(;&G`OSg56S-S1)q7k_uQ4Ws-+U#* z7!Y0&Z@M-iE(Ak(?~nA%gjM=*OI7+C7tY#+*^tbui@)~E+~5zqKEddk7^(A>MMdHi zuyq@pW!;8%)_Lz23SZ6(aD;jw{4k#U_f(Y&VHOHDSnN0-(H^{8#4-n7(}$Y-zHZugeaEXoQrp&w8js-u7YXZ_-C9U^_sT3 zEPHC^;4snN(g>^<;WRQD?t-qS%5ME{U2XC5-kU)F2CtJ0OoSTpZhgzuN!_o@k5RQ#=;oJ z0y2r5txn|}yJ?6Ie}<6r#gU68%xF$J1*)r0;8kKGB54L3cRss4|9D$LQG9^~ECTMI zzDEwZ1OP3djPfTeWl zC!fiJ@NkTT?y2{ii#u4n{>1GDlPn(e%~U${=OIxH*$>|)YMV(>Fi0Q&$VQ!>2r-lyQdlm|rKIXd6>3wRwSzk_Keeh=_4l{Ge2= zr@oxRa~%k;O2PFCrfPEw7Il=xr;jX5hTlUnK&Wa6z;6`Mk6l#c^YXM zR!;-?P94YU#HoE`>&1b<|HW!&#lK!tJk5I2M2+5$hHx+DBWFC~ld%N1hl2HnghX5*#iCn$c_X2_yvjX?%T`@aNSbmm1h0j-~+)I7a zL(B>u`D)M4Mbd_do>iBvVe1+HRXLTn0{r7b0EBeh5?1EE)1HpCXHVhVLv}4>ftZ{va3jniM#M1iseo-b!(rJW1xQL?_g>D<5H3>%_T# zzZ%Btp=_zIA^6GW)reQxrpxJc8>7O{F%S&9{+-~qj0g(_1w(LKq>X}Kkt3@l0~!-= zPCQ~cXcOsD>-xhqY;*CMjU}1A*0~Lf46lkdON9(tlN%H!ru9!7s_#0LPrFNY+r6j{ znHPY0VB{o%o1|_XII~fln&|1-iiVDIb|Tl-uQYviasSz`>_>(5FDQhxzFHy7wSP%Ii~R~mYOJz`Exfmix6H9PnnDFo{j=dVb=BpBkgn` zfap=FjO>D>BphQrH((596;}r$-2HE9+G`ylci&ANW!!odhax5^bc>(?7=}It@6~oH z*9rAU72QhW@s?2X{Qstm(cm*%Z*AKNzt#7`{uiB!+I(B0dLV%av$dRGU7?H{@@@Uj z$ikcj0;vT)!|4f8#~e4vA!iCyAJ@UNB7M7Yu3lw#*Cv90Lny2a*sYoO{MQ3P(2oDv zJUHm4rl;QQL2GFklaxot?-ytgIp!QV0UI%9M`$E|Pc?kw=$!v6(&_kbAR}QQM_Cxo zE(Km4NsQIDVsmfYngv^0UgTM`IKfXF3U7ucDS6@;+{3Fdi?O6x<9gIPs8JQyCHu>Vgbazys)K4t#XN_-vEJ&Opt%tFUq=`A9%JO zeaCVrK}qk;DDf+OZU28ZeGFIP6-C~`TA>%v$;cL-mY5Pi$mevVzRd_=K1i_=7r>_^ zD7jpgEYZa(=%WiXj;`9lXGZQ7hPIBM!oe>;Z6~8=1L;PkhC*2@mMzej_AxDW6>M^h zBkKR3{an*T!!mKlb+jt^tsGZPK(v}i(eOk~hxa6$bTJRtNNgjQ*%Q&vbN_e0^E|kq zm=fL|bYb1Mq?t1HHAj@2qwrn}M~RODd#v#>BiXYAqQ^fU&Uyw9I>i6K2R&P1*e~ul zp9am#9krK14~d4Wbs(qB!ut&^A@H5_kMS){wyyf+F`3lnj*g-!Sjc51JML=iq zR^8CZKuF`6j;91qi#;mye9OBN*i>#5_`6o1T zi;5VxI<|-GF4r{oIk9Z-)Xx{{hCXVFX-BTBL9q6N;EA>HUiHec?#hmVpExC!2KSWN zPQ2sOOTL;Zzm!XVAyObTfGtCe)u-&T?OKY$+zT|od$}FB-+1Y3{k!zD!yx4B1~nj0 z>`SWc>MBzEk=4n>%XHuYoTS8d8G%px`nE@~7Elj@-6PqRMXgMV^}EX zMXuk}oN8<;tCt&zy~@Y!u({MUR+x_^l%E>?sbCWf%B9rL#wo!3tpK+31v1-tpIDxQ z()lh>1NHfw|HaSvw&{%6S5W#J?AS;{#1**ZnaRPr8)g9rS z-OLWYU8lNxBgZXXjmV6sfHhS%;y;Usy*129IDQ2ErAT!)@arBE<|mPmq;sw-$V{qP zd@c`ion;7AgS`EME)cB6{${|b9*T|AwR9KpiDaROwFM@lF`~a25FaoADi~S%Kr7%i z#|h~uBJ3V)STx({Kbcb<0fgNhxV~wITZSr^$tLPh$edVI2{e@e^jFhoA37fOR|Tf~ zE$^*0hjf~M{O#_nngq8&m0aC1!?rVa<~<_LIV}xq`ve5^xASj+n>~3H$4L03 zg)BxqzE~C|B*}bOtMgd*oiRz>Ea4UIh0=HqyVGVXO5wMKOxAr{lR;EZS_U~E1j?q> z8YpLoNwWJDA&fjA3j7AS9@g>Ms`C$9F%J$%{T<6V2pf`fHy5|fIp#3CEOb2X4l24V zSlPr@_}k-##iUt?mzj%>))YHP^0p*EJSpBS%k68fczC>7xD!l@?Sp?0mtXzdDYH4+a{^-1V4#df2 zpEirv2-HCD5B|iw$q(TTD$UQlkOYGC(E#(H!a$Wt=&fntQyXYa#B_g?@n!rhT~y$` z$;;Edbk6rJDz@AaOBz1nJnDaWzWuP5ECaP0+ z!5r!^278 znB)+`gx4XYSo|&3T`R!ZAogm&w0>!75*ivtFoTy2u9z>`aa_VawLeBKebS1vUTbZO89V5|f-g^cM5^H>{CD(%n_yq$d?6nS;7&}_(*T2QuxG~`dBq3*GY@aN zqP3{dptswn9}2g@EE^p*iw#WoIuJ1dUXSo&$1=zL);ENK?ZBJ^Y`USCPglWQpKmU!*At9d~Qy)c%_H-7CRqnNG{O_yxx7?v3g082uY{feThM=p+ z@LI%fz3<1M&Z+1`t;0}Yf#j*EC(dLTuUZpTcIrs(@lm23RO};+E5?V6E$+Az$0S9) z@Cr`?@>y9gg&p4q?f^%*#uo-#fRdC$(Lr#zV5+D{f*Ux0vBlbv4xc;hwW^BjQJ>m1 z_LeebER?oDE5l^jhfDdU)iI5iS<GCQdfQGJUXOSqubb@CM6|d z4Kc6bQ9bxwXb*?@x!|J|S~UN>8!9_kT5NxqG(wAb{^(_fGxFYV)FVS-$R7WhI}0u) zm_aZ`CxcyFEZG>u^27Yu||OM6pihp(oWGkQ*6L`Wf)x zx(s8yo*@1e8dU?%j3`X6huFxt`szLQOsGJYA-iFsV2cERYQ}+KFjFxCm!|=9!}j3v zO1>GoP3Ls@+Zr2in_HXOg-jNSgfJ4SrGLVu?k87ZNxdMyU82J{4AEOJlJ7ZElB-lwJJ zBYO!}&Gq-2#eWq;ab;aMusbtvUBd&b+kU*8Y?Os$8_6SyLY$?5yVwd9cpFyqz@=>K zMu}ihrZN;Gnr;&Us*!Ie?Oo4M6?3rCm+t#a_vHF6CgNZ1sJ2^jVK{dR#e# zKwC&O(scJ);Fl`nVk0i8n+~!t2RG}Ky-rI6Q;Re1H;^N0@HZi?{169oFZY?G_kJ5B zZiC1L^zfd{ACMSJIfQ8d9fgV}#mXJwtOZLgw#2A`u^TuTn!|_c7}YQ!^j`)A!>tZy z;gdv|L47q`N`&g$J(A(kaSM)O*z2eks%*1kZG?H6?TVMHL0!A08aRZ^!1xxYJec!0 ze$}_qSW(c!(4QM}0#B@}@>Iy*D*N4hmt(dUzIo}kadcCS@>9i`(NTlWP?eqF;Zdr# z|9FY(2SOnlN%scQGW^NjUATHILwDUbPwHY(Lg+E|O@-LmzmMxp()@S4G}BH)=1w-j z!EOW2g_L_-tkCnrrzPfTZHS~u*>|<4Y};OUo-*KsR>rq-cUj%=DP?11r_A1o4c2Dn4yXPdUSKa9vpYC* z4F;XB?%}_mgo8ENp*6WX*)sr@n05r$EUX3o?wJCaT_-Y>OI$UAhsHE+N3wR_LXRPhVRsQAuP z6@Fi~;pZWxKcW7(qWhQT|4B$+P&=NXERiGhf%pYpVM&no!qDfW&k`dQQEVbThENHh7%PE-MFBnRCm3Pu@1L} z8pF|ruhe?aN5mkd-Z-I@wlZMH!hDe5;x8sbHdJvxK2&6s-`Ad=36aBKYc9$cpt}o) zR9NoUNSX7F*K4Wl%jHJKkG^54tA~v;v6Zl$u(w$o0b^1_8Y|W7g9hznW?Bq5py8`~ zhq|cj7m_mV8+yIBCTC>$>2?jal@H%M=Ve!PC#%^ZuYY7w?8ugb0YWRAI23QLC#1RB zj7UqQ$9UdZZap}j(%Xn=E(r+<6z=%}P)Ju-IGv%E=?(uU3czSs*P;z;84s6=&(l6z zM;Tjc>(RB;Uw%HUu0AAj&+XF(up0BJPtgaVoK0YXr}{8a6!By|>Y0#|h{!5|WV$40 zF(4n^pzF(Lei`tNrP!r}$Pel*;>S=>31vyKaFW3y440Gor@=b<92grJ4PNCaZV>~P zpvOFA^nI{(_p3RA4hq~c@~lYA8!wJ$^S%#706ecqyhwyof|_jXG=++yJ#;ikJ0<3O zY5M{)Xcu-gh(oUzGQ*lUIRk*v^~BQG6JE1GYiI#S%gy7acvZKUIBN5U8NQKFJ3bVi zcp&uQB6r`l0Fe%>r#U8x+-szs+K0gB2uk8=*x+7!@qq=%5QzgTTKrU0g4Lrw zONWwB03;@z&{%fCu3}U`w)nX3amnKENj*T_PlwpS zwwtSYoAS>)WZJ^EHIjB1+PT$z4&i#el?bBu5k(>CIIb1}gA+>4M`hFc>(@)enHbe> z+Job&6F#AIK7L0ZxFQot!eSeDHy{iG!JqAbRnnkw*`LWW)lqkOtZO3o#P5pp-B^k{ z>hyhM%X!2x=rF~tzvg$?&u@YD84bji>hxWCS2B8a%I_5`-Z>w#j$-s@{)n>kbgOHS zC+79**JOzl;74A7Fx>jC%Y?>RW_VOg{rR^llRH&aT}^FmOe7P3&GOG0T?5XRG7N1f z{AyntGU`MO3)YJfb~_>Q#F{(Me{J*h-kmf=(6~766Db-I;q!K?{xgs}BK#4ETdxH` ztzeLGLmGlxn|h^7V(xaCEQMz{*mb2WhgKyQ^sT4>st1s#M%XD?2+%`mV`B@^PPiQ5 z6%lyPDvB`Ieh)g;cY!tiM@Z29LkfO$jKneJs6S2@*RJVw#uSuOfjafBFCqiM^eaFQ zB@s?P7Vy2RN(dCUGGLRv0IDu*cLHyW5yXQ5Q$UXpLBK!DoIhW4v59d+Qp1*I8Tdz- z_RN2I+}#DpN99)#j1$H7s?YR~T>4=ch?8jy&mq#B{KfaNT>V`-2I8&T8`6-v-xN32 z-TWFNL=12HyWkmmprdXg`+gB1J;~K^L55`qq-6}4VVfc-ns&XHtAhp<1g83Lp)NJMca!L!yKak0FtrCPnp4+`7iZ&~RC#{!|p? zAC*pv*t6pqNI9K)nO=oF+}zXBo(QijPU?-cW^Cm>zL@8**A9^8B+YrU%hE8i5C;e^ ziUneuB}NAJ(8<+Pc{te<1V1Dz`z9`SJbIi6>q8P4dCt!j;=5L`CkvZ76t}!BJPEO1 z1rVM8)<0$;GRM0{D)%QJX|~p@fXXA~Dct?-H&$pEo@>l16kxMv;!PbM+p|==r*yxM z_%={Q)=JOHdL#J=fgJ$%=>ZiNH-LHFjQ{)BFM9-KL)G0AT*xESym(_(lrlH5B&btK7Ub}b@J*13;-dH*H^&{*VGz<4zFb-Emm|yhVUnA z2hN`Z*EZ9uRh7|Wtt{c^GjMYWiXZ10uTW|ODyXM+|2%T!Eo}6}+?CCbU4XkP|2v(T zD`@ISK1(X{PtVLOLxk95e^px?{jdJ3luvgKqs=mk%$4f-VY~~3P6HmB+Hr3yCW_ZO z1mio08I-9UOgF{zc!$3JwYwOkhQN|?bxnMq2}GO-J39k_!K(6x#>Sn<5v2=CPg{9Y z_gkDUfk24VGpZ^_y>6WDv?s9}+wUI$R2+oUuupkC5b@bRy|4*bWll=uY&D1X(jhB>uA zRttE9)Wx!|hq89xxS+e5D83Z@>LJYxY);D_7qh~5sj6J1kAca|ag*T#poKXk5S2^Henx z7CHP2)ZvW9(Y*_ci5n*Jr;V5HSA6>XiU#~r-}`ILpr15PNTUui8L~-$$fx@WxLV&}hIQKP9gLFh8I9d4!F_YtCQ}e|{cPE=K>p z<_5xNLVc`Qr+auiXt&*8G~?-i@+h*47HT)-4}-^XXr=K~#g&u!RZ+}qejbBtMxV&k zF4(ydg@pjdSxst5UGR_NJopB(4diD1t0rLL*m`2G+A5|1iwbA@pb!sB3!~tlBfv0> ztrK2M^srI=KJ}4$3w@S3qf9$L^;s@Lrv(eI_jijCXnwL`M*FYC-f-mUV$Fw|(xV}Z z&PTLnEEPsfeL8G^dhhT5`C?A=)ktE6S!blWrBaL8^6tp}gFebUkV%WRbH)`-7*)A5 zKm!{Prx3{wRmRv<dF_4?)#P4S(Vh4Vae^86RXtIgJtnm9aNR`L;e1z{) z*bHOCyB9l34`(`#6ph{%9kABN5k9#G~B%MC=0kalp z40XWd#Ls1b0zkr}{c@6zQp(6ZmNc*SOsvg4P2u_D&BYB5O5Hf+!Ap{61-FRI96YW? zzVl)C<__2sITqkHH#uo~ z?BsUe;{4;3#;bmQ=CvU}E`#(y{XMv&++#zol+e6<^BtCsM2u16abUpr14Cy5-Cqa_M6UmTn_P{#0-OX+0AP>qxcS`I9?SKZN z@s>C~=Jcj$+nt;Q^VZtBUYpx@U!C}6LQu{zTaiAOdVM&&$hFc|7+>sT*F(I&>$#vS zLcpYVC5@wVA|Pv(MRIVk;ubTs&5RG8cMCVIXLyRa&q*%lKJ{Ef@e)6We^BDT;@4cc0rG;qnklwBcV51I`!=%TYuL1Qh&zcL zJN7rG29c%#$xrm_lk(|FCVQ>f+@?}2jzHls!gT7$^G_GJ{JX~gJ#WC9a=vA2(s4)VJ;OP?X?y6(@6d84IA*-|wOtE(Oo5F; zV#ff4ci0w=BGT6YpGvI@H5)xQ@?`JDo<3|j6Nlhu|7cNP0qizXe?@dSVf|-xr}yS4 zvn;%Y3aq9zk>srjNy56HHK*|Y*WZNLd^)naYY%W=+}Lldy`YXwF~B^O!E4Qw5<5BC z|E?Vcg%RHmnrSx>=uO62y-!Y&T@wg_2NW5>bZ{`u%tg*Sp z{*y-MHfLvNjfa%|y77C>PnTdD1*~f~SlasSvs`8~ObyUY`|5Fpn!j6*OMLFvmX9Gi ze?5^U)@%H|_Vf%|}Q%36M@=707c`A1gwbI8I1wb-B{a0uiMcMj#wPCA6#VbH7G3u8=T0sa~46dfpN zcs({^ReihjtXt7l?eo6uk2bR~B8lZKC^b0ei^8~58u_ye5?l6Nk83#mBd)ng$ZZEW z+;>+UZb!eScM*(9pZLKrTVG13V>^8sSqQcvbR0QF*aWrTzF@DoSyBAT?ftZqjq_Oa zi0z1woG(gop%^Y1iH@VwM%;>i`K;o;$3?2_(u1QK63f!#B1EzD40)b}T~K%jA9>}T zk@|$Lb7|DB98PldZaREz@`eIGGu2A$&JIXEYhpd*=!8x!*o<-jtA@M-bq??r8$ZV- zv6z%HMjKCWC{AQ`Ns}dalOo<%iQjOO+siwc|G~?fcK)umD?|Q8Ojwq(cO?xaF1M-F zjYT&+I1kuXa)n?*`eqZR^OWS$ERVH*f({Q4f2z8nOKn5rLhdzGgkWkd=}LIjefIJQ zO1uuB7b5p5p=l1(7Cua7`MjpNgVD{<;pdnz*LF!lZEXmM#gJ+y$Q9R|qQ_*(jZe2! zo8U0zJ=0BBn=v0qvxBlAt+k!7?pt*vDknrOue-xz3|-1^c&IuBm|!7n4FQ7E^Lh{{ zT;O?rTY)xd;IOV<9mXHvY9Gh@Vr0=HG3Icd?-XI3%(u>x;Ry$Foa6nEA1d zNp2y6{=CBVWUE9mur+G8)2MZHL{Rtz1k>EG&E(GSPugU67r5-_u`SBk$PB23Eg*6z zht|GPdnkD9(lE`raeqH}W*{cNgOc`j$S@)?q^SK!qc+ZOExu*gK?fGGIKxx@!CG*q zDgU)PT!El0NCvF{xjl2b1VG-5*i(d{RcL-&2+#1`$84Yoq;YFHnncWA7toh!;4aLsS9+YqrKYA_j;34K~kO9pBhadl`bTZAh zuG4h!SM*eyLZa45q2#=zrmAxM6O{eTxh4G@Bh-@)zj+R4t}_P}dHrw)`oY`hc7F}_ z4vK*-)^AgLrgfXfTk2xk)dTE@+w1-CWY5;>;6+^f6(YBo9xd|6SuBMkVUo_9)FR4klwX7_|I2dE$LH5SNhDNOY7HbT<pY$50tIZ4JUI3*fNVUa3Bi^<3Vf-;<@=Z>cNr>Kkg=`19>qwo_hT zhq`14gUHjdhO*4Juoe;sf3D!FTA8c0QfpVXEaqwE^np96f!;tv zeDTr$u?p_u>r}qU1CGbNvWj%92-X1Bt=Ht(6s@s%|dP5Vur~1`o2~1?&9E@^8d*{)(a|q|W^N6}hu4l9%x- z;uc-+UkhnI-4#j{NB_I_CPZnTmEG8lDnerkQq12VFwL5FRD^00@F3-Pjcnr2(8SY4 zDk75isbqdc;<#78)Zv5PndU#vJ->X9iePex##>XW7zAPVM%jri=E#!?3@A2Dztnds zG}cv1eXZPh5}u#ZsABZXdg9xRWqOuBQ|nDFKMnil@)r%#lIw})7@M2l@InkfCPdfi z0rMp>bdW0h%vAc@x1A3Kqf0vTvcWl1y@$ONlqq6B!-ng^sLKFRbz3cva zkY&CVoX0~a$sKZtK`Dv{2F(zSnmk@j;Y&W9>J8%AnFB<37McgtUo-)h5d*b+dqJ?)4t}>~b2@%`t z3Xr%R(%+%$VNicm{0_M-V-o7WxlMh)PggJ<>Hj!JUBn@0+-WEAr9zrKr=Jv*e1ro_ z1irMI84tw?tYn^hmT`7rI_@lfsMIUg4dRccmY#I zh{_SH-;$u|jH&^btCW_2<0StMO1#1M&liGzPCq6s%TpXTO1PY!!skLK*v40LTHvb? zib;j7F}GFESz~^d<)5#$aj9d zOLOWO3qXYTlL<>=ioHlr=6Atyh!s8l7>Kfiwr7daD>)CJ8K@DRF%OGCh2H$nCiuDg zIWA3h0uRz+ZGq#jE$n49dKf>wyr@WI@;P)}ft|qw?|~-?F|j}SluU-^r3y{-2==d9 zxaGK~Un{tXOSSJOXSfKn>!2@q%kRM}9{hsACM(#AQU_O```0C}gc1&_Y<-x5peB~4 zw7p;-@Fy%=Aq`f^(!Y-pO9Xo**m0X(uQRI_gEQ7DbYs>9{IsKTugD8FZ8%C) z+5US3`pOStt&B~VtNr*`{cjn66KV{+Ul=d+=LVF;C+#p%(<+Z5_o9TXdvXzE%Do1^ zzR_nsXIBKOaHy(~Wd9SoGn~rEL+i}U%^R&{*AK-J?P&?|KQjI0Q*52}3X=~UrWgDr zM@XH>CTCKr=zwh)gvJ92{~U3}#PN<@2Ni>bQwG-;W5b)z_^QD>-tc8Z@uN;!_x1Z} z%i}*?ERD+;Ug&7d)O#$rH(WP$aScU0tr{z66zPiLJLyr39C}ucgRpA#`);n2%JgM# z`6ci--P9a@!pXSz!Njk3CUm#BwNsOb_F66Ps~ldpWHoNz;>+DP(tFqFBk{#9|W{sVE*u<7E!!12J;9mct&U*qb^7tmGZ%G;$s#|W_$R)5d~JUBab#IQ)M5# za*5#aKRf=NI@6a1wOlC_v&rG0r^vMfU#F?8XH1T?lzD+53P9`_uIeFmE6dKJ7 zMljY@7q)qs$cj1mPv<-5Y_Gk@Q!2Dl6Eg07$XWiI#CMjq5`F#A`fnfI52UOUBSdaK zgZu-ebIxo#0z(yB@b694ZX5-Za()+o6AmX2q=K%*UlB&wtUH~ako=hKF*zSYs>}uJo&V8IpSdX zkfX9?&)cgB8lffKMF~lBA(_gDq_;5nIiy-9!9J7n&Z$CE@P*Tmy)x7N-xdBMS|iI; z&)+|3BNulPPHEuxsrzrr-g;-w%_mOkmIj8ze=v=UNMsHbzx7zS=gWwSC(oW#)|o-W z;Mhb>_i>F))q*dWd7ak58^BJ2H#l!8X6x593=j*9tq*=iD17DC%Fpf|MzwKaOngziIDD9P>Q^_v zZn@U0JOiHNNHXVH<#?*Fnsyl+g&%TSGTufxJd=(vB4{Lwp^b{GP!i;1Jon=V_HK;w z)E`Yt5>~k3RtFtNFV2D^1xR!ESa7Y;p$g=Z^Tl4rT<&=VUu@Neh%wgfDSr1!Kmxrb zx3BEunjOS^wKK-1Xp*1lEYx7r&o+u-9Qd^d5G3T&qaxyV|rx7`8+%zA47PK*g>?)mrqYYL zGA^v=@wf1n<=&Q#SKyK2W?-lD0!8a_L;@qn2dQ5Pig_X^JB^wI&}&{52aO8MfF3#L zNDXoy1sTm zFc_&ZVb=686f)yBKOr#^TZSj0l-2cDPY$mLv2Y!xmU7AV!Lv%~3Qk0jdgX8f_&r^+ zgy~73y&CztAWCnNx7?y)X}Xh(`|qC$8zlSuR8qH)<$VP|K1JrL+!I`B)Cf(kBcaJ~ zEibVCXBsrF?jO9?a5634S~YH243s11AO+Wv@bCEUSDtYB`dyEPQaB0Q4%cg7L7^D8 zp{BprZ!kJy>x(0k-t_jI9q>OJH3#YdyL-yK#mS%JA!$L=rTM*rRGyvpQQ%q z=qT+1AgIa@R`?x7nm0>r3$+!T_CagE?QDptET~E#!~xhS3}B*e>OFH((0dzUXaS!k zo+N%gOvI-=-w?`0Ouaf2jK7;=Pqxy?&{UI5hI4mb5ne$QLbBmIHOQX{X)a&(!I=Rp zrXd(!si`Ch^SGDZq%rbrJ9>OUVvbvhx z4!vkSVA~Ha#Xvn-LL!d)PY2R?u+u&|Z34YGM^ftWkR#&aZm5WpJNwnDld@Ok$|Y~L zSV0y^HR6Yu&q4eU{7gx&F@I;xW1Id1?Fr>(g`+{GY;$qgF)%W#Pb?MDYxB~MvFQf6 z;*HI0iR%Yb-s3KyP=y7L$33)E+$G1aQP3s*;TiGvX*oH^;6eOz{=j~Huq<9{zum(W zQE3yjVITKK`$`G_B)Tu_qX#=dxz+rGbaUhQFeN?>$KT)EoN-AoaHcAL%y_YvWqPzY zV@bA3LIU%^u+y&fg3z3Egr7W7sINK@LoWBN`KL^c2Z7#&meXTnC z@7q6Ht;SrB3$~E!Ojw9GzVR4_M&w{lMSj$ip((V6bZ-ovlgECEL$z?c_u2U}0LAM< z0i+hnO29(riW0#$ro$hy9rY!M2rvLSl-@sVc2Ag zTLBqbAaxYoKMS4j^8XPv=#_huiC4+loSIU=^C^2m<%g30(XsZQ#`Wcd)c9q6v|3Uh zdaaG(0}hG(yD*J1L9Y99itd>N^$adRT|9Smfj)0uV8pIpcs&Y}+5Tob_gvO$%AWJ1L>H=R2y7D_&s{#7dBubu7@ z%Qb37koZaUCXY?{Q>QF(lMlN#keLS4RV3g8dg5`s@sXk}NF^Gi%lRs~`^C;9m*4KI zwZmb8%nVN_aPZ%J+>nYIJ|rbD{DID7w&9Ytm&@E^7uS|FeUg&_WQ|M>7U11`Wkh-& z>=FZHnW6kPrmHx~Ul;&HVb(S`e4MQO%Mn1wiJYx-psLK!q-k|-5riv#+9q5nV)*^g zQxVIo2jm0z#XL2U8=l$n;GlRbS2hlv3j|Fy(1ofleo zP=#G^&(ATrdlWV@7r5?}LLjv$12DrbIbZAeiMEW1(P%YF{1V%h!S>G1uU~KH71BCm zXDs)5MB@Ch_$PXjIx(7(YG5MOZ zvb@mLF@p+E2;_|mNdp`+QbZ4#GQr|lRHhQ%Ctau9Nx|_|4mgd{bk*XPgxd`iIcsv;W63K;@nleZ? zFSO&9`~B3W+n|NZjq2Szz>@#B-#8MY7^O>%kZ#TW^cwTK!BD)wf~l!n;nrI2efFR` z;Esx5nL7-8Q*5nYGLTVB$AvMFSp)N|*<~LEA@D(+mqRCfdw?3}iey)AT0ht1^P079d z`B80F{0%Bt{j}4D7fCNXC*&?)aAG5k@^=*)iq|$V(qh41zUW}QEQqSk*&uEvq@mgJ za#Jw7oD(qQdjZK#iRW%U#?-&kpnQpxm^5mM0Olra`o`6#kRXoC zVsry(jfVrPj>nUxDwD4-()gBEbD=!0NbAM4%}i|Nr@}HfgwDXgwjZ%6kr$n#kZ(hL zyadJby5XSiJhEOGBASWH!$2%OzDH$nkNXcGyo+^oLdYDl30+%yg^WHRJjm(;5Az9& zwSozxF}&0$zcV#SSd&5W646}z&nXxy;s+@p{N)vxS>!Cq<+lDAxOf|c6lT?P(k>uV zH=23G`R(Y*K_zT7P#h@$%8=WJdpkbF3O1oYdJPcv97pZ-xB-+OrW=8Gr8KHmXRm$x za1Hf+NPFQAg|XM#6q4iMe#ZJjX&gxx(TZ=~%H(@TjBbylI1)~M))R$(g&s62m)Fms z;a{A|DykCa`1lO_?ST2Jxn~?LB0yG}e%%2eVo6*%kP!D@2IamF=-Y;6T)+CXN%x*L zdhi~icDbB6&(QvVp$=+mOd3`P7wF^u^~E&iFlr_<>iTTINEvM?NYICa82e|w9^e7{ zc2lkxD2RNZnEc`B^)FixgV@kB=Gc^nei7Z69hhcd_^Is~Z_;*=K-QN>v)~#@8CN(~ z{X=dsdq@z#kCa72s@&Tv5-{4}w^JbxkOZq3G&k{iUbiB}2|)fWs9+fwF-x%Nk>m8* z-@i@(g_N4l9*dH#u~TBVn%~+t<#nn}2Y32DLkFq|V%NTv=nn%M{uj}2`Zvi_3|P&a z??ri|!TjL;la`_5jtiHaC#!_0Bmf*Q-s;iln!o7s{@y=9z^T^IvyRzZ%E);P%E@Xz zvpc~K62G6@y!QYxTB%lFr9m=&DT|3x<}o|Yg$O`7f`>j>-9Q`kzf{(z-1W zxs+ktG&8(}V&PeH5Nd;SL=wkkG-(Z+*((Xxh)*g2GgJ1E2o^?-mcX)gs`*@sKMS6^ z6t7;)XR=3v8r$1EQ_rybfL$>msOqN>5315QA$-jEUUs17IPnO>y9 zT>+9t3k`zXYr#R(oSp+3Bb0oTOI(2(e8kYWeux7H`b72fVB>VYfq&oh&)vKGQfM&p zk%Zqt3b)tB=+hs!)|?7hj>5Z#!EsE?@d9)Vs}C@aC5*lh%z%8tMW-bohdEc&_9z^& z!EvlzuohKDT%hi(=5q7&X{>oSVDX2cIW?s1XrJxN(^jz{eEDwz>HLJKtzTL2tAC?e znlCC3J1;~?H?&L3$jJDV?>wrdX{Qi`T4;w0C4sB%P8Qu6SeG@b5-2bg+3Es_0621@ zhC~WV!Eu!;^oQh&QuQF4+r?)Opnlu?JP+bTh@L{}0IU`U0W-}pr@3G5$y-=N)B6R1 z(W$W~1xn~q@InG0fM)6fQhHC><*>lNWXj~;4<|{YqZ1ThW6R%8H)>px;K2wa3|=QI zOK~rYqEDwT z_*;9sREg?!p@$)!ULbAJ89me?#{vies#r=EP2-N+C~p*AZtI%}TG13td@%vcZG|pW z(j~xPx6ncRD;jor!O(b!AdNv}=llr42q~m5H^rbqTIapciWXr4BV9b~%*A8n*L9w%pRDaxbQ)vCP-9 zKn%3|@TH^#NAI=Ys;+{|4M*su$j%yYHr2+b`#wF#`nd8~=w1Ea6MYheqg`u>FMovy zF~ltYs%uqP(0KbThZ3MI3@=V%0bU3UmntkAxp%-UA#QlF)MM8|3$;k!OX~2^P2ceF zyIJM9@6~0(^5Y~e@kFqOsaPuYrn6+4dMI?H!FQwL1|YbIP7(x()Ug46?hli+&b42Q zm&6M#;-4z;g-!-_r^H#1)JIQ*V3 zN!;wqEzlET3+GN-ZcNZ(`4m8x&~;`~rz1DhRW$B!^40%G*q_JM*nQ#S_?^fcnW8jE zg(#u{4GuC?A`~i-B8^f>G#*ce3>Aea6q1yR3?&-SV2U(TDh*1hlm^Y;YuzXB&*$^{ z{qZ}0JdeXU``q`w_g;IgYhCMFi7F5$yS|H)&aJ-cBc5IYL%Hzhr-^r0%q=jH zc#?sThT~OuWAWFJeme`Vt7``T>g(?c)5&&0(x;y}*A*fxr&W=?*p{eAL_|CX1>c(bFnO{rF^xOyff988=kx&pJIT z`!$iVN-*EIeOd_>x1fX4LpPVM6PL6DGd5w`$xpJi*&h@8^bEyYq&8}|O)qK5=p%ra zS$+;4*Eb8b>vgUJu3B9UX@o3M>8SERqgV*Q$U$yXI~4to9GDf)dbXyXC&=! zsB(|(HI>K;HGWw$FR1##>%(zwAFmbuk-Bj-`iIK<+JvzD$KyVUwx6gu$k>h8Jdyh2 zq;-d;{oLk~_~^eDQld=$%63kIU|M z!dzQAB@Bm{Jdo>SR0b28vJJexw{ybI(UGT|_y|2isc%u*&Hwgq(oQc-T|W8P^Q_O^ zbtDH%RVKZM{PYhsH8rKke%gP5DKn9PTcbC$MYd$cOiO4Ec())OIqtIW*f!vONPV)O z%I2G;;5oFVcBL!?am@Ik6hY-Xwwu7Bd+!9SMGY{0ORoGD6-wDQ`0a6nLvdHmwPj0E z`; zMXnn1cmeSF4ovlWF57*eXX?X;TYjTE_N2sbhfOG&6_pz!TnL2JCOW)KXZKzQIHCw$ z5pLbf&NY$P8o5DxXmSDMpIS4?`a$P#B$@2lbj_`M`!;+ajPuYOzAIj$==n?G6PZ)I(XU^R+B17gJOG8Hl`)m4fo27 z+iCQvG+2Jh^oe#;M{;&O%f{M5r&#GO6yx_3>!+KV6jNK%D(VYJR7$GrqJc}BY3(g0cKuLa*sh^@ zFP|faK@4j9d5>*xg5oMG2&q;ov`t&K<&r>38p&SP6S`pVTn_;*%eM5{e&SFHsuI% z+xx48)2MX%e$_)_uVQAdIBIde`Xetyx;+Ketx&F2rXPDxV%2R zzP{ed=@7?wqh@zabap&M#t997-SZsSUNz(Z3_np*C=qJynbw;OhpdVOvkRT6kj$$K z50s;MPP|BH^19B2qmRVDy=~DuTEoFZ*?hhG&cjtV6z!|tcy+A)RAa~wKa5S+az+Sz z#Oe^GpbrSZnfUE7}r}+>L(%IRI4h?Z>MatzVF+v(u~+J&AI*|sfM#x z-C1duF38y>)9ggktF%Kr->kOtpY{1!ie{!&I6-{#WYd(<3Ozwvh|lOMY6d+TwuYUd zd`Y%5x|i(Ep!!0RKW{uh4SRHFqSpawA8prYAwIh03LgwU_v!US5uryvQu6A$f_3gp zFWBZ!)C!Nk+$Qs;51|wXD0zq|7gTAb;bkCc!@=;FSZ!$Se-S zDSmGDvDD|#hPQyj>5@_h3mN0)fj>KT6mBmTdylkPq3x_+R&9UGK?UnI4tv zs6ubQUdo2SsMK8m(5fbk;sqQpiD{V1^?}j@UEYI<+CnS)6_V?3Q3C|guRq93C&8j` zEzbeE7|ZdYi5YQ>JE`_< zk{7Dk1^m7WZG6k^_$hd)F96f%aqQZR)nm)+^LzEatA?@jG)4jc$V}0bpKacT3X|~X zNa;$7-VO6|lYaZ7H()os0X<&s$h#D5)Vjrt0F>joMEL0yM7pXyW(l zkNbPeL6eOqKstPLLdW?a4Vx=r`3h!Y)adjRtq%h{7p(O!OA1G+9FhiX>JohJyo@*8 z1y3+hUGTz^kkh0+JKn(?{qk5nH_e{U0V*%-F<9IFU@vLLq$AhE=>cDO3y(t+6?ySB zU&LdDw*ww{%vXW)PKU=qSok-)k!^tNvZyMLq@IJM_(Q(uhYcL+gNk(kq<@tnQcxQ! z(OZ&jPNm>DT~#CW=y&2*Oy%k>=9>6t3NtmAOxOpbbaEMo2XG#vB3k;i!}?*(WiuM6 zr!B1s^k@D2;WzhO6M{b~%w^jXQ(FW$TFIr;m2C{Jq0yltz^=bkA57TYtS$6&HeWM@ zJj;K&H!7|c6&>ek26iF6I3jIJ#|C9bXJOeq?Rk`9WrR{C((=l}P7)=wQR_wbSp&=@ zAn+{GWv50F)Sbb>DdNF1K=`U^$4@Q;8mk(U^=-qynqkU%uoCU)&*z78c>z@`(cVHC zAQfLyR0g+J7=7W-(#jJ=JM5)6`RTFbq{2&Qj0=9hY-;s?Yf*KqZd!4F`A?Goomodm{ z9A-PIqNlQ|+D^&U6oydRkHqIJPhtIXj?EnOw{O_Uh%d3zhtT@Nd26&{?eYW}&%0mQ zq^jM=2Q#RK1C6KmI)vIkWfNxpAp4IuT(2fP18|aTD*AkoMp6~kDnqP#&>ujP>XMyw zxlX^XXe9b;%qdP3`gSz?*RA#f3pprcm|)|V9eh2WO4YT1f5E#~L|hzyMg6GLIT2+!N;%NYIW7A(vn^=j z@_B`wG`3aTET6Ac(G!})2I~d~WPhZ!)kW74qwe18!{@p-hF#oz$iU+J=>Nfcg%_Q6 zj8To%b#tElwa;@G2(z>Jk``%V0c`7E^T1Z7GVXNxb#F}+1+}6$EJC7QmPf&;sW>j= zQ+;`p*pxx9!AFk$4#F9a;^hN6Oyz$1iL1=*EU`S~(X64CdB7yV#`qfQ@1=DZa=AFG z*H@EkN*v4mTO1s+pUVy_?kQjUzWSpfO`ky#D4GG{O3IpUxdl6(S(+{|PFNf$efp-D zy`p2yM2j{2=N;I`#Bi3kEuFA6u$;%i*}3S_G@WfaznXfC>)aD|?!D@gph)BKXP;kb z|M1)2?*J48z|H3D>ZlbD&K`kF!m;cB{r1lC2>t`^Kp33qDLA0DH&q z{UpctZ-(p{`&W{KlX~M(lu)Ed=1|}7KONi_9hB9Uo(Jc4t)qx+ ztgX(tT#)B20AWeDmcnC(Ns~S~2UO%xoci#;f1C>is~2p#u@tV_9fr4sFZ=KC=3^WZ zMlYmyFzH9HsP95R6rl$^hU5Zs*zWMm+(q}G<8mR>pFU;~oW>WiMW^`Ul@qwJ?0@9| z+@hc&squ`J@?~NALA=fjz^$iOgo1X&IzG;vQY(6=uQ%@$|N5gZWWg$cyH0-vR`~@1 zMoa6s25aNPkDfza&-wj4T0gV?`V(Pf?VNa#&E|s7vtL`{_J-I>OvARWp0P91nHqyC zSvax`$4C1(JPfHJDi7Fx?|R5uLR(Qf20O1|s2YTuT=;zbYGOjY*Av7)a|Py4Jv8>& ztzF>5w`=jr7BJe$DQYy&;UVh&61BfUypePnx~?dbl(R~KT1Ub4dn-mGFd^Af5Lq4_ z`T=}&wM@rG`iCf~fZOYy7$|?VsI`D`4gkF{J-rhlSN11EC|qh!I%eLc;v*nv|Yd8;dpt_^=0|4`1+DB z?}3&x{?vblnj!l}U8^rO+@I&*P-obN+U{(K$Zu;cfquY@w4TEFh66MV^JXJv#bDiV z$@m3}$Ov;G*d;z>@02R2r!!Aofb$?zF?;4@R>*=X3K#rTm6DUK zKiuCCfMR?#Df35~#n5R1l3_onz&@z;hW{?o;2Dk2{h^4=6Xynoiy|0)z`L_qYhQ!!P*jfbyDEY-qXho8+(dB z(j|*NDU6@Y<$DuTaEkSPT(;dc((}c>f~fQFA=%+NK5td*Ee7oYOL6RTM33bS)MU^}8z+->a2 z`|VIyQ1R#^GA9dmIBSEMj+TK^D|Hb6+xMG*-RI?dAn{ zRO+!w6iMX^g~=koQya(ht+f*zl+~U@4V%h5{^TekLl{|n7=k_*^#l2bJ=2Q^>$yUF@ch-cFYtOGvU6} z4iEsiwRuhwjlfA+_8%nR)hEOEN1ggQq(ZgqZX|qO*5CEtSOs57xxH_bk}?OoAnJ(c z&%8T1@?;Sht5G@Rug>bCHwC7Gp8|B-lIG&?7eO@h2;@a$G+jZnQGFQLKuENBah{SN z9Ary<-nl01GnUV+(&HRWaIR?Yx+l&YIQK`P&&w=K>vJlumex*=WHzBB8TWqP&}iRU zKM})D_qNjJm&l$hVCABjh7FK2J9;U^ncYgB(X|J^WQ<1IRDUg#!~p0ouYRwOtpZlt zeuK@MfP%*#G35!S3*624@(0wd9?F#>%_F&hoEiWZXj0-Jx2pn`rXf4ET?$hp;!G0b z-d>`cWcxSajh;dRkoZ-5aqY4TvZx4$4w1=VMP4bdkqo)Q%MT7y#` zo6>mc5phP~V;!ak4{C2I(8YJyj#P+VBy;E}oap(xB#`9|n$JE|k(Y;X9KBn|ZU_7h ze@$Bw4q7WE%q&^`%tko;)=n~ohB5n2i5<3blA&=q@=Df#=wvLf(!1QTm{VP`&oGGo z_^EWZ0cDTb7-j{C&im5tT8kj@07!I6^eFmx)SOs6O+%Xx?7g+$yR83+bXmel>>1)K z+w9bFtO+lUioA==>IypJ*2{TV*xK9YgiF!)!yT4`8XK;(_}}xy^}vM9A}0L4H1L_M zkvjRLK3T%M&vC7xeJ9*REm~>q>a+T(L};1}d*?2e2=$NF&SveqO>VgUBX@lYv~U$f z(Kijy<$o&S*}fShmB~gI4Suk=Y8mR~%U-Oa%ixAAJIdQ*T;oC~+qX?{H|COT1jv-} zJ!KTB%5KZcM+USC_SwHC@!Nme+QpSP-HSFh{$?WMIm6)M@A2$Q> z)mPM&ldPrh+_7IHtwkt2hw0nDt#pFdZy)r(3-Ha!Kb^1Shb%PpV?`@%%WcH}VDzs) zoy<&MI-d0>r|8}8%((W6PAYmZxi?pnnvvYtlEXF_0{x2a&Octd0Vc?mD0ZfMYMKY? z0|uggDzh`>w+CymyLL6r5VuFJq193FBkCBP$a-MA1^1UP+ovkUW-~~$;$8=lJsgXS z_FwYUp6{tnwE<{tSzZuA*Twz%GYtspAGWBAW4VysuQ~{zi8XD zUM;S0F}@%7+u_c{-_%p|ZxCcVSeB6u&OSw~vl{11v*WwX)}x59a`yD(Iax&P zgUxqwZy~URl{Wy5u?nn~1!MaT$CIWUX-gy@XkqQr-cLUpVbwMv*AFK%XC*y)tmE%H z(Hd0Iu`0uNZdkHO>L&AiIBYBzKx7z@_C&T%FU7AU*+8+LIQTfb(kg6U{x^bEjH-DX zRDE`LpLyS>!M;t!y@yiw?-#pX8~`x-F9e=+ zsA<*Q5cu8@A&kX%oazbGDUT(ig8?Qaq_HaP&SW=TZ@ClhY8@Rd(I>nKaU)V25wph| z&8N}MYvh9)5_5=gZa%yGCHn&nIU2C5Z5x=RbZS$`*7=mT^zRC&Jdp8&@@*jyIxa=l4iOF4>(lnKwe&)dlry~-PkutRhzcI`M8TdDG=-LMN zU?NM=+#1$nkSTfauFjrvolo1x_Fvw}FTVVc6}6dTdH*mey9Qa_E#sr(;C>eL+pk0C zOF#S&$yLl1Un{h*nje=W1y0gTDj-6>EMncnq~1dnsRli&*I!nWpGfT}33UUvTgA?l zE)th%^^rZVxxXUz_~6XxgF2(Gt*tE?iB^RCnM9)?2I%~a?XgqFG|T@EjkG4;VE}7R zeVV-S6d3+Z9-WWEa%|WWf+O&F7n5$OeB&8{V}`SGs>@(h_h2+7no9TGmI*l&*{OmRM>U`Yh4Xoc0 zUfy;@RMycMfjL6CE4w^#De|F3rRC+~4k;bms7?#Hf9j9-(6KtJ1mHHHS|LTt4_DZ( zWmxp9Pa5*mxIX>|r!W_Df6>Xsd8lN!?gOm=rwz;%uNhD_pzIi>U-p}_wGNJE zq@<(@_po2MKGnte0B?QMDr8@6n;;jjlK+PNfJ0l7=iW^?qkA^-oCU5|egq#Qw&m_l z`Y^}Rjty*wrL$jE+9@YCf-${zo6IxW(22HNUdQc__r|5Jk>VAQaME}af-`*FN{aPX z4Gk>2Xi%6@(QRA$ie1WXpQGd-7U=PAW;zYe^$Ic>#uXG9N25nQ|F8U%;~*vw-UB-m zxd&e%roXDm9#w8Z+5NZGpIoui=fRPvdp%V8Sbu%oxt8f*Hc}`2wS=jhL5-Lh?q!oR%99_rI_E zrT`J-WfvB1;fRe|$Cqw-^jammpHgf;L|z#>z<*1+!VO!uC0CFut!)mt&nTEZ&kVMF zu-9ekS9;H)AL!VY+u8bx0-$Iird%h&UzQ!{srlihd}fa_v_t#& zCvK80S~wvrvKg8I=XVcFH{sjObNgP(o}y*~k_T$(qBs>c$%!=rz!okFG2%7E+q$ny zBQPcA^c0P5M_y;&V&g~*OZO=Q)O(#buZ+eUc|b3`^{2o4s5&QZv#!%9c{t1}(v3XZ z^=3tiFa{a;s!Bf=b@x`Y#8elUF?~N?vmU1Zveipu2p8>P-FKS{uWx3-svP`(m$8x> zjYbYRF8KJ+H~GU+WU+i{75x*}?R~ZVm57suG6y&?6=$l^MZD85sHj>?x@nfBIZ|*0TFgbYJs%V(j35Hyzo6OSf7`_Z&XZ z<~m3A-mJm}f3b*bSu3|tFQ3jvgh`^UC|J(|6+=Q)#m*P}u(^4MoONHLcW=lZ*8NX6 z3y!qb%MoMFyKC|gH9UMDW|0Pz7_*V}t)^~|gMR}CeT8>>D5}_%zIM}xrSe11fQ#};v(Vn|JZLo``i2G6pwsLvIo(!^tO#7N7?E4-E zY>V@;a2n=ND?_RY^8l^mLZmfF2c45Y3w?-fU!qSOBLqM3jmkQ^ZP5;bQV;SbtPxvO z?~DC1a_A|^2K27;TfVcXAHF$zY7aET56Ep?{xbsFUWP`$Rd4ODOcWw|8!;HQ+OIA4 z$QE-|s?nfz&Fy((fwHD?zJjai0vqmc-t*;UTvQ{DEgKxybM;svRW&t-j1lmjeJfkK zGA}LW6eQ;}zy;VbZ4qd42t-MF7>7+m=PnwB(<$OoBFWgYt|$_?67;lONx6IBZy%uXQ?Q?ux7Pip!H6El4)l#S*fDN4T(`Pm@RlU?3WxrUC?Z# zWPnF1%{gAVqhuN3H&hWw9Dd&$-z${#SkX49#Rj*+r~Nebb(&urF8gMqV@RZ_athcx z58XN%A`6E`$T16KkBAg)n~>n=m#lLG{}%$W0!8GUU^z`2X!1}$+E#M}RkGE-v;D2y z>=EJaD6FG8g^ZzST84kU!X0C@BbgQEKvxI!;SU@R4o*hl3}VkEROp8Op|ldwfT;{9 zM`6B{6crSO4Yc2NFPQpSaRj?Eu>!StW@k;%`+H;$%@C&iZq1g+Cc541o$#T+yhjbj zcJeA_7#8nAkwa6++MPPQ6TI#At7%v{9lV*+ces`CuIcf=EfL|ecj{itETcf^yFym`tcLAmH@-g$IgQ-&7B0y{~#dc>uZf zD-i6KpsVmZF9^`VmchQO-#+tB1J9f)j$vD()DfvJ(BUmEZb*bbZ_3M$@3Y;uXCq2= zYfj=J_kC>X+Xx%RZKBq-Xgx%L3ehHd${_j|vV+~O`Z0T%>vO(MV1{#V<)zVI(RE2! z{%&;FiyRKv5}giM5=LPion8d4oRaXG4tBq%v|(zj9?0x(r}9hyr|Fu*kTKxQrd~Gi z8>c~MT1d!rWvR5blwLm7Oi_X1)k1La5;IXQKUqjDf5q~~Grm{QS_3%LKRo3dXQNqg z0Q@~!9@s_Dxw4JkJvDvY90~CL0;1rEL&|l8ZGND|o8mZA(G^gCSaPos#SOj)z;0Ew zR{*D(zq?yU01+v@I8FZo6{jnMvD%x-B`m~+W~f4ATD*Aq-6kT@p94s$`s4=gER%!| zsni{K>41rGDHQC#4B;wSlg{JfPH$UFSX3)~P-j9rKUc~*m331)eyD6{n#lok zgODUvFq6tK-HzMOUM|u>@H?Kxk=Jwh;&-JiM;s-z0@aId8~Wru`=Dwcf76Aoj+v3m zut|ab9ix(Pz-(#0C4D2Jm4^2rfu0FnS5fa)VQ(Se zkoOwh9mlx{v%iYGDi@rYP>aOqui<1Y#Jv?xZI}0~*ocCdvs8gy za*K6f7=gP5qs-V};NpOsbl~>o8V^mF`TH`B!>r0#Vx1$q(5DkFJDf= zMOmQkY`l>g{Wj1kI|RPRa(A-ibmE}!5Sog%& zm!!`@?G@@OcXueZJ*2t4CynUH@5|@NFWY#}y(Fo(0#$-kE_vI3dGxOLkAyM5=54ApY~{pgySAH~WKFh0jS$1?Tjtt#nK!-bDtyKM6Q#tvSjwTelq zB&>{@A5!si%ErOiDK$-Ty%mNbe@#Tj-9YsqRZmfxOVw;2dyTU@4)2g;rktJ4+T`$s z2jmfe;LM+V3f%|j$Rl{N1f^s1H};EJE!lnNbUHbuRJKcX5A0fe${J_0gN;qxmCW2p z{{n~3%}r$_Y59q5@`!#HnehAB=8ObYcf+`$z@~6 zdK39mRnG>osBrSLgIfu9&t-f^`JJP0w=3L}k;eyXZu~zXV1yuh2y!)*8_Ksd3^!)+ zBA8{^yvSTHpgS`G@!+NLMV05q&>N=RWD@cklCSvK1Gr$fxX**;p;gC*VYyT2&igJ~ zB3#DZPQDy_y>}CS+eo))M6NnHVA-i*&k3Lf^r;ui zy7y70;+xO_zIH3&kOi*OpwlM=pH`)!FeTfT>W&QYx>Yj-1>{gWHS z2gKSbYY(AI;AUyB=8R#ah7vJqY#gtZfn6NFOyxk?^u!7;cQ~}xA(#6%Tv;@0#t39(FxB#Zd_)!6qo4fkzvtF7RrsierV137LHn+^b}+m5vgT=`2S%P`-I z;dN8Mc&6CI*tiPhS$ikt(CfgLKIi3aX?+G%Gx2R9dnHeF+IRnN9dUc!S9@Oh2YDq) zihKS29``d@NXR;5E%JT^o7ZJRMqx>eE&Ois2G$wp&A{bGSc?!yZOL1j9dp2C6`SjsSX}eXCCR+SZNBWX=Xg7wH>Upyq_ob)$>y47Ja) z)(?VCpZ%6~tPSOOCZQso*+;%<+F);5jHW68-5*mIb44iIJd~|ENsVR?eU-!N#c%25D}kVagw9^1K~Ya}Z)yMPq4AVJ3R zUve^?I+Ao;xi2b2HDr7B_4Zw|(au-eg_CkzG`l)_Zt?L07Gifa*G;$VH2xNLePTJ> zfHTGG{6q?CbfOz~>Fzh{h5>zl3-*9sR?~TTu=dDTzwXBFx^rw>MenS{b9+3`%t*LoJh;r1LHf3Szd2J z4<=moXqo1_YV3{h&v+JQY&1fp4SI1A$>T*;3|^Gu^)F3pl}8@RWcGZCS~BuY$Ep5h zxG-H@ShQZTCn6|H3R4~S{9P6BQA2mKPIB(tdjdd|@ZzqDmMK`!g*UKGW6cVpHcyRT zh+qlu}soyF-!Q9>;>dQY+h3SM6LtOTqm6cT83gdAD zs|TD>ArSm+w6p@kovfSachf5`WW%;vO$)nCZ*zk@mkec00g;#$)}a6|O!;BpJ7R)v z^E`mc9KHMOg13?$`GEhtu4W~DE$Wf_53>{h0xL75QZ?e>tRUx0O*=wW?B9h)3*vug zP>i{DOReZPxc)^oXXvY3W9esh8hqRzQHLGaIh0yu{8Zw9*g*O~Z;J$#25Q*}4jgu? z_EW7wt|KS<@f9`K1Ec@~`x9wx^yu}Q3$y2+WKS<{?AD*<(oD^o=*)@q3k|RMh!U_7 z4-uOHHJLZpIh*dE{+D{JlDOPz6yq?_>6-S@P?Bz`hC&I0c;Dxhb9tbmWV@Aw`{8pSdRiekm*Q06A|ha{Whj& zw@%E(fNK72$2cN;7%&H59FlT2N91W}T#}s#>lMrmi8!gJ*lWqVX-;bIx0cQ;k4;2U zO;I$x;fDG$a@0;19wZ_!@{-hQ$}lYh&x?{WH*J1RX}9LLMyi6UrjoY2A&)c= z`?PHxFV|48PSE)i{IxYKbQZE`&nl{jb9^;=j+WNN5svduI13|bh7xNpEiF4F!xZXEdU7q>d_9AF8A#EMo23)fue?6#C5t4wn(Fkn#)Pg=ci7qRrDgC?ML3@!$BdM zSFU^{Y^H!hz-0E6hze6bAn|1~4nP)cT+#P>#W}jOj~ZQN;>cNUJ({o7lnfwc8c7r* z@a*aq|HhwM_+Q$cd~Yh%SqdJ+$fxYeG|OEw3j%pMdP(F>a6gn>AEIbAK+@{42l~5^ zXv|uzZs|(j8!IcDi+l5m)8>yK4sHhZ`?&@|j(!t%YoDKS_c4EZdiQj4|6o90Ob9AS zn1A`T3-Usj$)Vd@hw704icU}#i(cGu*6DYa&tZZE{>H0;p`O z0teCGw&1j~k~OTcbJ?ChuZiL8)8t7BURk>@L@bvFxlN|BXX1viz&AXa+-JXPDa_wI#yYR^d!hW3f!lImzjPJuIc%8n&tE+T$2K7GT*0t{U0+Lx`H%!DMLug$_are<*v^BJ~RvG} z@6c(4$$Sm23+FXNRT!W5V4hTkR`gl2{hFvs^G8moaDaN-dUf0iiM4yB6d@+HfE0$~ zuZP)LBwICog_nm`3{`KY2Y^f?>YNsiL zM%BG}VYFc@2s0TFtpKYFIEx>!tSl|K7zgji%GH$C=JM%HQq)pN#G;Tny$%z za4%~kaS5~kx$-;Ulnz9z2)bVIz6j|2Qv!|20egzp1Q{S6r~K{%88KXWHF< zmC{TtMgJF$moAo z+wO5-u)ixHZJ;sjfQ<%a`4Oz$ta9FN>S73&{N}w5_9ma`3LG5%oD2AG{bOEE?(DI$ zQ}d#g%D9MA)39y!qROx}9$3-7-J^JiUOThQ{n)r{Rvfoa3G)o94;=**I%+3`I3_M5X#FC_-3SWeMMrKlP($x z&e4l!-JYl%j>w{G>4Hq!ognr}>?+a35|F~RRoAT;JPN|e8ZFc>nr?N44g;Y%kCK;H zJbx7VF`2L_u-%njG=-ag~zB3Wzw`(HZ$os4uM!_`AJh$?L;H1H(# zDb(*{GEq#U7spO~R3S%X6SgwvlsXR&Nx%F*fH*uQMT3fdDLN3Fa{)$=PBN@~%Wb8w z`ogg3JHNcG*ACReK?7R!{%ykSV_^TondWrWC#UuntiwaxTqV?8{D>kdb!&l@s1UVM z-@kdw)p*Y)TY&D3?jUhiQ_bNJr_FPE?(oVUxF#ktDZCg%R&h+C<-Zj*;x{ajp=UFG z)WKZlQa{K;UWIkks7!VnyP?q3BB+7K!qzOjY(32bPi+eY2w;@DXeelmw?S@zXg>>d zaXwNIc4a*RWn7mwQ2HJs(HwN+pfTX|a>Q1{E5XenMY_@vpZ^&<&I( zcGNk!25T6bsiA|(q$W)-A8ip{@Eo4nc4g4MAmo3LV>%3q+zqL61Scz%FHyTEHb((E ztgV+KeU(!okbCE5|1f5G%|jMoWS(Apn?2->{r|=Z&x~286xoF7(-*Oq`K@-*XcO!3 zsn|wpK$@*=ZDWpj0%#-m-R23Mw*LpTKYNn4OK#)8Xv(u7O8FV-g0Vb1(7*Isd&sXt zR1&jI_sMS-t^xmAfXA)~*KC_kb1M%TC{y_AN#TDljiR>c+DNm9#5kR|+_l1ATli69 zt2KW%-CWA_T>C346#{ILu~|#NKGft4UJT&KR|W&L9KOey;uu!A9v}8O_Q#GaqU35e z?+fbiFe)9(Y}5@_U{etPFO^e3X>dDuQ(DKZ=g?2JE6m8fe&uECWn~$ak64E10C7{C zV4PShP>I4ALB*8@+wj4)&q&z_Ey8EWE;RZkfH7{_vNW^j{m2KS~VRN}NBtp5rTd zbY;%)scWCjon6DVP!jC!KYee}nTQ`3zubSj@4emS{E&pVw(m>jLVi~9>0NyD`9-K| z#EXggTfU!Iq(5oy8vWxwlKTe-4vHduP zIku-{zu2je$4sX&-8=eKRs(jmw<~|~tn3awhk|pfL^frxK@aM8wr;s;DN2Zw<*;;R zGpw(sR9AA3NswaFwnxt)M)J6~9PFm8uXLge;vsJLF}ww!y*bh*#8z@55jMOg8ug!` z|4%WB6=dQHDJ|VOiYev-q-pLn&VT%k`d8x0#erzJ&X7B6Wo6|{Qpxg>11hfYJTE3m z$$bWvNGJ9@S2ko&3Yr%_f}(VKg*$8Oy~j^Q>zY0rD|wWp9UxP;RO;{u?@*TeP1N?C zcQUCbE0LokqsY_3HWxL8oVSXZBaC zBg(&L`)q8u67>d1`WYE|cp!D&-q5#u&3ikWC~C^47Me>z+0@V(0ng7&nW*NI4woW}adguYo0WFyyo{!~#?GM&0@T|4+{bZc;0-@g6hn+nG~ zd$V^jilW!Cwc5ny>;p^JpAH$yIc1RB=M+qi{rO#o;lB9Jz5nuoPxfBA2>nL^djiLd zMlSBjV!ou4=fu=h2n!~p@9b~;KicUM9=}(zH9%N&s;MaQ$$}K-ZD`=TA1b#meVSSJ z%(Rf;(0>#0&xJJ*es_G2pXH1=(Gt}T0XC3wRa)?-F0 zM2@ZsNyGWB%jhDGQ|pdRNoU#9!?DC0r434xnK(s!;w(~B^U0qnd1`NRYF4G4iYT!e zLJuU*qZAacEfSTce@=9$xSqE7>INjQXAx>Ds(RoY;VADe&3C=Aq}1;II`{7t_&TI{ z*g+{j7TD*#vV)-gcc$#Iz2)1mEMD0-V$sh zX4Ln>JotZGl`bTIw@qcj?>I0aDZ%x)TCU2@lwNV{~+I zK1@-lUQ3pNGcqs9W3L_nl(y}(3hi0Xn)4A@v-RHN9Mgjwo2&PKr`O+$ryp)94-N%VY6fFgVsy%+A*z(S?~R zJ1i>GkIDb{Jm-mE*V_Be6%rBvZd%+}FyEWAELWq4;?7oR+-qbUqx&QxWRuR%Q>Aqv#MhDK)M*# zU(C1u_I+OQ`kKo^WOa#DTMs2QYCp}gaB)v+*E&OE{3C}2K;{Z97I$aDC7R~h+o@Lr zAP~2>xAxJlQOx5SUjK<$Z5zE0ogOH0yvi(6(*rC{{99UpARw#>5Z5>y+EBW@q_jNV z_j3M!?w!9-&Hcfb6cC9Sj0EKTx;yM6-*>+77(H@!=Jf5JBp=%uONEG!?~*NSV_R-R z-!Kcx*VUxiLiNzZ1BMIWmlLX5*FJ;d*O|^A6cth5M_xAxVkNt_+&EZE*Uhgwo_@%6o-;l37mU~@b> zk`KvBKgR#wP=$uoznQQ{ON#kf-ORetwLwofh?mZcW`crA7c_jO&pT6r^ITY^+2pr3 z7R8>$)vi+s^~0E1kkyzB)oXu#!KISKr*I0UXJs%7Pn`y5q;GG#TWhI)3{KKC1bH?F zt5>h4@+hjy&V(9ZH5mF0?fV7BO`mvst=}0EODD2CTBglgc?aL;7?&Iq;~F^m&~V{z zGR#mE?dzNDB+PJ*_BAq^dPnVg_{Vx`Eo5<_OXHp|v3d-!hB|j-c$d2so z2FRgW*9_1!aUK>n$T~f71NkafoX<>di-m;+9Vun|m}Or<3L{-3MW>oKByRoeJ$+ke z)ktjES7IQ5GTe`Qw>&*_F)ju-lPAPP-g<#tkmHwq!I|0UTun+f2F*@fbrM~twA>X? zho0%uAaeRDwrlBGb@HB-1sbGsl^TtkhgD+k{Xm&m($LtbCwO8C8M$i^9Bc(1sZ8jm zQ*cmFi}zr!B4W;rPk*4*@U*)Ja6>gpi8u818Qj1_P3%ox0aZZ7zo~rEKMVc*jt+i6 zp5u0_pTcMZ{)<5^GYgUpW1iOaFB$m8yg_FdhLh(}!N}z#xTw7|UG=%Pts+0o?%iN_ zzQn-a?D~Npx+g9Um#OU)IAPWDX*}~}HFG85D3B=hp4Fr_s3plRwpzbJn83Gt-x-NS zl!JXj3YTZmlYTk5sGyQ-wKtWjLP%zEihGwo(8Ps=vqGNvFgQvJX#c_UwNg$0dYK%G z&(B?3k}#8#Uj$Yip)d@Iu?3~wqN1V}U>xsLTX88n41H~_QyrMh2m5rjQguI=JXOkw z)O)(;l<{}9kx#1n?OlX62lr0c`v`Y9cTxr9-6FbE`7Y|dF4~|KVYRhzW^sn*hiA22 zefMs@{4*yyv_&ff`w~LYL>>>*^H%0+zxERU`d<<^Q)@Tvm#&T|O2EJsmre;c7@T8_X$Kjf#&CAPt;W@I%&Q#8o;p<~q2?^SfJ;uJ04u*1@eS zXg8pafRw3QABFYbe{DgfE9499M1FKlJZ<6&PAncA>97HSFy!0o~| zDEjy|yh*RueqgzTF>>2*cCh276r$;hVe=##<4NBuWND$$Ne}kn)Q*l0F>!Zd!BRe- zf281s`{L}lbH@g}pg)A$Eg&*Kyx(6Bn@SV27eX+HZiSHi&m|>ST0CYn?`6GikoYD=y5Dxi z$Hbg1PjR2)b{mP-94m=G9?0 zR&@OCJKa!;jTaRYGv9SIa}h_|2qXf$gfS&7PvXIz)mp#C{Cz6e`gCfaean>qWS1SG z9Z1e$&|J~E32~;+vj87fBYAsZN!iyLs7flc!zrmu?a8v|-Mu!+ z^m)(i(SvSeir~Vn5vX5@HA&1O)o`)_lzL70Vz=vN#m)deo2}5x zUanyYY-?CLeUB+vz+(>`%91WC`)N6nk<1y+wauX5h4vWw-j_VK-ikfeVrkqz{^29* zG`;MC!otjq(~~V=9_RxI`i8yKuZDdt`l*OBVBty`49t;9a2v%DIjYI?Gw#?=epbex z^D`NjTe8)qR)Jds+)IH7chna6oT#dT7sBIgu&ACpH#o=!eVOsg-YvF6sq(4+3@T4U z=_2*{ID&(h1P~S8cko@hd-LYad<(bEUq=7w;3v5eUr;wYrdpf_GcX*54a~-?6Ey!y zqNXjCCIdT83932|O`;N?eT?i^Nl8OZc^0*`LArq4)#K44qY)1^VvfQ*JLe7E$zn+% zu96egLNVd>Tb`cY85o?uZ3Xawh!e~~9g<0eyFx{n4*^m5mUIMPU9~!m!m77HbF#4! z&5?2b{3K?D0wpW2sx9pA4aR{ z-kG4Ij5eGQVFcfhoKi9ICCHaeVvE?M^}?_z*FKs}gI|Am66;cH6tmrr)b9t-?_>@g zc$8h#n!=hB930sspi7|#@g3Jk9|~XF2RnQYi^t{22T17Z-?G72T%CffJQ>D7ql>-n zGxGMW6+7eS*b|%8U5821A>&9Y$W>1~R$)nkmLM|#)Q?Pu5V#?yaqP%$U8L_Ehy0>o z#izZCN#%0rqI0tTU^6DNr?ZX!8eqJ0eVK!otmhYmzV9Wn9aJP$X>XHg@YD6-KPW1r zqCvrc89+O!hFgX$IFHg2kREn^t&!_ey8kmD*4}?+YvB((Ap+FosW!G>9WqcToZpKh z`y3T1oJP!*LHJuj5BF;VIvJCjr>4<7cK6>^qggtNj*LajVP@_*6E+)qeSN9(m7VdC z9gC2-j&h-0qY?aeuT;=mEyOKYK-ot7uTQ0hl6|OrI4yc0Y2{yGxeo+Z47elGL;8Md zUpGY)3wEczI5NVu60Fn!?I77qkaX45o74FxoTE~0X=Pd|m);BhVj?c|vUzR1*9I8n zr1!GI*Oy9=sTVU<5cK_7G3boxzVo4wul6?(7b>rwLFiXCYJ9YRsZUtZcMy{7i%|*k z<>y0a(wY8(F+5#JYy0Aj@g;oWiw@kxpP56l_Mi3yUi%d~UX4J@U09O}p*hWcV_Egd z`rMn2&{oVKb@LzZxK3YzJ5iM=$%2zGR2dwSYhvhaVkFfT7u)YKcd(oXl07>3iZHVEcUPt$Q~MJBmbfh?WJ>NVd*suzl0u z6p99B`!AKM`}75|0_p3}z97+!5a%mL-khK12x^wFF`_p{|D}={!@;z$WG3d)n?T?X zQ`Ry|*Mx+O2pRU0LSj<%qjgP1tE>VTMfigQ{qK!rr_?|cg=~IuRM<1LNnv|Tz3^@Z zH9tCpIp_?xd?OUN7gB;&NC-Qes&lg_x&-0Cd))LzlCY*T$aE2hxu>JCx+$^3p9*^j zMa;m5!iu{IC?d9JzbavQCG%{-QJi+YS;s~^j>AO$9Cuv=s( zw?qwOECAE9MiVs#w@@6T_BvH>Wku(!^qdL@H+w`#twfijp!aXa98Do2p^2eCnOw!1 zVTQ4r!Zay*WicqQKzNWJrz#?ty)7p2{8PP}#mjc-f29WB={JD0Ep~BnA!LL^7cEeg zMnY*s*8O^|r*zx&q>f&__;>{TNX8D#r@DF~RIp8-Uf>J+o~HY63;naz+qG!m(qpjiR=ZEW& z^d?@GI>f>sf~Cx=D?>-qjkugxa@!v})9xYpMk0!n9wAi^7C>wQ&p%8f9sk4Y&6>b~ zOLi;9GMo?>c~`zE*>JopYTjI6CkND%$&?!R^TM<(1zfixUrgV?{5h zI~|{=!XlQMV6PnK5*$i1EJ1{=dEEmQ|ggZE2KXD>djf6G;2lyedp5rD@gK?~X<}=(0U&?7FQ6qdM=XwWV z`#hBH!xttYj^#f-UKgdJIg;syeBl?%+{B|LiQNX3KSBlv;EnoIQvgy*r&1SI+t*rw z^;)Br8WFYl>1X<(aOa=KtKW6l3=c!KmkghoF+nVSrD^>pAkZzP&StDi2fWEowhazJ zKlr|b44OePFr`hYaFTi_QE(fSI+F&JoF%e|sa&m+L~rnt91Yyn_V4fSj+Eq}bCf6# z9zT|ZorZ??p`}xkp8UvGI&o|_>yjm~JoXDC)u@kz~5PN^tTL@pJczYtoJ8SFgxas8g~3ei~o6yIxihv86BxjRf%Nht#zh^r94F6?IA zDCXI`z5Jb#fC<-6PULy7If$+Hy&i^$`=<=^LA(+93TmbXE4?X$Jg2`|s;NS>o$hWu zHe2eh1>GVZj=Z`c8*(hMHd*z~MQ_1B@At~B09z+KRq5x3viXCHTT zBAc^VKW9D{{v40Wjq#*cGFLLL9m>;gg`%qxy9cS#0$D}}=c@R7boSv@aOT`HS^C2v zDf^~E?Op!kd!UX8t%XTl7Xmz_*?xd9m%<1k&&DGyp?I(|UFCH;eS_mN*J{}&By|4g z47{;%nY^s228Tx=vq(l6u3Hk=u5@|=u;`Q8sMhqj9$BHYi+G$UCgPIpS{lj5Z{=p} z@#%bK?`|Ql;0UdgEILFpskVr+x)xZ7tJ3MC`Z8mz3l@PisML0Z7tp~&J5p={<^3hq_PVWuH9=KD5p%{;gQ;i)8hI*Qk*^Z zkthiz(+9HZV9PYi87-BV-t)=#uwCRs0kmazo;q<7k#RhOEyf)k9*Z2KdM+yz0Gwl(= zzu$9hCAB5|vysXaGS2L+wFl?w6RYJ4_(AGUsM*rw<5xF(yvUt)VB(kXY`v@Vk~~yy zKLO5?2gQd$1M1{i!9Gv^tQvfkb=Pr-(7Rp@R~MiItm;I^%3Bg`6NA#HN+)u3N6yym zs2It#2fYbup8N(1eL@mDP;!}VnT@K?jU7qXPF;|Z&Cy$MmyWX9fc7*&C`ZRsFCt%8 za@uo!8Nuhgj!?20U5eF)TU{3`+ip%Hy#8dD2o(J9Ot7A}(8O9o$^SMVDY_yjI<`JL z9>pd4!UcM$x{XGMEKcrUoU{*}aDFA7&tgI!+h5I{GH;=xrEoOr3c=U!oryXeA?Ng2 z_M(_73F6GJ?1V8I{||%>wR+ zcOXv}RW_6u0dXz6dAg96Q!#()`COgeUhpfT_c<5{OB&YTZX{*sKEeKcAlp~uLVGeJ zc@7~3gmU)-D}*Pq&fF2|KiFik*{|tiipGi%&=tF9y4-uR1A_9ynT^a77D8c^gvQY` zA3s4j$m=aL!hE#cg#%YASVVO_kcj~P^*~XA9 zy+Pi85G9;-i-(L%YH_?mMpZjl)k2ZW#o*`a2iOq#Y}u^R$hG_X^6~p)z4*Hr1LQ+vOFbpbN+#J?j~OXmH4J%2{YrXGZnEZIz*-alk% zD6OzXgFtI1mpwbJ$Z0;5q@M$_5J`Qf_L5mKLFtd1DaW_}{h8HvAdb|51DU7UPWQv1y zZ^d_fH(MW*U6Tnz%sKOOBl@u%KTN`&4^poAitAg#WYRwIrjMr|Ls)O-%;>`H=N6yH zK{D-IKXc2H0iz2cmb|n}x)NPv_-H5eP|gpI~}EApLFA3KnQPBXtIk;+Qm% zMHnmIHPKx!IY;j`%3oPbNIXkl3B|z;)u{0C=Pi40+7g(X^e%PqCXJ?UC;sf@4v zbsnFFfK$7<;M^(2IxD$s0t9EL=|x za^3b33v5=LyL?t_FQBY2m<9yGDtBD2BA;h<92~=x`#E5H_V_=AVa-IiqwkO7Tq!N5s=W0YC^t&(&zpN=3Qi)2fDR5rl=9rNMxy?H`7ZCxNeG`rzyFr`=PHgLhXO9;~ta>$$AMQD;d@?xbI0h0f~jLx}w0oZ$HwAR}$ ztjN-imB7IMg>_$2n~ zUVJ$0M&mFp{BA{y$~9vi_0k3q+n>$2`hlN@GL0v`TM){(I`O#ZHc!^^JL01cRXl6c zWto}z$`)rl0)8B+V{;en1zi*_PFts;t~HnW*x6icb?UA(zz1_GA{SC z1C1$~q7VTyL0TTN%E4(v?!nHJN&aG+(vQAf?ZvXPZgR@gxGzmvvf<;FB;H5lxh)z@ zKI||NA_#U3!A4HJcY3Y(pnG?)_@2qSx)-;C$L$T?yl$!~@1LYk5T1O85 z0F_PI2iKxlIOx6YBU=gA=v5iy|2&Wj`k?uX?XWqLSS>|bUrziISOm&c zJM?N}RpdE(8!*VOIp7=c+~uTN1LXe-JSkpnw^}@qV|0#1v*fPDW!K52V0_nAX+{L@ zz@ZNbI0YsCM|b`p)Hw524cU{rA>@h}` zCW|hv*MEXfrGvV0oa^n#_;6Wj6Y)&Bb-HG#Jp9PdQC<|A4*CH!#Pec@;;qTsA7PSL zJh$N=i6y#}jYMPK1nij*8<(@?!3VQ;#}RhT`by{la2k=?9G3itYpcljXU9Y8KyS^T z;yX4jBDVSCPf9kS+E3(q9VE*sfxdA#Lu8==*!j!ZXOJ5>9z+@;8uVRN@8sC)VZCe@>F8bVJH zqBBDQbyxAnGAa|^Ew6FRz}py67JhC1d1BG0%5R{3K!IlU&fPv>#5lC477^DpKmmg7 zqxF%ix9PITQqU`Z`^+?ZQQ@D{3s=dkx26$nEAACARg|gVG=~+jQ9JtIupC zhq&(D7$T#(D}1Hv7MjJ2H%cAkyJj_-kheiZpD8xAtShaw)?uJewMVhEtldHMdQ4{G z+qxm>hPT_@H5r7?w2AbWLclTI&>uA5xdVz$()bG5wBR@~!(PCuDDF}p(G0@FX)-g> z`qBrN5K9usb-L>V(?cE*erD<_-IQPq$nKBR1O)s1qx+H~6b$i_063?~!Z}xOWdn<( zZ(2X)%SOX_FN3N=RNuq>%?yu&N0_&{Vy#eab0BC$Rq2_H>o{5u(-+xF@)BrLQBh8+ zTiT1h(S)q8(D?(VLh9Ye;nj+FTOGkUMd6qcmJiZLrD3zxS%{Mb%i-+I-@|1OI4>ri zs9wq-7naA?c15x4Op-hrsA2M`A76vR-^z;a82p+-S5KUV8xiUz?OqOB@2cEHve<%W z6?cZ@n{%uLL7H%~@!7MH6C7vc-mK(ccls&M2(gIdx}G+#?nEozq^G3l|FscczUTMV z=k808-@mD+qX!oOdcR)^U#3*Xp@HBrt27TzS4`<$vVCwMo=hr0HG|yl^0E-#_0x7z zOR#+xaVEUE9%fT-W;RvdgPL>Y_GKrnKH~fEbLgM%%ye?H^`0PfrZ0U3)LqASDhmgL zg8(R{<_L--xuv!oyQ?UN6Y_I1^$!9HV0y4a24f`}OCHC9QlT<1@+hx7w}8SeJiV@r zpEv#i<9Uf{${fG9nJ~M=jKOz!p+Au^t-nyT8-5XOZ1TU$k6;0GLATk!D<@@6 zwK(rwtzrGSEIbv(z>~!CQ#OG3N}B04IV?K)ty2O1NJp+iJw@^8Vq$uDq#8aJZL|)( zyBU6kF6fYd+;a{*Y4~J(^?4TYk}hM;y!*bQp(PkMTs$|eRpZZlECKe)pHh(ze60BB z{5ZPTqGJpcnBC8wvM*mjd=z4_cZMZTD47hrIii*qPeVwRQX73^bNRGpq6@mJ%0Fk3 zxifW?5)|&OVqgDlAor2eIYq2$g=j)u*fJwG`cIxMnpW!>Au6tuT%H_=LlvbC)~YIg zf-`wbAi4Q*a+HR{a$7a?Bj_Kx45HC{`4BdJUqEzV$8+IeEWMXH|L*!}!V8Jsj6SmZ zf3^Vz;``n?>+N_8u}o^c9m)5Xf8iQHl|pt?tG;u!b0gvHzdQp=UnY2+X>BI^4B(br zYu;|k<$uyhOGfm>v)*o=pG7(2&MU9_r9z07(T@svD z%jKsKrTvLI;H!8UX+CUF6vA&=(Qi-`OMFa}CPo1@kgeYP6?439^zW=~;STa0R zW9#tUt`cuATp?g%r5*HKki1nUAMiy~^$1&AY}!iv_0x_m`%elge$xlQEH`!5d@j-> zimyC_+;cj&E^dUP;%8hQuq1}tH+{dhU^BU6e`_$<{%(v1C~G+557`- zCg9KNKO-9oL5METtTCwk(wpfm>3RItDwaQ$aFrgR>cHZ@)*pn@OEFNo(D-;QndK4I zi`5!t$VphRRG5*2p?7(2;J^0WcQZS*H;Dh^<134}T0l{^Q>S0HuyZXadhhWO(s(Zs zd|l3N_Rc+?4_bNMfzi-R9mf&bb z@LgY_1mZ*`$%U4f?jogal|d!V{*R}c(GH!{8wM5;f>tVa+D!1qZpQ{5kDN2@Ff$vc z$;0wpx9OMD>{lyo27#gaGkKI{%isO25Ap98Xs~NiTIDayPMyEJRfDl;CycAj%-J40 z(?A|TFGzR3yH!xR39Z+G&upUDc*6JSl?4t*!B~0{GOa4DLzKARUn@AYCtydK!x$_W zgnE+F0Mq(unj)69_^(e^{IyEm2iVu%(G%k~~Gry~Dv7|pV#!pDS#Dzw*WxY?hEkbaeVmdZHv6z_b zvyB1CBVz%6Zo?=&the#){P5T%*wWdVx_(W3*|F0ztuOX)d%Cxccvzq2gr}Um8Nq^e zcF*dsa~r?Zcw!;m8P{$v$T&)#qNpZWxNISz@^MuM{tn!edPBS4>3;s9+t#ji};^EN#4dQ{v0wvma^QB`ga=(t|6 zH!hsw;NZZ#fXIO-21Fs`zai4i6leqyZ51eF;i>zI1*7G)Y$~?e0OM*oN>(5q$fm67^rS1 zTUYG&tZGx|SyJF1v5O^(zqR^z(z2%}#~2CYf7mXh{CT6Gq=Xq`<1quS>-D8;$>^k@ zpdbU6=V4)7A|fIr13q&0L16gsXgrXr4(H#LV8T0aL=*ni`<_f`g%_NXQ+<+8qoShf zB!@8S12a-2*4mrk^{7POgS_`^0pAYULlj?u!A6ACGHt4`my38tKdmLC(ngA>{24pn zX*S$-xSx6B#rL76Qns_84Uok>B*xmx>OB%|U>0EHUUaf~E|2u;Bm)Mf62o{Agw15G(ypolqPM4M|A{iA2c|AV8pasYS?&&OlRIdc4ESB<{u5q6+B3TUdnFt$?3#N0gfv z1gb_wKCTP0gX{15%^OB!F#)Y*XM9-}!~iJ=$DIU{%hecnCN}=#omyHq@LDk;fDCWy z$zUxA!%*u6=_U3_0NtUt3~M#6aqqQyHxjcxyZAHhojO<8?jmUCXJA?K#FsYZG};v_EWLuZ3qJ;f9S>i_qPQrKmm7lgG~1OU+aT8snXmN` zz;240PrtchiGkZGDJjaqXwqL`2aAGyl2I^l1KX?$|(~AII<$uqDI+8 zf&O*4JX>N7M!90lgj_`*mFz~dQf@L!I~tVy-C%GCqe%?;{1O0zeVnYt&O<9*dVe8Tcm|Iyt}F9%Np zK2=H%7mqbWxMc&tjRhmT*`ejYURK$hCpOVvgt@o4V$udHuK?TT82c3F1%9p&#EMt= z0&+1ANFE`eLh$2I*}0|xZ=8W+j{nATj!~g9BtHX$GV<_{@EVBh!R)*wT59l-`Wef^ z2%SSZh84rMIL@rWbYK?CA9Wx-RpAl;{C#k!`bJs(t;C6q&J+DN(ntEvN~UczpB#wm zxpQdH^_Ijw-XqIat$?FM;PcaK3Geq1tKERKb{M#W5x@eZO!nyKfn$M=Nf<@a;GRn*6w}Lt{24hSl zvU34|nP6U1*$ul75cqxj+lG);NF+BE)}sRV#eA(Oi2?}Nbf4M_+x6)R?=DD z+HqtsoBh-ug!iEZ8B&Lk-BK6guQ1XZxv@IZrzUAr>XIxQ>LDr1Z3x*K5FP|>Y`tno z7fKuO@;;<>$vbRe(XH@u1w^}GLUSP7+00lsh9R}%5D#Zku^U4sAp`LK9`q1W*kfA> z%EO)uEHHR|ia$};hu@urrJRu|f*bz*TFMN;gQqyHc%(WDB* zb%jV=pD9;&iye0jJe}o9Y9M5E^KdRUE4Zxiy0VHrb8$SZIP_k4Cx2>W)+-{eI z3P4KUcT>8F)vd{X-TGjSI7`hXzF^_)0K><{8c;sIX>S3v3ku~^c)*|AedTbJWA!8k zA{5oEa}mG^kYeZ-z(1mZ77D)9T*SMKhI6-~BK!{lGA%*BHTmX19LJI6Mn}i@Y9`u- zDS@FJ4`+xU>Q2`0I$K-a)S^xrsD8;11Nw0?Tu_^T&8^)4tc%QZ0C|EIKu~#0XXlI2 zH`rdi4}Cx`wM^lWDb~=a^*DEPawt20p$F^f<4}PJ+E2aU^7{G`NZ`wx{XN)(&MSS) zsDZFngO?j1OdmC5WZoDgh2{q}V{7jO*2gPg3W&@@&0T!N$zlj{52$*0k|u=Iqz8N9 z!(l_RShzv?`Vv#zNo1Q=CGh?wN7n^L1Gj?{03#wki$WH_{jjg)c((3%xC|So{zy@W zUgu)3DXt^V?pTTZTpD}PWxU%~5a}tHo{m!y%AIV3U8VimbQ8QfPeg6b3D#9605DX!&-B3CKSpZ)Og~ zhP?f52OgEbRJMy%!~YT=5~IE1cIZp!O|*4%$&c@SX*zL?82%U^*zjr0FMCRJbOCSVA$Vc2DH?;6Pg;W@E-}9T06w& z^lbohID$&b6mlMv{yf=r=q3Gi8Y0{R&zgNzkIU+K?CqqHT*KCCh*dPfTTS6u{CxZR0?C zjxouxdZUo#2JC`mM&{ridecju_$fhg&I#`ZyBcY}PTF7UZ1PY1`mwlc1zdpMvncpu zm+Tn`DC`07?tPBSNIV2T0|Rc6roetW(IH(}d|*PRy17eqsR5yu za9-Zf$~vv*bA|4!z3a;xUHTd|6)l`oZ()ytKlJeuw=)lFVRWCRPF`uZIGIVS_?9I* z&CD^f@5fr&kw=Bqs;(BF#W-I8PbS8IEVIV|UJD3tH^{~iWZ3BLoH$I|2lQ}$X%b+C z6q~e|c)m48Q=9cr;TKl6v+eGhE^$1*rzxi$8gBTyK5{LY6k6f(QYUpYwn0^Xd$wV} zb!a)waQd6Sliv-c9#a2KbQ;ve60$h^h}XI}r@w z*fIzO46f+_eoe-SVt04TS9u( zBWeuCWn^TmtgP;FY$nE!Ac7p(#Ut|KfXz*4q7M;fV1}v$2am=<0YQ_=E?f|4@Z&Ab zv(8YzgtC-{#D)Dk)T3Rmi|3W5ETi1e^#Gh_;1B~P$YJzB3{4#-3vj>Ap*UpH0a8#$ zKQ@GUeXA#325#|>t;s&yKY0JrShw)^&JJ;A%0J-AWqFPC4q1@&@RR2Q2`76DQvDeI zh4o*>MRarSE2n4Ow-4O> zB){9i*48%rK5r27$&+;nwp+(iIrHRdkJ3fdY6oS|(20u1Q4X{^)QxE)Gk`%h#@|9p z#SPMz`!d$>#uisp3@tcv?AWNGWWRunOB;$)+gYCpI>P(ZKhqvfI$hx?o0KuX2XrKt z+@A*w3!WS%3C@MPFvK3B=na%k3{3m)Gy-u86t7O>wxc?JSe5(b{GQ&SU9OLLm?b6&&YF&6L?4ub=%PynUBQ+Q9F zCJ({M;o$j$T*x{XBZgL5rnSAg_Xn}7CA5x?u_X}?jKF<*vVBiv8w7&KST6>G8gnhj zue2LnAprRvMixunwpx3vVt=9Ox@koddg0^TON|@>9wg6Btj&Y zn|6B?yoe_wj))5jYe3f#e*yJ%@tv-&E<8QF$oUY8h!g;bt=yp=vs2U@fJGjdM-X}b zP8gJwR8|hfJl?q=!^!$omtv4cC2+PjfX(F4)`u~&Fw2uSBrS}M-GTNcR6=sV5JJ2y zDw9(qBDNp7&2j>aKFXUOkX|!Y>4yWJkA_R%1)ZCsA?^vqvh;kkUFLP-5c@+K?|TBv z2~M+GA;QMIB|pZMrM$KX@iXBkCT{WV6S9@wGTd8SSjhPF2t&l*v7@D{tBkc4SU=Ty z*~3{`SEaou4JGz%F<~d9D&JTT9o3a}Vr-JmZ9OzKh-C88 zTM=0O@|BpXF%gZn7-tyPIcNZW^n(oqz zxVXKLM}!$k?ml@!?x|DNFaefugfdjs5E<>eI(2?&NlAj;<&o=tz*qNNn>_ml4aoGzsOmzr?8@8U0SG+jot+wrnatKQXdLi9%uRsM({3o zI_B`urbWA;vi_bk$~|jdm);GA;q})KGA~(oO(eChJm_s@md9()VBbF-6^#lOts&@m zVcZk#?d|LPixj<(iMt~SyfZ+Es`+Lpt@}%OZ2#-muipdfN)Fw{xIc&?fovc;QXvnL zA5Ml1uCc)XFzAX`94C>tFpNSd`ba;Fng16Q;IKhN>B z8*iIhqK;s%rXS;%JRFp#Q@j-GrIWXmBbb83TWtvQ4Ke7lOM~+x-z30dkFnb#7!1e= zgAN?7aLCcDRURA#I)Xsly+}U-sWE0sW=RsKV<8j@i6rj}R?fic`RGl~4^{B0NLfSc zlaYMgU&ul`xPjz8L6_7ro=A_k|HkL|@he(Sg6|L0G@Y`!J$EGZ%AabT+Gi3}(@ICF zi_1%zE$`yUcfV|4%qnkATFRHi$(Pdd1j-8nHSC)<38Q>CLRHReQgWhI(SSUE4gyZ3 zxQU)R3`B_iHji~W^k10*N1rEiCEOQL=^`BK|4a?FcY%W!Y-$&-kQ8Mw$nBS_0eUfl zc~pH59FDinKR|!@@n^Y@NNv&@7OY@42`ta|(wsAB=%rtsI&MY^{&Yo=hF*hzE~5Cz z?%i1}n_^$MRM2IxC9T0b@wR;DBv>O}#IF2&B<;+8D13R8-4@d5Vmh`5P)!+-@&Z~G zj;N5zR?E0=$hsRL81czylutk5G2)dsSF|)Q-B=Q+YG^wkN~~S7%5c4eaIUy>dSo3N zL9v3NXE1?NJ0|FbA(^}uMba>Q5h%OY=?)w_>+SR_+JVGQ!K@2t?0nN|)y=4-!>PpU z=sFuhfhSEOIliPsMT1C+Pj0oCTvu4gq{8Ltu2IC5sVM0n?da4*bHa4ZW*XuG6X|eb zL~5{ymRaixsx&7h%?%+92j(W*C%_Ohr4$6XWptT|rcFX#W-(tob)ftK8Q>Q^Po8JU zlP}o@sR1|yG3wn|s|Rjl-x|&XD}w(i>I!?4yJSH|-PHTX=ucJ&hfu}S>(03C=Uhv= z7&>1UJxNVX?MU)b5ZR94kR#wxKH^*A1^C{3ombufMC%H;2_q%CfwJl3;3xvjAyund zFkCjwJe2;96WLmnzVJ9vJ0eNV@GL>8?zus~?;g5o0q*rAE-ntz|3Dg5go={Z{>ihL z`->dS-IxX_N}?N(zB$^GkYOZBg7k7t7v37M?|CnAF+j`dSSXW)_8~21E5h82^a!z8 zT#5AZL=EB=cg*@dJWE|#zBkHAWw)Ocdoxu~4Ne{U^kRGSP67!$! zJoPu{jTLzp?mYH%YTUfR4VWf7`bQxGR=xAkonz5A`#ZeaKqh zN!vo~EDk(nXbT~?E_raN4fg=WX$b5XtDBlco`MQX@OT+-Z7#XTHJL;Gf4cS zOWa1@`i)Ry1H+1N6A&bv>Hc-f;y*HI8=$GTz;g~ecQtrIo+@$Qn`j1Hbo8e)$PmYL zD>F#D4tPosINe8SYRMBvS0QkGv*(M=j%0C`WQV{u9h@I=< z)={YT2PGvQU1A{Cpf{HqWXl7^IwoByhZOI7BBL!4`V3qb4`cN(fz_}dpv~R8rjS_z zVYYeVLuV>1>m~;ipDMLRq7!K55fE@L&i8+-?ob~bxbOU_j#9yW*WG(x#L3`gA~@z1 z(x5ivx5K1{6_zltwqnp_1h(GhF%esxi&g(bSJ9s)>k;w?Y5VmMzm_honaBrW|>y+ZL=yxVb5rJc3$#cBsY0UQ=vNN`%< z89yUX817auMFqLNA;Dq;z~^$qBV8v3tN4+-<#SWi4KV7+%)!GM^b$%ocN$XbCd`ql z7zJwoNTbiwo+kT z;p{Oryvo8&FHAvppNzZ4w;P2OFKFQu5AMn!dmy72V^`tv)dd#gb*gdiFnQKRny;>| zVAxIc0484;^tZZAH5h2Ra6f>wMPyDK3hi=NxOFT#-TYrt#CMPLnyru1EZAFqA zI$+=mh=$G$PIOra>;sAHxZD9Cwt5-K(G!`MnZa1-N@=f$z5Q(F(41N(KVKQUw%<5i zOK;?sW<45Y6H!&0H$8E>V#1yzquH_7`I-4^TGgZUUrX1xG*7R>U9#iq+=*aI*=p&dO0l z9J_!@t_SY5h))v%0Ri;@ce6sGEtHnXYSJY={q3jizQ$SyL=tSdmJ*40li7GTQH*k+ z&CJ3<6H)q@ZyL$?!N>D{2v~b>0fXv$n9F()88^sF#l$lmzk{Xe?BZrx63_RTZ%Zdp zUAYP15#BN%i?oS#+}{WG$GBn!!uGZyQTPvX5qSblSvE;s1>R&mU{gR?FKRGwNp1yi zfF1yaUx6?AJ@6PcptNAR0#BgdfSn+Il05BAcY#v~uuHe#VjJ2HMh&D+N7B7%E`wCC z^M5{4!Ez@gnFAEnE>(JlogK0C{+BSFHY`0R3K6(d|~ zuMQGlEK1?|rm@Q>O`%<1yLEtWGJLZ3)-?$@Da*d?@ zaI#R^{e5uwKfwe6Rv)%n*v+;F0{ynDt-Svt{&0?Vwb5{*a^{+XmC)hd`?JOw23Kr^ z8QW;B&U^aAfI~tXxM#eN)%MOQhEOi8sA2PZQK338mXOdWxt{?@o#!`)A&e>Xw4e8f z;4%x3&YCo}bc+-8I)JYJr7G=Qwu%_Xo)XorDxTlfBd9BTjAw{9!4-ls8t){|*%^qC zZ};TlV>ln&e{OY}y&XSRoYzQ7z%j1%nvx<8_A1F1Q5fKq3`=27FE|af#9LqQLp_Vf^a%7`~lNB zUq)m#4COc|n%2LWkcRCgDHQz_rb#-y5A?s+ zoA0w$C`9uehhZh|{+Ks|`yMLaGuAq|3Hn#8X_{+`QvJ_Q6eC%Fc=EyA%h6S-MXkhd z#adQFT~Uta>+j?PN{=XI-csbNO#k)CZ^jjheq74@ENXA)@(lD?paz=LCm8naizu3! z(uW{q;KRJ`=3kVH=i_{w+hxULUIKAaoPP5=3sIE^UmTNFJIz74#XB+yXfBp$bkqNQ zC^uAi1WvB_3MDMaAXmT7Jei@~3oWHNg}cCiO2!3eW&NB9O~T(y_dA>?I7F)~AxK&K z&w}{BMuU{Hevq=Y%E_?L$8QBmoqb>|MeHhzt!%=IXp-VJelx+K3K~;=%+wVJXfraK z4t7n|LbTYK zSmHOQ@@i|cE7klQ7PypF@P{UZURVBFze7ozNy(@)WNpmK{ABKsbxizEHizGq{t&LN zr}n;}eCd-Tj0}uV{#v4|^i*iclk@Di615E$>ND{^S#UbzM6G5eZKt!a$>hp3iU>r3Cun`ern=Ux-|+-m z@h8R&Z@t;Y!7q;Sjyf?vL+ixbwSmisU2g-_ z<_aFM%P%h4?vYH`)cXY)eF3X`KBrd+C}<574~MBKGEXid{2S&86T#Rf&up=U-PY~9Z5J?SWb6Z;92?w^lTCzDt4$*`gwwUen+kCrwV9Sgpv1Mb7N zjF*stZuTKNeXz#4hq$N-ai1Bd;utUviTZ3QUdKsP8@oFa#O=LRoYX(Vf0ab-vbxPcp-UbVCtV`=IK{XC%=H@qZ3_0H@9ZSw!vFML?Y`ZII1*! z7MyjXgFq;(&(ySzDr`k1sC3(G<(zuM&zu|}7F*L@Ak2jhOAtiXgLyx5KJFqIGRzn< z2tx16FNHo*7yqZjdMxv%8J2rnV19p+cShM?wGx?d{?`3E@HdU}Rtgi6rTxLKAWci` z+B{F>Lu`8MA5?y_8dJHRUS#h2-@)3opvkIvr>Y<<)t%g>wp(4X@&_Rj>X(iq#fV)%1m_ zp}iQj`{oXuyc2P4b7zNWW4EoT?9ApJGIgJFD0_ED<~@xA-)&~aDqb7Sd{0+bg_oy@ z{W+UhS6ff6rXjw%&0h#C`RNmFlcy$pgR|1SOvj>{Z#4-ta7>M4TM)VZuSd289eT(auTi?th)no5(t+Xm{EX`Q~FYbLbq6AJ{zu+Buz z&V0n9p7?Lo*~xR49fvg&zYN!=*N&(D`)BP*6QXV~=Hg9@T+glVEWWJUFKcke3fTQd3Kgvt?i4f=FRXf#K%4bI0Rnpr*LXAwtH? z=)WIR7Ko%pJZnzG4La+Q$Go)>B=)ka%UrVa`-|t0n<*nHZq?kyOiGM@nz^Jk?M07C zI3CH)K&@t)7D6#gdrzZ7uAMyaG|oQ73fkXlBG@RJ48RCLvHZ2Qhffat5r@I+QpWT8 z2~CCj4Y<#Vo!5?dpJqD)+c0zDQ5h2)YFKRNeH3D^Q9}D!J1khxvD&z}Wd#I7Z<((N zm$dX33WDaS2jiq6_m_rNF0XC19y6lN==}WNP#0r0vDGG+%AvOquc_^R;I z2baU|2I7)++Z*}ygt;r+4Br-I+c@`Ani}m&;v#uRIA884l^^@w#HRWP5ki>|HJueS zUqa5@S3@PZnw}y6I#6ex*kN0%B&y9zxf!6XjK68Cg(h^<=INb&P;p0se^K`$*0nYc zFz~#j04c)Sn|(qkI6$FGo3;Wo0HuIyp4m~X@JQX(mg^ibygl`cm%%NZ?JP((JNr3q zCOMJo&y}X6S^pf_VqDIcz4w3Bn;T>BLy4HBCBJju+ebUXXaJ!sC6lf z)6LVe-QEc{cANaK9dwDzAEWP1<372;CEq4*NMn!W;Ms&-r#;+akHAQK&Nn5Dx%gjR zOZ1M25VKdwrgSXUIBnEmc z^Z~#QaH`KeP<~cUd|_A5*WCgvh}#T|bH3HNpD;jYM8q6> zvyPyg*!YVGX&0n{6%*Ku8Z(4*{`e$EZ`+z&^Cv4M^S9&k7RRKuf^*I`fvd>4t8@8E znEc;-q{??Ix^30@&>}WYA{vM1>bzbOamDLGXp+#lmO3CPJEsq%=1)!(m8HF?@|)55 z9vj`Z_h))X32=Ya?HEl(;vF@NfCc7m}xB* zv>+R(aeqE&njC%;H<+)_RqHY^nlyNSYORWkWnS0P%H8QD+>Y9sAjXudzs{~k$?EX} ze&;FK@v~hy?#`5{mzNws7RLm zJMZU}t0dD5^;!)R*h=UFA>wAkuf2UUzPH;+UlZO4e1ei`IIjgDU}x?HhRHI?NJni1 z5RsH+!rbZ6=@lx{>J0NRzvnbbXz%>DWahQsZN`iiz|Q-dA$nDIl$j`n6_G)h-uXEIaK{Nl5bPH@ zy;^?#?R%_ycXvOd0P$N%5l8vB&8WF$PH}iF>9PxQ{zxwoQxl$21??1>Z<>N}RYGSV znzoPO|7vJw*kZ6Qej`1`TzP%UdF|VbNjpJj{(R|lSVKb-eydMX@s#eaJrT{$K?;e7XUm3#r*hPlTbUNEPtdi+|n7c)Pe2PUo=N|Bi#!-Mbk zrPNHSCeurpmyNvG(!7A!l{jCm`{q2Ud|qt^%yOw+g}0sj__!xvPivBxH{;MFhwt?@jl0 z=uP8S$*JzNwcU(2CG0FaQmqagKdySl5L((f|0CZhkv&zd%u9(4wm%+OmKKb01;Blw zrO=6iIU@?>EbVJ>zdsBnzif8GT)hM)aIf8A+Kd-BWMTccmJ7~b{~GZ_wqu!_GI4o7 z)32JV^|ERcv|qsxsceDm(8@G$PK6-+nM)iDi#yjYBZPQjc7pCu`1Pa#(rSE*4ovSm zU=$R-GMgs?FN=1tz-FlrVT+z-bDZWxc#v3cVQxUcr>8<{9d8m)_!wj7ee0XU^CneP zEgG!~Qd3-;*R+gN?fvfb6ipAF%{gF`SYyY2KDdqB8NyL|g^7^#f5%Go<-Z4O%v~sS zU!VVGuwIq6GOQ$3fz-hS`JZKiS!2`7nAf%}pAb{T%bUd&zl`x6H5*%7%JfQ7p5Gb0 z7l1*8(R)3AUPeFWh#G^O{C4bNvrS1AO{+JmKl$`u0Q&p)&EExI{m8g)))VC*l%1eG z_41J|*dFGtIMNEg$gTS)JsY^goK$se8?((?Ymp?{W#3ZZ>U!b0zGaItWFb~=^uqOeKDhjztp zU-h=8GE1bAn)llLhE{$w$yKzJ$XGtkhPx4=xgL>r&}*5X)1^TdnaO#-nfo^{hYSTcI^mJBLdxo!)*#_;x@ zFV|=8``VTkt5#mTczM$;H#bH=`ccy7Yn;#9Ya;N3{2B;Ry!}1qFN;rXZ%{w~ETQOF6#;$|u$H~=&->V4C1v70&DR_IK>-+5?4PRuz+4P+xt}t#Grl){ zIA@%s24bUMKNWF<<1;JH{pYN?dIcH_WhS5r>NdYj;n1oa@E;ierX}D6tJer>WXLd3 zSV|C8^HoOEJq3PC(q;5(iKjpHIo`}m#g;HwqBe=OoU2X1KhT?t0}|3TuLBtm3tK}O z(A0+`-7|xRg>yP*ygko${0$yqNgeV_&%eihkQ0rnsyn(TY0HZvc5w@c4A1GnNNN$6 z<-+{nMh-x2cL7Z}Hr5EQ`n zAz%-wetS9$B}F{}S%TN#`&d09UFIC3bfiSvM>+?KP>qG&zy#X*`gcASns(O+Gbq3c3fYj6*`PhNv#YlZvjOg3cB#2vxQ$QB&W_ zFwyk^SU>eL-I)=?=M;|gBQsA%QjVM$`W`4Lah40lJuv7KQaiCD&?{>FBI;}4+K~$L z6QnMtlc+X7<(nrq2`g+98MF6}|=8JRy3g4U3AS|dnEK!Dl8 zz9>)^QpfkSsi%wd^v@Qb!Py%m);(xDcvQI3W6zj7&^9>0mA}~w2qr}$ZOjd?2WgTD z%o7dAb0N{?I*8`BbOa7!PZ;pe!;|fRvf7U{tpK#**K52J3-Xi%(G)(lNV5EF&ZzIQ z)!%yFSQIr!Ulny77#kpkG{oEQ)gG%X%Q`^Mp*lPUEb(X0SQQ+$geasewz}c0q|vsh zFeewl`avL+;d^s6|;2O6b%^d>R%{PWQ3T#=ls1)sw?K^^FYvQ&l8fQLM)MnrDC_z)qdWg$+H(Z!} zb|-daG+<&+aBX2Is#R*uh4|Bl9wG{6=HZSk;$K5dj!pPw$tc<>JTU@WCdmzz88g4* zx20hdZ|b_UA!WP3Gx&x2P#!dncm~@prK42I_dsDsZZR-_#ps=(+ueXqw*13~`X+RB z_#>$1wtjcGs$`gb8R&fjdxC&I-E{8DgrfAf>GR!@+gPNR#AwUy?hc@CKIA{A=T|m~ zfH^y-YRIRM2k$|s(7gAu6xV1N8CpBoJs#5Z=!L|6ls%xr#k!gTEglW_osV0m=ula7 zW8ZAF9={+@!uXnXM1AO=@qYy?&a%D!yTvbt`FJtOgQ7zcuDzgNs_ zq^~&}akBu8a|;vuz8xmcK~;Q?%`vX=*5^r`0{Rvy_OR=@x?-eV7V!fBMB>kkZZyCb zw*Y$BK!QJkVtYd-?FzA74YtTQ4I$~bF^eZ^hAUl{gGH|$oz>DT^cp8?HG;0f@(x&# z0msTUY&=rZXKX4AFt4Feon1wawjkDkfn`mA05$;Yz_R?S0SO+8Q9l+^Zx? zJsX$Q+A|jqU|PVoIcH{;&327d;_U-ry2fMKMYv(>6qhUg`6>~DyOThrK6h&7wXi#u zTs?7(Af{shU_aa_uPTYzMR5sWAWKqD7F*Q%*#${q{Uj#>t|$LV4_6yVH4Ag6duUNs zB|rpNAcm~qb$18!9f1zZjGow!W%4_(LZlz&wurI^o*wFxr5YxwHZ1z$h(-^XP~0-8 z^&|HP3$J_WP}BaTu3K@e7DAnLd+IX}1w>AY1S!0MC(TkIgC#tQ&7i>P)D5?qmoX z9md8o7(Mw`q30!D|6#M&ZG``mxf&4iiV2v(1i%?BgrwHifjEx9D$vbNkz3S5QPmy;&3S8PY>#oJs*m zX9L8~j=%24oFRzwy|B-HLgw0u0oV-oB2ha+%>i)h>FVa@7W6h1R7J!i%^f z$N~sapa)3$0t?3mwmZ#xr|3N~CH1sb1u?|C25hb_>1csn@`?z;o{KqO4p9 z(pzg`m!o;!u^X|dhn5TL|FJr>2zGmb*ScY#s(IQ#DH-&5<)5Y6yUd1dMR4&VVu>WS zr=e%x)i9Q(&5wlR{tq9rx4`W#_3_X3jD4F%BeyrOVl^5Va^Nqy?TZ-c9zZ(pNvY|2 z-JJ$eT3)yi4+Zc9q4>N-5HM!)X-nR5GTL>+)NpnW7(>Qcwy;RLhQHEFo@$#DQuz1Y zv;(XZJTS5BMoV<^9i&xRk14vM)<0Fn1U@C3$14EE&c<)|@mM{O4g?IQLAaYF;+q)^ z!`}ydv6>P}zfkaGxPEOq3noRx_|>AfV+cL3g}}~i$ouAN3b$6&$JMoEMIjNb%|Jj# zcVgM*XJze~!18cvfaP)_8iPRl?gf^cUgZ!fFpyOt%*=8qAi5T|MMbAJm7billY20@ zxvM`7;a-r1k{zI{>*}rI644qgjeF!f{s@ZL3}M0vHGLofD8Id9>%@J0e0B@OPq-L7 z^!ImNv~-Q?u2saYvfnH!z1lbC()}QkV1n&VA1ND1>(rLqByv4hNKHFGWry>@kLpmFAQJK@5Mx+n3mg?#eBjC zM|m?FA<_Ksay=x*IO?3Y@g_SXa96b30!iLdi*brL$*mL1&BPNXkc z;9mrK=%Hip#~#QT?NT{}iG?u(0-%yEL34RAm^dz1#AMo%f%LQu-rHu)VVyJ9qg6sL za-Wqjy(G{Fq4cM46zup$VL@v!o;S?tWr=Yn0P=k?!0_h2it7G^#5A)kTa0tvczm{? zjHC~?Kcb6vz@4Aa`yF6D^9ri!D13sG{f`?$@72>sON{DF_ObR{=Xczw4L1IAqu68< z;4JX~2($cHF651poNHmQsN+3L6&^ZSc4J8*m~Yd4M~weq(9WEC%;lh>AZ#G3^2I3| z_zYeL*V$B=y<0bHBT!xm$P&}e-c?1gkAIa!iiJDPb|renwW75>o``2RbnHgh8)Wxz z`eU_+7Z_Z}$3`F>+NQj|53#1Q5F9{#cKLO-1fR9F|7#&-V(cVZJZDePe%_7&*k~~C zeM=@U$OYu;#^d|6ANAZegpxoNuL0=ix?DIQQ=eivjjelwoO_g?&u&yrx4{gS#8B~d zbz=}=yb=?J+}u?#tnubb&+TqRch5CzD3&E0a79zI^5=|wo1uWP$QnWe6q7nmNjeO% z>KRz`T^z57Yu>b%cCU#0^{cxMEP7^tap#&=;Tx~_pJbAMA@BA`ZuP5Iub<1Cu9jCY zD%r;C+_F`gm)B^i*_K)!59Xb`<*WiqKWrALp17vOyHDSWdu{SZi46*G9@3iYlslxG zbdO9hGR7Ics=dj7z9)BFgV{ga#n{wTtStbNlBw#&W zwU{~F9*}$%7>z8WWecfj5kbPU>%`Om*by77zd-sNo?UZ14kg>vpEwN;eW&|sZwH#x z$nxN#$Vz^fk(^;TUfCC0V=OHqps*2eW~n++_BtWq8 z3xJGd0u&$O>Y2dKwJys9HX6t`;MaS}0oXTgIj22+x*4K;dFGml@i8lJPVMZOv~{0y z?3pU_f7ut81wE31@HwWAUYzTIpSh}*?1dHb*Y&?&G+>W*s2HgPAfdB;AD zDH}*&hRF(V#R!A(Hm`LP|8!3|n3xVX=U$n3k*HVxkyf`l|G+Clm!9CglT)niT7nA+ zDf@*PQfeB2mCMxRlXkx3#=BR*EO-KG4-fj_ksQ+_7YO)llaI{bH{0HR`l1tJj#3E=GH#Idakv}5+9`kF!VSQ)H z`TF;6h{;_dKfB_I?B@~Mr@7V%VO@iXT9+K3bLz~_#;X}@jcg@2GZ@Kae~%tLY0rh6Pp1-0HD1TZt6hkF zI|haed-9o>mX~KI+SHwDUB(7G@!Vg?aOOSic!1v#wReD_V3TmXat7pz`N6CpQ`+w3 zeBWbde#l8M4^E-FFcq-?A|~sCy^dK+2*3@)5LV6vG(^k+JIyTK^c=yYOJwdT0JNM* zXvVCN0J=pMBN;6RK&u{x^iUP&XH^#Et+5s9i@qec=GigADTLJnRoB$7o8@VLcLADu*Ca1x!8a7C5=8mW(M9}Mby2*I5 zuSwIYAn@@JM3#FHF#bkP$KP zo2*(@0N^x$p18s8xZ}pMb&O#_Hm5N|9pv-UYt9WSC@NZwsSTsgrb|qYmZfJwRu|89 zJIvw^Tl!95xBAqRJ!iP@UYH(kMuN6qMbxIl6?V2vU>cHpJM{Otcl9e=h7aKsZUsmi z^`TVW%V|kwSfB$p9F6yuNF9|2m<{BK*687XN+Na^N#Um&63j^1VyBO^D!Ubl30Id{h)SOE@`D*@N* ziX<1^6Kz0lBJMEw9@1>qV}?MGbo5_7Nlq44keujefsC!lu!d_ADVq>I**oG`F*V1~ zS2Fh?2X+fV*CGROt#v>J^?9zlYX5P*r_F-JOTosF^-|%P9SkDhLLdpRi5Cio&RRGG zF>%s|4PW-2_p&!=wZLY<#=Z8i%`8Hf}wP z6wngR{bG;btuvXy4_@YE+P$mfnS`6o{j4-|><1#BU(4a!x`OIc!2_^`U1XX6W4G0# zO2$Na4j=MIX&iu`59j6NGv6PTIOVolPWf@A0Ix7bUpQiJ2L)Qk_g2=8btlj;^t^g( zW_hl8dk-LDSd-<}WJ6sK=l9`@@YL|dlvhSnEK{#fg;)kW%gg}KTrOmIX=~8lGS6Ou<3U{O*Ec4kXT$tCx90oAN zelg6<&xaCFR0#9_pFe;8zDd1sB7m)LYt0Hc{T-cOJv&+Xm-&@{S%oe7<&T4xLTh3| zcb~0<0QV3O?w=JyP{0=>b5aqM9GhP{bPnh0mp|+Csn<^g1om#N1(FjUFd*g>Rs8V& zk>8ES7b8nl>}vBzPoK{($JZ+TJo!cD{5Hw2%lGzj)H3=@7iMG2JdsgSIUUfe;RV%l zNzbcYKjz-hfS^#R-$jUY2^ag%M_7ZZ(64`H?fY$6e11D>w7-xu_34+HDy*EI*uZ%c z`=RXMfCS|HUVXi=e#z^{_EnbD?L8;AZ&1C zC|L0C?M;qdZ$5m#v=tqwJc{!w-SRkw5AfiH*OEq543E6+8s1cUELT{3{X}KDjEsrO zgXeI8{wX5Qezq3`L9rDmEz9JsdD;-L^hRde7mLhFA)EJssY4qqJC8D0?{3=sSAE@$ zM47U6o#qf#A98+vCmL_JTyR^(!E5y}$SRxj*-}tcEEQC(jj0KGCAs z+z}BGL36+-3SCV6knETPI-<$FDKRlCjg5_02Y$BFReHdUj)^S2 zqxo|>X$HJ`WtxkJOGR1PY$eCmmoTwQx58@9utR!v9#{I8k(I&U$Ce|2|DQmtDdZ|H!sM6eV?%X*l8mtcV zWFG;MGRR0B-_~#4x>e>-anujUiyrc$$Nx`0>Kc#M+5GLDT&R|&fLWybLX(n`ELKfo z86nyQB{;|oIny@11cfM7Q#@Q$aVOMM_D)3hFfseocvjRm7L!?F<-sWQ*x6Tr(LE2p zZ18!E80+h+LgHVmJG3JI$F%1rmlDWT=PnxfjVaAyUwV)pzxqTDbfR|H(4|kVk7r5B z*H8NUF7p@eLchKdSaQF*`eOgx_mKtp|7#hxQF@ovUxbX387Ne_d`@gm{!JzGf)JG= zFjF9N?u$%f7TCgW$HmETWJris*Q*e0L$4*Jk`|D^9*R`&M*;?9`OM0}fNOIAkGNnl zc5WzhRu!ws_VbC}9+^!fxk3^;?2qB}sdw!R#OY8aX2)0Gxn|-`#PBqD8W1vi3QZdu zo6av^kOx#+7+R1+z;?w-)LcBK~vj_Vk8j6%&&^rU2|Cesm5y1l8MqI!mgJ~ ztT9AtTn&<5PRD!#0Wjq=LX(Jt+cjz?@+Gh92e}vAe5JNW>{lGm`do$75b@em@d714 zFG3KYBq9b2#4q$bsk0to3&RUgDGO@4w<)LW>&_`}thkM#vv(U)s<1HO98kb=!Kj(z zJ!2UIsRMmhR_ll4-V{^tols`cS5&qd1td>CU#>Ni>pGqlzkON#q&BE!M~abN)Y5v~ zIQm#>p#55Uz~O@DmnCv^G4x$T#mV9Mmv30F>M>v;L-5GE_`1~3fGezt!+*%C#Heih z-aQo~fFA7VIQ8_jFl$rplQV+EDZ|YeKP3~KJvD$SEzh+FcTG*nZX3TjM<4!(Y?V=n ztz3l-OMUGjZb}ts8b7auiBlKt`;wII2l^l3{%dW$cM}uWfPh(q&~Tg6)HAhq4Fe96+5qyNG5)w+40sfk0O>=7JGTVO|;%cAPFC^2SzUM zCF9yibu;s_2UeIH;Ft-TbnWRi;hFT!Cig?JmWQcYMO4S$*$UI95it~O8iX0^{Q(gg9hkL)c{ zfK=fEvzAG`C`9u3So3#1Pny6@d2gX5TO{9LFe&g)%~(MEttyElKz6)RZQ&3a9h| zvgb`aGboRH$0%{w3Dw|p^CKD4{9yks{s1vI6H2t`IA$ntX$nHvPiM|sA4D3f*6z`i zeysXy0$DESbVP#U37*&rjx5W45y%ytiRMSV(h+>zabPjO)OLC~Nx_5SvLT6lIt5Ij zgck9RfoN^na%1fZ%HwxuN~li5Q)_;31YadLA+&$_r~I39ATFAFLv!n@K{Monattrf zLTx6A>X$=3!=g%Arhts*cL^8xTW{hVX98~`eB{WHoCg*lF$KZc5*kWCDPvWK4}=FG z%A~%}9%{-l*9F|m3NbkX)jG<@E|>;|kdOM22qqXPgG|Zjg1rWv?c?{(b!2;Rp|Rpi zD=Ov_GPD{~-Oa!pKd-Az4F4Ks(n^L{mrLYZsC=6`xL`}K%UWdfd7Rs+sj0E%V%dytOU?I#gP_tXc~JPG}UH9 ztUU=;hLn0k!!sv#O*LuD`!mUFH>P?uartZsRqccqo%C?qeE#-u%y|N6Y}Vcm@Hb1NT;RICKvc#oQ-4srUvSVP_4I}K$1A%8 z2Y&crRe9aQXGgvf5E7pFD4=xHPwnFl_`FiKni{g_YEW%ar(wy`Wd+=*Q(C2sCw_2f z)RKC=ZIS-P#S^|c*PEsHrmw{H5(#sN;uVp)b~Atwr8p?he68)&EQ8IbJg!F2Tl-*_NYUy!Y4_LRrhYh zW=YOPY;%D)Qfb%)Nt#`}Z^!SkE-ls!%NF+~%ySK3Gm5n)pXRXi6uf!()JHKRcXNRuN-^LQbq$@Qn zj(K(d*CFZqmPU~Gc+9zOnW-0jslKsskajwZQFMiT>i~+UYPG8W`+F_J`g^-_0J#Y~ z`3YFCgC%J@V;($^ivjakrYu2zii?Z)-vJJnrT%9iqedSUCs-6b{P^4V(+dDEa$6T} z1Z?O@0$`}_gn6kTGqU!qUpLYT9&cLi66}0DCmHbwhrszn!SIGUc!hV0L zkH6gaaLOOqKREnuHTR{Um~-JjZ$O%rZJfB2`w}%_`&YfbviY0Xv4(LAQ4z?;l)Cc^}vWRdCknxF@vMYwt%a&OeregOpJnVQdS$ea+&tS18{QgEsdgqi$|U&q^*rKbrLp|TwOdI0iRmh5Ol4g`UpiM$-AL(^yGidz8x+rHiB@iXG| z+q$8uMQ|ORH8F^Ks=Y8PY$}N|_Y^P*LY#Su4xa7p?Gry7NfTgc)P6a2`^T3siQRNy zEZupWQi&45A4L3L5AZ$=f~NfwUR+PXAZCwfCBG!88f>k8G)x55zv%_?)+Ni&0|zX! z&Tc>PkmoCM*bUH{+ExPY5znw;lEQS5Qw|+EM8Gy}W&0OWks65AW;>)qy!|=#e&Y|| zDYp8MfS-X4jflE?S6lft4ny$42Kbt0F4%8!okd=;)P+7nrHK{yARS={`hOZLLoTf) z==Fjz0l=2nWV^XFx5L91Yif-=!D8kK=DTzjIbHij4daUB#&%2aDMTpfYPoA7_^hS@ zOqtZAVxKupvsUiuujOtF)(Noa$uS7VvjCjqGIq7kNd2aPiS*}8db=fb@4zq6A_N2% zDj*q8`+QbfuECWAqO@R+)#^&jrpOuxqLrV@;2fK!!Zj#D={fkIC4zzn)}<@CTU_u( zs)va0n~?mNDMS-|dd`n$2@BBX8Peueb-yccok?7_%Cc6k!W(d+&a}$IJ+$jjxhPEv zsCzl={@if1AS^CXa%k|^KF{YDUlU?2xJ;y&1W%^iM;g?PUofHNo4LHya&2MECPc)0*?R@bklelr=)_I}xLIxb!LSztu zqnKCN52U*Z!-)@PiIBwS2iLOHW$4&`cNUK+97>eNGN->ZXUYP<;{}Jm%Ae1izbhpj z*}u|$MdUF1bvGtPhkfm8M2F{2(@?(MIF_F-dglcqc%DDZ zS5}}IB3T4lO?GTMPe4*;j1|seQ_CYrcc6l;8L@ck8yH-@pN>V-Aobs4c77ZytA*r@ z(4<}#+S=OHz~$|H0P1por|YB~0zP$YT!OVzPjE(Z%JQ)DALHRGfa{;Zoxr84q1iZl zK%~!ejk>I5WMo7?$3cm7Ki74gzQXuHRF}olWy@+1O4{hDvBIomu_Uh!(l^@xIbi!_ z!YmDB+o~Ty(@{FmJM4-}Ed~erqiZ38HWVqJ z5$jvv#A~{esB~kE^-SWCCMr-OE_5oW#F7wbiOmya1xz95U@&*-8Zl^IL!PdNdQ%MHVVH^2OcC8=6hSH}f>TLWub{fKZTCg^Gk*e1Zr z${=O17Rtb1?9H1uGMF1dJfqc*pbB$?KrjQ2>o=@ko=QPJQwpr zn0>W$9qs4-*RVOXLAuJ@w{I6Bmr~mc7^GjYNy3Y;YMXXphnS$v{?p4$du*yFLWWE& ziJJj$25?uszIJGXDRh5@q5C6wu$herP36j59I(yoQYeIvw__fC3L=TEzK)NF2TWv1 zPQ=5j$KjN?I~13cWQ$+hGkuCmr(X3V1kzbFlLu7e`A!qDFOo;ke*RkH!2gmcdCmVN zGEJ3N_YJE%Dn34*LQ$atqTjCo&?jKJ0L$+tDIGQ`oq5#J(+6DO-L7&Pu$Dt?-NE}; z;pkNxd|NQ5#|%4iwtx}0CZtcy`r%4#63@YM3UTNwqH=N5U2WHi;QZ`j9B(qK-q-O3 zwIz;e9XB6>AeN)z2z{PS@Ydiu=GHqUaqInb>%5^`1N?91g2c|c!DALU+4_6;-aMHt zsKip=Kt~ye_Ug%lyrwr&cLZ3ol}Hl@k|u8Lt9Ki)=z|B3$0xE^YN4_V%7W~8Z~sxn zruH&SoA6rlBm|>VQc@~pZPNQs=*Z4})-QNTh!wVyhMJl6L)C7U_?A`JfP1pC@*zR- zZ8Yc#`I(psdx8l&gGM>;)O=cV)w5r|*2Xy3Z+h=XqlvM=>Kwnd4NC(Y+1f~Om{h+> zvZ>7EE48Iu)|tu*E24AmO^d(3RN9s66R3FnP-;Czm=AkC-Ppc~79=ZTYN&jB9^T-) zYmBSeP#SA$)(>1+zSSVVHC9@TrG5#CrzIthaGSPGhYcXTmGzRIx}JJhFm^-kkhQf? z!Pe`m#lbBb6R@rSCar_Vde@3)67&vxW+Ig{`y+-sZDq$I2#xHAX}@7ObaTM+mXyHl zzVW|qUQ^{Ec0Lx)xBm9+mru4*4}fW3^(_5u+b(U3PnRX*8e52Ge?Io?B0%+-xd7p~ zu7yzZnS5@JSSYzpw)fy$u+dMUc;_pbnfsUyb6V#e>8yeNUZH}U2sQ}YX<4$of3Win z?mRmw8#1p;C+uNR$#(D$UM=o=q60TP^~|kvWl1)s%Z=g}bA6|rV7YIIgPzZHLVj$U zHjeH15xL3u{W^`{K%S15wzHL;knc^vdx|Eu#Sey(vv1;8cWO~6`C`Y0d@)Q**a&5l z&BxMHr{cOs6=ZKH^ONm_-}{QlER;xvpHpSy*1Ov*byuv3lsNYKS2}1fanQo54uTpz z6f?8TAmv{51kdXJ(B?V|7Icf$J2htcqGd)zb|vHd>KPc!B!ckj>qx3Bl}NS73%X)R zJmW%Y4&zvx;=#5a#b$58z&O+NfL9O#M)?^)e-s{*PWil^#^~I=dv|)lO}iITT6mo!hI!@nH;&vuKlhC8pj|eUaru6x+{adAsR+HUOp3Ujls7e-nUjn(}>PX1d z3vu8hd!xs3e_}nQA(7JYvH+)g;F}N_*VWkVOeg#cGjQ+HarY)yLC+U!`0?Wk(==ro z7m7J2Ta|a|>rW#n^W=Go;Q?${M$^iDs`qmy4fEGQib8&cPcKG;1FNqCh`;Qf3NXO= znSAPGMHMRdkS;5%@g$}TaQbKVP#**N0^1hC&0~&KHjdQf3Tlx>YK!tknf3&0q`go) z-W0Gce!Mwpu-G^?n{ej9hSFMYScRE_nSAOZK{M7%?N}r>ZdceC-%vhfN5SpZ*E4qQ znbzCYrmJiZg?xupKG`dE85yYjGabYh4u)~U^XVwdBPmCI?p%!Qk`h-^V8q@VvbmLh z8ges#^I7>=k~Cyo8k#4FO*;M+hgyyij##iA+bUFOVgkE!94jbf_t8h<2lIokpNxR- zYdg?W9~toN@YlydapUWed1byHO<|jqOQF6_@*5+8GM$gFKS^IosenZ*nAK+N+BXyd z1Jb-CgysQJ>$XR6J*f%|3thl{3FhS6h>AUm1(80WjfX()aDtz?f+jaQ6}V7;D-KnJ zKOSTwtwRhsuT@SMK}GA%MJ8`?2nX*%*y*B3-OzwbYkWzag_xbHz*Y|hoFAtW7yFCc zT%m$3L2^=vJ}bj|O`W+}1m~^3jv&iP?U!+^+1DChM{2@Xsv-RjN90quCTu=osh41G z*P1nJye!}@x~hu}pmd52Vc9)_6nys@!SYlp7T{IHLzK{KRgG~F=h47^C!o2I1iVTT z$qC4O*h!D@P@ZA^KrPZUXzdN!juJk))rIQ=HOt zloj@wYOR!*ATQgQ#tQ=RyT7INU4lgp<+aEe7r2=Y7;?=YPbcRZyTNlLXWA}{9x)e- zSWQz%Uc7jbX}>r51VOj6&^CE z1u?P6P**2nmM;R!`S>(@V67=fOXZEpO}p!3(XjRq4?U$@ndQG1-jWx}Df5d9DEoO7 zEzQ2Xm3tp&y7lF_&2_k1bXzkAf%X)Bz3K~ktIg(a6(pE{$)ch%-q|K%&mc&i2J-YusnhKynY*yTu{XcG1n8E+T$`U`3U-3&6;G~Kl*W^eM_ zG?&vU=-QTXY%L!@Q1U05n3qtN9X^^;Km$u%;6>+?e6^)gQeLVq{7iJ131Jug7M)jE zh?6gT-#F154K9>RMy>pJI zrzgdKkTmCKT_olEteOkvK<4#M@{u1Q55m#cZS^p9xIrrgKz&R99G0trS)!~3o1uSi_IrJNHGRg zlOQK6EA?6KOUQg#lC^aImQIo_8AV2sFA$_nw*F>Zk`e(eaMZPJMkMpN+I^%aN@R0gg;IU+D zkZ^2DyEY}eWh@KBCVn8`_(QP&Q?}HP+GmV(zGVsDrJ;Dxwp5X%T_yeU!#qVf;|G=( z6X%bg_=6|a6KU-5_p?^|Vs!LIEiJ8*R$%=_NV#o*;bfit3vy~H$!H64j$NYQ|8a5mm@?z5Ga9dZy~VJ zF)`=sa<5T|lX+lJMyQw|QGF8qLgt7!^mp!@0Y}IiaB&TEp5A7&ms1droSY}34{D+m z!sHPzAzft|Xwi=TQc#dn+DKssJ$4!bUzP{OWI>EK4PhC*^wfjuD5LiG>+>MlhQD9# z<0voq)%Bex?B!RNR(lvm0oiU8d;JFcqeIu(NucOTkh3HzP`9regFEM(~p53??o2E#E`E=b} zk#Efe6yl19Mx!Dexf(Q(-b?sGWvdF5*aAj6JNgrgnQu5140}*-43$OM_q!2}Cxxm+( zPhrdpuc3eK?o2@hbE!AE!Wd+uJB!2q0E<)vB_AMESBjL9C^TGOq+0C#`+k%@L)N(6 zp9(Ozo-s8A=En&X{Q6zGbV+gW5lTJn^Q7<5I6(O7<~I|6+;A=vxQrWixB9G+8SZZ!5btB+tAM+Z7x2b|J44@LKph zwR$N!w(hZLq2ZLx?~|nKMptB1$vsPe&zFhVSGL5*N`NM+`(PYlYJQo%=DZoyNBhF- zJ5A_u>g~Okfa3b&?$E)W(9x~w8P&223Xnw(FqDp%@R8se*kKck7MhrXd~IZK)E^)L zsPsfpr`RYNJQ3yy_@yMq4ZTkLlac*Z4-sF%!v9iwe4-`DEU5e)szcatmE$G&#cUcl zC$A^a1fPUza?uH2Fy1DUTH?o^=a&(!zo6jKOn0BgmUMLa?aG#atAi#kxT@Q9b_7yK zrEem&q*6PbFnVE_t7q)97w+D>M?62GoUC|O3c{Ssq*7PjJ=3i+TldXDmy>g~P-s-b zpF}8yp!(YA79AOt^L9%hO(?AtXR`eJ44UG|><*X+URPrhjLtg!efQc{WDI??y6vc> z`BOzln?394xMQf>!vmiu%F)V=+4`oZK2!|#o2Y~@1VO+&yD`DoI`*xSRss*0)pde9#rT5oJAm!_Np~ZXsAJLir4C-~~X1 zG~v(O?V%_fAioRvGr0W-926Q)6^Ib`?)9N>b$1w(>C31dY2t?2e6;v&+j4mhIt@J$ zp}aAo;}v|o#3=ee^xeDOnqn?;v_eQ~_`;V#WX2QdKaBLs+*7p|ZC}ddWYXZ#P{1)L zIY54VaNQB~3j2zwsS;U-A_sv}(uj`u`EEGc0M}OjIJ^$t?~p{BPgUro6cS#Frrh65gfck^JPqZ(Im69;?tOxiUDn+)4OZu&MeBAMny$=5^s@H$x9%bK6L)^ z5_tJF2=Vf?Oov`_LHd}?=s{ko{q;=#Kto&LI7wmcwWlHB?9H*j?~s84e1u z{sv7t9SN#plta^LZ9!Fw{95yVWJ_L--M@X%OM2+L)Tft{9Qu`RTW3YbRy-sm}}hwG`<#}o{VX|yb!US zyLZna;ESOcU}XUT0sB+isK*h=o5O^F<2crD#)*JPDFZVg6*25HzS0Y#FowCZ*jQ~| z$l1>mKT?ep?(^yrUB$-m;LcP+NFnLO3$cbn9gJ{ChWd!#=BUm@f$YN5$x6%1{yZ`V z@mm~HSyWjDJ@YW5qQoLUSd@YrZL6U#cb6Lz{@-yj zG)|rBQS0v^upTr|Znr(5xe&8N|D=LG-FIQ3xe-)7iwp4)uOpHV%qzTlG6GhR2IVnNG-LxFHLHDa`L> zO9Us)7Dg0(vXfKV=Fi`;V}}N6=|lwkEuHBX)1VH4aKKXUH<1u^6@-*67bPLj#B!>m#$el@lmmA% zcN_m1lUuJEwm~hHoQ4Ts6K7F8jvS9(2h8}`t^~dN-#fMM$2s@FTqxvOI`1O8M z+!k&6LL3~wT&Ds#Uh_NIpf$OD)7)Ir(PThZm@UB{n9H9&4XmvAN~g6Gd8vMD;Rqr5 zrNiE3U~n+iB1n7l=G%BnQBK9kC$jF?x*Zz+bm6xvOi~ogj{r3%wdA=UW=k(FIo;WC zkrzUV5TsxCvn$~fP+5SNX4M4g%Pu2R@|8i_Jhlv-D68dQX!MOZRge=1zpl+@s!7Pb zEx2`IP@xE+_5#eg?{%XB|cS?GSD}%g()XUxB$U= z*)W|1lCrj-`wQ+YNaVZP@cJu;)P#HX(^2=vn|!3W5@P%(rq^Wx!2A_Be{TE%B;MisBr zDexHz&C=HN6}boxFS>1OA~K-)Ms1`B39CWX$uq95(3Nq}F$`!K2;vLS$Jy|PW|f+p zK0+f!bFHT6Kp~r@LRC@igSqUeyvJPX+5qSV8cJWC@R2`LpR;?v%8oM=CwX5pagy5T zH~Y$!UV@a7T66{)_W}_D5=NBL9|?9{PomnoN}$3=55^-(?=#l|arkF146We?P^BD-YQaH%iB+uNIb3mdoI_Y8m$m2u_4z79r)0K1(H9iY;n1Wn8UB0<)t2?&$D zKfmpgs|_JE4(2%vDh#c=@b_aYwaKa1M#DB$;32BpUOWPF-dw;#*y%&rTpSyWt&E6R zg1X{NA}%5DDibwAf+jb__|1`LYTUZYTn(N0qu^bGYF}N#+5LDpNSr;(bdUgWxcq;E z9>aaI{eRp5KXUikzKI_fBkc0Qi%~I^{3OCL5Jz4$pzSJQp>8nHHL-5});jTTx|HtO zG=lMwF3UY*`?3I$7KMYjGo19KiGW-gB6U`}UE9u*_6D`>eFS9*U92JIP$9d7z;%Gjb1K0CV%*qLoxE}hn#YpVf!yU5%HK@6nn{AFF$b%Y_l zz0prw8Q3j$aHlEEnOW-Ffq6qwn0rM2=-D}sGqr+fLVS5uPdy?7m&_xU2E*OSCyoGH zERiMmjvVxdg9E)Jt)c}fD7q8ggxzKG*ulz7rLk)g^U|!pStGl{6cFv+eIw39Umqvm zVR5RIBVNX@eMQE!X>i3IXsolB#oD9gfxI-W?=y(Y&7q}i4Tpg>0!!F8W?#(l23qVX zIDmH+H%7PlJwS?avy|2sV$|^Bk;c5&PwoInN?sW18vi-6wGyN2wGIJD{|fW_@UaLx zcL(oC18W1WUOmW`#t=}v@4se`7B9x$gn+ z$}U40D#YwkCn1(};QRUVz<#=txzik1Sf{`@t|X9V{U`yyI5cee7YvRHM(tbRDP&6! zI^!-5;wvIhsE`8#%_Xy-=IFMTEW$Jy^yUHTX?`TbT|freZuXbqv)E3U3FcBiFP=K> z3wj%TDP5B#*QjO8ib4IQX}3G$jzdhZB=)X8RpTdLO~9dSCy&YVNWmL%b^&^Vg2{8k zt}nw5zNF5mZLn(w1W%VuXIn~KYZu(H&ZalZ%vBom{uH!^n8_S1f2hFC6e2*bH_8_W zps054+Le>umz%DEqF1&oxvaFn_bs4x;9kMQAxgs%27-%cKRae9NvSN4bER$u22ypR zMO#YWDXlw8`XE~cB)mp#UBq`nK`~WIII-!fsJz^~a@rIJsk=B*bp{gXrqc`d+C3LH zYV7(wys`+JGap7PZ)D-aRs{g>Qu0Y@*hZ<#yhjZO23(w*7dLGh+yfs#Vi}u*sL=;1 z*g|=?u`y*K^6g$V?}nt4I%Z3oq&%#c&^X=}b}dIfy(dr6nk>zKgqCCyUmHo4LqlPe zd)r=|P++=Mm_gKtY=sI!z_Cod4|8|4@_)b!!@=HW(L&ag0{>A#6CMj&q^Qe>Zerav z38Bl?m3xB{d+nlc-CAf~Li}X5*wy)V7ofJ>ic#<)FbA0_q}XqxdQYuQmM|D}h>3NF zN=a-$Dao;iOQ{?-KruG4`cO@b7u)VegiWNM;?m%D6V|hYKWqoi-j=Hz{*e{*8$*Q% z6!+Q_t>xFR^lpT4zjFH3XTmd6$AO|X(E2tB@hs;sB*@ILo`bsW*hy@(xf`^yglYSNgDro7+(NbdkDVZ7@*J_ambt4a1ECN`X6F< ztJw-U1%%FvP$~@NC0o1EWKRcz>h=qZezxbRx4VA5FiA_OKI((cK?ssL(F zg~|QwL9`rgf&U#0I0N;{5E=4iUNWrVY%~f)C6pi|&|T`*U&`(pmZ9%FMpc3^49!Xd z44@}6?M|%tPmXdn70TeTyIQyZ5m*2^V=*f!d%m#pLuH zZRvxqhXDt}4vC`he0-q%iyxpcgqmelP-1gjyH~34k7v!3U0mOOGGeC*q-|(>H$psz1HA3jY><(Q@kY2h;Yk zHMU&NTv)o`ZFt!D z#wQ!yd)qdt&(KZ7+M44QpLjhtH@5-QLq0w}=aRMWOb=CaJD--8w!3#&h3buUA)kF) zR^}ZY9Ub9lZf+izl;pT2sPZk3&_@WEu1mG^uePUMDJUWp$`mK}3U zK>(JWEN@dG{BUvPhYug-)Kr3qZiH&8e45Ef@;Xefrluw?J-zanE4-xc&c^MXU0v7y zSnBco`SZ8$-dQQc?pUgS?@cwFAaV9^X4U)Ch&-~sOH4^A@9g9A6%7mwzB9R;^W@1- zue*`qJ9<=ShO^xYl6{OodY#;J2^S|zdP%k_?=dV4)-8WErkO6(B)VPpn7#* zpR#LTchRvf=*{UfXKHop_qVY|}$Q_3M_WvhM%s=|=7mmv5@Mkyuqe5 f{r~A{dKNl2e9iu;&n1{iG+ICFXvD1l<+uL<^F93p literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-25_02-59-27/plots/cte.png b/tuning logs/2025-02-25_02-59-27/plots/cte.png new file mode 100644 index 0000000000000000000000000000000000000000..4c43a9992ff3d0f3dbce2343a5deb347405bf746 GIT binary patch literal 153700 zcmeFZcR1Jk{|2tpPFrP0l*)+gk#UGLh-@;Fl*lHVk_K5R*_7-VW%f2QGa{KGWJmVS z`rWVdIX<8B{ax4Zzu%vy>pE8*dnjC%*|mda2N@aJt_$a-6v@c; z;E&{gZrg(2V%VD{@!KXV$qUNc@XKl2jVJj3?dIn-tjNf;&Jq7@IPl`E1imO}Ev;^? zWOmcqR?pIa%tX)H{EnIRo!i%s+%>SYx@~64!@x*P$N60QnNhsTe{rc{B=jE;MMU%QLnSP2lcAXFAI>d8d@4lDEkzY6HZqk0@kCxo2 zw{>tgO*RXMo>HmMrdS>--e-3#8fAHtniRG?H=t3_%XxTM_;pP0&#bNg_pWF>nHJVq4@7f{97p2kK*4# zv3?T&e;0}&p0cvCXV0HE^r~U3&Z^i%*3GV}qqCY?_)f=lW%e6AMeW7vm#0Q19j5~e zmkqLHHj$lg&Y$mW?;Th475i;Se1WX{*shv6;t9=<8=0B;t}M;V$jQkyHa3=ie6Y25 zG`q_uHa6DK$jEbUZthcEov*}$Ez%Ma5?*vd+~>S$4h}{*ntIU+a6H;Y`*PIxuXpOl zl}4Jn=rsSKYxJ)3aAU$1Rn?atJ&r7CUcK5I6R6|qyfi0`=WT3il0JL(?EClcrHqY@ z`vwPPBqTn%I(yUbv0l7*F)BLxSgp`t*d5nRg3N~xA5J&xDrkLoOP;hmRc$ddRBvc# z_+(&U;N;1ZPl}6+PqMOlrt4RfFHH8n!8cl3T4spOQTH;eEy(=(_U^>ouWuBOcOUkA z^ym@seIyd;Bs;s;>$8u`hw9(xFE31T-Tl={C1PiuB{RkoHq&;h)A#(M=8QU>0N*z1Kwzf70=X|R= zQGtt>F6sZC`Dszf99a7Pc0+Ca8t-2$$AWxzmy09bwe^S9{BdW_2MvGTB`pqwPL@*0 zmo}$d?e%qC)+gR&J${YgS@Ord{r&x^1WdJLgSnZ-e%Je!_fWO;F;hB`0$2#yil#-d5c}2ibT!>;U-_6ZUJ?oA}$K7_5 z3hlI%6z`?651eC#YpXlu!N>e*)^BZNV`JdB4JRUac(kifoRy93O-2THgu`&cP@U`b zJv6*0Z`OuUTMgEFC#4m%DJ^X{uWDgoK__e-U!lL7UW5uUOdT>*^ZrJqf5VjTd(+(h zm+Bwxnq*aw-FsL3qvWxE>63lm=#Tau!bR*6nfTMU;zeL!#V&!4FTGqX+P2#Gzxf|G z{*+HlOeEgv&%4gGVM13_RGMxrIgecJ@^l=}&#p_IkDQvCViFe@pPHV26CZ!_oDUr} zezHZU{a{&+Mep^m(HFS%irqhb{yZAEA}?*$r6qX1^hrG4Frq~)B7QzGDM`O3h$~-s z{_7=9Z`}Lr=%1oPzkYe)=c;F$YK!0kEq=A8yL>k*y0?MrW=&9#u#Hhom=KTHY=Zo3 z`}j^iK0YponIV_lyROr>0)pqO*wRXeo08s;NFp?}wDOA%C6D*`hME-!nHH|hQ3+Yz zV34&NFfuXme$3z^*qp3E!CA1-!=n4w%ipREQzzM3Xj#`wJD=8D6K)vGM}D3>b;>(X z$Khwrh`qi2Byyg)+?zJ=M&O8Z6_{YHAVAai>|A)mifocSCo|xsOi`nh%9tJm@KC?yW!ZU zG>6|ydwsE=I* zi6bFW;3bDP&6&HuhUQm(tQnh{`k1*)hjO_rFD%six-_2HaI>_K{>i)RWu8<#H)Rq2 z11~ybosYL?7+iYs@?|+?;X;|1hwIVRS*x2Rk9Jv1mQhwLFHZLs-QVbJ`Muz7Y^USK zt-HMf*wpTR=xlC2q`Nv5$RoH92Nx&#SKgm6Y)RF&_!$#ej;xNtn>BVl`K7ImW~3#} z_bF$AAO~rpxHZQ@Uv+>uZ8AX>Hnmi*kdP457BkXhx!~IJG>?G7md2KrikGLZ_Po4m z>T%`GIcW_Ijb9zPJnj17{x96xaU6Di&tx)0&-vaRZ9AwGciEfPjKnoJ_C2&oBQG!S zIvye2X>qEdM=m@}83k)vN8Cj$uAT@tuxb zbJDW!4_Nta6(1GFgxH`gT%Ao@GV$#cY#7fsPRr*PTb=Z^{jl2JwaSk~{?8lFXC|oE zd$ty+DLJTA`l#uXkHwc6+k2M-QU5to3w{p=iP&4-Y0o;<-dm(`yV9TeueQ|kbLJ%t z4&k0`LQ>Mxao4q_{{)Xe^CfPK8FfaAn)Ia zo|BSV9megA!>h+fSC@vb{;QIkUQg+eCzy7Xw9-%~l&-yRX0dA-NLJnC25``b#gVS-%fB%z~MF5?QWChHc8wd+es zmFC%uWQZ19WM*eqL`gsGN&PV9nU$4=*V9nBa%JE2z-J<@yv7`dzPt_+vbuSvt3dS4 zQfzc;DhJ1hUm11-!MC{c%y1y=x&a7iI0svPVX@E+O);W(z13T zdyQWH(xpp8@waG@6JTCZsOr7I$mB4Rl6@V?^Nqgua9ewOFHhv6?DDT$;?;8}{cJ+{ zO*|ixQ=XHNkx`v918&fGcQZV|?8oY$_!@Pfu8X~D7k}Z+&mp$XJSMI}wBz}9&BfsFBsi`TE!CurnJx3W9&%b!_qLgUgt#9?N zC@AdRym>QGehu&3@j`<=V`OZsKi-+2Zady-H}~z9eudBBE4sQ}k0S{QhU~~;;G(Da zqRj^}$GKmqo1eR-ZZB5KyX-%8>eS??qrOs?FJI285MtycO-L>;*17szcz)c#?lmwt~v!;-pe&}qiwvO#+p7K*k;y?uLn2RXSuE)b1; z-{;St3D`n36hN$svF{&x&0LqRicHt=5Gh&_xy2zZFHcx(KDREs@#@>hyJ!y~H74;y z+#EUGZgyQuos?%E?esuu3nH*ZmVUiUH>iFYpO`58V|0bTyK~v zQ73*BKTJo9rx3e^o@DXOAh4_>*Gj+Y19q+HF8n8_WtuXF72WJ`Urnfy>Gz!(8sDtfo>p{IMWb&t=!qvxd1 zhtODiU0Z~Og?n-bBc7t8F5t-N(@<9~)cuuVeo=*ME92=dE5GS|@lPDNdFAHOV)qS( z+jd?EZ}{?MuZ%Cf_Zu1CayD#w&YuSFc znH&f;E4M9}4qy1O$F;S0i$Ep}Fa z{_Oo>ERW4Jf414wR|EgJ!@5C^>&7QPm+;Lf$DNfwhlhu&=Jw*&{M>-=bAUJX2W!Jm z*y!l#>2)B%C!5k-_&lFJT{6fDKVw@?{NVWHWG{3kdSC5)hs-$Mvs+GSWE>-)Aib|f zuB8F{BE#I62uEVZ3d6!JDnIQ%nXgFf-88?sev`nadS2TrR~T9><>Z_jm;3z#LK1S7 zO=BLtIu{gO85`^Ng1pC{e8#(bbLNJDL4ue4RG)`oWN_x@>fEhll9H0AZ`M$4XJvBVD|z0; z=I2*t>z`jA3ew60w{ zf|E>ENd=@oA|^(U^Vqg$kBosqjAokJ$pcTGK0WJ8FZw?50bgL&9TStuq57j#)YRJ* zo;mnGe_oHCk&@jzI_llpsy<3y%pj)&q$sVUL$5^2%@qQK_1Yu0(48rFtBsYDvtqKh z0$pSSov6bBV9_EB$xh-qOHmUWYn7gNknAbO#>V2~)V0Ew!MCwd8Es6b@!WB|l>4JcOe`$hm11S@-{0UIbAtHpzg~jTy;0=n&!5}K z$(5+z$a||}@SqZR5!uZk=7krii4eV-a_$6P*SMKIHue;Yor6Q7)9SZ(x1M-<`p1V9 zwtuiqs~Q{~9sSYWeMF9H?N)zPK+WgEaABKb)RniE{THu2ZH3l8=e zZO?wA{o!s@A5)(S3kyr@``Z*s$#HQfdU|?zjfyti=!b(7egP1zSye-qC^!J?R=P!@G@LajvX|_pC zHi?qr@3;Ak{`)D}^>^Iu8yvZZL9B+Z>y^YtI&l{|)X4`aDJf3^R>G5#*b0`$&S;VB z_Td==*g5|`rN7Q=n;!ZRtJ=p*lw+f~+&DHShEY&3h$ZW4wyB`iz|IhU6IM%=HT~PSJM-O1mqVbQaLOWEsQfH}>#*ET3wy?*zO2R~2m_U!}}F-J#76a~(=Sy=<# z&a2BpV!wxurcC|JU~pZ2X8&;1&u_1tqoZ*+=DKhyVe6AhzX0kK)Yao{YKOn1&u=Y= z{dGb!(YcR5GTx2}E*&SFoT(lwnfjuxECs133oDx9RD6E}ua|NF|>aeSSh- zbyCtc3|${DG`hq%Kj*{sK0jyy-H<9n# zw-2M>qdR66s#=%_Ko_3?f6a4@A-}b+&ny+E0c^-pUVyi zxUM?wq~@0L3)}JVkNfxU%O<7Xx_Og8=x%*0Cxqu#nlKYsb*$Fd4kvamAWC7tT|8PG)evaE)Vj?Z}EnohCj zg4*G^sVTS6&`{p8=D8W~ zwAz+wEa?3E{jtpTr`MC&RkU6vj53k(N6|xBvQQ`mEqXR3Cnrm#UKAZ|%Pfhx6nNTc z!94fUKU2l8B{4p}2qQrXcPs)uGjT(GOA95%iOV;9_K=fPq|@A0RaK?pzY|nNRq#lQ zv43EoXE4%LmHO!Ha3PRJj_aD3Ss0S>oG<+;32FCFM~@!eD84d7VHW1?y-PJ!i{;`j zw0Jkggg)=~T&ojkfzk;Q9La2XE`X7zd3Y#93JVLx#}nU?O>}?UNGD>a@TJ50*Gl`R zXGgE3>4*k!(F&Lz$ltvl=Km+;n-i4chh7-}9K9`GUCrU&aD zOTPB|K)3$Q#3?O?K6$cD#BSnG1Arv`V~OW%0r|u14|WFyQ9Vo2t7uVhoE=utDs<8I z*F+su(A3l%okmNCkH|0jrFgiI)guF7@1{iR+%te$aWyONfIg5N9qpRG#*`uh4i4+|?B$XZ+T zHf%byeu>d%|8b!yxHayIv2X9Ta&T}kslE~2xN+khgvA;VT_4B8^&lXwboIEPpnCr_ z^5*C{FTZ%2@Ab(VJTv26kt}ml{naNqIVp3Q_zAWU)2(v(`OF=sbt3@CJeoUH!b?k~ zVskq49iLv^#>fq{MrP)vm{1xfWF?iN|Iux;tOfgQ^MNkcHBmvIUhhzzTf3*F4use( zjbyv_h8ARf9r4B?Zn)#}fYggtU_dnd?=aQTP|`H^*+0 zNhuk(zr3;{oqAqy7Y(o9hfU!snwp-7L`FWogY#qG&tAT~+tbriK}%~Vjw>iM^o{BF zJacPncNAC6Y*TNC+2Kmc$@f{sn#P=cWsi~>tC1vHK%)EU<=+w?xhp%jphLX0p~AYF8}_)_SwsqkK*JbqjGYnq@|@5 zSOZQA2t0oHaPu#;>z*FBL#H$+__z3l`1T5RATaPKumo|4nwm5bqKI&_KZ~@ z-)A&B_{i6H4-*rUT`yQ#i}^9__eM<@-4c~~PMA!U{@I*D3yfyh6?)=w*q?Xr zX6Y=aoH};QU7)e(39#K8jPHr zX>CE>-PhQ!X2~`RueZOqZ~oCdzoPC2_0-hVyuICU{8>`HE=n7!EU#%-fp=fujp(?z zqvGNW4_&`kfM(tH{e9vTFiUPcM;I-`0*`)9NLl^8r0Lqcr+qF zb@CnbK)Fs#PTp5cI6yjQ0+js&CA6GCt79EPDK}*VxVhaB&Utr7cgV}j+u7T{2Bh)# z(da6FW42?*j=dBV4-m>kXaa_Ps;xbTOTaArTH)k1J-rQ}K?DT_uZ?x&QgPpSqAH|Y z;N(G0$#I0A{}3gIRuNE~#oDTKYykOcWo_+lymHyS4I58m=xuFpH&zL4#4GKiruG0J z#&}DPkW_UPKN)aQ@XVPvmjXG4TGAK*b>eKj>)qqoxVZLladG81FYzlXD*8o4_<+wY z)K0@Gzs5k1z@v6q__4Lp*lA{H-{lAq4;1es%*>m?8W5lzKMC~ZCS(9m0+B!F=H^9e zy3WjY`u!LnP|7`lGTl0y>NL19NEokG*BUY0? z8{%A@IV|b6l9QA38h#<$y?eJErdX-M1XUxHfrZHm2JjeMfar$+3)DttchT}o0lQ3~ z-IsKA=}xJ9+ZJlvlFG==z7w#As7Z+ZMu&V93DlO&uCA^mhyr{r-2S)fB7Q(B$hkX8 zgLiK}SbLacH`$YBmGSyDBm1dS1g^wIbib<;I}3WGpCfc=pHHuOf7QV-F=rYN50CS* zvQnz5&AKg|H*ekqzPg{1a;oF|_j+(|Gd~-)BFUl}pNEHg6K4P-JI7&`m7AN}FEH>i zI*PKYYH>#g9e{;AIeke|Za%mR1afoS>K{?3D=YDT&`D7O5Cu369pdm z`g@*H<&TXURm9B9%=RFY>ZjCB5Wph!uO=(`#0k(gxCivnQA_5v>XP~SkDi`8!bI#9 zGeSzI7AEzzKHT*dNCl1HFIxaTNWF8*wQgVib5FKh6P`;{Lv10hbZLG(jsG|z1d)0# zE-o(qf2gK(-+J55tm&@~6e5%LEqh8?t(_XJKDRv*wcZq@Vc3HQ8>d}ve&Jy`qWj*Y{pHn6ql5F9Y$b+GTHi97)dI?I z^S=~8JTo4mX6ZFvTg%imb;xG>!~T_B_sF+zfA&FHBH+b~ZI-DdWShXPTDnwZSX9_! zQ4tZl>;ON%SC+K6)qV&WZ|Y}vc4al~J9w~cabdxH$3w}t(>`b)0w!&|V_?SInkor; zk(7B#D@UQ9zpA=A7ujZs`JmU!+q;QIpexJR|J|)ROMG=;=dN9w&v4-Dx%cjojiDe@ z#tbB>rCEY@?{n_!>wDs_tF7y@$ZVE^`G5Z@R|$y?*%rO$Qi00dRv0#RC#R(3GGBUW z9vmDT)wC)P^1m39e_T3|cLo~I>2=|pDTW4<2_N>{gU-!8jUj2s+OT-#4Y_37$3 zCc;hCgF{1~LcujUvSvSvh^YM>DIRIuk(1swF8WaNI1MBz~N>M9xah9mNkEYmx%amGimJYNTZ40nvh>454q*_-M zz!tpPg(zoEIDrRTR0p^YG_-l!w>G#~UtN94V0q$4iF8tSRFs=>WBjwKWfa7fc4PJ0 z%FfPC&6aY9!zzl3Q8paf&sELlr9phu_?S@#ImZB-}f!ze|{v@|;7#)QML;tDag+xd7 zt5>Zsk!4znWTtP(A(6tCdY*C$qIr0asKjj$6cr5z=sG+&Hpa2&f@y(m9&}`4rdfWAR{`HN=6vC~MKw!q5tA|m6^l2XR?}<^Ylnds52<|Poc{bxq?1r3-41Wv=acy$F z?Cq%+P{4Av}jn~I_3_`;1fF>>!qsTHW z^yTA6iMKa@h4diBNJ}x87X6!}jdvB%Rd5y737B=VYwluST(fss22rV8j=-0Bzx^O^ zqWy^6<;$z>#?eM(cR`)BMed;&`63+1@n%bRTT)I=(9djds8knJmF(?>)KI5l>xM&2 zi`}=&j^_gfTvBa-CJ|&LY%}~q)qbe8S4~l|_=7KMQ3decCB;4K@zb>Pzl2jG69R49 z_U(F}hk0)9q!BP>x0L47m6qPDnyh}GU<B{czmn@cp7);0wJlP4}R^9=H=K7s4yiRp4yj3-ypq{jywo zBQV%~a4$PT=F!CsAuK_>@(By0lgM6?$GI=eG|1PdYM;4~X4^;*B=7Hh+YeYIb>+&l zj($H)R$kr%VBpH};NZ6zKk@hW^nCfNNZQIrh)5K=tem#!k&2Fu-Jy61w}Dx}9Sss%QCVI-quUP%`#KhZ4g-*4dwcZ58 zjJ_uu2gjk@{j-}kZ7OPPeBU-$T~!5we!~^Zty{JvIu)Q0m|IySB&gly0eOFq7?r<9zhuN9Fc>*Q-T z$L209*jbNtP~(vN2arJL2sO&Mh2zS!vWm(N$QB>BGB~}W`0Ua4HG6U>6imz;wKSa^ z`{~#lLgYJk+z1uvmZz)G14}hAJ1dP|d&dSt`X-3=rS)%Q43b_S|6nt6NJLcBVziB~ zQyp9p7#My0bA^)!_AATuO)W24Ei5kTp=)B24*U@I7jFU}dfK4sKz-<#vi-sYqr==U z5AZIp6B93HkbpknGNC)fu71R!#5=FJq~yoXpB{KqRob3+EUm1FOiR|vRs3p<{=!rf zDbAo@?zJzu(g1oAi3`U~FteK~I3$yFroX zE~_Xnk3!w5dHySYq%lE>pw&+5_fO-k66uH`LP}5Xb#$&P(h;=3^w;q&OAjBP0qA&)PTp`=@Ur^c(AFx7?U&lIN8`rkeKP# zKNagONgx18Ng9pEF!DQ3!3}W@g*78ZIDx!2LX;dxSA%APD2j;a>b84Y&mkkchTtd5 z=15CRdlab(PATveH&a|qjVvg3CJv6vV~UB8n2GPu2lmWpe)i&pJDBk&1;c5qp!Yr^ z53O&y`HdGW?FI;YPNF^^2&$yGx|$s1e_+a^FJBa9#=c+m3t)suxdqm(PC+5H4d{Km z4XoypeD8G*)iaF( zhU~>wW|SauYa7&H%$&rm(+grSs@W2AD%jOca3nUK zCe&*IKeQVao>hP6&Yi@R;lcV<4t;Iy&__$rqkIL%&jAU0z&N-KEUzw&tE@gUfHDmb zAYqkQ^6}$+ma#9d&t}Mb$vmM_7jH+aI)P9b^!BEF+3(X>|@4< zagY_@lWd|iki3}-LvMUHb&Vk&CO!*vZ7a~u9cs6mxnOR78dA~5-0CmeTherif6siC zW+dO|~I(l^x?YYCQQ(&3N~oJrxK!X6@}7Eh3I{J7KVRwi3cXwtxTr z3HZxizk2m&(kK-zEn$EnSzrbVG~qLPIiOETNjdZDo6?9D!j6j9(C^paEAjlb)umS8 zqGUdHjSTnWY)lylDr(@(QyK;K(*umhj}K(lg@cbr9tR||%tK~T&oO^}EEfo>{)4UA zjT<-4`^yKQAEA2v9KBeC`5h#N3U$Nlvs+^y9dU*hTH&98&WKY6eZ0dSp=0HjL_! z)WXBUPTNgfLr&46ex7@C&YNh^U%x71csT+(Y;tn)iI-O?JQa;?bFf`~AzUTl!YU~( zDwuCCjW)5sc!E42h@00qVPf3Ipbl>6nyKmTZeQ9RYfd+A-Rgz0FUMs?7^v|+!Dn^8 zNMLcM^%e8*^{x0YUQqp>^&WU4P*>eULlEuAsc2}TUcDkiQ^>Iyd1;u`!g^pwPHyfG zgeaj#e1X!*d;9AqAi}p98EzgP+h1H{hB)IF8u}D9za!6voX{;KCI3JWH5&DJdU$-y zFsOd(vf^;1d^!cN@`@tv5U=XfHVTJIy6L{r5q*5TJE8tb#-2M=8S*8NG zt3Z3RKsqj?Hhik8+OKzPiV*mKFG{VKg+XJqrt8ZJgggr|LxrpnsNuuIfq{`qH++ud;&A?F=po5%l3hI9~(Aq z=|)L5$_Ey7fIal|^78VRER(CeCT#~G{X-9zB6>ha?gI>)M}&oGFeXa@4Nhl)ukp;a z8mwyG7KG}`rC)w}r4R*~;5)&ZyoKczgOLIP0%6`!;7p5C-mlC~nwqi%zkVRw^tffrE9&Y`B3*ua2$;g{s5!c^+qbELu*G6lOPUo{Qc_y@{W}V% z5|H>Y*rZ>-eqA#%!gPKg?H&pQS+-eMd0OGBCx*Xxn|BkSy$I;4QSf~0)~)*J6|(7Y zR!GCFqi1He)-vyp%R}er!PA5M-TzKGs>1ETgUN5VA}7n65|p-Ls&sW;HK%)=oXif6 zk&&5MI>k5;qzt0_AkM%oJ$+JlEg~d@DAciC+9ABR-H0257mz`PUqHaa_wRYZ zYPsbeB0~UdJ?BNW0o+ffPMi<^Vqsw+K0h%%JpAzQ`Eg%?E+-0<+p`U^a)eTYc{U1o z93H7ppFR~~6x#>d5{-CZnt18c;P8$eJ4PrpAv-VKN|*iAisCd$UT;xZSy__~Qtm+d z{?AlYR7682{HmE;TX)kH!Pa%nFn(p!2s34l(_#ihC>4*g=9o*A1FhgD80hKg4LeD> zPhen3fehYB1)CHYu?r|k5d8@CZr*l>cBI1PgUxOIf`d7Ec|B09NfxL?HEaU~W0_76 z)_TuK<9N)68(9J@aQ#rL^N#VYvrh?I*1?B+<9VVDF1w!WC_o@bW z?cAAz;5G+8-b*j)5X}wxcsu33eIMn*1fTJ6b6-#8fmsHAPyN-kO+_|CU+#k?8pNOx zJWa4<)ARFcY`*E~T(+=R4A3Rkgr5l%GD8{71&XyIID&rAi~Zo+auKx_U^v&R-sxBD zrl}JrdV;M8=*uQyU-e7^=xIGYbV|7#DfQxNo;8c@kK)a#B$AdvEm&+*VArsxPsyiq zY)9K>+epw`x-tLO92T+jtFEl9H_`>qZ3X4L7oi&DdloY~^RZ)w0fBY!Q8x)!kag41 z(dB@YwE*Iy8O%rZo5!SNi88y|GS}rWaw?^~5hQ3Qmx%q8R1zIsg#|PYm?)-$=C9&x z?8O6(_P?ALAmcc8OlnMVGvG(@j0Wje9ewBg{40qEIUtKB=zY=rIsnOY*Omvx!$4yx zh2xeMdBFx|E9d-2r}l^I_khPRDW4%+)l4>Y5#Cu>!MDBLr}rD=)U_4zWq; ze9TnJx)*@01te1@ebesKfha`^GZcu|JAf4(#9%71bWmf*W4ZxG>we#i#w< ztvzbW%F(J3iHWQn+}!^2&a=Zrerf?>H0v)n0P)ycL6Zo7myw}J-GJIj+-V0MA{XBg zpkHA9bAR@oZ``%b%`XvRly}(kSQ#1b|6FVS|6tjGQo>?l3^MCLOa+E=>2D#Fynsj) z)^8n{NOJ+G6K2KMFv7025vl`Z_%i{M1qB6!uV)_Qn2~V;+%ea$U(Z2kCfFSQf`5?d zQg}rMRkbBnjy7}dGXQW7ruRgr@xsecma+}155Rlj=xSPJbibMW@AhSE24y z9(b$D8CRwmzS}l1c~(1xp%h8J7gnEAvvrZZe0jim6oIih!3um1>omA_Wk-5Fp%buH z7;Ec8C%k27_-T17ecbp0 zvbC8B`a(wIad+hJ=}}ikmp3XcgcfA91mS?MP3*Aaum;JF%S;rL;PYhq^}#jmpPIWj z=xLsn`j-0oD`ScVB^j=F?%YXqHihWZ0r7>eDy3HL7vMj~^e!G)+d82Aq&9iKL8Z~c zi<>uc0o}&q`$5eTjI0NFGV3wN-wg;%7-3#3Q8eK^9g4ZOdDSMKX7%M=Qj*5XO~mQ~XD$!Mvl%+WV`edtB2ka-E=f%3RB0mr#JmtQNK&X0uQ zg2Qf?Yo7U!KjM^GgX>N~hv>lgw5f{|4Ub^9*76t&kMoitv&_+zZgkobSFNKHp(VG767KrJ`e!j{ZzE-WkU~}z13rh(1a--f z<)GzT!A(ljRAxbEi}@p!pk5ZCTIPCr?ev~rp}4g1ZQ>dw`uP|r$L1m7w8TWu53Xwk z*Yx)(SzEu?tSCd==RzPg3L6JF)PkTHJWY-Fiig(pw!rg{?167GBkoCQL*(pBNdmK{ zIr!~^E$8%Vs#+R7B^6b?%~2hcg=~{{{@T{oAeM39|4jP9NaE4+=RtU+SWuWDI_JS# zeJqbkir)~#aOs@}ny>ECIB{zPyD%q|fJYOu_0F;N$=_wu-w0&cnGT7^W6qXJ1$tf39Kvqo zKe7ES+l;~N6p({|<9cXEJ8U_!?nE&1z+}W-mTCH3v+tr&)?boa7jAB{WRLg}2xh0Q zW;GgqfVE220%Ug?M$w7`#y4+18X7W0X9CR@vbK{OgOgT)6E(o2>?HI{EGC4PFOnSr z=ZL5vSs*COfn;APoP1xU7LJLE@EH>j!t)@T0_c11tT$%8^(WFCC;X8lnQVEz=LIsz|=6sL${t7!&glAA` z8MdaqhYx!Lop@?d*B?Z#!Q8smQg~HUvnMXnMbgmlq?WceUmO3(?2e}`;jWN^2^uv_ z+?5`}0gXuuGGbKnhYlU0Y1&Li7#)%Spw3GU=qf9_ z3t0^qhRIVjIdlA8SU3V97LKC(>FMch?J6e^KuG>5=!?#l$|1&{3(aU~uijd9uYG0=U;}P=!$pZDdnYE6f zgV8KwTcMrw04icBAw#t*?w)w(#_{}ldY6@1wOHc`44yxL6*c>nWo*V*Ffsi=$0Nqq zbL}uqo_(-o*LxQ4MkWx4D=mdWm@J496;eaPe4rYdplpN)H3s;{F)_?$PRKw+s2}{8 zsGMsf_At97U(MbPVRm9-LLuo;x9`Y3Xc4c0s%0mE0Rq~D7NEOxyZT}ofxf4=w;s?i zWm*%A6ru<#2jmUohY4ixEHE(6Mn{`aV>|2afQ2V43Q?ZcN}xcd&Gw*d9LS{^ozPB_ zl9K9%Q&F@3iI2}Yh)GpJklk(voIMFtuf|pY`UNTR=*^p>H|rw20c<^$sTq5!K7G38 z`R?62iroF9QyD&ITi!N)2N0@X-TlV1bt%F}bQTQyeSraFKl~K|uV~hjt?8c*zH&H& zgL@jQsw%2kuWF!jEuQqikslESp3uQHeR_bi^oE7Zs5afF6eb()OT}?g!aa zPj`_BEIM8PA)_ZQiu08$HPo%3HF{c|Fu({Ly!bFtK8|gA=XS8y5YCuX3Aak%-p;gK79yD3~@02ndu`RJ=iX(KH#v zv|bAGBDl5%@Vo>zVFeYH*=$zD-fba_e@;^|$QFW?qBIb0`q$CX?gE!}=S2Z@Zhy;Q9yc2V&!^q6KK|_6!$-F6 z+DhP~7jyb_Ag*$kP^Jn7?!EN%sr6NyAq1U5FnZT9MR@{ok%tr_XRyPztzlO;r*1(h zAO>%3S;qBQ>;v$27BmuC(VfQlE3F02ADWX$32%U{jZzM=AF#Ex{neQtDlmq6LSn0q zCm7rsxiaL%Ijp@kcxp>>L8fI76b6H^18(Wq<7B81PAju5>V+=(>}(o)zXOW8!F~MR ztV;(}U0aq3ZMn~3whM%K$b?W}xeJQajc;wW5{d+@J2h-QcrDE@%fl1X(}ZKqNLuM4 zs*u&YD~M!lv*~UN=|b#cRKOU2%M<%%bwF;fEyP|1Soik!f`E*+*sV%eL0E+aIF1~- zmtc`443)D4l8{|5VE_V;RsxGauU4YY9&pF+bRMslTJSU5a({xTUT_l-(N%l_uJ zKTfSS;CO?M$9#j#4(>%N=`1T0b`n>fOE^as2JvMy8rgKLHG;A{n9DTU2*^KA)pFB6 z0Mg!3CMHRPoz*rG$}cX)H1ApgUI6QO0&ATfxVNSk~?wY@7Pd0%Z& z+oe+bX3=JXd){lOYwga&hm*}sCRKm>v@Jz5v&UOMH}>e?V1kL>h-{tNRb&Gh_X=7k zOBR3fFXk7J*yvD10(lvpB8`YW->Am!A3yG6jUb2xMWj&r@@1cM_8_QL#MZFvSk%y< z^v0xG0tTrxP;76})-{_>Q)3SSFh1T3BS{gqkvCQ6I?Niy)kbz;Fed!u_jiIkGPuX)dFh%Z0*L=a=1Jv~fStV2Z%0wNiy-Nfb&ciQr)W7wf^T3eaVj9R2514Zlo>(`x5*m#B+PoGwJ zQ7I`aCr3EoV*}d9A#`-GPYYuONdmRlt~XkJvmgvxFyN6a+W6lQo>YNypakqX!FJfp zN*QU}Y5(~4*9T?=i{~1Jbt>xW_JAdOA;QU+)`p9kmZDCEaPhi6*YT4dBb=>|US$&W z6HbO?0oRIKACdVDr5j-&EC++MxiX=OfNM)@p^=ekO@m>n*Mj%@#Qc=fC5-VXN%}e~ zwxFZ@FSo|B6d1q6&+5jTr!iRq7H2K22HSHTBLI!bRd%z&75>=E;jFE5xF3s&ZV7fB z5|x;k7-5$Lvw0dD6GV&2!PKEs;KZUXmH^f4++5eGRi`JjqB;C}D<7V`cusHRuhvjF z{wX1Ae5p;$MeeQEQ|$sL4Y!Mbv&8PoGV`tn*8@m$6G1HwsN=x*vDGu6K$HVjFjoiq z`xiGZ=wWFM@X1578iI82>Jc3+EiZH{Z_B=c0mz$#QNl!xgOGqSL8E*#b$Ui|=|Kf* z&F0F0$jCa<@BsAQq5KU;PM+KbPU41U{Xkv7SM(1?34`e4gwO`>B(p6w>$ld{(|pm} zV!(TW-_ZA5K_p~qn!Jz)e&jOk5R6rCzNyCuL%4^%!69eDXwOxaf^yS1E{iXIgiaoG zJyVEq+hD<&sxyc1j|=o0diJ*!H8rUuRR*SN<+{O`+?j(B^U~dw^qZe)V9g8QLJ5+k zxVNngxVOt?$s{FY@8h8eC_Vb9s%~a2m6h8;<{RagW8)V1`Vi?5nJh&%ah`q`ZeTb6 zesQs602jz&3_ks$oZCNQ;g-Q=fzd3Cu0>q3M{qYrtX}VT+1Y`wXueNlOS7cCJ=A`- z84i6t;7cYoW-ka-6a2Zx!j(I^MsPCsfrX9Un{Z*ROAT84FiHVW`S99ZCzNj7_ zp?48%CR)Tqy$r(-G;8p^2bcvIoAgX{UW}|%g{Vc+-s^9h2mFJ%)fI{iTnF@?F%=s)Ju7g-i;fZof^PiT-8w6Op>1mL% zq;l}!L6U$$aA;^!{(l4^6(~JlU>?e?_LIgOMo_N-T)@+AylcPOv-iM=OR|7)Q=fa# zxbH3M2!T_H7fC0um*ZS=G+P73_iVkAExDJvXMa3q;7*ZbeSxV%#C0|7FW(!9Et;Hw zUk_mqG}BU7r)n7fDLFYYaZNK^S(lK_2>HN_pno=L=O+s@I8AH-abVXAx59(JCSxpT zKNJ`MEgoqb-rgb*Lh4BMSY7478#^Z)#lt9vk&Z!<~ouau9V+4GH(mnV5;Pl;_3F)uGKsnjiye~JkKiMGOm&T2HR0Xhz0Ar!dWaBx_C8L~eqNs$ITIrb`P z2BGAY;r8li=MjNX0Pi$|^~8#=oqn{#I4up$#W`nxzhS~@Nw`Z*2xL){j!ozwev=Tx zOv0;CQu07x3>ZVRU&v&e#4(k<^;>@CTJ7r zFi^z|LV|i#fMcI6XRDh`^7Y)r_TUON1Gtu{MQpwlx3s9Gm|Uzx6N8V&Kjy+BjHLvC zA?|wjVc~12F@%$XdyviyLO0>q4$JIH!&D zwv_4n_G|vakbz+vg=u|;O8e)!#AX|sd){ydB}<9F?eOA^CSV^6i-$m}>)I-|241{k z`V&-G*EYwgz6+Vz#9moIT^D3sznfACgiI`lt`A?u30vxnVSIpqSq*ys`zmmT51~SK z3c{X^u6H&GK>(XSjA@?eelJ-Hzzh(Zj1U{85Cpu6x@m^j`#wE`!ju{*}whR?_y z`F2U+GXtzfmB7$^0mreL(+y;IfkXRaMsW&CPxR*+9Q_HS%$D7eCo|l(+VE0;ZRVh^_k9uOCZ@!83pc@H{maP8jhZ=W#JL|r!BNr|53jUbD zh{^@)MkYP@KljK;24Q>>3-D9X=g+$cz68@59CD3Sg)nf{*X_EFIOx|NRSmzO3Ps-T z1TWUen0D^8UQ!i=%Nqnx4-{jpTs)6?1o>DW*c-+o{fKyAkUH0vWHv;8P+3sJOT*2F zg&|`I&7tof1elH<4eo*c=pO3$!0|1Lj%c>ADhB=h_&kma(*!btt(9Z}j`e|J!i!f? z;!v4G6F#1QZp7uV$gye@$pB7+}pLx{#@vnZEo1Akajq zrft3ko3EjwR-P!m(t;Wb)i%2MC`deHXEET#BwRnc6{-PZl>$ zn6|PGf=N=wW48O z&WEv znV012c$=ilt3L^Q6c$MuSS!gUP$-$OC)M1<`ee+~);2KancQLU2zd6Fym6^IN-O~v zchU*^32?xb4%#-VMX6nk5>sr=jPr%z-ap6)H!7_X2sy-{w-xW5*1bS&gWgKF9tx}C zgPcguAE2!2;j=w7`}KkqJPdT7#sFoJxDP5Blte-{i`&e1&!BPv4aff7) zD!Fb+BrED6v8Q7erZxB{#N*CN4mf-pLs}IA-!6Au5XwC-_Z7at(y}r=nC>kDqXK{o zN@{A7|FZAdsm-n^UAy+GYS0no6`YVtf#Sc6N40puoLc zmJ&}-z01)O{UX_QtFmp=UF}yROZ3;;*Fwe|wHXRI=p8X~%344RVp3brzGz`<8J@ol zSOfr5amKm{%XMZxhD%4|z7TDmwim0D0-bheVFC0paK%Q}>-hNdDWmvI1@5xX!8}_r zNi{BtlSWW&cXcHiXM)7!GTT|57@Vk;Yxz(h78`0AVby(y06HK)VGS%mKs7=6Iso>< zuXlCF;=LM`Ew$3(lQ6EqX%NVJqM9!N<2idIdGgvVcKt7^a)K`IrFrrgcv!HSaJ?CjLZilvoY zJtkdpimWkBH&P%L&IW(d2^wC*BHA}UhZD$xRCBWN85=sYvOApyi>j)sXg;)QqAQqr zL0#Sy&`1Z@IoPRU%=+Cwf3nyLX(qvNFfMhR{dqFs3Ic{_)mKj)v<|?gBt8Yg6YMLo zSUXOd-rbO^c^=zFgnw|QS#nc}upV^Iho1sS^dqe4d=@1c8XW68#N;=pE*N446Y~idD%xmSAJoFV7vif!bSl=RM`0Is> z1GI!`1Y}ph4Fh&Lq9c0b=R13ATExA5yB95r*rCQJSoq@OyD)@P{KpX@2A}k`8#gv# zdTxG$!b{4{ye;brTDf7^-I7lF;QGi)e| z+4IS}b_J%?w)Gu$pwJ0Z1JI(NlcJR-1%oiVU(*!Ujw)5cjFwhRTV(8SujYYtL ze0otr@qfgEhw?&=eLiLFiADY2bE8i|k{&^2Cbn3G26a$!zK170mmBS$Z!x=x|M ztk^ykXCN$u1`IbPTb$A9zg+_`h7d3pQ1|7VYV_D>$}U}LVt zxlmei;|HJ#&xec?kf^%4*W378Mhs4dcEmesIJNmYEO}UM=c=GQbm%%Hj-kc`3T)cl z$0sI`!2~AU@FkTHRul{4_$;s>j!*JA05`0AK)^w)77=^=PK*74#Ah`)If)Q{pXbjX zAYtlFJ5l%R7cxOr$l6rq{*Is{21ZUbI)-iVaQfR-tr!ogZv{ z1_(Us})(<*fb?QB0t1l@h~)$cIVFMwRcg_`Wq6x+UO~P**`*JvFim< zQPC({?Pieq0ScH={%?j$4{XtW3BO6ol;MMz#Ze5s|GQUbd|XWpEs)1i3FbSQhSO)r zs)gQS?4&W%-Iiy*`vCc+=i4Bc{Xjet#Lu(HNKRW8w`o}T0Q*$RC$uRiMa8d|Zo}4Q zqDHVO4==A2s`4cMX)oN6fSnac=C|Ms2ulq<86qlWcdpZ-CF1x=hKZu%TYgSOir5LX zyLSW4|4Gf+;)B5@>t29X{oLdFi@PHKZh21x|JnZFQu|1^geJU?EnyLO@z`y#=1@9( zupi8Hv*410dU$g+tT2583@JN!baM|wss0nVvISz z5^+-noeJ&rHL*317D&kIB)4$&_rXWpY|4)3nu!JOsIWjAXCX`tFpy7`3!nf10uWQo zrlx()uaX9{)GDv^LK3pm@5_r#REpaTAZgcIYI-kWdxg&z^|=JCip@oL^G}tc(taJo z7LhqHWr`J2u@^p2x5iRpae~AJu?uGE3{fDPva9+M68D>zBm>$OI#1-uB*tES*_3ac zaL6QtN4@qwO82u_I?Trooit@)TRk7fTqs4mb-QS-3qc#px9<3lFsNDv9z6*L7#|cQ zVNio*m_+9^-F%0GNPVS62gcN3>u?O;u(+PK8j$_fmPw8c0|~qWV6!`jv@L`x4~q6w z>y2}SDi(6`iQn*B*{KbmS`Rb0FP6 zWE@koA1}kDH#?4W?P_msZkBbWx^=iB32G!h^h+{wdy#-}UM!oVSe z4CTVY)~3yye_$r1F}tcw5LAq_jv>Tko@M%d2c~^?t(?7(WGn+`0wD~0>sGgsL06{m zwrV^EBCP2)RGnh~jP?CTkpeQ+rNRDkn zC5R#@S;-j@5GC7^5s;ig36epw1mPPCrJv?`>-%%-y>+W@>5qm6&OZCBz19q4jya~P zFo73}RY=UKbaz=V*S%N`K6{-Y?u?211CJuRJ?|W-3S7g#ywK_D*cb0wMdnbXSAlAo zcD2by0gWMlJcv7j+6N8VF|7MdY-&`o@9xCK#ohI&(#Mhh%h7Rp=-B{QIM|&iU!uF= z9q{%;IBqfLYfEsp01N&W?ODk^A9Y-py#CI+2Jv&d`0cRX>5S;;)u?);8UL`6v0JV8 zxm46kxGlhg#|8e)71o9vL%5|I5_>h3VVELn=K?saDW2~a6>A3ap!J?A1fIJ^ipw?j5 zxx5DObq7e#DwXXK`+I8QN;ib{o9~s3|8kYl@jyiXbjIt4YO?!^)9WSnEy#;3ejxB> zR}3RjCjIlRx3^@EkEoK?6VH*m2A+-ejnTLvZBp5+u0G#p5dIhpPxM?Z0g(c^;(KiA z6X~bVx8%xJbQiibk;)1*9q*&p1Z@<%6-%hFSq%d%bC74Q+qzY14c~DCc+U?snfdo) zBRGrpn=N&YwK*W(fec52My1lT?J_zp53#e$(8>Z8hWd(h8w2RDC((Rj)cAx=ma}9C z>%8O0>z&D+)ezDvXFIF0MMv&VCdnkWWyp#7@2p z2$9eO(DLvVI0LuX6@p|DHm+)&0|+~TDEIgIRvljGhl3RN6_mk`pAP3f+pQ6jkij^rVLfx=;$V_WkfkTNsPj%%jZDS>vLBZ zkrX4f@4)u5DSlRTU3$I?%}79zRAIYty0hQ0#Vu_$REaQr_g8z5>`~54|Iz z>_6A9A5OM!Oa0OVC0Z1JZtp%DM@vW7N}xkTx9G8nsMbRkO`6^x?b$iyY&uqsZjDEK z%MKVxs!-MD=HBg|cF7n(cM0eF>yo+G4HgKV#~DVSN-V5uk{GDG&sxEvKM{L7{FbQ) z4Xg(s&a}fvqpQnN+y}HtL6go+fD5v!lJIpJfB->8zmwCc#-l?%Z>*y%ELKL;AkVI4))k$`djbZF(oChd=I&Y9icMlH+wg1X<_jR zaf1aKsz7ii6(z7_C13Vu?&0Ctj1Ti3OZF1geUH7S+Tty_$7<09gW^q8`fwaFDFm-b zw^jge;e;SB$g&r>KBB|?zSXfH5b}*A3@*ITMTgZNU~#$Z-M23rCBtiI%Ny-)P`Fw6 zN156U$rGxba|z}FpQSx|8yw?qZ#Z?-i0Y`r@ol3lyT#X}2gwABOFu}-iMjcl{zT;( znSGx;1LcnJFDbVkJpRaVJ^ywG8F#low+${=`|fn~%V~B!&Brq(ZJ*w24k(p!wbfs` zs@YWPCtX6Cje=O{XprulLnFH>^ti6{A~SsfcM#T93qjU%78Y-c`K`GV&}dZOuSjw8 z|2k4SsZFsreQlYWRRFG@A#I?d;(H-UHw1vaqVLN5+BczpzrUtB;|{?Az?=FB zhLFNz^XH$bi7A64D^Azn^wsONuB@>XymhUo_gik0((acCr0CG!s1lg^}t5>aABd@Nm{))?9 z?YBFc9Iwropnpktokt6*+AIjLM4V6=i%sfX0RH?jAZ>(~Ag^!G+o&S{$cnB4M zrJZ$Y)~_E0Qqwa%n3>GG(aqRc@{XgixjB!nf3bci5%e&qhQnhyk;&7XVXKUEIJu~v z?b5IS0II}`HNR05)Td~-i7btgjaEGD!$r_qbQ56raY_0M)@dG#-qnPH_b~}|Qxg+e zte1O?7nhzV5~Coboy^KLK_{sNSc+`wla1oUJ@(L6slL5_0*3k(?>crm;P+q^)kcFH zZ7%A){33n@km04$)A|*Ou_*WEhnLU}W@5wYw%C`XKS|))KSj+_V@6h#qW5uLu$Yq1 z3DKKMR1SjbfpsYP{vHbbB9|U?7wa28c03~?!CBAPFlt(RMpV=R+bbG8yDo5ZQh>rD zi48?ebrHgI5yAt&7RErNtUVmzwZ=aAI z7|(bM)iiCLwF(^Iw%g85c8VpL4>U@{O>rVwcao)|m4zX3;XZe*n#*HXkWV3_t)vI- zv$Qa;{=s-=48Zu#AG9*c_|3#9{B( z(NQ@Bxdzok93S~Z-KQmdq}T&dQ0xWIfjhG4jd2jJpl`gRw@$aw#ntsZN;mE?Z0Dn& zAv83~lk<8AIW)v=S}OKHwO3Va3)-WWkyh-DLN=5a`OJBURa^pU!%Z%<5 zs_ga$`wFfU<1NA>>YkV!yebjrC@bJWOP1ZujFU32S<3DKv|~$EKNz&&$t3cwk=U?D zE4&XdD%18wZ{Rwjf9^4DjDx0 z?KoBrcAeJI;o)*9?K%5sRs7u(aTa(9S0sm@gWIFkTMmiRut*&8?z4rU5f(`v7V3s5 z`!)@1Wre?%EYq*%>-8?YVW6cZd-XWWU<60$D)(N4y(O#MBd(*ccwR!nxoijq{Zc|G z2nS|Hn%rJ{(9CX}8oPoL`**w6Clmk~+;*9;8>}zrldMIZ={#(+i|+C@bit_EU+~Sp zfY>P#dOfeWAi#QhdV3*ArO9 zVt%bYIseC|OP4I!C-s;eur?j1*6v^5`DG<#=6ShTZpfBnA3Pg`&UA2 z1lidp{E_WeHFC6n?G4zBh+JXb{p~GrLb6^vBeaW~`#j*HmzL2m7{n29_oCZc$G7xJ zL1i#@Rv5SCQU`enyWhc4tED>49tHrf2wEJP7d8DUGmgN@iy9glG%v!Qf~?ZxaJ-tm zPP;=Iz{=>~s}9y4lwk3ET-rzuo5W4$LV2G+kAhw~B_!Bx*~e9V;)~4DPJkF7T+B8%~+Wfs6H; zO(-CDIdINhvAX3DQq5veEoGsmrVi=^?WeI-F5+pK>RGW3G&C9}-cGxq zcv3^9W2a@>W&mb@i{WE%wgW==RFr-=`h7ujEeLNSQ2nD5u}fR}n2Ppf-K(nx)iYqK zrI-);FD)0`y;DUtM1iFf8n;hirurN>srk+No`EiFP_1OF+FtbZESzeh5|8cF4IeIo z&!eQ_9#i1M69>0>m9A6~N7cCpq)+%|s;oM)%0gCh=&v^w_5Q%d%Ui2i3}z#PTXqs$ ztORt1Bc=NxRT++&sS}M-6zuZw*qCIM2{?%{DBB3I7WyJgbM_u(W;=Yitd%qW9&DYV zT(U{0l#{z4QH1B#11H>bK*T=$e2jOoHx4%&KYu-0hvDWkUpl2O1eCs=5ODwfQ{GnV z4^*eg(o-HDU3!Ro-By8e-b3joI9D!EyPPVrj^{ksXiyDW$5~iRV;Fv~#%*o~)r2>~ zfKcg_lVWJD>~U1VwT!(J$#&j}OfC6sg*{BT^s&e3i1o9Exg-ozz$a7=&4_q~`|%dB z&wwM)ug2JqsD$L3pfTn!%x*Ojnlx5np$%lw<^l^7)hRKjLQ=_N&#-Q<)TMw0>L~v!7 z2N(ECu+%aNSyfV=g!R&F%mr53ms?W&6h`aPi(BJth zbLAg@oQseN(XU31S$wIbpHQ%%2E*Np+)!iG`pI6skI(;-ZUX0Fztph3M5g14HESd* z_{lE6zTeZI^)lJzqGF;8D-8eS2Xmq)Cjk5=l#=SOM?SJP8qKff-zp37;r zp)5w32fd@&noTH5-#|RMe3!Tn+#UM^r1168hyBiLQ3F}8212-BtrG(`5|wD^>7!r{ zFZkzp2tm*LLYhT90s|kE zLc~4xDP_W@?K$^c^c5GRn!M36x|68|;y%DeE}86)@>U{OYz_dNJDhsZVRc?GmEvPi zG_;K$e<-@LB!GiE!1x4GVIKb_f~fuG6DAP$00Vt?n86G{{;%)Vx|c8Uh&@V)hi3U zg8}>z1RVBT7oT^KtY;8zX>xh9i?WTQ6^TBZkfgMIsdZ;0vBq z6yJ9(EiKwXPB_~ngIRm($)w=yw>EA)^wV#^0y=QU4uWINshjBh;DPvrtOHmB0j~M=*lmeXy-PJgmt;Ke%>8!y}Mw+N719t216m1L_%5^ zwtZ5!+vOr;aGNiQgW<&wA3Jpi8*S~7&vKH`)zx_vQ+BUFGCQ!#%OLXYknsNRrHU#lIO@Ei zL(q$^sI}tl^~0T|aR8y|t3oH(van1&V0Az6clVBXXORd|csipCTQ+RCVvIb6ge?fY z4XTN@7@BlFH6ajEjR#>+?XgE*9PS{I(`o0M)YM)tE&q5W(*NbC|2r|uLD(|&bytN- zgg8XzW)h0M5r*x-9G11G<{hfV2D+d5qYOxpQ1;svRF67(1R^?5dn$cugh)%N!!8;iL<% z^>uXCR&=LP`;4YyFZ#$5VdhF4>&jdXnIv6#q48P`?p|)g#&Ep7viC9yLk!%em?<=2 z4%b^OVS@;I%*u^>YNI)HgbVgTby|B=sRB7MZ0oM&yIx5l8UVXhQ%)IqFw&*cdQqEQN2~=M1$#AS3YswvWAtNibS`=&F>y(|!b!k_5V= zk13))3>^yVd&Sb}PwTGt5{F)3+X`Z^w(%{5){?jjp2#LFVbR%*Dlpb)CgSL; zJXJxzQF!L-F$g@@v~rfCe@>lq`wL(WYyGb19%SKZ@oIGL+7oRfG&$Unpk&fr9zskP zd!6MR(tx$6cBEte%37sP>VxT{kIN=`!KMXmkaydoUhClk)+9*IbriVgh0kIL5(WsR zUlGjtJzwA7e%2D`QEjvjI+Xy&?_Qy7C*`jUf{~;32Rjh^+aGk88 z;VDS+flEkFEv-CIA%kj2EuTVnTp}mYJV~+~(L7W0Efo@K zT)LI{nip+s(!gdqM$xS-aUkZ1p>M$vrN@DjJW7Z51@xg3Np>6tztp|4Ljf3mqx>$jKXcnV!f`Q$OKYh2-tKed9WXk~6OJA)9|Cc9YMPsuBk2^{AW->2gxZChyZ5K#}~Is0z?KKegKc9W41*S58a%@mGa#?@qP*o`T_jra>0~ zg$rRy%qG^OVi?#J3Yq+(a5Lce2=3y0r{F|>fM1e4LE>jo1dM|fYlw#Mrw4Q9@>#fn z^GA=?Cn`0;dQwgwKO%RtI0dXUdV?jt>wT>Y8elz(=eUWxoVMRg9=K>B6j{kP`J>1H z5Yq0Ut+D_5ZaMiZ^I57#8XUGBjCiDCd>|e{Ya)Ydb*8<2N3l$W`xaRfq_Bnr_FcdsyX#Q^@iALxb3MigijB+hJlXwZtNT@Gf;MfW6H>`=S=yY+bY z$y2B9p=ccmoH1w$utGS1j1-ej*PH@}(GXNop}gZce|$G?-D)_o8g9J`bsuM4)G2oZ z8c)^Ax&`pxg+8XmW<(OuSj7M>e0(qh`7KrB-4%Hj>}f)%3BA`WMzCQDoauBq+VS+O zp`mdCr9&MTP5qD0kBHIhG^U!L#Tn%ER@V;!R@?=7UK8ElDYUoXs);fev2ULWm*AP4XrquU=5ggY|^ z0WSixWAFIQPC}*UCi3fVom^4-0Yu683tH}z^5BEo5AFAYaFJD5Sl!Cw7UO+NsfMFB zfQBH-I1O$Uw_bon>k8t$4fWx$#+Qi(v27NgF zuLsnwj+-3hgPnM#1dyL&`L6j`w)US)cw}g(3^~&_Xd|_C?o)gzia@*?nZ$|?I$W#`AO$r&c5mXPnhmNOurU~hF6=>;5 z7S7}8xEu?!z|xDMBQim$20fx}KlYNUswxg%EuO)M znIgd~fRbb~FRfdK^OnO$5u$SUB7zBpCU+OSkeRYIoKCL0B&k=RG+S?Auxk*ri4N&< zBAj;xcy@uYxeG`cXpTH%k<1xy zZ)+nGN3>N0x`t(}!6V-vWn%TvI0e-1hWutxjS|5>#fk5IjEzWOXAxI!lTIx6`Oa+!l<$V+{lEIf8JG9CqgbiF?gf!P@ZGXk23x zwiB}!vX@6-#^ zf!828EVCt;Lcy>cUH4i2Pi=M=gQ`F%0WqOxC^m+`<~&;Ek$Gwvvv2!;>NL#@B*n$c(XJc}V?}E;K)UloyXY8oXc!pu8x^Nv3L=1ZidER?V}_qmC5C{u<$8by z7mi|#jw%oHt1AV8*pl_pkX5-$QsRVI;IU#p`Lzw0XBtMXS_Ly3iTXRS=_Fb$hE3g% ztu2XlQ-I}2gl6HHnx$@hE=(e-FwJ5~*rd`Z*>M7sC}K797q-2CwxPdJFpGto6KFRP zJ4urJ;$kh|__Dw#dO?eqz&Q-6K{-ARF#DS5j^HYw8VFgpZDf-c_iCH#?CW7E~`ZWu3Y?5Ix zJR##wDQ*luGrn(gVB)@jF9hN4;E7Tn7-MA5ad?p0n1m>%rtR~<*}0P7izNKktCm1s znA8wo5rt4f8=<8bPv+@zSaEqw(IP8{6_y;b!b6p*ij;R@of9udnu~hj(1y6N-2gGG z$WRx6Gl()IQRq(88|j11s06Pn{rh->7>_TPQL_s8BWK5~P>DPxgTv#}LtH$zl{WGg zFFW=#Fd{B36X=-gf-|hd29!-Yk1i+VxRF@l9wgb+F~+%TTn=W=yc&AD^LukP5;CPV zwCuYidDOpuhL5G=&~(P1g~8dxsJvw_&btwenx8hZl-$lTSnMk3)TK(iq_97LHQ2jt zTUPiuf-Z9UkPL>SoD*shgVqiuBnUOAp1T+YqLo^}UCdVohP{1 zM}(Zj3rtQ=;~1&dXWC~rxl&W?AqX9Y!&d<8J$x1+4l%0YPY=Yv!?JO6R~srx1qjE0 zV-$rGfHq}NDc%!UFqN^T3iaS{@B<2}A;Qpwgk`Px6X6Zmr|4Pbj%4K0-Qc4dvJ;`d zw~+N~5@jQjOdl@X3v=#wQRJXAfFbmIj#bK@jewbi%FWFol&OpLo~}9YSEdi<8x66j zA*Yr{s3JQfkdHuD4(!{u-#;L^(?%@8c44Pb4?Jy8b&Q@IX|N**7a+E?Wprp;EQdl> zWu*MxHhXtaEus*ChG_d$ermM-2m_>Vczp!W~S^ybRzn zVW^9QbXg+m!jt#%xBNo8ai8KjbUvq%MTWViZ%H&kFyIFXec)Lik=RBe;qQvi+ggE{ zyJ27v1%K(dq9`9Jce-rNDQH;MU^ZXqdS>x16cHZ%a;R5l?PE4c@U`d z+$A}}s0xB#7Yvi#fABLEZO0gv;S96*lS7fHpN1gJBt<1at};Masu5mA5!EPoy@FXw z%yljIt@419*WBUQHJDunYfuIEYKt!EDR{xhF`0dB!+Z6!&kLX1Q61Hma={H?Kba9U)*IjzP3+*m}L@Fs^Yo_)GU z@#S+&WY!m?wZnOZL3xDc1Vdx?8bWwPU&q_Z0Cec{PaC|Odx|-x1inJRA~ptNLF@sb zf^c-!XanmlFnkHEd{golgsg!$F9}e5n?3+e^#@+=7}ueLJeY0DPaEw`d!z$zWAQ^^ z$=QU3XCEbjFm(a463{>m2Ft1!2^x=T7{CQ@0rS|#Cclx5TBz2Lu%RIurDKV4W0a^( z2O8^C<7GaegN|6O_{%x)yqhvzhzxQs2z$3JUHCzGh!p8j{(?M!FayJ;KP)1+Refvf&?lIOz;E_ z+j+$9Byu9)4iMDSW4GUqhC(ufTMrO#9Awn!r6^|yF0@`(~ zkR*>{UKWuQ&ZW6Y=m2PgC9xE6#MG4=c0VW72LO0d(py2(A#XZ6I~!ri7eRDK!t7Ot zCPc;?+i5aUcJsyI&{D|+$r=rK;b`Kk$NlY`n}ZBcIMz4 z0EzAKc0oAUTdGc;I1vHU4&JgWG+SbxJ$rVt`mUp+9W4%w5y&~zZUm;%~7f4;GJd(oAH zl|Zcw%3n80JPQS$Uf9`)!ubeCM{WE%h#IySi%BiPdf?o12SA+r5ZVJ8XTw1OoYx%C zSq~3yI^13$Cwa^>7}Od$9IJ7w71XCnvyd>YnYPE<52Ktvg(#u&(0$m6xSvXX!?IW=-u z1C3*?ircv#g!ClxwC>&w)lT>e!xXi#zlp`$#fHEW244nLhK}A|j1N5sb-|fQBha|D zZh$!xrFvHu$?HUEcLocOVn5VeAW--b(5wf}=ki^@sWi}>6(nP3BH(Uvd9<6~7#{;$ zwgR03Br3=0+6#UP`rZkuNyPl2c|nXR!jUt^ELbICbaE>u)iJZ;2*Jm3S2~TKXqlMe z00`>f@S@>T21PPC@)YwQ9fPSR87={6pgtt`y_uBP0Cq+p!eg_G6&eG&UM#DN6VmOr z;$#7vT(}#oWfX#H1okGmr9{JwM4yQ0PEVy@O2d@VJr@$g5e0?-+b94G1fV_zzzhKH zKu`vH;JqR;G?!DX^d{l;MA6}27y0yYEKxr}Ag=q$hxx#T#N8)+?p*yHS%W;dHv}*CNdh542F0Scu2Ojj z%o35&EEnEO04NkZ0T@R@8a+QR?<7!4jIydgof<#WNrWqhHiS5k^K^kqfZ;3))I#pLC>0tZdyu4){F(^+8@- z966cz8+x^+s2obdV!NlNP6zlr19mTqFtH2~u_=1$92pnI)6kAIEEn?x;U9S!p&rjpsgdY>x?S4pnQl8aSQ!ihqMNI;XT7ab~;ulsV#F{_B{#G2S~H-A-hQrkj% zY?lvB=+JXAnGa#o6kM*3GLU9eiq?LEWnps1{bj^~jhy z162eAQ35!jnbcEZ!doGs2@(=Cd~^GZ;pZSuWB^w*5*%BSpHFz(Xd#vRp1K9jfKZo3 zX1@hpeAQkWphnNFe-7~CMOVj4GN}YDT5+U=^ybkggkbzO-(Er&P5`u=Y`5I8A=8!+J3BkB{xQ8Ys* zbUE{_ox50APSPcL@>5*H#|u} z^^M-@;v+g_uTWST{TS!Jp(uC&0mGabHG*aoo&AH5f(X=ukgE&R&##*?I2xOnR6r(b z45=PJ*GX;daOh4v$9WXsa`Yf5CQcBaz}+UrAuD1JF@X$WLQ!m9aThe3eAzq7aM&Rg z9Dzsp`J*XQ4ygGAeSvrPWn^wD^cMpEQZ)vlf6x>n)Cf2u%)EOActbc1Q$y{g3{5>z z9@EA4fTnzO1^cHX&=0|M+@dGY9}K&?8^I0$$)v+R(cS?qeoAu*%eiQ zCe6IjU(as)MS3Jp$7-4BCxsCq44n$38adldr+dp z*M2Zsu_yYTvGia6@*#r63ve|DlD%9wd`hXVtVNz%iO!`_)E3_~cG|(bUo-nHl}tQ> z65it&FT{zr%7YK0E7Y}&i|A~PRw=0QZCj@gqSdP+qkVf$6Br5^CsKKOt&>Ms+JIOR zvMdhD+UbFJsGcD8C-onW>>1+p(v{y2(Kszqa6N+cu zh%Z6!4=ZXC>?=g{5r$J9c{%5SXY2?8*Z{Wcwq&G-^agw4X#vKIb`~(wqx>P+-#kQ z8xWyZ11d%8vM;QI;%0fJ$Ws!v{18;>p5uszX|6!pi$ov}i8cxKBb1^)p@a?Nwo7>g zS&S|`Gg4o>4F^>lwQs)K<+4@Cn=R|WC*b&UpvaOK1L`~BrylJnaUFF)bgv6Th^@WM zhxTtB5ZXAwItF?q4#dbamJo{iYvYdrM^3omH`)%t=JP0C!OLlN^JBApB+eYWKjp*k ztX^Y{%9tI1z|&K|nBFMu^Yi)I6GgW1uX%(osJ0A20QW zn!|OM;k-fonyK!)*mIyJT`(w>DEOgl!JN9aVI@}L0#a2F*kWNOm78xXBxp(!pbb6P zqUM#DFr>Uw|_>37}V& zJbH`I%Tk$`#xZFt2IsIBg#m(2;(~n{n2h<5)Q@1zdSjBCWl$}|4~4E2JU#(jO>$_2 zBxgv+6y5Uez^96W#n}rfHd22?*?{4dA-44B2aeJ%NWu^?+zfPR6Lw*@&mUCzDxma6 zBb?BNUmyqKJ@>KQ$Uo7I90l`_85KuyhY5VlJVL!yQBRBSkD!Os?40*#2ZX4&{FlsR z&V4VXy07j8{tg;W@nl%KNgZ+3stSU8;(!QTb(cml25TY>fTEc57Y=yOcge@VU32hrDX(QT~ghH%lz~> zv*qe*lhSIg^8^%tJ6|3$4?RD--dtTgZ)}1!kjm8HlShH+p+KtB$Unn@GT_77reL(s z#cH&O$-;xl!Ab+w6vZ?3Kn>%ft6v$HVWT2pr(m;_;1YJX8#!`>us=dNQUCz0G#npd zt=@4=OF~AGPLMHX1SNS)_LVpSvomP6RZ5K}9BCnNlyuQ{PWS~y-trvvy@!c>2J&$o z*c&8+U@WE*#@}8+K^3S0)xb>O0A_$tcQ^8LBob0ZJ$tYrMh8*{2^n?@aRevIK5{%) ztw8yKd4iRDNQL|cyWA%BN~!-v zKmoe-i4icek?_wAtS?tVVCo~zPzUxR@~ZmiOu%3Ow4wkDM$I#G|9F!D3>@f?B|pYU zlchlytQ6oH$+01fKiWt~7m20m0y5Z9&+SL>3}Csz*w=cXpHAWa6XB`l<{H{zvcmkW z!~p;h4mv~iHShBPZ%9xtGs>XgKRa!X=UTxUU=v6!{7sbPk+8>!mvdGUl{7OxI}{Y; za16Q7DTzey9Q=XG>(BJBHy%(?BwZWDDF|=)x2q#*MV7@2z z!Pqbo0n@$a`4Kn|W@;nA;ACM@E1?m_1!aAcB?tB*IiN#F z8;NFZ(TC&BXA+7Iml&WVA>R~9=?lQD)xykrarBNH5Ht@qSux^)$>S+5 z9_)UHl#SfhclcJ~#8Cpd0X|z~^{6^>~&V zUFU$Co}{0%JNQ2v~GTcc=soA`7 zV+cZ89T*p2A{fFJhI}zZB+dln!5v6#3CaR7B{-9nD^^Iu=gK2^Sv_e&TTU2`U=Zmc zzlJeTxN@a^Y39qF$oY@xjZKW{>m&7oegbj=}F1heNR62TTHF&RpSW$2~Yz{vQ$bAppB6QBn; zY&mdNNr@Urz&X+YlC9}ZJJe|1=E5@y<0dq03`hv$+{JKM@u|qUI&|a*y?OqOk^eYi z{In0^#j*T61TvAJ5AYsZ2X0306U<*FaR!RA)>n$*F`~h=$@?o}{*|HHlzCq7!eu@k z!iFSy8&2eOzBj^kf{@R@r`r&^&XwRbZQI+xgR20D<{@Nlwmft`+J1K3{7382!j&jq zCt>}@(6F#enFGY@d5@X@47I;7ST$B<4oq3`wkKXR>(1dH^@oL*IvgXJG6C`MfOhJ^ zg~%Z?oPVQyUJ|*%2MG-i;Y004+J$$GDKoYJu!co{Ct{uZq2&8ZF<3@C_yjEYlw6;!K{K)Y? zWgRDP>QMRLcM+EF%@vga@av?o9jZ2@X#E$d{FKMR1?WH_@1ad2QZEwsFQu7}Yszo_ zEUC|b3j9Z^0_7ysJ%%4WL^G@kqG)4vz*r8W-RN*H!zwUMenZDqENs>MCxp4!-v~4D z*q8A~GWPRAqF(^_o<_(a1vHS_HVtVzN$PIN;%$SO;1CGRO^(OMJoIix1Jyubwe(%V z{L3S9epCN>ogZJMHX^bCijU2JL#B(Cvb7Sw;SpzGD(Lv5;!Jx%sgZ-^PlFFiEZ*n; zTt?-OpS_>|{AA&q%|D4L3;+Mm*H1_P>(Ko38*qdP`N}3hHYuQ-h|D&_u%JO$>J-l9;(ympAi*8BRxcF zq&)X+8X41GPR_~|u;8L%@5kW2ul*Lw2U}eArWuz%-$ve1(WQ4yuozliwpz_uLTitv zoPvgyrn-6S{-5Pp_-=;j|3ky^&AzW8Uh0X?mb;&8Of@bA9@*m*!F*drLX=*+O8e%f z(Ld?Md6&}MykjQOw(cBn?e38JI`tz*Z^|l3TneOGajR^}%O=gH;(;u|LQ`h@iO%o- zG;gRVH~(;0{8_i%qx{z{`t>K|@&8(v`9tt)GyK{N^BaNu=htTVwHbbGhJRMz*Jk)< zDSlaoUz_3AX830Xer<+-mg1LX__Y~+ZH9kV;MZpOXDNPJhX3cAVWw`7O7t#jCkm-e zu~K2On4dj{k{-YPtPP|RUeLLStwAd}IDb<@9OdZyj%qTjDJhZa@9(d|h-(Zqjt4B(nb&_2{fSf^!59G zd#Z`5*BQ_TqA?my2_%e2KR>^KSrH8AfD|ZLn=#%{I0e>8b7AGb-h`4B*Y(hjnj+O) zSSSu!a#C(yUN0(ON%8SR72lF0dp>=74#`=iw|D75hDLZTJ|DHEB7F>!GTUsX`s`&i*k`VYV=r@Rhng9@7 z`;4T_OtoUo1pKHM1TLE8ZrsO1BCeh#nLUh0>={Fr@<% zqN=LOzgaRqHB}jcJh7M+(PNe>l-kg5re|lD0o^Cr)KvVxwF(rid!VfZ6|rQyvy0HX zZ~ZGAK5qb5Ar|*K!KwZ|$}m}(^zLaUSnivc?f{{{6lJ~(%E|(-c`&?G8ZAQMm}kn= zK%f2hZT}^QHoOH@i4%0?O_Gw55nnjDxN@MS z!|+gOTrraG&MQ<_p|g9Vvbs9dAF3ujTex)PG&5INKwWFdZ_p+zy=LKw&VS{-yqj`t z9SU(uD9gT;?`Q#~N5pQjNG%tXnaf~glzsg8C%!m=0+EMalgpr_^9^ca&;p)h9!k{1 z@ph>xU%d4$qol}JYKp?3VM=$X#dw`o8yaFBVxwoHSWCv7IYHZ$#qiDNyHMpfOjw%; z&~RQCK)J*kgg08W-WUj`ot|^v;PB!UIDI>FA2KoFsNU~HHFV3t zw690g&<%GOwN2jM=!8HN|D`cc2K>Z(pjHczH6lF$n9j%x`jwl7nysxZhC&Nte8Zzs zwJ@USx$&&fm|UwDx>JtJ%ga|*Rpo$1(^{l9dmV$01R%Z~2px5>K55h@3l&-+(czks zl7d-c7fKqz0LuZ2J~F1)o&%91B8J_czNieIweAGfmIsyKo-vx5n%>t!Yd0;r8=Vf? zd|nlkVglk&Jm`dPzW%+6rWCt72R-E%QguUZzI}EyuDNK=?B5M$ir{3s`;e2`%ns7z zF;W5s zg7b74#ZlwBt4|q6oA8!SpaBRDeE{KUJ^m{1NQ>WHfq^$cIqbt&#Fc4l{{8k@kB(t2 zK7wXQ1}5(>!8_1`t9=iI`{eFfnAdEkxo>&dMwv}$&c{s%8Kh*UV;AQ#&3<*v<{-2K z6_67RO5U_S*c%9;@}Uo4Dz$-OsB0oN&lw-;RhvtxtMgD$r3JU*z*n(`_E)tSh(_ ziM)_gR9CV8K4w|q&3;wf_j)1Q{t{{i-aj$gyx`3Fdgw>cadC0s_TF~-@7}vtpgkH3 z)Vc5M9JE3nf~v!K{k(D`nj_=Er_j_AnJRnO3J%l3|NgL>@L_j=Ds>NZLRSB`W7WzS z|Gw*>B_?ng7wu2p<&S|q_tB)D)*hmRUJ+^Z4YbZc5X3bOZIhNoK8G$H^}Y7@iv1<1 zKxtrEEQ|DF&^8g2W5gtkH5@*_by214`PG$K=Z=HvxgPzty2h&K&u;<)J74b$2u*Eh zp*A$mK)ZkidLxIuz3!4-V{BKwa7JS8W1xA4ABqX5gL8yec&G}~kqQ`b^mn?Y)!aE`F z;4W?$YmHvxNxADI9bhFpW311nP7ebmf16{8Q7mZ6-Zl8PxDEtQ z8^~c9nL(sv?wPQy)sgWL}?It+=Lcg^Bm=FU_3}%*_Pdg0G#}B>Z!Ux{AKdv-ibkR?9WDld6 z>qM&!dI%%F1elcY-5&w}BGkL({Mgu7JRD6nhfc=DSaWNTi-RzNBxwc$o7o1*P1Svv zXKy(4=@xaU=OT+BIzp^^+U!*C{SkEN278NuCY^10epMEjlT!O?J)bi^;R_qNWsqcBZ6H|_ z@r8QJp>4()C??B|H0-HKMRdSJ8gVYzK}3$M(|xUSt5i@I59sRZdi$+m5*8$`O78l< zyf1}vDwMMNL@VsMq;CNF_#?h_rewy(9;ljmU6`a$KUnSU%-L)RW~?zNSKI=7_wRQ> zOvz%$ad_dj=D&8A4cy%E5{q7&pmny@%Uz0}t%^|!qDXfXh@?=Y;crWQgRCo}+ba#8>L5)QZKFM$B`{)mPvAB!tQqvXsnuks-pbFw+! zj_XsuH3Mf?p+}&-FuyaE3lrc$pbiAvrp^)`g$QaJS^oQq6b3<cee)`c<3P|uVR7Hh zuPA9SBAYsu_EEGx_pg+vsDfhO2%dCt37Qr+Q45WpQ@y_SBpfNmTl-d;G}}%0Yuaak z1*-^kqn^ntr65aQn0YHgLlG7JmPSR{aI=(wB3f^QdUyGkk>4q9+yOk=PM))klxyuc zM?0Xn-<)lU){9lIPNHvoeJ5E1C5zOfY0B^bh?n?47Om-yaZ+YE$Jw!ia7t zaP3d0T;UGo4{cOh*0$gARhTJ$7tyVrY zS#71=@vm7BBx0%X6JIS@a6GjdW_~exswOr|AS)f;^rQ z5Z+h5%6o_R4Eb&dy#yCT(L4fCk&zEzg}0V}U-bI+rwB*?Qfb+SzR%g4eUJ8bh6lOs z$=|ws=PIM8Us8pJvT25(O~574i`FlUpbIKCUli=Sxwe0yzov*WU9zod=azlKP{M3W zvO#br*H0YCZU`AOMAM(Kgb#O2&io$39+ouU>~q$(M;2oyp8t5rn8njFH8rfbe-)XJ=xdU`YESFMF`IOQp-nq_8nT^}_{0})fxm_hb(@ZOMFtp-it6+_P z|8^{3ZYmKD8fs{neO*^~IFEq_0U3Xnz#@aRdo_9H2(l%7H%C%@_p<(c?Vx!>s<{yf zG|DO~EBnao<%h5{-Om^M(dXAlNXTH_7k_^QO3iP!S?jlC2pRk9m5#gJNiOm*emTgE z$V3r>tO*H-$#_B~ysn>{Sab{L6yf`Sb4B2nJ&9mR=HM%YCR}6_mtKjd`1bZglfZXs zEdm2^U#1VKpi%F!o2m$adBl|3pWCu(ktK4wdO`i%Z+rIcHSwQ>LYiOC+L*VQT-KW| z#QK%nC0AcTz?LjO0fpji;OTEbDraP-ih)r`FTNZZTojjxUV;}`7aks-Ke<01q<_Om zf%cS4kZ?)+u$;NJ6Z`>lNyYp{fey$|dYkeEm2m!ygyOJx??JRc)OZWGCb5Kt({`dBn)G!RCOeM zx%YEMVTW?jown)?n6>};m-YDw0)lK%p_OOGYwq2{UJmun#A0So;%BnOMo}u(=%!_c zj`Ak*#F_2k&xgnHF84Pa0?BQ50ncwCX&V z37LXsMC#FaoI?`u+3Vh#TSHt>rl`c!+_Pnoqj$JL!Ux_?Uz0!#0M402zVP_MBU7AZ z451p>)QKrq#>f}L9{W)TOgDC}?}T1}jBcI%bVCbluGu1!@%$UP79wLOuwZxjTVg1H zY=Iq=71wueR=IZMGT+;D7Y06dkJD`TS$lEj2_l)~`w-95qtS*|*v0}~`bjyHcwUzw32a&V9f{$3_)s0=W;}gf z$RdpRuUfbk`6~LFY&cpTLzPw=G#kVtR7=y0RZZt7jxL)6CJJ$ChKHwTZpc$rZwo|` zEQ4>MiE!3e&8+S!lGpm4X-pdqM0l=l-yx%*@bue+QSHkYRhf&To2*C2u~qUNsFsp^ z{Js`?TKsB0fWpjN0ztZU*qx<%nsl)#J(1ay2uo?<2R2Brr{zbvGs4)qq zO`1$=m`m&@Qd@Emk`6y6(wW&B82@I0pLjiu9<-ZCjfaEX)QNP!MghNb$@>AA5u`yA7n zi%%^=VL-Ij@#$em^koQh+}DCx*-9`Dc>ArR-$`zU27_GaAJLRHA)!NGp7Fp*&1hTD9!rN4euy?fLCl$PvoJ)ntnvFbJc(1Pi$2*W?V+dQ8 zyeQ6YEXue_ULi->DBZ*2_3PK%vA|v4z&n|2Qj5bb+k!VZGU&SuQN&@R<}@77GlI$5 zWr3JedQEURf9L#zE``7atKEoC3o&tR5Jx_pmH==C8VH;5I)nP3t?57R#-a5biT%3K z3~Y!wk2~TU8!9U|AT`D#rP1;;J@1QT4D#`FFz)xj^B2R|NZixjcywEwze*g8E9A0Z zo{y$(VZU8rsY(LSiWlxx{E-%w#r_rnZ}_4%`DiaIkX{`4D-Y4Zav?MT<5TR|L-7Esr*$ zee?mq0}+zb`)WbKpiL1yN&6s-QEUlapL<5Oy~+l&(~G?7?yZas)>PXrBE=knphGT> zx=b-2q;538*O$ilC|#-T#lCzT15gsGG=UVwR)Cjhg%)`~hxfOZ9Aco7!jV@5z(@9q z$Miv@cO>)eVQw48jK~j)FV&CiY0*`YmR<*{JP;_&_V0#^cEnn>m08zrL+k&fAPnA6 z{?3QT0b37W*TR2W;eK2oVGxJkK1^%$I-xdQUqkZQ!@$_mn)o0}0vt)wnV#o>k@=zo zn{4jSe{dMLW?OXnnFpq%@C%Q4l_qw(f{1?t=>&n|crqu81&y9b0-JJW^|#oe3J>!P z&;$mKGmSE0mY*>a{5%3w;;ffJUS|XMBJ2L?ngZEGcWU76p8;->@M32M`*m}v(1Z%v zR8SybWU~8qsSk7S(aOe%edG#TFNOwv4M=Go)~|i}t#xze79cnKYGX;-1cQCEqk|p4 zcm|1x+TOT=K!?Xxg!v%M;SE#dHWM9E~8z1XtLB^_&`cm zAooVc1YLlN_eYTLZPupw_i{V522xg^d{ZGMuwP1`KXF{O?WL@$>Q=;__n}dhII*W+ z6T`6k(-$qKsB}*)KIr0qb0-(Ku}~=N@EVK%=GRaDy&k_-5`1#OHB#>3_&GV6hKI6if~!tL5w5{^@)Z} z{210km&aft0d3&4j68{Q(7QB9SstUSYBAR83cJ_t-MjChh@FF?1|#S+(Sz$2C})DU zs4HQ?6Z$^1=S_Vd?#mrD%5dLHnYZIBZNe8}< z1>qkX*IshWfjZ>Y%q5*Am?) zl0|dk#0hCd#VzDlm@v4P-Af`SfM#gUe=WL5zVV`1+J;fc_p$fd+o68*pMMUw?ohU@ zT>?slOVNSU=<`dfFA{dl0g$FZ6DTMc>n+->X0r~LC)?83Z-_8LKt0z0r6b9z2}-6p zX_h0`H+>&CjlUtqQOGK902js7?7)BC1(Xhros_#`C}bKRzMOr}*YUZR1j~Gj1IoGA zt)wp2VM>uN_^|Qdefb8+qyGT&$jzkue^X&X-Jgaqg$T7O)OH*0v8HS@hip9) zsQyi=IhnW%;|>o6F)#thh&(8^GNN(F6&#`*hze@Vd>a~qhN@<|7>oOTaQ+W~bGwn% z?}m(lt+SOes5iNoCaBw3gM&jT@~xPc@(?b_?Os*ngcZ0g z#<{dw*&qaLY?*GJxGuPehAi5)18dd;vVk+MnG2d^!ay$+lm$`1Ca>#zjoV4>0=IyW z?=ePpU0m9*_-c@Dd)+TW8~HMd^6?lM1M9>4sZ^TD-)6Yr8NaD+wUDGY=Y3_vx6GuL zuHEpu->?_fzzH{-1Nz+t$gZlB-hsoKAD%_m_@d;Cf;J1TZ!9`8=yHr&h_i&R)0YH-BucZ1i!oJvzDdJ_s5yx!(h9hEK1?psLxShxW(8y3^Ir|M!k?xb=V7 zd-JfI^Y(rG#uy`piAX3j$x@_|(x$~IP0@msv>8Q`HYug`84r_Gh(y{fiL{K;zM5$v zDn$D>-Bh&PlJ@O;UiUon{dnJej^leAzdt_T-|_p+AJ2G3-S>NWy{^}Fo!5Du*H5%5 z9|c;BwF;7gBi^HYQ{U4osy-7U>}F*J%*|H zHdbQkU6HZbIW|(A-()#9YKKL67Q85F^Am4l$g3`Euw01~kerPwZ%?n-t8|0<;ir^z-DQw~QZMd;uMO`XeR@59R%lqb0x85#0e z$zE#JOJxq}uQkp15u}L24IUUwQUcf6xg89?knhPetVN5jV-B(u_yaq-Pk@PIiP0M5 z`#+xL4M)mW5ageZe5|LJ21>$U=ScqnFd}+E)VFHf0LxaeJsx>SISs!FEz$ECsf_nn zx&6v_h@O9WNA(86qcfu?tCPa zy5?d|AStRu-YXDmiYR4u{o7a0KL<|Iln8p5Tpr2s{86)|PKEq4jwKwaOLtfX!PeQa zv9b73BJe<)q;QRKHPP$&SzDHGz+<`tQk`oqT+nD)RF@hnCk(R9K|?|CPd#dw z2)5cfXs4oFD)7*5Lb)`<(-7=I+kjZ2#+5)}H#iyq%2OeDrYX&wWW+U%V}jR#0RDCF>uMaeTM^t+J7JuB zW=&$ojjHl&ELc$bgI*;Xfkv}UD%Zfa{Y@RX?S|~gY6~Cb!IPh^T$apKJbHDKYmq6b zYc6hps2|nuuF|>t=!f5MvxbIM-~UkoZ+Df>k<@DQCGf6Ibu~xAb2B4j$oHVO7LMkd zAo?2*=3vH#iwuLJsP^Yd1S~780pn^ZH(Y(7am*1nPHOepEtpVOZDyn1#uA`6xI#sWw_u5s`?k zR`}1op!-=hI>QLG?R8g5x#F766E-$B@#eW%#cB`oo`PxAc_Oi=UandMDNt%>QtrTB zQ!o}4l=3$UyVm?-T%B%LZ>V|k(>rI$9GTkUr4MEOC&oPxpjN?h6a>e&;^9Xb*GWXk=vIB4d898p+@L792>`%GWk z-w~w{>9&q_JNTT1pRINJsyzp#ua4&pkSqtk)Qe4C0($!Ki5yT>*Y7LvC7p^Wp25;3Inm3{@je%Ggh-A3Sw0>7tJ#-h-6s0ac?s9D;T_zY% ztvCStahoB=sPHm;*JNyxo%N7sJ-sF; zMf9}}BnIISBKBg`KnZT)U8muNJ1AHVnsM+qx)n*{J!3=zuk0H%(ixk zNCeyTN!F@Y9_jZmW>T6+w(%bDAUD&jK!1cWxd%;jL3`f$5pL z70nj1Wg(rTX>!)LPHb|i-HwjDd2n>o?+)VTU^n0WP|okRK0y?Na<9jmv=gL9zKnG)Q}+cRFN z!fNu9e?}#f@@Cwbh3B&#i`ETcXg@;US#0ee{Du#9z<0%njstwkwgq?C{`A8EdaQHn)kdtPpkm_J*A~ z4$U=q<_(Y+84qGuc9D);qk-n%j>rGpl8k4dBFh}=GcH9CLjxr8@XhgmIp{oez&0bn zTFo#kEu!RoEY}E+fsZf$GOKnSANIlg`HXjQ_gZn& z{-}sm*X6wbV_M{e2MHGWD%`7&c)CMh|GX?K(WZRl{2#gZ-UbM8>gDY7#|KEcSEXES z>a2q)FI8n~|6C>a-+^j3XZvEGa&vRc*(*W5F{n7!C>y5?<}Q~9>Gr;b>da&BUW!}y zxq?7Vr8P*A4Z|r2(1_LW6!c63?)K0S&r2UTtc45QicDdqmC!qma2 zbsiA9L$kXcWtoRgal~s%?G!&9FW!)S8ZjHk3=xE_8Y>a(-CF)NIQCHvj#{V2k34=q&^$mad`7LDz5m9gI zqmEZMQ-X$Zt4lF0*Pj+)|L~4S|3VTU-|6n|QaMt6OjpOb>NkNNvn|;UL>8xl5A$!5 zdzSpTPptvV!9`}lrwdMv{rt|<7S-{$di=eU>}m&ZVgAWJ^#+W7%IGcL9-4dmA1=TW zu4#Zfw5fq|O^a~m$E9Zu?nYW{2`=r9ojd0tTJ)BvPOK+_b3~Ms=)j_>xY<3JfsB=y ztx~dT#!kOIgKgn2f2#76;a(q7qNZ*LV&S3KCrx(Y1d1kBeL9hAQJtLh+ z(TR9Wt_4I2Ck8Iwa$e*rWk(Fm394K1ixE5``4D! z-z&*{+dTHOtW8*D?2?X@XI^HzV>|l19egUh^5!W|WOQ=b*}iq+&VAji-G(QGA%-VG z1M)|hwF$jqNV9=6@f$}~V)gCGaQsW86El7i`X^vjQacWeiv!>gK9c~L>L|+jH;qEBMJ2r z7czhfJSdn^iM%vVjhmT;fG?rf7yo1q3K}=qSloQ@K&E-eonH_UpSmdc>7GYHwR z40A|@2+@qGcJA%s>(7*gVqO$iT7JCsQy$K-7bmRA5|FbXX-}2wRikt5n;&ZQL zWkBi0!FF0pge!`Wu}~O zjzMZ1YqrZPoT*{GBgp8J&8^0<;An@jBY#@UGV1SA0R$OuO~A9Xc}2f7h3;_IIvXLq ztwDa+zspJ8^Bl+3(iM#K>dq2~L>3;xWR(yPQs~4Vyi-1Y@8X8)xYA4A?S>ITnoFJ3 zt2SI3M%K%IP^o*C6e4Vzo>~ZxjGIufDrhtAUjI0hZ<6|^rlxPi?=SOwzu9nufy*Q! zlLkU!O4u(Jq-XaAKS&fxwU+ndpu9yko=>=5ZD@{ux zV;79Z{bduHDMEw7$DVB_UGPS7wFzOM;;b&MDT@xD!9a{6tyK}1oGJi-CQFZ=^BJ=& z?j)7x9^LZvxY7ivyrKP?^dj$qoK5L zdvN=eAAeY>8@|VK0|#a@0o8hnZ*S4g3oLtbdE2^7F$m5~-}aM+oK$H;FGBMSmiN)Y zjVW}Tdru86lEZ}C`-d~`HOT$)$G-`+KYWY<*|J{6vT~MDS?dNs6Pa6+9{~tJ7`cTG zUR~R!ZMYj0^WhaS?+LK8oH9f}Heuvgiz&@1Du9+G^e*OhB|jPP&|OD36>?a?HHPs& zd!XsoO-@5a`Q!EZuO8))dYIi@3xJ|TJT`pi@)S`~tfU2i!1O{!C;BZWWr3yduykhZ znHrD&55g^KeP~V;%T}Atr=HtV_yKWy5?1&FY1y<_ML- zRzRPz;aH`PtaPWv#2X9gg-r-H!r00Q7mRBS4GaXZ)4ht7$$SSsPHy?u1ZIe!HVE*b z$G2KSqK;$C&rkk9P?;r`dZjnInv8X5s>WSlhNdp1=`DvbOKx+xd)rlNhz-3;@?Nma z>*I5g=?w-FA)$hosxirp@L}nmVJwvSdWhTJWmnO6AmJE05HujYGnd^DpdEZcHV5aZmeAJL9&j(lc|z54ncIj1jw7}Q8YLi90??#nG}(*t(-JWi*p06rY$RDt@H zYLD93(TWHqIm{)Dbkf5My|-3WFbo5p7i~DWy;zwHu*f*+K0YruZxSJGKMwC+h`6mA zj@R3zYdAUenm6a)&=heOOUxaplNcOFVIN;L^C2VlzCJzG@oPdBk#rS7yN-kXSbD32 z`Wp?4N9mB^7s3=J!l?r7$yP*wb0|PgB=smGe}#T>1KCpv4UT^Z%@07Z=e)|Dg)Ym02Gh{l3#KWR{G!eBpIv+XIt=z!v8IAR+PCBP@Os-B2M@^oAhfi{;&nh$I zSi2`u7>`ZO{#C_s-=B7)GH4#DO5YFjJ%0Y|5bre-J|j{B{`4K|FusV;v=|R+(9%z} zDm4%5j(v<(4MaoAFzYykgd|;*m=({@je-b9R#8XWP0*Ah!w+5gzy3|df6OSiB?UCN z!L{CwAV>|gi(mBAqZ2}lh18`~h!odi;s!N|HFxZI?(KCNPz))*7eg=mC?g5m&k2Ky zicwzWSo94P!|mn45Z!h`<<-BLaKq#QEp0TFu6Zwa(}4vqXl0XIy8$2ip@dC zB&0_xSPcFQ^XP%11zcp5Kk|yg5vqq0dM~hcvZdL|)S5Y521_qnGO?2F=l?*)Y3nHh zK|s5qXY~D_bJ=K?o};QpSK-Yi0_c{)FzJGr764&I9ERVa{*D{adI;#>4-M>t`F;7g zg8R51i9tz=yiKG$ACF9zqgjj0xmfzsr?<#VU?mj7@o9~6e|qZ)#INN+@}eZsrv4QT zk;Oc}n<%z*XRJ)ZAKAbX&%vpIIxF`YCdq#Qn;@^EkJ=;^s*|3$Lr$MEU(sORU@l=D znA?3f?TSIHc9&&8C6Ut$oI!N6oC~uWZ^Y0oQuC6o6`w((P*4A))l!`JoapKsvhn;v1 z1do#XIKE+$dX+}z?kgy93mI*%q~;tZe^r#;Ek^%?PEWG@3v6b11o%!1o$5H9^!_5Y zZ=MuTADVi2KJt83t`2z8knd?v?xtMeyh^N>bVIsWm-OT8#><&A~EkE278XhzM;Y z!WPg;SxCk-_^E?Gh%>HWM%Kvi9Q{KJrOb0o-pYyo{YIT|m+C-oK3tl8SQn`>``x{y zpnFMqic|y96UZ5;v+YI9DI|gna=80|91a2Ap@mqNX19bcl9JAH#m;znKw{39Q*k_H z>$a@>itqtqfS|K1fGy#V0fU7w6cdJk{0#8CVr)B6(Hrn(puDsL(;Ery%Y$6H1Vh%d z^ost?wtS5L7ICKrDglKC7i>=25(oHKEx5VXX%He4D-d#i(7Vh0(L3FE##Cw$c}Pra z9>0&$ba~NM%H_ZsS%p;LgAgMkv3&PxPmw=KJel=qXg6vXXayG%@@{J}x;F<@0(V^o zWW-XlyU8*=g~CnFZsrhykre$2heXS%!daVnIfrK<4I)AU7X}CAMZK_DyMUjcs3ruB zQsth3?kt-cN~jVh9NmdnK)9xC?y?9}l_#`89?PBJq zpZDS`5aQzK52p(jQk!o-r!>t!llhrlcmvvGG(_15dT^tO(hgabUJJaKPvnjkUxCdf zIK_Y%&`4~&m^aNIikgoVwIHgXhoZCK-^^dAS%Y8TdP4$*dGMy$-&R=hm>-oy=!glU zQ+5_TEe(XJ8+Y!k9(>6BW%(BD#q(lX;g0zH-#^8AB!Sp~EIh6AWplFX6K@gp^78gGuTx(W z(dT!N7aN;aVcYSO&&&gx%9YD5{MYBupYCkI{nQ{pi`d>Zkbp_ntxdO>pG2`CF&b^M z?h^>fN5dIiP;?!Bo|5q^R=rzN70>Uj#6xvNTWxEwm`6O0%y##mnJY%k3|n_IIzp9+ zJ|7;hQqX0_EH$%R_-l~XDihJhsn7hD=dUC1*AEN+HH}b(Y&vy+4i=-1G5H>fTx4F1 zz90o-bS*MEZk$DIYpmJ^e@)bg?%E8~43?T1Wki&3_P-k+e|{-q>L&E$r~~t*C@2Hy zYav=oWg@XGAJnqc-+V33K>S%Omw!!lT;UBDTXp#8x#mhKO?N{{)7v~b-t4}efpQ_3 z-Da7dp^5^T)_g!#HHoPP5)0s@7XVgj5fJ#ul4Hyl_|g#D&JzrqAh?&Pqe#Ks`3;%O zbffAP{+ZP1BbtW0F3+;GyMee#1k4G};<|Ns}WYe$KGhk}F4^+K{9{(7wx zjzzQ#%iEdDLO%rydWYeMgu{BZHU$Sb_xe1TpRO;22xQ{ig91~&RAx3!D3DS%;JR4k7pt-OW?cd`NC{$_`#B=Tw-tFhA)3=z`Ag-OZW+!u&z_FJGGJ+pffXqpXlS zyQjB+t}IQ?M#V_``h;V?r_RoE;B0Ok*MIvU%v_?r+Arg#zK6FGTQGk}gF3fBsuqEW zGaO{_T@%_PLv3>TLb2gTwW-c%c4A)iqiDkgzE8MxMc9IAfS<5!JIu4 zsq9gFNqiS|{7bphl>h5uX87$jW(8p{XT*P#gCYej!X-C}DvpNM5Maa)!b!#CrUtqm zxt@{7p*YnXHL%JO(@O3%{;!XsKj{x0wwsdCRapN)qlNNw0y0obIKc(42uH(yczwF- zX8EALTTGpt2X^%v^T3KO0j49M6?{u_LShPY*$d?1%@HMvST07xvZ7x6Zuk%)QW8<< z24MW&o6E*mlVw-?h7of#0`yu@nC~X?CHZ%A^E7m8ZDNX=rIF`R(LOYgo*(hsOXj5; zXeLOon$b=r>Nt@c?TecIK5DdxX|=*0)!(Bha~091kZc8BSgu(NLMt^f9HN#-5ceMr z)=S8msTH;TIorg{mDIUJOl?T`XfjY+x-D32Z|dO%gudp$)r&6d&D&kf3(yat;;ND= zA}YUBL5`*L6i{rh{i@d6N|Co(eM6}lJVKU-C$`;{G1;QSVXxBt}@I&U(*5$m` zEK7#Ip9t~*wSPblBUQ7>@8?m4QlBc^LnL{^y#Ru$uUWt=+v-K!x6?$jU|jkU9RZb#Z?A8IP`pf zlr;GaQ|U*3ec&9sbta^@g3=!VNKpx(RKDhI={J3s&Gd|p=8<0*xU=LQ=~c?SFtwgn zbyFSH)p5?SN1G?T33KCODj@1x_P={&bGCp#B=ld)i4VpGSQbb?E-}llRRVk%2_sAa^?;AHQWQ8fOR#tn2d=~>t%Zbg_L(7Owcn%FHC|4Qn zg63s&>OtmKbKHm1@h05E2q)&sOHj$3LvmAye4H%NX`KSuE3qGa!k4>yfyWwcqeWn+ zx)AK%3#OnlVHHEAMtRAcWjx91v>;S8#QT7W^cjFU>gt84?Wv)5j;I!YoSJ2cHE|!y zj$SL4VCvq%?J+y4!wFLU7GfwrCqfyV9G9Zheh%35h&Rvj;0vGn-W&^K2e~3U0m|ud z>Ly|qlt*MPxt~->fcJ0*nlknc@}OZXrk))Bs#tY`t-2L!;KO+l#xwE#DVAk=lH1P* zS^I-9GYtDq+mq|b+>b2Q1o~5q&tUz(Ar<()E;srA)&-e9Jf7DVaR@Yty6Q(4miGzs zLNkfpdD8^KD2O2o8{DH8vy)^&o5YyGj0;Qc1EJ-Dc8seDj@KZ?cXv7fxkv6~h9!NY zmru~NNCCXfEmNriMUUajFc<3f?h~k>zFdLg=y=dcXx*1_HWVEXIzu96^W>+pS}0yY zCq>})h=QS64NOEwl zQ%mTx($6d!)h>bqmoF%$comZm(ML0`7zoSU7%$yv-8u zty~0-(Z|kehjabFyrhT?`PsVyFqlYI_N~z;=hXG*bqTakuK=O8?+Wu_`POZpk}(gF z?;Opj0N7Zy^R59wG-PNBin5nTCC}S65ocNd=sEO$sJ6m8O>?Fj`he@L9-YrXGnQO3 z-M4=U$)j%vsaz1<0VDp5u6Al40WYVNh~o0t*UVHu+K@0UO6t(XSJlA!7+5{U2T~(y zWKkJQD!<;8sPVN3unW=medK(Y`HJVL_xA}$f7g%HsCxuiy6bp27kM#L1#m)4fgDsC z*#p30NTrCPLX%__=DA({3A^qZtOeEGc90o;zn8t12scoa0}_{N>cMsA)@6ng8*182)3X{6psFuu69U4u;Co zc|?l&^X`O>px(H^VZJ-o%N^*0Gk=yfr1U>uYQCTBYV^7E>OjPd_Z7!qhkms|En)GT zKQ|XGJGEqJc~S5y4gSIpR<8S%7WHV&_xat>uq0XW>hro2Y0JVs+NPume6{PC@@=iv zw_h)uTKjHx@|0O`50%apDqQb4)Uzx?$a>wN`Jx=>{7|K&YK6f9ugG?liqWf+&Fzd= zEAd$kZg5`3ct(dLMs0CZ4?jQ3=>IiCVU?X2nIuO+o>K+eUW4no6{G;S?he1=krcYeQ)v+e4}FO(h;+PsAgtu zFJvS~>IuHaCTV>e8x>>$3{sd)B||urA>2$54QmfEIp*hu++Eqp8ofu^JmoIM*-ib4 z+}avQp}&kywx_6Qu$cJB8NWvFYD|Qnng{ioA^CMUu{;f25JNFP(~qd!?)aNK=8k&(t=|+7P#8{V_EF8k@5pA z1NU(*{77nB;@v)RF=O6?bTlhR@P$ku@P2vH&$`R=(p#QSs9ZvfvF($S^`e^v&~2_}yn^oZ`#vR-DYMaZuzmPE3}! zlWZX1^5x4E5f{qJDmE}L<(2vrx4Gml4K<~AXsDa>ll+KnIhoFIekOVNoqPArVgT3A zl`?zx?!6Hc!!^SPqE=^@~8Rl7ik{vIlk?L1@ps`0Yex1OtkwHqn$F4 zHFQl(D+g4ZbG!7EWpSDd;!HYAz4#6xL5b{M--fhRZ@IoTw zc@F)#EXdD~8p-zA-DyLQ^}Oey&-M1hJBOZO{3iN2Lc~2MeAyz2X+*6y{qAE$wU{il zYb-&5Sf-5s-E z(K4_JR}D#!2(D<2I}_YxmFi8AKZh={;p|0 zE_n-7Er8BrqBQ;}Xj5h_jxM9LP0U5{aq0Ayr8pJ++S=Ou{MJeJY*i<{EeW%6O0Dro zB<6we@rLI+Hua2&I;pE;oFXdCoGzZW&T2_~4yN$c*jsjMw2;p_RV%Z1j+ddnr;@f~ z=UDez3s>g14@mJ9DEQ~zP{KQxUMU`aeSCLodD47Mfr>edA1s*IJVm|)6l2ASC^4-P z+icRkV_r)9ewRh-_p5{Pu#vN-AR>iX7ya(DlU3f^t~%+S9_oVj91$dhR@60u8u;>! zhsO?g-~&Ru9aRGXUuRMoafbLcm+oj2J0%SDtb56<1I#0S-y{w~LImAQX3P~a#m_A$ zeSzthZDNcIXI;Yi8U*0GO}H8L-qni&X()_y*fW+os$J!62p`77Xc|aMeB*es@id-`tH zUW@}0(|XaXtW$}82?%Z>zeq5DSDPL-Xmqu`ljRyMbSg}nyXm~ft#vdvjHr0aZ`kJf z`B5N0`!n-bFP+EjlGQ~^18QoEVzI`GA3+9}X6iOs(W|h%=#Zk0Fuzu?df08@NunC} zB525@93k)k&f>=&zgmZe#BV-BzdcQ69H}h*#q_X-%a0cWZkqVH^1%}~kGHPiT2PLd z+zxy(me^=~KGTzyJQpV; zDHa>TOey!%G=q_jds0T-z$l(=f2BL)UH?765!$5JLd=g{tvbDBD(1Qfk#U0hF)zDx z=b7?4l|y*w0?Wo)W>^BW=nYBoT!A611H(@-v!a9$S)$hvQiM@SO4@nD<+{OQG>H;4 z*~cmv^7H9GY6sq4bn(>=5!2#ga|B46L+KOr!mjX|6vuU4TO#yYWP3uH0PvT>3@0|} z@qw#os$+-&Mjmd(%nK|F@E`+mP#&_eIYTZefGF8>eTKFWVc0UiTtV@i%ev*1`glW> z6Z(e3Tpeoet675dnT0eZkx+Kfm3j=P2KhDmquY;xpJ#~iC*uD4Laxdhi?`{|+`?{C zOs9DOq~%}cz})U?E8^&^Q39Q>H8H!#A5l?5z51wqVRLClCNhj0j>lCZe6D3Xv^!VI z1X4B!kW-j=fC>{#2#R&-0@8f4b07kR6Kcxi;+?KlnNOEIPo1437v<^kpmUQdiY8+D zf=m}PTaI}t(GB1Vya0n{F@tE)rhWto=}qB|wyD;${nvEzvta%MIjTvt)n*cbBe58~PtW!Fcxw@m%ci>#}nH==FaQm%28}y$*8XJ3_S&{iRsUwVo zC4l}^5XUAAU3fy|~`Esz*;Pl=H({I zAx4v7MGhNPg~S)Hjchf%_eYPZd zOa;wz3>M?(CodNA^sq#8-MEmz<3#5dbtMjl3ozcS z@8RpLoEbP-dZ7v~0)O=RflVNaR?1MaPSP?q2HXWkL9#|2g@9n59seyY`gtJNkJsB< zVo)YkbzI&#UR2>Vx<`@+aJ3wwqU1mHpR|tZ92}T;5)uN#!Xmp(NO;M4KF)ln9qxPu z?v&LFuW0tH+m_G&{C;9z4YAJALgr-pPUme{cTEcTp6xJw*H{_W@W=b6v9wG63wSV? z8Xue+7m^H2?$lfxm2gy;mHB4f66TY9=8R9Nsormgzcim|*HH+2sdU}g! z4lgkv6R+d^ZJR2_2s9R};}p*QLw0s$ip(d;%DseTM}w_C`wIgd9@-7dSB{q;rZ)Yv zRz2Tmt@;I@aR(%Rrm8lKisoMAQg0%bKwL=U@($=S&oniM8?10P^{tSRyotz$h=7+r z(6Iyg8bnV^Y{GgrHh~XFvG40MjMc{K&_N)e7VHJF$M$SWQpm^Qq&oAbKCZ-5z9WO$ zi}N9OT($*fXb1S2kKNaND`FpT*AGGGmMSFwckwF2gw6bDeQjLjL=R_T9X9|F_wlm; z5Qq$y8~`{&h^?hxighJ~g5;oFX6-zgj#mVxpUY6 zK@`!{X%cfh(x!WRm_PY(9xfKC>wF05&&lWAc4JI&kGX#&7r@zKIxxXBt4Wh|oO84f?sIe3e6nHSqQdhkF*6g#gS% zT9--CDVRvqtC}LQ14V5phnfeQK&$AzTH(2p{O(X51&f{W^OMox!rN<2($*3-Ln350 z#!jCj$r^Hy8<>H6*w*$Y27?_wd?L+38OfVS<1*$&M&c--iF}$5<)X@^rljY89e&$} zYimNjSD21wo_I$X-$rAmyLcH*d-)2cKM3_4JgC#2?C2rH1fN&~Xa`I=WzH%$>M8T$ z&u9<`Vg|}MaGCfUC94kZC@j0-$b;5Y07GG1DGT|G6ie_gUX-jMul`Sk$8MrSUD;@y}SP@CY zz}yzLvg#+HHHBRa(8QMNyt3de3=jhdmqPAEKMMRCkWn#_ zlrWhwV9Oi@u};56!$9V=#TpBk2S^PNiIenDg@7}^tJu`H{XuH#0#lEIDKiSQ(J_%H z=Suiz24ZGxW`Ne3Cs13?JKpGGG)B@*!izvh+j(r9gr{U#fSS7)R8m1uiNtrk$Tj-x zOKIJ#&d2cM5>zD1D5rCPzYm$V+&?rdCwe0xL2?2!&5MDQa{qR|uKW)G-YsqyhWthP z6GG83Nt)X_foR0zoJOsmAK5b!wiGo~xC--HRo3N?eV_+ddfu%ft`}B0pZqh5{%eN@ z*|)?-xbDRqaY^W}doK^{1-FU*ADK?Lp{cg*((lsnWn42c-aM%sq|kN+MyI-%h3yqJ zSO=FhI5MoF|2kBap0@z)CW&7@zuP+t`3jzGYe3_k7*EB(hWEbk3WdgORk-6%)RDL~ zYUoeh7W6gdM~!z`v(a{utj*&JbX{J-fp4z&kMJ1Wo9s2XRkn$NDn^IV>vJSF7{Dis z7s=Mv^lRMS5xOZKA59p$1C?fzVb}~2x9F1c3<&MmUK|gLBQOmtDes71%weR(`am46 zmo}d0Od#+G=&@#nR;3IX5mRHX>Sp_;CqxS)<0gRYBC4IF-UsWUf9PK3E4NjjJYtsb zVPr150XiQbvOQ<_@E~0V2VYLyc~Y*>d`(ONU#h1vY}EiUyAz}i94BP#TwiFoY=ww= z-zGmRNM_%NRDTQWRcb?$fl4b`Hatj6)*Y5H;_?5sAv?F!Q1$A zqYvlI|Ma@lWHHxR;?;{6^OlWwXj+1nt5F>Yn_uGSmq3fh)wt52ThgMFu?Y+`$fCg# zh#Eiyy+Rs$D-ZSj*`9QQo}npUjB+3*N7uNKZUXyA!0e)!mgl=&QT{}2BaIdzts^5N zi{O2<6jVgw1`QD&sS0CVGOnhltsI#ROe^E?`dli{f6AD3nwj&t-|R zNQpO?n;AwPx?t9l^jIE73uhsgwm0+azh}`{e`moPQprj|WT8<_p#l|XA`yv&u{mqm zkpz(~amZQU14;um?VhKSdF{>2%uJK3gSU7W2TGRfe6kxi7J~z^kuO4c0Jc>}3l zb*gIu0|QBMB4FlB^NA6R(krYzUoT&FM$hZrE{$p;w-dd%!ul9*NW9~U?>j&RIYqeV zvKDZfBvU?zx8X#f2Bp*FSQ%zj3!#tcv90}5<+pMT-`RvM3}2>j)XEgU<1ic!VKkLA z4~MaofpED!X;(LBkN9*Evf?79{%CNO>=9AU@|DAxRZ(U5vEJp^@r1Hbi}2Sz;Qi~Z z%fo}iUsb~YMF1eAWL6ug{b1J6A{iy?*ixW;Io1J)6LwRdiDE3z`=V;p=nPsl*24ed zdsbDo5VVLjS#4-)99!yGFlB`T`Sy@dZ=u-+fYvpswnkdzom#LqJO{FmK)5P!cy`pp z+bC_ERB09_{$HjbiT7XgU^1YDzI-sCRP zKoM~Y^gN8%%$0EhI>4!sFry%gSv+iEW6j65#QeZa`+R8Z@ejw5)t| z0Abkp*aQV*I3L~DEMIpDWDmgz&fWa_rmo!BoyULp!fj>vkr@hxL`S*=G!l?PEN~Le zSM9j-JsRtr$*5e9b1#zP23Zpx){a*D)V@;RHRansr)m^E+59Ny;$V*J_MCs8cxg}? zWE-*T3Eux z?eYN;6;HR~;eovLotv1ET@$V6&B0>5P=FLe$Z6EEy1xlW8P_eIsQU&IyF26sE?|3F zhc8n+c1U+n6|7H>PS|{UD`7?y*ngRS_4%dwia4o^c>ts%q+c^xZaG z-th!}|6q74)KB_Oo8y<9+%}n%0hk0H3eUd$ZL{8K7jV6bF#KBQ;ZZVNAVMhh!n}s% zw1R(qbA1R#DDv#FSe5>};XSHgdj#~6HumjA_p28kAqa1*MpBqZAM}oBImn0xD?0J8Iar7;{v0{wxy8uOh6xad=|Qc4mRV|8>Z*CE%WGj z)7}(KlV&sVNM@$8da%ZIFL^>ms>>lwI~&&h@t; z=U?3v{e~tSQVXMM!8F5{%65|ElIwumcIe*aCbPt56Wf79Wj@VmoAQ@O&eVQ>M%7EP z%13{`N&02Et83QWJF_k&sucKn^y?!vEq!pG^iXjo<3{?Ut%?Kwn5G;hrx+5`dd5dp zQS&j&cmHj03DfiX6Nqb1rgb*k3LJ9#4a1MU(CURsKpn@$(O~rRzUB4<$!6;Q*l3ZI z_j>Zb54YM^!nIWm$G~!rE}ZNNW%|a(LU4{GXIYui?b{S)U60v5yn1c=1H3B}yesYJ zogA-4%j~p7MMDm5JX7=jm%QauSSy~i!}V^NXB#<6(jTim(KkJs;1wn3Dxo*%!BW%I zH|$^)y@QK0xnm~e4K3+)nj$C4?UvFY0CY5y^Nu4@ah-f|>9-^&tA_s&%=-?CY>SiY z6>p=5ZN+Q=+TueYBEdXUeu>sE_%7sG{+5?AVRDlE}f5vcq`?mfQm|85N?OQ zVA@-eg(1pyk^X`pzfG zF>bd_ahleXo4rCac>~&%kOeo{aFh?mW*lh@docD1$SPb{m2f8Cwqdi^&@XNE*Qcx| zp|^pdA({3qL|tS>5*oXiZgdL4285VUuAD&{1drFWgeGkif8Y>bjFeNl5o7J_sKbX3 zOP3#qmxGi7rm%!L<;8@b(x1&)SI;wZ&(6*jIU1<$R_bWY1yENIqP>?qakbFd-4({l89?}3X*N^Ko(qE z*`A5Hh42n-5S*9t^KAGR}$d+FNS;P0{bQpN#JLSIj7nMF%HD6^I0(`(EHW0te&tAI7XA--m^20fpH2)qs^jPp2D0_{<5A#I z_V}b{R=rRG$>H&~ptRMekB4>-8v0u^I!YZs3;5Qzpc5Sgd-^KDW6Kv`c0p&B>qG~i zl+0JQ=1xTms9zWGrupO?#nt59*@2oUE$F8+HgD5jA&F>Tp}B3e3ze|@5t(Qc@;8LF#DHtJyJ}eDe z{I+H89p^VL{1oKYkb1*ed|dy)fgZ1~Iy&$m{vsPB((|L_v51kJl7xXbq=YAR=M9V& zu&E~JWD@M+p(7&?z+juLh&p}FKf3ObY`hH~@3qjSN_*dKxFP?aT`gWs-H?p7Fx#Vf z6}T5mr~`D0Q9LguiXQEu^(y*A`clE=Pc@jX?Y{#=)O8z5<> za>LFUgdH?^X^zOP+_yv=JV>kpx-j_m(1k^*cpdc;&{jhrEFMO{&w0Hk-`lHr`0~+( zKdsNnK9c`=Lectli>t(%HD{?E>-2PeNg=qfHLq8aypn(jDX+KNDBGwC^(X;Rl&U%D z%RZxn9Ihu2YL{%99=MrwfZPuLH%{O!i%5< zN!}VH)xwd%^<4l@ir5W9;CTtsL5LM(?$Nzq!@;M1;OZ>sGVO8$!W81^Tz>wR+BDy;gCTxi8o2_xQ(mJ7=zpGIlPmqN%O1^97G5ax*${s0l$tNYh_rG4xnt#Y_E*Gp^o?~DBOv{2LBiE}9iInb0| zL^u_42j~BGTdvEB7JTW(q0C-qx-RPO0=d%>&O>bGNfTMu|4yK@p@W0(wP!{5YJzDJsrx`-%PR*>ClLXh_ zq9wbVkuQZGJY+KtdqeIlC?qd{m!i1IOG2$Bri9p4o``W<`RSMV27#w?mhu#$6L~#O z*S-CLvo5=99#MqA`<3Uoi%Uu_kN}tzTsdyCH-FEps8ik!3AHy9IEexk3|!~gh1D$U zS{mnsiXuU3yh_VxA|Wo$p9%o7cKOvR2F`6KKf(Yhta2Q-D&bCfdmJ+C#j6p#mmvFl zTsuK-p)khZ$lhS*b^J@$I-?lnO{n<^n~U?_r@d*04SgYT@)jXozrKIx{?l`W!<@X! z!xa=7eUN4ewai&>RA~TXtAB9t3t43O1rR%ylTrT&_ghek zE8NzN;La=iWy{W;dnH(tG`0aIAg`@B1PTHz49BvOWNAJK?}p1-X>F5aLSxhCp?@`+ z?6-1qHudCBP7uJeoctoJhtpy8Oce%UboC(**cv_(FoX5NMK92M1jXH!#|e#{?qygulNA;+1j7H#$V) zn;<=uvd2IG!GT4Tus*)Sq2ehgxtA%Om^*>PY^Hi|Iu^PFY&Hx|6mDL1#AVOV7hL3YxnV4 z@8SNnACz%pi|joWI^GfZI-ywwbCo~plOwos^B~k2kK`=^-i+CSwzigRKX826v~%+& zTrnkn#*KqqiXt$_+F>)-+L*>u-JjKNJFsIjVKuYE>y7l1Bb~sT%j8wzbm|7T^pvc2 z;ww_oF!U5a>BU#dDG8*|$2oM+^B{(f;XeG0Y1QuiS#mQvE1$zKyg0-6%H zONtlqyu`0o7_-)W49vG@-9AqsWkBB~h-^#9z^c@oScilo2}KP9F%J*PJ=#sOcNDrC zl_n`2qyjR&d+^U?6F&kFZRqlZeN-!mQ;mtrpJiE_wHEr$@?tw&w--F^$MvHF)uFO$ zjJ*7oG!Jbx92kKVrsB@syEd-gI7iNrW!)N&H+zx&5vmR_B5@~iOgWGbbb|RP`K^+4Mg`P~fQoT4lSKVum}IgR zAZ}72VTcG9b^}+*Dh@gmHjY8k%BLT0B-3ZIf#MQjdNV1{B!b1p1NK_HA@Ndbcbw+F z-<(kS6;Bs5J>PqkewiEs$tDzIBUZChW-VOnM?RM{j*Oe~SZl(*m7L?QZ4f+(p+IEL zKyCqDd}1ux8B~n$n0PuPL#sjCUJcN)FDNvgl9; z$aj8(vaB71^x~g+h~!pBL#Tkv$>9Otz!O6zk~-8EHMtaHT8`cuAj3^zT8>rxd^GKm z?9zwQeMZv*DiV-{ZapU=OxuV}VkUYfWMGB7pN=T0{PNrJ`~Tqrj2(Rnqy3^kjzthW zL;A76%cg#hCAOfkh0;adh%3H>b$ZTz?ASoc&*+82p5$?982-lcK z7)+z1)UGKtsUp}hSnP4Vx1~WcmVqGhDqka6o~6G@hX)`CY96X4i-J>y=>Ykn%s$tE45|%C$NrgnUWzy zbriOFOvET;X2H!rav8H!*;SUu?7T~c5y9;|T*KEt5vp(#br7-s#k9gak=(DLAeCdC z1zFP#3{SAxpaZQ3$Nkf!mc@GXEj+9MI*T~u4Ie~WGm_-z)AV38HOWg7@4YYbE}-~c zcrd4`l%!=snI%YwbQANqWs#+x4cz;e+mry$qj+9nqp}fZE+a1-EGapOtYm)c`C0e{ zSgGc2e!h|G=(-+cv>FuHvo6Cqbig0yKFCJj7K68p-LPOak5gIgEmp%Lj7V%HLkzz| zJ0FabZMU!bw-K;!>u;`JaB;aPb)|6LuQdQA>C=Cb)u&`!z=?OgHj~D|oYQ)t^w+=V zhhd0Mt##iOMw*WDNuOnJg_0Pb*_gP5|2fJOlB)k8D*GeaJskk_)McIu@{`lYPwEWh zg7y7b0pBGyrZ;qg#gM(hi0OganJ`84aFEBYWb+k#dQB{rlFIa!t>jqiI<_HdczfhU z84fjuF5ZXtI@&SQc^&CCinHXB5fI@#rc+F1&eU64Nq_*p^-g?3O3R-L8CmV$S7VI& zx~_M>1WPV72I0O!i+K%?HsTuScznRdK6>ID+=jC{M%ajl-%`_y@7`%{9_dQ_ba&ks zIiS`&V1s?_&TEX9hMzMm~ zQ*CoHs?$G>v>f1P2!6j~%YQ&T86mht+(%Wl@OvJ%Gk3KCsx_S)Pvat-G$0a7078wq zFWV1$?&<|_GK-&qu(N#E?!?kTh_fldBBnO3yKd!6>imwFoLQoTz0w!{38I3h;d^8k z%l0#yfWHx|qHRX^0aEoG}RC+UvWO@*9|6ue6eW6{#0F6ZzfAcS`TM-RS2>4pLM* zQ@&H4Vqj!c0$gPw8T*b)7S^}<`;m%_B-{!W%x$FBgEhn^_~_y_*G{g>DsGJWawdpJkx3LG4%) z-s$jV)?fBra*kNkWIY|Hyjak4N%O{V`>{@o$rGe<=$7Z%Jw=d!EZ|D9DXFHi?xcy& z^2JS6^%)uU88z3mvX-2#EJNRb>wHEwSlQ*w>riuAv*wtua8U(DcMZMO^Vw@rXqWiD zKI6NFx};;aN3tOh*9&+hb7%XhcUZ*ZT4UF-~jL(%x(^( zsoX?JKiJQ6+6XM0-r`E0(!{7C%_q$>q}G{^{RcbK4!gH&Zv0jDkWBH2d;qrCLb(RV zEm%*P=QWw(;d?#B1&Reh@t8kK=_r>qg3-BAt*BT7S4FysQt=3XVEf9wwEL&ck^i2y zAu*}~7OlTwCO4BwqW|3zy6j&u_=>BKfyxN_b}Ij1MZ%pf50%ayOwl0^2lUk!@$-j- zgwVa$pkTO3(=}+!Cia~r=6kGr&9i7%!|GSzckmKQP@#*^tcmM4nJ?w{lj3W5970(w zmb}NJzB*6yffeod87Z3oGu4RbXQ~m6&r~D+pD|bk_^0n(%2$ttC$qwf*pR$_0ILjdx6CVqav+f7lh7nIWx&c{IIS zQFK4*jAVYhRn$~RB_PfcG+~QsLgJ@AGz}J;{@CCSj}I|L?2RjugQA=eoFRv!)<>d7wQW$4i*p$@pa@fv8n7SddL zSQr97?c$fp{kRiwm2!W@kZo0EQT^K&`T#R9+nhH8cD=W)d{$VR^=7a!4z+(Rq7 zhs@$#p+R#4pQn{fhe&5l?1!&yZ|}TIbURX5dk_7&jC>s;0xg*#Pu~iqM)V?}rfYj} z>aR?HUll^KZ}R>&N1aC6j%%B$ML>GMthjk}S)?Fc@BZO6u?a4I=mq}7J<2e0-hPm0 zVNp<$0lQ?6MNYzKO5)fx?U+`s|6r#{bE$T(Tm&!(>OYc+9a#siTtOWc>M9eZZ`CMs ziR;T#E)NCp=FH>uA2@<}?@tX4LiL&Rn(||++2}lc;7&KfHSNu@VlK$<;Q_GZDx5^f z8c_5`-ba&IXp*Q+g5m|kF4!1^sN*sJeTEa8yH7k;GFB+JXu5z&foYHTnDGx;O!ix# z;XANeEzXbZmWZ*48z4^SZX>f-`U^Zz+A$v%pB{c2qT}1bG`II&bqCxnQ=EYj z+m*kpftADs*D+AIntM{2?`ZW})COVM*N@{8ZTc4@+Le_fnNKUbx|k+N*7ZX1WH(sH z{4N1>ikG8BsH21-=e6%>D(s7{2D-70)`#QqoWAwejoFETC1}ha%dTc_xai+0%||P@ zt`|^E`iVgFA!L;X0jNAs*kzjwBt^l5Cm$O_wRQ^=plwR(cP4g2ZkFQg153^N@VocX z?v4?r20@w!?*rL}2SPnr-aD$wb6*#onrK#R35pdf zHoz98iHaJ7Sh1lJ1VvFnqzR~qfRLhs6dR~W(STw>K}111NhpdGvCyO_RRuvH^mdk+&z-*;X3%PgL7Z6LOkwMWKhtOjr zXI{w=3C6Ypgt38U-G$kPi`w&)LWFhCVhbdVyRiSR$M<<)kwvMC+uJJf;HfT>9ipi< z1=oPlp%gakLDT^ehhr(>Lx4Jsi=2*?m(4>MHwnrSMj1ZrYebqT$>t(pQ&QGDoBjKO zvSF{C9L_n?e1M4tRnTSx%OjcNq>ETqjnu>g>`l_k&%0i@uGc}q;@KX%v%v5+u@`+y zH}dX_DrWnHLi9COnAz(a@bF1regJq%DK)2Pf!Ed59G^n{P-dN@t@gs8)bEZ=T(k7wGdJK`PRAm;55nCKV8&!o@}*gjxy5R&3Fj0udU|6QBnI}@EUG$=~7O6zOGjnV!gqu(D}=>5ED!mCbNisO$M z;j^K*8d|5|VLy0L1$+3UvPWkFP>vpPn}_N^-u}hVpCZ!NH&+r360q!~S#|W~Q(1tf9i?wQdxi z*Y_ABQqa{XKED(vx-;90RCYpkuy@~|=36JsE!0X(QSS52Cr8R1jXpeg(9DXz_!?;4GUy9OLxssT3jpBp}q#8oAl6BJLYA?{y~1~$0xyl`|NQ?3=+Y>~ds<)NQdunSyThJwG=*hiyhZDtVh{{|UqX)cb&raAA37jf(pxNDb(ce}P zR3#rS)1#^;S&)G2)l*OcK!a<3>FCW$p23jFwOixVT6{kvBb_hC zb_1X&g(x8nce8*Ng!Xa7xavaZf*SGSyBjI2bR5U%iovXyrkTw-h-sfXP?Zci==Iw3 z0xC05e7*g2jM2g)R;C?si~GPBjR5D+}|>4q2Td}BEiH?Mp^iy z-UkiCm)?#MGkWKAwqm4`jERTUxO+W|RmU+X7yBN#T6C@gzZ%hG9X3OA$4J3vI*y@T z#M_nk-=2tl>HeZ~&BFeXtv!V!PR$2u^4_%{t15cv@`W$Mj6v{uBGEXjFZT5{%jqL> z>^7_|`sLQl+V-Cu;vPKo9ooCdf61=zC3_9r_HE)JmqS0ipF3D_%Iu=Sdtb=zH9mW6 z?|_3o8*a|N=&^d`_1xdyd5pNZL-KdYZ_WRqF43pgZ%)_uoV%*KIia@pWJktppD@F( zZO;{2J;^bynD0~D;L~7J6yy*u5UiK;(oDEv>-zBhW#Up)CRWaM3fo8P}w=Ab^+s2(1e%a{rJ+oH#3 zT;5|JSEGTxlzs(>puaS7{>U=fV?x$U_NK^t*>eY)TPWiL1~>~JMXtA`qxD3MXVsPZ zM_*Y!N*5j>36(CrKbY-W8SnYygY+4bwDfzd)0NKx3wp_EUmb2dO;so+Akz56_~ZZO zQ+s8<`eI;tPYQqk4WgnHw9qEEBlcHULPF)-#2zoo)~ol2g$9^4F3ov~URCM};hpaJ zx?e*31$0@jy+J})sG}mxT}3m#?{#Qg19D#spYoa&G$u+@ZCFlglJH}i;CW{M5QvJg z%!8b^!sEdS1u~eO)3ti^|HQwVh)ZQL?pE{7i0>{B?J)~`vH{Y~1*FJfGVX-ZmAr#* z!Cx=z@}7-Me$Ex)uG?-NBxmh-?jUB0)%UeIEX0WH{e7DxFdfk)7 zsr~X4b!J{B3M^-0GnZNkWA2lA3!D4Ag7;my=kDf>f&0AMYtgJ^1JG8nxF#dRvsKEn z8KR@OJxHt2&M*AXOySemQdAiy@>zdtqmKJX+nYZcsaPGUAx3{VQ{$j=G&Zh}-hKIB zSb&fI_VRA~9sLqCBKtfD^*5JQ{#rSwW@QQh1T!KE22;^>+7w|^AOZG5%CY}dqfuypyNrXNY27d5I>xhcSJPuMRJ~O1Lhlci zulv42QkA3(Gdr5Hjt0_bce?Nj7C&w&818s{pj395w{0Z`jOc`247BNPf&tf{d2cQc zTiG_1NP=oW)@VQR1|{}rG!U4YG5XW~$Sf;N_zGm=GwpjFf|j{P7y7TJCxVMHvF7Gg zQ0^gbrEv4mvmTRBnf`sYfAmQ4Bb6nh5d=OBc$%APM4oaQ&kB3E0xe#(PBfFo&$3ZR z0II!b+2d>D_8^9mCh|WSDo@?C{A&Ao?tEU zpGWR9(*LozPo)F5F%S8>NaW z7`AU3KvYPCiO*oF;`tyCpe?jziZDmMeDnc?tLVJfTI`S0jwmV-%Ffm)liWoS~>;SZX|R z8>G0QUJR3$pEJ2wztSM?{NJo{5VA&7TL-m5L|Kpcv(XQS**fR3I6RzkH^rpScnjt5 z@Ulo)+d7fA&Ci1rVERJ0N1babtRa47fsRKCeAZTG2%q=j^7W#bcfd>_6WgUItsS5M zMM}1wG3+Lo3JkZ(!V2$c5&LvoBn_OMD5g`3_RD0!IV}=hu7@ZO)j6q3Dsfsb9Q7yR z5N9gQkWE6cG5%$}xk2oQM}?VoQyaR77e=kM*|JB}kz2JX5~5EWCvhE6 z;BlR_Vw9xI#IB9+h^ZwDk-F2WhyQY-k{?ksOclp~Q`u>HG0*}VHU+5W01YX7Gr>x6 zwD;}3?;xY!+SpesdDxFp`;E4(SJu3z3Jk(ZzewN+=xlShLHeMl z1NyxrXu>4Og&Zj0!iN$JMX}0|7H?xPHzo@W*hQBu@oayDr&(4bGGWgJ4IuOvzwhGI z88fKIX7OR@R;7USE)I%LTO)=To=9YVKw;v^hQi!QtS!vkcP9i4BtokKi(DZ{d~QKA zF|^V5m7AN2U;lYL1!a5lo(yyjB{*VJ(lJYBs}-Efl^Mc9aPe-4zK0s5UsP`ft!CxL zNJLvsLMHm}xB;t8W++c%Fp`MMip5$|HX0^;UY?i}5SJ%a7z80BqY7|r>x-<+dz%4i z1clGZ8W)vO=gkFtK`QOUKa_iD)YuJzTp{cOR|VLTvtVSfqu1P$wc=?$CuAJBJ(53( zE{}i2*R!@p-Miu{{PvB5Aa@l#O?3Y77a#C8i{B9OuJtqxLkHy_S3Og}K3a8A7$X*! z^L}w)syAa^msMs%4j=9eW#iK3OdtZMWV$+Wg4R$Z-%$1L-OB&;_gOI0Rc|H=wakW` z-SD~4W7;P10PqcpPW^RC?DOJZ1@XP-Yt;Xy- zVa>a}7zE$|-eC=f7PnS}0TF(dDy5TFY}nroK$Yp!7+suha#2M%7taWBbfR@5f%Sg= z{5j$O<0P^!KbQ}c*_8B)vv;afl|WkhsY1Fp?j)Lr=pz*jX*&I@AeB1PW{U92Js}Ca z45$@Qvd80Zf+w#S44rHC>9B@hmTJRw+vv_Y+1{kB>nO}jLV50z@g9_hNAki$`T788 zS&=&`A)5-Xy(30lh2c)Fj0C`!K-M% z7f9NYn(<0qt)sBGb1M*}@;345oeQA4J_4$Dk6M{KUb1h}M&|eOD4G*1dngGn-hCa} z_snXb;VaF-4<%$#bxgFiH8=bE5K{9xw4xHxihA-Y!mGBt zsLLCV|0Eem7d=hU%FOeM41);ntsX6?4=PVsXRJqep5|Ty&Fa!UY^_%Pesrx_Ys3d@ zs*H}~icrbH*+pltw2U-gd$7tYhW;#kwYkt8RMrOy6L^*(60OSbD~hUhsvphht|)pw zA0dRvU)UT~Fb>>md|}Fweo?5c$v9@FhS6UMG6h$l4b>Ba|1eimINWX?T5k@0UUdIR z4nSwr)2EV-O6UV99DZCo($Hspy@_yz$Q?&<^%sgf!qor+n02_p{I@@1p;SPf81%@M z;yTJ_DNlQh)kT-60y}S#Zaa>1Q28C z&;4hT@wV%6oYytlI=8*OCdMc~K0k}DD@nb+8vUfY0eG}AoV5PZFlT8Qkfe9=425^U zZltc%%P-l+0$E}TUjC53Esnt%g?ML_b?sPe6qD0duumM@{ny&==Wn`@>=Z~>3e)l@ zZD<_*2IOxR0Pw>W8J0afP1Cz!i-ga|vEEp-MtA|Dgqi&kg#Wbe`%fST|Lb(vkh6Tt zBanQzXAx&uV zI%3`HHsl^VvBm4O92&Li$YWT)soX(WXm|*mb7I z&c#4{2cUnie3JbNYBQ1dQ(DNN`?l~&Z5)R9LvWNyo>GIF+Wz=~0Mda*s8C`7YCFNcn_avNA73mSM_TWpXA5qb|Xf=MKlW zrkf`tRT)PkLDaHet%pRFSjGsiX{r3~m46bFjV8%CA7OlRO#MxyyB%7=Hh-%zi#^-n zSA>iW(?#(Fzi)Zr>YpM|t=7Skx3&&BVhZGW!is63h2ukPE{Pfjef+yskrAS65cS8L zU`3wrd0d~4GZvnZURux7N5CfWk^CjlnXZR~0Mfgz0A&G>4{F9AoG;dv0tL9DbD?zx zggSIBdvu`?NB6ly(g*3^H`0J+n0jl9y3);$oNe~g`EDV!q$zm#dTe?mB}HE){FGO+ zuL4~g2GJnV)pIn zA#Bj|A^Olj$*ralo9K!cOG7C001^|lPc1P5N%xd=DNsUiN-R}VkQq9yN5Wd&j+6+^ zuB%zGfXbgS0MkdgRyE?@OMr}c(x0s$B9Lk-{=3l-9)A8mT|mI(ehK0Ld>=t##TnY8 zue@l3KH_lSNPrg3R0vPTbt?GI>R?d;l7lk_Gf~CVW*6&noVG%~{jaxpmR@>VT3Szg z020K{UO_{u@Fid^XDe@ml?=h=OTNC?SZ5|tyo;GGL2y}(D4EYG2)CH{QE}|%R`b5* z;H%^g^xw^qq>UVhq7|_I!ZI%j2_EfHacFe?H`jcs9o4_0O%ZBft^F*UG5bARxtmrz zOLMHPdx9$4nc+r9_d3*CU#{V&40Q7HGgsaep|Z&@vl)prcE*37r*f>|Rujv?^2J8- zKH6*J$4MlaSBwD*@Yx^b>|JCv;(eVL>Y<1nQ;{Q!2XQ|@|4mxDwxS5Ow(iicjUg3Rz`YDht@Y4_+Kime)uzh&5F7UX+FDi+8eYueLCcXrONjTr)j z_~U7BDvs0uW&*>4n`L%X&UpUf#qO~3n>gTXdX)7@;2$K+P8mIf0AF-g3kwE+paqmz zGz1HG;1PPTP*8%xzMaE%254VFtp6$hsqF)#yU= zqz;s+1swgy%rQ5Mv_@NlX)>*m4$hLUU-_q3b6Rc2qV5iH@e)a;JfH|N{7&0$#>@yq zpxCk=fpOz8anlBXtN0ec3jFM69UQVRFxT5=jwi)P-Bdp4 zgH0G>(jmYI#bg_LoFFoZ-K^Q?K~*g+?T-|QjS6wQ8{Ru&N0Wb2u(AMqn$s;DDTzGJ z_TDG|9%m{=@>+0A56N8EZUQ!Y`0v(Yi#K%eZqd+4%rwyJNYYCrK*%)z!IhDMNA$`C z-~u%&4k9^7rW7EfubKip)gDS7kuRRs)X6IbK!t@aE3*f$k4crB(=l_VScGlsEWyW# zE)R~}7Vf+d*c6I@{8dvppBt?O=xC(GC`m9%d4IO9GVZ)rGl0!vXL8`N>wq4gOG&-t z_#WuO?8~BpFGFJLS5l6i{7JT;Fp^Q*^*H+KLUcL?pp8`_CUio7il*U~T~m8p(owAV z-}E})X;G#SFtnxH>IgnP4YU)ZDKNxcHi@hPh>d`pBV8|p|k zx++p*V&*uXnS%D?%dM&NHlN_h8J(Ae<&EQJe^G%G zGU6m4YsUZ$YrZbg?cuDh%|I&A;fw8p`TQk!GnoTGZGROByJM!BO$?*nV5%+Ljs;5F0uBd?)<101!;Lj+pgBBV$8eYp|me_aT~I%)Lm zL1S{N@>f2$5clmsG8UX?}^GFHB7gY_0pV2Th*oOXC@ zCa(9$EzFZPGoA-;tP(J}AH^A(P0H~2iOQ|$IhZ%<3LjbZR+JWyG4n?He{T#%C_aGA zm47`lU8g4ekSZaYNk1xTzf6=~q^FjM`+3}x9~KJ~Py)Ep-deXb7+9RC*yVbo z-fhHewmahh3PkG?zn~MhuE)&{#m!+o0385HM$fYf!J*TUznPTx7*i7x&(}o@`_a=}EdIS6>7u7{EV15&(9XY?|TH}Qd3}^qqmpxM;%nu5jvo!BIK}toI0b#`%$--G_ zg9O)>5XWV^e%Y9zXk6@9Q`?rMq}e+T#M=@St0s-Q;~Y9H2(p3>v|8D4uv6P0N<_Wr zpdMxY_Sy}Y#R7qlHq3aUG?x`=3uNCB@wfT0cshwFMjElr)nbggN^S-P@4ernB)bQ@ zMCmwaMlJ&aRa!r1MndG|SM;5rycteGv%2Y2ArNZ_g2(kry~Gs-Z4y)7VLb_WkI{xM zS*6#up`%={YxghS2d!2mpj+fZl}+)m5Hrq*9C@}F>U?YMrmj(Kd`{+2Q}rL-&X{3Q z&=#${xEwK4FgeH&W1;b)6>8sq)Z1bQPpa;l?hoHsASf(T>oSeT1*19&O&RNgQzDsD z`9nz5DG)sQQY*xIk{}RKihDl+R3v-M;bq<`A>XYH*%r&*?&MDl-)^w&{Q`9Y%{HiV z2ozdaOmDLtvesyx)ZsWv0Uvm5A$+4bVPo%qZq0*I|G>a0IGb3XlKtewx#r`Aln_DH zPx5&wrM@8^H+|(x84rDZPun)p>w*Rm*KKx9J`)m_DHm)y{u0XU=wo=8ZKY*h}}xA|gVD5sOfUGIyN$?b+dwNaBW-4ks@ zM4Ivrf6B*)*3n4iVmmAL_G+7o3VNH%u1yTq`86mgh$8~d?ORg72t|_cgG%>);RD?A zQ}2DwJd3E3tdB-b9R;efMYYrbCJZYt{NviXoyGH+^^<(M0Plx8klIgTWJpVYVX`iB z8~}#g94wKU5QVx+?{I195|$#A<79P6cGfMZR473*lY=tc{8BYFREu0GoPo^6fF%Gk zWU-ziD8&JK@kh!#tc2GsBj4v$Z1wd3_Y*YtfdvF9r;9 zF*)&Y%HH4nr;pS*I{xyAE;Z-pnir0RM|vK;@?w2hK;Y8X7cWNsy6eoSm2$nMXO8&! zXJ?t8SI#t%`_6Iv#K#TorMBbGc~$PP2_LyF#A@zC`>j?EMa_i+D&L+|7IX{l%#um9 zc3jec7_;ecEIQ;WYlO!{LfrCRhrS}t=W345y*;N(d!D;s{#&m@AX*s$QuCse9w4;b z;mC|HBYK=(J;gd|+xqpVkN3p#8RG*!pt=lwT7~Q;)1pV((X_N*!hEjkt2x7`|9I*@ ze*Y6dj^20qET1IpwK^G{n+6ZzG~UtPx%Y=bRAPe^{i`)O!)NM_FpsHIAKL>#d}r2r zQPKC(r=75&mCrmXTVu=$_CNhra3Y99;|{!gp4V2XCN1%3*Bm03Q-HT<=xI225w?hf zF~)F$MvKWcO-DSYaqKpcQn~h#aP3}yE9n@tkDwF~U1J+Fozoh2PL_aGqBn-RK&F3YE!m8gp! z{2|eKhDg-`8euJfh46B`@g>rF=A=S=72 zm&+#&CK1&qLzpy;Z@?4D-SAE$BF9;St@0mD-Zs*F;*IYYLn4-FLszT{l;F zOk77dSu^*nzG?8|2a%tkjJGar?eU4Cj*~+iHTOmJ=m>#92iK zNIc;MtXup^L&xzGI&-g2FKEM=T2bU3%kot5$R1q5O*L;(*xJEEJ!8ksn}o7K3PN1A zdfEamJQBfq+aOKht)A-NuGXuCASv2koL)XjZtJ3o3p-h#r&`>+>3Qy4GCFjPbIUz6 z^)VXqtg(RzkUur)DWNxajA9lVKl;Ea(z%i#BM@O1qW3o(^t_WydVV`TcGTp_?TLEB zZOb5t=mcflM9S4+a<*PqcQk(u`&OMN9@bl{yWoYw2clHUo;pNSSjN>MZq?kww>4lU zG}RyEKbz%R_lbwXY=1QSnR4lfof4D^qjIgy%H;>nt)3z#Xi;T~+6oYE@$9lQS&vvi zn&SXU{d_Za^q6`3AMVKiBW%~BGl!6EmI5SolKK?oMuigH&CRPJcE}MC#hld<5v)8E z?tineWjy7r$-*PimSi|?BaidvmqEylB>9!ARt4ZHEg&tv6eW=OP{%>W9I^z6hqUI2 zg0=8`xni8ij&=w*a3`K#Zerbg-yAPj(5Q&`WASdY`p5eeU6_rK%AvdUyx6&jB%t+41L{CeMe1nNgZGDbCpySBfT-kNdg;_1(lT1iTAanOnKmQMT@HPmz zC?N?Pn7HctoEeZt=KP)Jbw~|Uz5#rIi!A`qI_=fbVeE@j-k;*ECCo_PIpYH>}{>B2R6A6S-({SL&dniuFeuG^cBi=Z^jtiPppKF^1wV1 z*|@yNoqb|tCuYKPxwkda5F+j}@R`agNwhX`9T~0o>xcf-7F|#_0Y;D6N zH2k7hl^1V3^Jo{@gH$HkgKU^=koLr8L9AIk^ZA?JA2gH;?`giZcEKLl>{4%nTr$Ge z-Kkr372YS?lITTyrTn__D`-9I`~_Ji%B;B-HKUE;OyU}3pywPeUUC<`t~a3dcEAp# zFsP)~oj&6&8P;(_sP07(;p#XE2@r1y4JNQ709{w+tL(ANnYU91y?~RH_M-A0X?%B; z1bP2_YW)kHN8-!a{MYuj0BML;mL)*EJkC|sLUN8CNXVRR zEo%%RMrDz;ba)cxYol-l8E*x13df6Al7~5tL*tktC2A%P`ew*C*pdgp#;5Yv=t|6O z3b%9>HZ|{>GxDF!tl5|9WY(cof1rT6mzTl-jUuIxZC>q5p3|Tc`8{DZkRJ1C)c&W8 zp5g5)zQ$BwK|VB<05!X1f)IKA+{*ef<8?^+mdhckVDywnu7k$ROT=~1>#{gFZL|c- z3eL%Vp#E;NX2pb&XcTjk88uJFx`(bmTTPr8@bvfa^h`nsETQ5VO)IFG2bQmf%_XRR zimw;^*eooZ0jf)nFp7xRF*nyibA)-ZvkxGKOnt^+bm~q3E8c?GP8v?bhafrf)bGQ5 zP~|B>$`FwDd}sAJXtSuH@GpTyh%@94)G<-?zkXeYdw>WXpwd(D2*BCYKVQS)Cue}A zR8WQ-$nE;Gvu~sXp3Cl#Y*M-}J zZWBA^eXtmXyA)6iwsvn<=|O)HO=Nc8IU!(1L}^+8Yc1?B(%V#I4lN7{MRP0oU%ArO z)mYDw8r1o`EZ4#phW!w+`s(^ETcQfL;9>#*;$;7J1Q_rXRV2WdRBz29E69X0-tib~ zY8&~~2m=9e;2$vJTiRLR(Ol`gh_fh#jZ%0M+OyI7z6%rxa`+h%)6{l-9I74d)z`;; zvFlH;4MtpY=&})KX1C*~4t8#V(UfQA9^0#!0c7DdJ2|~iO-J6##42--V(1*2vQKMbu_r0*6YXPdjd)A5gc1nLE~CUf<2Z))*)u(X8pg3i^-xxyeT~G+E zB5FH1HUWgG_-a7|rzyY+MZauba}~%0akQXRAYnonoKpe%ME5~YCu+&0G^V$?27AK>`hN&z_HVI4DR;=GD@c{ zW3i0r5T&+0%dfL#8~_y@LaJlQ-7L_AjI=|`pW~X|Akv|Cn2fi1!7>xQw*c^?Z5QlB zrD~CHbnR+^6{it^2sIr_9tNJh+bTF_3`04^nKi)zw)UB(>O-R43q~Q0vgEv(_QwtU*FH zfJ18vARjy&?&O5-jQlswGL!fuQX8SRow#DEug7U^EnSPH&p|*>Z3HK}1<1pTr?n%$ zgSiqLd8w+n=0DdYwW~6hN?Hq%BM)0%b}quh*ur@1)H-a6$%7zOr`pz5_yW6~@S#*y z0-D%~n`$Gt+MCg%v_wT4x^AaomHGWSDNpl-l^qg4l{HHy$j+K|GG&~@f^t8;wVe$V zfFbvILro-_QSwS)&Yv9XYZ=S-A5JdU^l0F31Mc0sm)Zy_1ex#r9fTjhgPAz^ynhk) z0$%93O%u)1zI!G0{tr;tI=Sd%1Qaq5_`gkLX3lg605-6o0erIx83B%LapPvF91@D` zX^e22x#LXr4K%l|=4h(USA2;avlI;$jYvae+S*>eHF0OBXr!hVtiFiuY-%GF@PO}- zU)W4#W`q>2$T+n4sd=AVX|M`Mqh|2=^XDsN1O&dnzY;0Zrr@h``J1M0QeAe_@R|W3 z9B}A~N^L{|6R7HYU~OY<@uKoJye}!5)~8mlwgC!HljD?G)2y1Yf(gP)RehWK=;#$J zH`$!diNdNsIuOrQ)6)*wk2fA_81~o7kn9s83q_P5p>b#=7L=7e?DfUY-W^5n^~%`tcY+UcjhCVD6a zhmLGBd;ljbGZK8&%?NCCGvw-?#)Re9{Jbj*!v_gxHT`H~bXD+SXRoQ1Jp&M}6z_gj zWaXVd2R+_X{le{C=_%0)dgZ*1OP3r*BoAKTc6zc_Ja1l$@ zsyCkTg=^VD>D|xSv_|pZ;?(Wi5xw+gy}V)$a}tlLq@*MZY+wV$KapMdSgLMKwp)4r zHadXXnWt(xhaT>A2sHzFNY@IU5o!XsqNT81_xB=jaw3!GrRUBe&g>4gKv!xE7x2!z zvC1eC<#O^P%r8Zcmvlw7c1_nDk5_W&?&f8&ID2Jt$VK9dO22dMX>9!d%yVDAHMsKl zf;pVLcQOr=ZDzsN^NGgeM5@UONWpm;{*M^kF&p5x*)-%5LAq7w^bb0_P6jf}ewM1k zuLakny6#tLxH>N;eu=%cM7OnED-LyU%eC0cr8u)P)=Pi?zB_0lOhsdC!yaRU;4XR*&*&-7uy|@3**UCnwJ0 z>C5V23yk_DH6*(|pI+OvN7jxeZwjNE*G$g)XEP8<{vnhs%p_Y~A1pJ2ss;jaZrk*i zU0s;Cm_{%8uH7BdG=aLAOMki#dqO0iqfldoSgxIL?niViFU_&~wf8VOZZ3uB-^Zc8U&6JAH!Q?{{HdGT`VrUWuoz! zCs;ZioStZAt6zigNn@ebufva%VhJJplTNw8Pex0u->_luHNV4qv4N1X6L8Mf6A?NrFVM-zyJ+t+W9cjKo)t$a?)6Cdwd`!~4}O}WB75>|NvC87 zz@vRjgxMGllH4~4%E9N;6~jdZkc=bu^`KmunHa5)N30L5U8_^XW29I^@#D+j#Fzk3 z;VQqAIBI~SNj3)wmDQPvg+4$?mrqKmS>9YDZQ0Ou^I3Fs*_l-(sDf8UUPJc86g(Ft zla)umkMHlY!K3u7%Qkb+czA$Nw-Xe8d#-!Uq`^#8TIg+1d8L*3pk*MtH;kDWz?!$P>*D@vDJUK-)|OVE+i!(( z*7NM>=$%??n$wfogJ#y&AgpxG^nEuU6bf1?4H8ZSp08Gn5;1+E$?Z5iwuXaK-VhI z$R`(7HOMYNrgr-;g?cp7kmf%AL0WVG1uE+z8nQ`;M)b_b2W_%}5VGA@&Xl*<-d}u2_p~q;zd4pZdE7`B zUCKo*xN_yxmHA_ufV$6I;r?!&eqmOy&n<74X0121eBg8iFzaj&lf%Hz4I8gqW|P5I zw3RG=?=yUteFotJ7{Mg3$$6ZbT7rReW}98VOmyAYL7l&~nH%xMf432si zrpw>|LR_TWj9^opJDsRp#M=GHEeYbY93%GlrNE2b>;8JVH#(wA-^Sx`90d2576>;>i8agj~%6KhU0X2pKL7tt23MeAA5ZxKEd5B>$;w% zKg@}?1wo<|)?Y4Yw|KO-HNBTYhU<3b%qWNJ0>s4PHP!N_x2XWh=G=w37A4ttYlqE0 z=Qy#e_W5Jn?o#Y?v2ims!zm_)5lm6gXyn1}@F7znE`)$u_IQZ6G0L)bF%3Z`ngo$A z>PO`Vjeb5_p*+q+o$*)>I(_ zWrK7*`Z%K}3s9@qTbsOk@3XM5pw?$!JUGfIU!DBQ$+!OlobaT@Z$6xF7PX`X2R~&W zDIvWhqEc&fwZ^87!n(3zY#?z>`_jtzCYVH8ZEKnp->$j34bT%#CXh*oo!fz%lFji} zG-hF*p5GD683u6{o>g!CW(;|nz6XbCw!8^TUn)>jfwDY~(S>aeblcL_3o2hn`(@|_ zm2JUIP|yP{k5|S!*(zEEhZk|^kj@9E;T(bCEa|=T0ftrzl2F{ zQ`$l;v}R;vWu5Wu@=!kwN1$`rH79cG1Z$n>4JC!XdYcNZT*fpXsLq|;1!pgD8?`)Q z$$?E65#C#xhPlix#UG;DhgLLB0M3iYr{<{_q+q|5;01;c)wLbg2K~;|6qu$ zS!0Y-g>y?B*S;?V+gH>cWgjIPUFR^>cnyA`3!r&*5HxQtc&jWWH-F^Z)5{YvE#HZ0 zk{IBzV#SKh2AW}s+(#4NkwnyocvMowGq z@7-r0c76O3d&_?08k}7W4~6l8zCh(2o!g4{#V#kX231bN4G%**;p0jXDO5 zUSj?p8uuj>9ps?H%YO0Rd;9ymf_}hc<1peHp)Io_^4h8X30Q^Pj8}ojSBScOr$kHw0%wxeLAIbDnwht4eL;#E<2SXP#F* zr69`Na7>0N%`a?Ub>4LCZ3yjB9OB-!ADFXqH-XBTwo=e<6dl}*!RFDMIREQ{^g89l zy2Z40LTA8@4+4~{F_b(Yat$e|b?cFn8Raj<6wcMrMK%xaMpD51li z!BfvZBGgMfByFh%b?}-lR2m$T4Gp%?&k5irG{F#nwY}QO!h~)4h8o%mBv;Z)hSLz3 z;4O~~f!Cqf%N;qsyr1ClI^Hz8RP*x`jf;tNPDGbgC&V=Wo-FN7DB6#fP7?fNSZlhV zUR1|1;EzVZdVmD>;8O3I=$LXc$ z$~95UadadCaDi-F+b#Ra$*Bdo&qy}xJ*(C(s8gft^e82h3!z@b5+f|eq&8A39DU|F zO0#r$k`R)vc}~9@^Qt7+JD<;rWWO-Ak!{+Mz7c3Nvpb)!>5YtROgEq)0hk?)^!?`J zYe@)}O|=${m&b|fTYoQ?ZTU<1Ro9G|w}IXpf-gbO3W9Lw(B?W*v%f65CTbc{d#>s2 zEPcs2O;s&!%Z`|%WR5sqciY^48V*p0s|8x9GkDTtUcAdh>Emw{MK9|$Vy_d@!@2k* zwC2IVBPwfR!?q)>F;&-aZqs zA#CU2%(hbPX;Or_(!TSxI-ZcpO(q)lUOWHf-c>`v z`aq-r01Mr>af~=ytqX_d=vrw&$#zb8HA>W^G1dj4TCEeMIoBjFGT$C-N_S5A@w@kP z|NlDAg;;vzo5X0c-da6C669qk)dx(V$(c#45IF!Q= zOt8fsPbdyg5{>Y*0JVtO`8B>X_LD>h5!ZOJEO&Vv8V5;;n_@yFjW}^&`vVseiVa1= z4QHH$_ax$(Kg*boPBX@$i?-a`6PnXnndTL?s-34paeGm7)8V2TByX355XZ%%u=;-( zgQY_yaZ*kKVqzAQ7tw@Sv*?mF4c~&Tsa`FJ;p3iEK8fnuQ zwYXFp^-)b!RWPV4Lz-HIyshV>31r%}mKv)l?8UwdK~@xPNC9+gXLo0F<~twV{0*sN zluUlyT>1RwrfD@epXMUQ+?^+wv^u`~0gw9uPPb%2n~AvIT;o8i6+rKXBX3Vn?QFR5 z;K5u>TH+JY#^?SV8Q%?*{kJrABiE#~S%AU1+_ph<%ziP@+B-2%peDj~gc$XjJbcL^ zbbCsXhq4-QEeKoJ2^V*FhG|YuT?;}mFD8II1qd9vM~#e}Dp=Ku$9sQQJ#ppAl_g}Q zbRZtPv3x>q7Q3vO8=LbjVo7NcC+~B2-x#pMX75h*5KA9`?1Wa(-IvXKFn1E`Y!Z@! zmEw=AUVFKq9kTd9MEgLc%Ug_*OzT2Bld&O*CgX?DaiDRc8^=uNkTGF4=!|NH)+>a? zWuZtR2ZPvcl6wftvAP(6VJ*flR`cXN(Y;&-`sGe6{n-{JiRdp37mG5GQH68yW8e}F z`Tv6I0?yjU;3R60cG8552 zsvjd5CpeA@{J#^I_WwJe+~*7Wc#|&v4^YC-Pw4-qC-ka2%sfR5Is2vK_O;M}1^9Wp zS`R}uM~PlSrxcO;m)k$SOOa@Vgrgujeg2To&jc&v^E&ywcRq)L&!OORD8Li=911>% zg3qDgb13*63h)H}w}*m|-lrx1g$3aEi~svvwtP;}KcCD0`#0mi_TT5e!RH#;DYkvk z)4MTkUmXem&2hZ6bnf^OL!@Q&zc-ONG1PFQ!mB<0$v^k8bv9Lhu6#n@_41O$Z*3p% zaozf*cHuvot>UG4h;s)M{)}*k2DpPH+bbaG>s0n@^d*F>09?0 z)Pa%GJtV*X_x{U<{3rcI1I?kUL(ea&H%^E9uAH2l{#gwrXN+2wV#Ko(AnlV+H#ls4 zUIuKUiRmcUcpozf|o!HNAL z@Nc8qiBf`c$SQbAEF!84N;I=xh3Ap1+XCD4krZ+jbB{rUNbDjl@%yjFNYXl-SO84q zw_Vl{H2L+(LiY12xnNzBO-5F4X8r#-x8CsbR`RpV*!8fcgLb@ z;MfIoF@(vk5{SPzMoEZ{4NQdE%uoysb$slb^2ks=?5hY^3WZNfb9bI}17fVg=+Ek# z05Wh4dl1;^LsaPmH15DcV@z=Ahtz@z{}>Rmw~vijT}*T&$ZP{+1#_>(XQzq=NI3#R zw+s$nCBW=uR7H|_R*fkh`P4Cf-jj)Ej{ z1pQo6gwyi~81L?#@E)Sar6)@vX=wCD@xKB$e^45M4^)F1lO|z%KK8Ilw4f#%=24}9 z3%G%MMNOIx{5hY=13)hPAxxu^sSTVbIg@cEhWQ= zF5!R=Lv?o=oC60r66~u(J|OI8VQT18Nqk}##)=g?J7cy`#tO{X_1fBbPl5#3Y4Y8d zj=z1~hN)XAEip6VAY86Wg%8r)2^=6?DHrHN@U9e;065MCdajfYAFp&0HNFW;D6yd# z7sh^yZFk;agN+5CU{$p&pmCJ$5VO-U`zDK$QkCSM5P(Agl$0^nx?*z!tO(ADtummR7}YwFi> ze}SbH{31@f9vd(bz=a{U1S@fDOA~e_=mYr}lH*o~$#*iCjh0P=;1UFdqsXH6z_-AP zxWmgjFn+KmQqtWS|Zfn)oh6Ga0w z5=rmFmJSY$dmsKX8A0n@ju+^EYi`8@4p@hcRdK*z6b~_wmo=(YN?qma=Y>&<08Xrv zn-<`i*!X%qCTRCoSjNrpY;5EQ_@sVOLg3f2m3Wp;JOo1*?t7IWBPW+ym4*`vbW7F2 zwv@$*$yog-!1&*Sk!kNn@EPM>QRP^$ik%w?w8pzW-yEqJ36X|UXe`_ahmzDC$|C)K zP_RgIPjS1h)7Bn|wX&j`JYcynD_^qaH&#?U!}A$Z1=P3JJpgoTt-b*ep3%Xrk(w8z z;x|XWutDT2#rnDx9uC9}vG3ZaR0TooTfC?pcr%1hkE#O5?`B z3z0NU?|9Htre;5jiw2lR+6>&`y~czVAyiFyA;cVZC?inxUWnC^*oNom^R5Gwrb*dh zqeU49tU;7AH3`o%xRIWDz#1w6?l_q?8fZbUb)=z>1Q%oYLV()IDv=X1rmuS;1oQ%@ zd-bhakoj(8fc5l#NL6H$@p6JUZ(Xyu2I}$zATEi1h=*6_v@;RHE4-bb4}s!RkPg@G z777kM!eMlpc;pVyHJw$(NVUQVIjy*^H3yE^m*vlRA3Y7|d8lSgZn|ROz%*i7@B{z+ zd1_Sa>SoBzoExzruf_e@miF+z;SWXw zn$KrON7G^mWX>1a1V8423fG|2BQKOSebdLWO`D4<_S;_B*yp(r%cGxovfuQ+jyO#R zTf6Vs((4t%DK)w^O>YCAZ2>Mz#qKpbL2qVnwA{OL;5+}oOHv}G(MXgYmiN08jwLqUmU)52 zd0ktjUmNpoeA`Szp~S-rYl8j#r70f-d#M-M%iKn7x^u~M`W8r#(qv$uk^@+Dv}f(> zy|$?Z-zokMnJ+U(ix%fE0JqPm0hGBb=?#5X@QivgP4px|oSq*!f;=Meu#wRY%dW_Z zviz_Kw=&lpeGtE-0NA{3Qdrx!!np^NAW^@*cBJ6hm+=I&?458R;3xeOIB9);n>IuN^Xz0eXbrH?IM%bdDX@mP$@SE(au24 z5Olj3FCz5CW}O$Uc7m_15BV;n?@>v5F49KziE-HrBz`|u>7A{5AF9}AQNxTJAH2t( ztJh0aH5@EnQlNLy+WMtw1XCg{)7z9d#3RdT6{x_7o=y<04%mb!jj*`)jp8U>q|k$_ zj`kCUAQ2ArGtNAAXW{&zC0$RWqA6g4I3IMIqE*Ni$0Q|f`*NH_Xwop9L?AmawD|xV zJZE#rwobj`SwIfrc)q&uQnfY|o9>%Wyk+u{=*Q)aut>=}{k0QnX63l%7Zo!5L9%rt^aupR+Ri%)-uj%?d>Y`d zF9;=v>EkeAT3Z9A&`E@lO*->|lP4Md)(acKpG%(OT7~Gus#}>bjBgx++TncI)SzCk zlJ_~>kBp`Q7jyZ&#>n>Fkz~bgjuza>x*CSW#Q`?IAq{_TTzz zVL3T~@DHxiF$rBt%(Ea40$iP4<-;lk)Pk)$J7G5HbUQr%=70E#Cl3#RSYVimoYMQ< zAXFO~`kkcv-E63u_|Lc+(k_Jp!7V-qm%Gdd+2s8qK}zoU$24(J%iDEU!=K~^Jr-UEKj>$+73n?AT+BF)4CuxSvlYk=J;Dr8 z;W{_MWk4P7XASoSYLJW1PC(YS7@PuqBpHg?@hv4T8-F<`KK-aXa6hln(>P+Jyn!0x zmgLZ(SLbvC{kr^?`MoUlP>||#Y%_olUSBJ}x5`yMWBILGEU4ZIf;aa<#*88QC05sv zDheyzY(P%dnRu8vfUn*-RokZ31Da=|TM~y~W$Ei%9xX(3k3od~lD0_BjqFO0tl_1K)lZ=|JPgTU+L z?5V3SoJuVKhE$0HM7fYq5j>5Hya{Q`KBkb$dK8m+>((t-==n|wt%TUpqxJ$jP{j4{ zoL~HS2?7oHm8mwD+7pMYos=DYpz2&}#8kn3opNA_PRTEgTk%j9p|oC1hTYq%=k<~7 zC}!(~n~Ve@>(DmCK%DV|LXq`NX`&c9J`|PWlx(X`zb-vW>S9m)Y?lsw^~!~j8RWg( zUMTSCN;tNJ3HKL+=8ms34Fxk%EN~DakNa#&Y@@yuYN52Mw0kVyog0B$O@`P#stYP9 zP;tRomEE2qp=HpML;pa^NOeEr;q^07x$0Ay+N&8Q80`^;*sf72_lQZ8`xV}yQ;vBe zc~2p!xk0HGRUoo9kYhqYbt^L!!m8cGwH;*)O|VcEvw`>?LW*{5B@C02KnJ{#8-{8~ z4NM-CR_l~rnuN_oqhp8|v`+Kw>U(osr(e`cf*_Ezr zu7SY2DMUrES`@b71t-!OjZB+SRfH(B(&bK>=i3cqOu7{K<~~D~OA#Aiw2qjulHd_q zNwq!ZmTM|Qz{hb{skqRB=Q_BZ!m7&<^n48jU-qPh3H&p>JF5E)wuSDf6zu>(w+q^A zc=B&j{zHtl7m^aPvO(TW8&=q@e zxboH>tdj!70hKS(K%LM-e`IVONEFlHkg2n?m>M0_P(UC_p?=<>ieWk?66hG-c!neM zqyH4fTpbuII^_V~ZyipZMCA9Q7)#ykai11gK*{v>1?D>x4S{4dXrx%1QM-q-Tgb3n z5F2mhh;140w^4TXu6?c0b4=c(wRI@Plk|%rm9{g%u~#TG_0-X5qWlvj+r+&y6cA!n z0JzK`W0kHPt8gB=tALqe0ng-x4j5f?%+8j!R?*ODbBGJQ-=!2M2bYu z%dA3jvj9sO4do4$@^{PVQlJkHJ_{(`msf8^n~`c02mCgHOizjvyriyV7z)1V$$m-Y zzj`k|OeIkE(C$Hh`GpD(EB5SAq@I1}v!rdUOf#0B#(^~m)KmnufGzBm9+ZS+_Ld&} zvyZ6{0mD`09cXQ+Yy*jK58B*vmC9Fe$1Nb>jAazUzKFSmXVgw272AC_iv*TJj>)S; zBa}oux#@jD{V8=MQT3JvXl#{`GlJMKi|w!&AFoX`NToDM7Md+FK3a$}lpLeZF1ot) zmQw^bt$~PPG9Ij7_HW!n;=AV2_=w-+oADOy+y#)SW@n$`RP`~t4|bC5Pm&>^{gPzR zd7L|!-R6oaS>YI5ooT3z4t1h|x9Pb*0tMfsaPa=xJH6btP$C`NA}8!n>4iwX4zV_i`PF(VMhMRCXE-6*4vv z*o0@hzYZPv`Ba)97ZzNwWniz~+xtR}jnFsXS-?O_m3*aKur>p58vV9t$u_YP$)GX$ zPmF~ZzM^-+onB;?qumtnTh1O2DqpbuNwwU8u`7Qe9a4r$4PW-RN5KE8&;0y3AHS>5Pvi5``1=WbUJ0L9!snInc^7=%1^-v?f|l-3 z>)P)(=QMUF=tV!?t!*}K%a;#yzf_p$_U!<#K#Pk0Ckie~U%Msw`0@CFA?dq*bGz_- zqtY6sKNqi8xLW$=ACfZankPo>SpVJPiT!^K8$aOd6|bWDKQy(Dcj!1~-u1wzP_HPayd|o^Meiom1*1w;{=eYClXYn~I|NB{dKC}M)EEa!0 z(f{jVIR5IPps1)g^zc7KZ~nnv>+x^KEv%~Kgc8G=VcVtqy$8}SD>wI0b|w%#>>KyF z@DGuUQqw@u_;J+$1_b9ph*UQW=zvIr;_*`WFbgOIg&iqEH~e}?$gBi4QJFVnZOT^I z*tDv2fAz81!4`kYnqV@xP}ZBe#&3a5 zb|!R(`+ql3bo4S1-Zpm~y1SN~T&z#wBfw2nt13BxfOTx|)nAGvrP}+7PJMH5kZ62P zH74T!enNRNGydvviwO?0BEdLK^m%#y`w=<*pUr>YZhV7D(Y%|0T_s`mm(kYx)xr-y z^987^2>6_&?L%$*%3$C3lQcD=aqPuN?n4 z6Tm;Nn{QLU%cM9?HQXd`F#aqQlf>L;Yjea(byHJQ4$2`|I1C@|LVfi%*gXGmY=ARC z-n8X`4*serg=xk3ylGALKpq{LtbzZIj_obFd_fh0gmnSqI%S}ZeW7uFaAd_r0=Y}! zg=8nSrmyJUa11&7#C8*|4Y>F4{e4BRI^cdxi{flJXi6!WI8i|nh})76um7yyzVJv>*d^GJ>1G+! zekpod`O6p)Tq~;c8XS_mX zN})`d_EwBTj+7Q#nOVLD=3+L6@H8sSs6B(vN%6?!=j6^CiVVR~pC-l+pwzbIuir8r zSYTGF*P$=gkp{96Kpxk&wzk|zD?{klIXD9~I*)L{x-nRz7CBq3lW6ONA-qwL9?#wJ zm3Vpx&+QnsCjt5)_UYn_n|xk(Fpab^pHBMym#=nWB23g7X-s(~*0g+b11A20yy2QP z2Ip{%?N7%x4-`3`3Dk9XKSH$lt94ph!zlocRBHDEWw2pd-mY~R)!neD`&sq;ZZJxc zL5|_FFOB5aVb;o->g|goMSB)Ok}jj&1WMtv0fF`@S_F^~UD?*uibNTvpclX+ts@}4 zc>bOzmk%|hE5GcBoiTySQSxOR|F=TNhvSP}3F9yI0vqMee=%c9hFoe<106`Ay$E1; zu`eDuVxt!vx|7#H@WCJbXC(p!uw{Yms)x#=%O6hI6l2whuC?}05Q$8;1F@TaAce@&5n6 z9meosvl!)24ilDRk*G9ts3BTI2dWh%Aw*~O{@4tiG>u3qr0h%H<%SI3m zkoFk_iHm@H;Z)S#(WRky2U$s1_w6qB#7`?-33~wQA{CNzO8C`H^~u#hBoUVniA2wF zBuxZxCBrr8{P{^_BFwq5%i+7#t8M2sn8H2=UbKFunZW};YN`FnzO6KQM4qxm3Cl29g!dCu4l9)P@fP=Ba1QYw7MEVIuFv5Q$P3W z)vKl2PS_VbjvVeW&1Xn)#u3mC;+laXuIp%X0b%?w_sG>er@21gB>==rNr~%c zm(-Y8y$ImpkMh;A`D~L7yy2o^5XBF;frS?I?*oJ}jB5&oEF_WqTWwuje_UyRy-B<%*%OY$IL3s5okdB;bOP{{^F2K}s zEP!hXhdjU4M;>n_b>`p9x_#;uJfEw`q3(rLhLiL@|@d9aWbV zz_bMgdwUyJ^}$zcoC1%IGWs+s;Yv#>Ew{S*FfGqto3K^p4C4t=BavxlQvzTn z01EEd(by?3ub4@yd{q}(^D9ThFexn<$)~L+A-;cl;Bju*$K#C)8H>2k11LAtUZ_y;ztIjhZesT#?E?A|?5KlwBk z0qE@2uZ?<01}(%^IHQlhrIflPx2%(va*7J+if#Q?Y==*O&f7hX@y0|i`JE?vxJXN3 zvG13)Jxufl07@%SSYJ`;e5SzEn<+F)GcsN#uKO2Cq4R>JKcmQ*UTO#q6U1e z8?>{Ny*olPren^}FB7IXpC8Tg+?Kf@QxF0jUI5N03 zGAwsL+0QHRWE(BTCo98dR19x~GA{UzL$VbKorf__bNw}5tA~(r1zw$Z=~qV5AO!$*o&q@k%&=pSJEpShg|1VycPs+!Iv&I;k5Q4Csap*+mPN_N zs<4uh-ol)4GMH1Y<~O*)x`~3`JXNfT&k1bf{tlRHm;pgTKRfOoa*SV25?91rx50lw z5Mq`a@_UD8OK*CPKvQo#k)j*IBks3ERFpHAca0AlPhY$M+SG<+mUN0%; zuwfVDEI?yEofNjG0S?=a(YHCSZ>=bm76YDn;u8}ZavhA;ta*B>u>-Le#adJ0us`Sc zZh-d)A!0ahk;g8gNsJI+ByF{gSFIWfm6fcI^2cHQ0=~3tS-dozcghrZ<5|ojulFoC zZ|t=?vZTs>t0DY7r);To%xP@cI-^yq4%c`RD(P65RP*ye&++8NX1K@WNMi6*n}a%^ z_m$Uv-b$@^V8sJs`vWKG6aO_x#H7uBAYU2;XfTj1gP!`uvp2;M1o+50L)$^NYKerT%l~&Rv{(??Qm$=>Y31wuc_fvHE7oB7Z}_QxTFc zmwp|ae(L(ku@}{*O!>I3Wy$2)j1kQRw(*VeD=c-xC%4C!K23JIzTxmwr?!TmdQL(y z4%?1tf>O^uE$~NM?VA#eCN>~o_u{n1O$5J&rsW2^W3o-cr7&(yOHs<$j$qbKrxrl_ zyMX5(%36qdC%c0t*vhm|H_(y23I&{1NUcI?hlic6$n)Kg-7bta_<=gn}2KcN5Vwg1{h^a3M)Uy zz=(g?O$3oes`K9)6qH2c=oB43k~w1U`eekV6HpC~K8^|eLsyfq>IvTQwLk#VnZ}0I zqzn?GRY`w<9PpvLZHmv(e#?6a8oTiAdNX4AR^FEa8cm^dC7njfMPG#XO~|muH>XTm z91kz1#BMzYy;oV^w*t9hXzj_ubsDZ5mxFb7w*D zxprp$;9=D#y*bkS(Le<5iO9|2P58>fdlQD<4!C2`Vn5ArgBX0p{tX zB;E4(ehL%rVp=jN>pO38Nya?vS`ztJQ<&Ja9N7lG8nOW!qBLhKqc+AN5VMYw0a&UuE1dzW2B!QhjHcc7{KMwg`vK(xgbHyCK2*5C~X}HE)Z@dy+qP|&usqNTfG$ibNO^M zQIna2S$S&=?wMwu*mkF%=z;KW3L%^Aux42rv(9!M3~_VyMYvjY)FvR^y#%Ksb7?iK zs9lsYfZC?XJ9`Rgw)kBmW8u@Oras*1dcI`6F90lk< zZRgO|tG>qbS)9K_z?ehxX8$xdM3yr~D*R&C@Nj@OVo;P8>F*a<(oNZRx9j&#GuxWmr zkT*-TzsuWd7eB5*%G=f(aeBj@ANwg>mT`>E1e7O+?z`XK?(5(F>s7>FrDui-(T+Ee zYFne6VVW7bOJ+)|He>|sam3M_)55JPH)KvCMFb+a$WkiSaT0+eH7C=Z5Axa8#CR6y zAL37!t`4n*TSbf;Zs(-_*?uGVgD(jkemT@G^qQo z*HNdsL(u`%hTk*6NTfu!EmKFd=!fy!%2mpOiVk-ScI1INsywfCdN|8JtR*kGEsy*y zJr!U8)3CeJhS57+!e-K7=7j9VS>}X%fC6x1IO%|uSLe#>ro40e1Dkl`e!gvs5R9C# zkfq~}sKXBqg zv~JJZuxi0ctv!S^DQ~DRZ|EFL>qlqUaC{d>3R4;+FnW!QVnI;lDB6mH*3AjuW4CK? z48m&KRmj0sp@b4?$5K1~>;X!p-Q3lP0UAZ>mY^IyyF4DHJ$0&Pm?H@I z83D&#sA`8B)Zq>8vu+h{u=VUAg?;Ya^4JQl>e39D$e) zr>tCBO4|>?xt&>R+>!7-j$)Y;7W zFzJ^v-xD2CAZ*~4<8sthJX0Su=Y@oN9vr|KJC>9KGz`ULd(m<#xr<4)_&g`hJ+bn+ z*xtTubeoPKNz_Eymou3sQ}^%RPZ=BV+9W@1#Ie)6p;4bXf?Ok#TYqzdv=fz=tRH%n3i=d{GD)!Ax%q|t=L;TiZdjhd7Kfq zO1#Bz>Y|*we0k=j-GXGdG1O?q$-Iu{OC3He+`5kxBJ{=RhVfs+7935z84UI6K4S?h zh8$aS7Wof3Rx-Qs&OtU~L_AuVtWiLS=W91($t9T=pZ z{{k;rOp+kr`)?KS(1?LnjyZ4lYg+DiulEd?x}Q`+O!h!Fb8B=yQz)_1!U8rEaILUU z1^o*Hre0S8yTB+|c`sfbCgxN2+OQn2A~~F9U3B*V1vG!Vc#*Syix4GcRP_~dM)B%l zy!zuiuv|ID;?=)-Q(j&^K&LkxAg5H%vyEkXa7mOd18~)~#E|n1!uN#Cd*btI_cC5W&L@ zCX?K_fH`BS82THcnmWtAg336UJ}XDQT`}&hn1XYbbFJThgBK=z`r z15v`%I#>BO>HYiTuEV-=`kHmSR&7S^bM7gJPOqa{Jz%=g*~4}hY4Qfjydb_s=DRxzL#3H$`@_oqVR*?gCwdIyPQtjv&yWzr zW%ADf^f1iVx|f|DC?h0-Qoi_QLv(>=_St=I*|E=9L%4$oQ2gv=WkCGs6^WXlmMm>ld{W+{y>)nitqFKPai7(t(6m*e~O<;+j73&NAvrGH-yMT z7aR;Wrg|Mp@#k;nf>CEMiPUf_7Kj0htJ|xpl_IB@M5~MjJzDo7^f%~Qgos-ZcOJ>4 z*+dyEFMG0I6;@s=91W51ML%5iZrbOq?;28fox|{mg9ggjw_{QG!-I7jz?D`Q3iheY zyJi0$&|GXf*wJ+G!#yqfa8HP; z1Fu>v>+ynhFvOZqtSS-L2B0ghs%>;*Eo3d}Ir=zg=I=E2M9Hz=imn&5r|Sjj{d>az zp%H$C)tDC=?_(Kmau-B$5v_z*=uLV8-_nHk`E#qvA3o9D@7;3Ed#USK`8r2@ zN*5}A`m31>*N=v^lb3A0=blO+5-^vn_VU2vvQxfO@0qj&d%q9PN!snP2l=G<*{jm^ zzE|qehjAF*CeftlEhID<&2_oqt*=!383t{oi*?*xZaz>({bUN*DTH-W*y(rgHN75F z*4@xR(>f%^LQT#Z1@-txR+Xsu9wfmB)&%?qR`N?nT<`W}L$cs=FUx$#2x~1ZmDw7V zy2nMAC%u6?4gg%C4^pcJGmd0;FW~qOJ415$BMEv^!^!uCeUSB#!Oil z60F~%qLy##8ibSc!-_ZVKAb`PdPK_fiWT@AGtP!0egPlo8au(inuC&JgpZ6zsKZQb( z%c{;*kY6b$mxSvWy0*G2tq`Z4&vq| zfR(7pU)GJK^UZ;q;_8wAHmR-BG4)zfebjIe?J(YTtc^p+O)e3#D=0;-I5xBU1o(Vs zup6I~`{cKQ5@fK2yFIxj4m1FSph?}?0}Y$gAel%Z@r}{W&1L6OfvEYpQE_#o$zYUJ zM5%QyM`*q|D)mf&$ykwrk`2SkjH>onR9K~!9rc!)CSM{?V%-oNSxyCP=HfFkQjDI( zpCfYqeDY*`?j=YzieV@yy)3=nZy;Tk&2F?#-6}1CZ()U$Tqcg*EqS3od5;^5eeyY0 zStNx7|8HRS&5nv66%6--U!ji!%pBFzOU_OcFCnbN>5%^3ZXOaS6}!@LVJwkv2n4G$-+@MLurPd9{XQ6xuMHfMVmaYHc+$|u{L34blJu2;q0qv0 z6Q6cg<_&kbNpI& znBrJj?ci?Z;Z1@)swhGXWDnX{V`C3s{JY`)-ud6}^82SqW7u*$yt< z=r#+vN@TrfZ;3KAVwoCCnto1l0jeCk2Y}~Ys@nVj z?W~!7Bo3Q45vX8f_Qt#O%}A^tMY1a=eky$FrDA5gzI`!aRJ(uLXrYSS6{we&>JZRn z8+jPbIhwn~K^^U9QT@9Ma?>GjlK09Iy(gJl-MDyhD&@zYw#&az?{fE+>TmV(&R#_a zytSp<4n5Dq{-IH^(NSK};lH0iIB6~_sLH5S++SL_KW%Bmd+!Us|9;Ob9NjsKmd-o; zuvYpxKrGqdPb-!q!&<&AxN7Tu%cSG_<2SCUYQYVlIVLab_8rJ2OQRPSpy z(0%qt{yP4%m3zFvPTCOl^vRP~33i8oF_2db!@3-A%2|7Fht8lYtM`<(*QeWTL7laq z;UQ%vxiWVUjO{3hMW+CP=g%=-Afrh^$hD(D(*Q-*Op_M4l+&m`-L{wCjKs5h@9AeT z2L(6rLlb3mz3CjqCBSYu9-OpfwA*@VE|H#ySu&OuovYZzD)u}bFG3vt`F~b{?n&B5o z=!0cdW`tpuxkhM0Eyx%9%T`Anl{#*99vIXCl|kZXYGIq+x68}rxO4~99U1rInM(>Uc}Z08f+1TUHV z301y=u@m>)q1I;zkYw(D2Mq_QF(W*Y`v@nh zc6NEypp+ZK|5u?P*#11RyQfCDx-)?-bS*-$1ttY=O0et(}p z$Be42eyW}M(5)np8_926Wz4fMK^vevIwx$<6(_@mRy(#K$hgc(4+y;0z+3-SQN=QF zVMkkGDjtNjV6B^)Bf3`i?|Wl>o`M9D)*&y(zyA}AhLQD|x-Dua4cgD3p~-srLinmD zPoCUGcTeQeNAsbwKA)Uorvv6rcDO!o&E-T#-U0@2N_Tf!1r^1=hkI|?E+s>8j4qgu zd!I|cgt&Z;LmS#z%QhZ5fes1ahO1gD?B@HD4+&0LfeuMTDdDt9aSWYXG6>FQs|bF? zAEdmmzJD`6y&-AT&aAH7v+va z@@vYaj!u1KeLYw~G`foSj|;9%zK@w{Zc4kISL^UCHsDYP~_WDHoQ`AGBPi!1wj=jVA)gPjE51e z0ZMzVL0}VG>|Fx7<@@*5{B>r(DoAdB8pp`kHteUyB1DD?rH7sxb*YYomzSMnu(qd7slY#{EM2s#laJ|nNNP*~A zm!WPx6r6wta7vtaC~T{8!H)IyvqRH-7{FNf+^WG^Z5L(dfr>6a60#o3zg{Ji2oD63 zisjf9cy7PVEAHjP%mjJ%#{mMOxCm(52ky4u=+vq{K1Bd2V&5g;<=Rou8R}0Q*|pIn z+U7t<%9;VER|pxe<*)OzbNZn#`Yk`?kvh_8nXDPS-bb>%VBvkiSY;P!H^98hoCkF; zSQtTNiXve&Y|r>P%V!3FMQb9Am&v7z7Y*@BV%RQp2xGjV!!dCP?s}^ltd6sK!%`~wGI2Nd6=f;=M()rzYX=)2MwF~f}rt;VJ1_p!>@kxin#oB?A4%EH-Y6_ z*H=F;VKk<7vn7-8Z8o0Rk-8UPL3F!Ak-`-3CbOddp*8cgxFc^nhlguK;>MR`=*f~oZOBS zV9BCIDN_s0*R2~xy#Q*`*VI3?wA1lG5g`>c{L$u4nznCW+-AS6j|0xV8!7R$DhbTS z=gbe?+qUP_>o4{kow?zgjH-D^Vytl!S~sULK%SYwkUkX*a#x<}pd8R~4YX~G(4Dsi zrVIIiB2n!yFN<(ci32b)Hy;5KQG-a6n6Yf6pog1(wjHO>7Z8KjKrQ>Z1L?wk=IH-k&D9Gc`Th0?P(C_1LP^ZDfu;;Ct zn`oO+P-1$MQMDQNgVcCh13MPCmL;aIM__a(S^m^3?}l(_MEpp0-zH(1*?ljf4Mv$pHVVPv-R z)Qo?HR3?BhqyX6PZI`MyeX~L+0KIH6h;`FVI)Hya{z4<(2`D%zqr^+?Z!YcdYQ(v; zDM)Y|DB~vauGRDostuFhsNUbcdm~^B(HsaBkTd#x91oTl7(2AtxXv z!jg@na04|!^GH!vJanxqb^2iN0!0M|6i@T4DiMPD!l5HshV`_8Ii~~XCLvQ}4NCy1 zl`3J3g8P@~XbhgPB5WjZ&yLZ~QbjxJN`$42 z?0iQryWfA{QS9j@hyZ@LicvNM-ru;Ms?!3)t^D<}H^{`UtInum|FFM~{7VF(B>)Xq zEt^WxGw%sHlMVAX^C$0A{}HOKo&LGy;}u=@OvR}1eTGXBP|CSw^)P0sz@U&9^rNGb zM;U6@+yw}=+3=F4gG`P2KEg}2Tihu{6 zGrAKyy|31StCJH!)pa15x2LETaC~cU_2SO`hW~-+8C~+BMnL^b&dV<@Sy0p4O8%qJ zzX%vYKfr0L>za`m6k!nP%UcWg)(|*8yxqSkJLu5f&a~gEu(;o?&R-kyfH^#!&xpuG z5Z;OsA=*ZlS@c2A0O+My<1NVF6o0ra{|&wE^4U7^-zsjhVowkahU2!M%f*`YN4J6+ z5_2lAWEVlEDet^95)@3@%YR*EVE1};-huG#8B>C)|KroH+!e-j{b&8b|NNJ(wZI_K z|K8PTcWiN1N>r}{@p^B*Nm;eTA#wtN5me@WT)yuGto=hxfrq9Za` MWVrC+0;@g$2e_IcDF6Tf literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-25_02-59-27/plots/error_v.png b/tuning logs/2025-02-25_02-59-27/plots/error_v.png new file mode 100644 index 0000000000000000000000000000000000000000..46b303e12ed9929762a8bc4508a152e87dac422c GIT binary patch literal 207875 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@Lgd(cU%(k`BGT}Chs2~W~D&~Yl0Rdag2!f!JQA9F`NDxWgwhBlvf@Ir(fC5TJqDqo1 zC^;x7NEXTYdsYP~&hdQXj{ED5aZioCZJ?^&_g!nvHPd>YIU}S9;2MdnA4(4_37``m z%XRbJZ7d)7^O93};cF}5Fy-tMQ)GbPl`W(YoIlRO9nZL%eF|a4QirR!_un=E;QGSn zzh(FL!cSg39KGXMuz_k*%0`-R6U9EYUvf6!peqXifIn7nv9Vo4T2nK6!x!kvg{yYU z*n0m1&g(pc0H4;2wCLa*Qq*BIAy^0bMk+z|={c<{-&cTCSJ>%~!&+&a>rrQqppk)@ zs}4Br4q8Jas;>Qsx#2e|+jiVaY{9&Fe?5Qx{PRPk=2~iZxNDo08k0PP)xCS6`-4A( zZGtLQ6c?(ZhdIM)2!7#s{9_L9FhngrV#bP45nMl1^s2)E&a2f7pP!{X6f{^ye3$(W zEJ)h@P1wg)?qBnb^a#Ky)&A<)8k|@2BN0*X>jF;iaeOMAy!mkdUp%NL_YQH6VBU*O z^CA9Du&qYI8}_a)dVK|>UZ@(aNwpT(EP8GfFRN(~=Ptj`FjJCcej1n|>b7=W@%w)-Qsh$XZvO!Rvamk%xl0eXFC zpK15&+mV_i>m~3e*s=;~t}3U}g)~HC^CEXb_l6JcSLF>Rf%!v(F3%mMcW}Td&1R(7@U0xs0=w>I{u4g_Uw?VJ-~M8>Z3>-PWwZT zj6dGw`Zuth3psXCkZ*YhSNj=f(RpyCp5U(U5&&HlHGUp6Hx>k!y1F{yG|gMJj(??@ zx-M9_FlML^0HK2jSA;?{=^L~~J}&fR+=nt&*gZE?`IF%w8U}?i-UhEGMhvR_StCm7 z5Q2QQzx;V5oPU%)UxNJEbx?egvM%+<_V7*&-c+jjd(HyEA@NqE=t0Vxg@RM(2hJGI zVPQGikuwS*ZvYYUJ+i;;g+4%$A_E`I|7i`Z+jk`T$I@@$VuVr;41-m30qREF+L`JM zWn8g$WhI#@!qxfm_8OrK5L1(Ix#e!FIm!NGK!(45zIyzyWf+(NZZP24IR*8dP;T-o zOdY54h&8+m4hfrG!0c{z>l+w21h(7d7nyGPf{_c%X*t7*%hB7k3 zTS0my<%bdyKiKET02)7g?p&SjhD;QJvP{MHAmCDEopik*dluB1_?(zy1FQB90jw)- zUL|pG-@X~}g|DN4%6VPgBPmTV{>8m4btp{m=VwzJ2-pGGCHSPzS_<58DoF@npllHl zBn3N2WhW#y1oO<(aL##@;~se52)=bdb_R*t(=;|`lSf(Gl4APotPz7!d5SlX8wNoB!lI=ophyyUC_+Rw|C)XC!qlncqYkV5igh#Mba z(Qve!Q=i%e76%{zFL+LeQ*$5KCyQXNv)Q%m&XyKlgpizhr9Fe3AmE5rN-!8lYayp2 z16yBz5JR8^LhZv(v)C!xIM9PAUej1|7l}~<^X~=&vRZ53K4jC#!eh}LjK`hbVPl%O`dk!x#24mJb#7FwmIupDF% z7QlM%j=wYjpUSwY@gT%_ zoOZoS0CF?NxN;e<-Om|dIXu3qVfdl_M0@@clXW!ZQhrV$W|-ZOu4%Sd5o97FQ1Lel z{XV@^DGja_n-8_S05vz_I4!yx4z$#o^qp93xUH8Us%ow4mHT`lCSMVa9>f@n0hL?Z zh-8Q}MxcZI0|q3e^xbBxubdy{CzK;uH_J6=DuAO*$}hBb-XsU3WPczAJn~&>`5eNi z0bg>gxarR0-u6m1fTiwxct6`TpMZ@K6YlFX0t3_uMMNIK&=Z(TuJ_KJeQ$7}`G=$= z4`6~>@SI6I@UKf{7MK04fDw_{}0 zi1oi8$y%cX#$gV2R@SpQ1&RIS01&0)cDTLJOcBGRt{*FYI9K<=g|&d`A%UsbCq~k! zU3J_z#y$Y;@{F?+&YtN6Qnkoa-T#_WqBb;2MrHSYu@n~ z=<6fZf{UNa^P&XZyV}~Zf6Yn-XOA|J~xApS^jCIE^iSv4TjnIW>Qf!4B2EWc-&&Q|2J%E67|M~MzJG0gG z;WV5{wt4;eAyU_<%9!7&?s2}!B0rYf+0*k70{T11POKnX495X|MjUWK7y>wX<@`w-Lkt@V4qAn{$%>NOLII>;#$11PAh17y=$;F zIu4s!RCb9s7dSvLXUSQhQBOU8+{Nzzw_DDo_zIi2lAQ*7c<985rNoDPuo2!N<`pSg zu2(2CM-n0Br$8;j5AUn1)rN(Z=zObcHBM^`H>VYsD@2fYDvV$G+vkbwx|BmlG|EwI zvBO=%OJj%Yw#Q%Q?7a1-;y)X%sI769u>CVbFh=oYQoy~c(3ldBY&qZW&&00$>+!T< z5$gf>;jsJc3zxHg8-6io`GNI!DeS^l-nx#C&KEws>)hqNMBFob&scPi&p@+KzOg`b zp+#N&aGB}4uj-(US)fp4$FDq~5!zpcgohUlZUd3qQvGU2Y{#3zzvl9AeE$6TBLYw1 zl%lYT zaTZpx0T~z%Qhg3#x}vI7z@2a2slCrg*~*frQ${7M>M3SGfta_y&W;U8I^-&aHR(RwDRR_d0Cwi=;z}G(nT61-bK*y{l z62%b#W)`{#@Ikq3sO1?zwcO2c%L9I0A$4IuuwHi#RN&2#AMt#my~X>bob~D_#;UQ9 z$z%Q1uMzwXmZyz>4vsD9v%CMTxezr)fnw9o50Xl&E$@Hj#97>+P&$&LlQ(^fZOMcyWtb^%JI{bf;Nm0ECECJZgkl zFdML(@TMeKa`&01Yz=h0`{dt$|Jbr+OTT`0GZ`1Exwd1Q8~AUtCl!Wk5B4JyqhD&8 zbM+j&0drKg?b>~??xc0Cd?SX`BCZ3?W z)f{)OFj?>K3YUkZ!vt1NU?RQ}`N@5A z6um3h)x}xrRjVaw3~@0Cc!DD{^BVK)Oqlj6%M>;_(LdU{&14)Tuyw!mi*rKoVwTG5Q_EeXr_Qyign~ye$q#5*Ba&mGu+&RSK0x$l&XOZLEIqVt8l$ z+Ktqr9EpwpIK7fS+3iOLZAp1zk<@N?LAiSlI0<%x|J45LVO&Od%S9Bi&H$=UAj%5r zA7#V!&UZMIW(gg?eqrJS!;}*b+9W;J=_r$T?WG`KPHXtQv4bH8e{pnm3L`rD# zHEJNL0vqIIpx-BenYW;>uYYXzFCP!h@4o<(^{VL;^J4;0nSyA;Ry1RO2)`l4fr0mwZ1!EGlZHtlATb9FaJ4#C9xvi z2B2wnJ46Juz)O_C3Ac*9$KJM=(G3u47eIL~bodYD+xyoO33)r0*A0m3okqTSv*)=YI+~KJLq%SG=-WZLVYngDE>w?qRW6I%&3H0+Rqwt_2 zQfZgGvq>59ReMCR05KQ3#SDtqct=C7L&b{kOB(6n^%<@I^& zsXyU`^Gt^W1p$ialvIC_v1hgZhNs)%D}TsBai>Z`Inmku?<{=ry8# z7OB#GVSTD3u_*96U0|zYA_Gi27CE6baz)6?m$DT2@2}j*&wIDvd3OKJ z?`<6$EMd{CNge+F1QcA?jvSmQT4H4Ms-}$lc6CF^v7PS3D?sihFixnN)b%iM+u~_!quo}8 zs3MbrdRNVZZCVqY$euV5JG)A}JTN38!UIe7s32RfNoUCO{7#R*u$A*o>nXh}zxb)FKtJKC&~ zPR4q0Kou4Yd2=rP2#nNVzMdo-u{G57Axu}C>o3I_>J_3y${S;kVcVL6q>)9iKBQ~K zEv?bD@E4=vo?L)6X++lot=&oE%VajBD&hX`A8C- zMjigM-r2H&5_?+P+M;*M!#s_C+bHEyRaG?zL+IyKA$4-bMGXxNiJ$4Sk|dgNW%hFP z3%G5WnaD#nwUfsSWXTIf8{P0ffd=$6a3<0KU@a%sP3oj(G;n8Rc5$OW;ff9JvYcB2 z%mnEhfuoo05mA^SV$|VsXCpIR z8sz|sx7zZP0_o4evFFlxe|UncDr4iedm!N>3N=YQO&of1pq7LOnF}&iaC^E@mO}>P z5fl`RG0@AG<&d!m zq03SGW4mcmM;s*fv#BQ_$QD&aj>J*I5k>>b5IZCNn1Psu^ilCZ1EsyH@sA&q1!{;6 z8Z##9%qZzI-%uiTZqSH=+Dpbu&C~@=ZFV6f@-7iW7SA2o6$uZ?;U5cSeR(zpTvkMR zG!bl8sSHFGJRl^T&z)!@UJfcUO2P+Yb)7-Nc(-aZI5aDPnT3(nqz8DKvxD3-Hp$@HC>U<&PLvh>@8CJ zKgRz#vhHZjaUZ27jmZO}X7U{`%OhzXKNC#17D*+ZR90R=97a#a(I*AvP;@+wM9Pv)!GP~rx)-D#G(_=TL+j6 zlhiuctVWBV5p{Kts?0N351qgGuJ22N^c=yl^A*w=st&b9Y=Co>8XR+WhNI<< z9A!2NeXyjLn4svt~r%$u@_4R$MsNg`|3zyv7+>nqEXE+TGOBXES*tG`drb}^(kXz+(`RWVA zdk@jL1U)9UViDPiuLi$(E0+2k0%HY4N+kAzD@WYng{wt(5pPBm9_*6@o34?FR-&hH zG|mn9?m6Nj;E;U`>zpO55sBF+vLo6NQ`+EfQRqSp`1^Z*wuzODc#>nJdKA;cOb*SR zxC*E#=?Oy~8zcu3*5j_QZ=5j5)acc5VyyAi`^C5L3DSzfu7NGc8P4|i-ndtKVkM2X zdJ+@2H|u1%xk!z*$cJl=hsxV;0mwKY)8(!ie0$RMD8_aO=h8axuT=a=C#$-3w0_>p z%t&B`3Y}mjs=QQ-r#=PJ6TI#H(HKxR%xA+x9S;|z{hMvo@x^|{f`S5+jeblTsi50P z7F=*0^4LmB%gOV?r6Hj@HG+mMltB_d;trb0%|PlPuS5nn`pHYpt>7o}`msh1Rby;A6Ps02Mz?AW9mS#T=38uhBxWr0V@n#J_5dgMn0mX5-G-KFBwb_TY_FgL(P-=GwA==n50_vWV>u@d%J^UHOl;7? zJuek5PAB)Ky^7zGHNuvDLORfRqr&t$P2{`Kk3!9BV_rD&$k~6~T)hnYLp&uJp#!o1 zqCXy8i;^JoI4UxIG!{qfW2^q#6p9c{>yc6 z@-9+)`Q!_4fGUL|-n52c3Dl$p-!4&gcU-sDq3?wjbrlXToc=vw6uPo$4SjB9s{$ju z?aZq+NYUQ^9vWo?=bZoYk7E6fC#57KfKCc~^G;#}(rq*cl0J)njdhqg-tx3>*9q@* z5JwLj;tY5_&y4`?B3o{BgZAqu&|hFUw?@MVtI}-dfsLW_*I;G@H?!jqxYxzZt!f7=Kx_k9mCL zueaCC)MmU(`|shU|NA(M8TtSI?A&fpN88Au$2gcECdhL%`RUX3pdWc(b72eu|2_Pe zgwqH#C4coGXv>BYve?B+sXT@LLnU|H{-CVkMVNd5na+r8rmt!5RE9mmF>65|2j%>} zvk{DjaE#B4@Be=#mdi>0Fo&IwkMCn~@y|O!-bh`6k&H)5j01cQRnA8aIS}0lXW+wI z8H)6w#y%Fx?M0dv6bgz<;YR~aGun@#(Ce9UQjVI6ig&LWP;%x#c+Vd}!TNKAX|K_n|GQHe6Y{@`gE15Tt5&CG0+#WAjn3qB{I5x#oQnS+IV^|G zX_nJzy=_Opc7FS}YOnSCf^AI3yz~u*e(=v>{b*MIi=*PXn!lB7kZ6>(Zdvo}$$1i^ zH=?yW+|%#%u=kx&chAI#nxJuYYIWo3)M&oIp=zl{kLFVuB1VgEnU$?x$#>wo%ERT8 z-~SOp^Z9=M5x+ND!lCysAhdoD<`Y?z99eq9egOunprb0WUK zcJOyyxQBGv|r9UaXU>u zsgu$?>MzapsdlQJz|d2LFQ|$rC&q3H12Ze#)Xp~|HejpBYCHLLBwya zzh;&%lM^oOO8e#2{$rf+6w{gwOkTYrec%gU&Du42`P*9<&(7p|9DYFi#Y*4cNWH3i zfr0we^Wk;+^6s7<+pARx-Ip(R^ zk}n6DBe2ah0g+}AG&!avJM~20*cnrIk9mHUGv@ztXXRGr2j!#w;GEgtoI|JRMQ zX02*Ta$Q`<_Sg1T-<+N^d81!{(PnG+Q-dT8rv2B?MioQc|Gai|U6u)L0jOVlG)7;& zKaLly3UQrUy~Xs_?5j#XF>hJM=P`|U#%pc4rp-O$J~srbW^g!76x9XHRZ$6Y;c+b7 z!);)&a*j-<)8mBMYZr&OynVRriN2tZTSJJs%gFhRgnZu3+wX}U$=wnzdupCs)`$EA zS%3Z=M@(g91Wl4P%`VRPWAP3S8MnVTom*<$(ivSNC3xD+zV7{=u~d7xdqvN;D2I-x zBo}$kSKf2E&wEk_a;~ARlXJ+^G>WM0ob<_=lAc8$_MN(OEXw?oe}7d#pQ?l45|CEJ zv=`$-ZoSKyFT$9+JDOZfv&}-6z;(>i%u4&k+4(5nnDu<7PakA_y7mCm@}H2R{URg7 zSE4neMlDx6d`gs=9`cwllY;4EJUeY{)JKw}}iUG1BhZ#_)gHz?7`e3eCX zVLfPjYt_pYQ*#h^g)xL}inYHV@LuK-&tQBUBj!%u`@7Mde_GC>O`l>4eCl8=dk?dYhg@xZDQOt<-qUndS^VYF7PgsZVL&b@75A#ojfIKD}N(ujAhjQ zsW>@r+I|~pVh-s%R**V#@{L{pp+D2wsEW_kModblm_oM`PvezL`&UeU!)YHw6>j$0 zs<5Ma=9Fpqbcm)gSrtOhv$ghDFuz654zFruo>fb_jgmPZJt6Wq{{Cmb8I1clnb583 z?(<9!bs{qE0!g@{|F>?WX}d@NlI4%L2i@}cBb9q{M^ipEZCp&Qvu5p<2gY?HEr}D& z6B7gG>#7^yC%L;>NJ;WbzG?np%rZ3#*8*wN%#zc($WN#5M#1YZA7ag$vaLJ;*0^N% z=(brulS{O+@%aLB{YUdmM?1m>znYyA9N{F-M14swU<^v>@$N4IX%lUFjV<2w96u8o zpP)z^(Rbm!<#`XzyfQY4j+`7fC5D5st=U#m4#{McNR7VUb8Yf{Coj4|-k=(r`l9mm zvn+u6jkE-KnCw3|uZgJXq8sFS?w%=b&I zC#4ehk47$#;@SDK%k_C#GAsM2jk!h_^UfKxplKOt8KuYFOGSc;GI?~w8cvRMaq2l3 z54>>*XWANr7PQCEKM~;>x#Cx!eIB!CG`ffO#7{#`G+WouhDm+;^dN?zQ&McbXu_nx zhv^R2qTKIw6R~l2yjrp+wt1g?vuJX@UWL>3p6f45mh|sOW%$DT-cP=pF1(K}{&!CO zt=7fz#o1X=g~^3Tei2^DPRTin!epQ{N}x1LW(BC8mn|(xcS=%wuKVp0hh6=EpjY77 z*w?f0Akdb7!iBWkzU5Y(w}Q&LS*{E; z0S?sua0O6j(O^5~PgJrmR6bM9EJf%`G^WD$*>*D~E82 zeT{c?4Z*;Gl;l}gSBD3(r{d>2V#~8|45rw_{op8HAqbl`_+n{-!%2S}+mh4KaND>i zPu3C4NCMh8G=fFw35vyLuo}WKS+1bB@T33wa)L~?>$C{E)!*MAZrcpJ%rdRPckIJG zYLG$>rTL3yr}HssuUFTJ1<^K20cMSe+ab^_8!P}uu^#P_ny|3@buY-SzS2XylVdKA zjrM9RCc*P$5%2D)_C)Z($su^~R$MPPfT4u6g$ zNA2fsa$EiA@u{_{-fjgvh&TLN@?jeSkvT#dd)5urnAAJ7bKHGyu}4VMO){usd2 z7KdF*9LP?ksW|F(dXxrllf@mqId+2&;WL;Ipvx){H1vbI&9s2hT><>s83F|CP9$gD z1nwH1Vt8!R%3IyQ5hXTRfJ^8~)-VD%k}!M+i^Enwm?c8RIiiE{C%bVR3wvHlO#a*j zW6Gib;67)~!I@tkGb!DQzbPCX%L$$ur7<-d1gPK!&`Ykkt=fTWzfcYAwq(T>RYEtwo;^F2IkSfi)JEXeNiTXlF?}7%vMV1ww1E6pM;5 z1NsLbu>wRDQsK$BG41KOoCP+5cK_BT|a&}2LYJm!gcXh z<~h4Yu6q3+V+B6}6-;OnAo>K1+}HKdWIrc-y}_lJ$VQ>0YnPYhuzZScVPRp09?^-|FGo$9 z2$q?^FqQ=+qKk*3ALjFR+|j3OUswL>bIc1@TFK;EcEMlR4vfbYg)I-l0s%s)>$Y|r zunx`l70{DwPiziUE;{y1Q60GO(EQvI6t?BXR+6_PAS-!$)9?vyz)9E$rn1$7>`A`z z?5O%bXVsf;Rc1DONwd?Xk8OQ$v|DSUPs^of^u5&R{^j$pD>cQ&#%A()tKS{W-yUDH z?E9rX53Z=F;JCiw$`0>aGvk>~(*Evd28>jXg&T7+ow@P5@rraD|sY9n1fldF@S zPKFX59W8)II@y$FKWA;0s3!{4zXC!1vxqb4!JI+3N8zO}I2EZWfTvp^M-kCtaSz!W) zJXWvDUTq=UAQ0R6*%&Q>T$)uf(j23J!Q%@|>nl_9DL|m2Kj*sL*o=!GnPLj<1v9lD zJ%dcxyEGGvw!y*(YjCxz;Jm3SkP|*Obss<8sccv6;^99hbAjl+;U{-Xu2#)=H>SuL ziA_G%tL^X(wi^-j7?6~Fk`{m{U)VhYTEkHZEl4(@V*2FEy+=t0wjwP60`f1E+ggVw z;erb{B-%K(`xVg~HR=_eh|=HQhE0A%f)|)XV(9Nx0!V$R9V*|Yh=B3Q)f`4T*c1QZ z71c_zGTC5(1un3b_ZQ{ASBa~HKi?tRQl zRC`()do!Rx+mzLy-UqeA2_IeVVMq1h9iX!?J({UdZkHILsVx zjuQzoLU9_GW}=gWdj`;lE~AIw&P#{Jgut!cw0ypDQQAOC*MZZgPaF0SdI<;_CJh4Y z>NCEj-G|#xIU=)9>Eb@a9z0u#*Qvj&%MMfgOZv~!9u@y;SL4}L%TTsuS<%MhzV};3 zRlBqjFX;yNj2Ho2<#|$mZ*1!jaCNIsYgj59_CzHA$|Y5h!UDn9`$~XEpPI00F=5F} zu8y?SJg2|BdI_=y2J*pRKBjAT%6oWnUN&`~KR@6|j{BQ9Jg?zioZg!@-1>r;+13Gn zf~+OXfcRGMlCP3|J{AbyZ5M}N)Qp5Pv|xhv=u}N%0K}G1P^GT72CiO~>}b?kDGMTy z$HZvSgj+{kbwsNGfrP7@XRd&XY;$mgzo~B9^2{6*hxL-y1w!Q+Hzj-jeN&Iq)LplU zvoWMTi_58$6V34@UtgC<8B|-0pmFYQAovr#>K@+ z7Ug|MEBe0AuL*n!BspF{Cxz-!Yb^^f5r?H9xVdzJ^zKrmiKjCEz~?P^*&3^V%DZh{ zzsXj?r4;Wu>5Q9G(vyZG-co#xQM<>b8RnJa_Ek3y{oh6T-u{ z6EsUgdsJT3;C8Z}FaOkJ@*R6Up=OQ{>QcjyG)p=(SA?zPnVE3w2`uO}w#Fa;L7WrA zkrSLyH};a{@LJIV!wr;1VF}Xov-=6}*d~I=yHU@7o1o>0uhL|J(wHBc%j*H<`_bN> zZzmbv4Ez6b*wS$W#Yu25St01NU#{hZukJ*T6n}f{^ZK4x5!+VJD?zryK0n%9N4geL zid*fPD3qwC9vsFC1&L6cUJfPiTNgH#IOEGsoQdlnK`{XqfKlMExj>`8`gv0(>R%4M5m@|3+{T_};m>F?BbWD3x<_}>~21r&-9UgvnxS9Rd#bQ4mIiz(t&06e? znao0U^oIK<O zGz%aR%zylQGm8Mx6X5hcIkPSJ;z>wfnRi>G(NJpYnQP1r4jcjfBd~(q$tN}~%-L&L zu=&B!S(iKoQOEv|LLe;(Bch>xyrZ7r218TRl(uAoY0jY+V0o&YnC`BL@vhKRuuHUG z(Sk+Va}sY`RWZCEX;$pnxHA7Gc3)=Us^hjmiRysIYyN(b$il-hqp<1Ou=rd-L-~4y zQCMIH__Q=!9SLOHnFn3-F^=vhO}2NQi)PTxxlE z=(!8qp1&V% zf;F-JB$&m$d-u8&#TZgX0Sy%IwjhnRIN#c_*szV&A z+N8GW6FbG5*&Rk+Li(65$OZ*^Wf2;FE!=TUV`>&ff5jn^N&w%GEodnBbn3E>j*ieG z9uZS2FdLBo;NA*5yiW!pCscg2wU#n13xE?J)e`W94Nc26fH@7e4(S_zt&@EaJ0sXy zKLgmyr4Nqw@vh#ve7-rNq6@+kz(m_{cfNl32+n%f`1T$4@gvf@CYaga@`E zP->(-+NUtGZ(Mc2$cxYbx<_GS^bvjSjvgX}Rho17>CHM4*(jKNH1lIpZa?PE*i{^b z=4f|q#=*EeFXl*fv|>BUw~=V4VdxOzw*0P(P)ZvE;kcKg_#)Drng*tn!Uas{5e`&G z7ra21W)$SL3GQLvsp)SciOnb5EYb>O>M@CWgXaP0Z4LZ0Tai&ME7al7AL6~?*0ZLk zXOJf5 ze#IDB{^TpUb+N6MqP~UM2e&4h=W|^h&rKd%{RRO<1!fzfyFf0==y|_bd>g-hbe+JZBZhgRH2GXe^oj9QNY(-dr z)kP9LvS9+=Xc;Uo(Jj*;fIO3&u^u?#$0ekIF;^4Q9($2C{34?VJS)jQecNLJ0RbOt zYXb)J(O^ixkLpxjQcl$ju{v>pIs0i$mO9y@aL>l>QK|7pDZ+UU&9?<>hq%EbGh_*H`pC9 zS{8)rlknY34KY7@_YqM0m~RgZ`k@`($3}}tKE|Oy6vQ>QA|xmLFTR`i8hmWz6iQIo zxB=VoFKL0CWfoFhCB-A`$m&9$%QXmq zRvofxZM-XLQ-50cfCvH#Z`qL^sAGYkmlkD`950Ej?MwmNS6eY}7LkExck7Z`7dai< zTsU=($AY89U7Hqy=9UT&_D0EQc=BlYb*ctQ9LtmulJHp#rtfP|Z8DmvgdU=I%aiUv>`wzz83TZEPcf|ZfvRYK84(wi#~6I*N;rkiRxH=Q{- zNu=;v7L+0fs__^$2oU6Z+IU-<2Vv9^XFo#^#`=Tk_xmRs%*LC{2%YM%T|Ws3;Qy4{ zH(waeb{x${6}xi<&4gkC61uaF$DR!_*~D3`x&O*=9l{5fc|D1i3AdKi!%f%oM5cqhiHVsd$wjq4JHCcr zo%M>zl2P-J_pz0ilME=4MW5se!kIx>y1pmJ<`GGRlI$>a?I))Ke=wHN{&dq~@DpeF z&4Yd}4l|+bP!bP$$D9Z{hWvGL6>@$$qt zA5YSlSb%keWuM=Kaz^Wjco83}9g^q+P%}ke_qv$Ke{((3A6b(POe%=LQ@yps{>T1B zDTGPSPq<#lMA)IUy8O_M@b6^ykyepG-D)tJ_V9xbhnNNv?~Yxb@$UM9M#3>GKK>pn zU~oj>t;tp<)`3$N^#IP`2V7e6agvaR#V0gdQV9V?*0yOPGw{1pD3IM(lekdczV+m5 z*u5nc8UqzNo*_!U6W3}{l+BGW!95*%pAhZ{;c*2bV?+vJ5JDOH%~p{VJ;WyG`z4b2 z;}AAJ(~dS?{K)o^!XP@ZN1j;i43s7E8>=Q0<*MGxJ=|n5Q=2NVWT6 zh|Qk{rI-XeJ?KS|nB^37s+j!Js0(egao&GXG95piTCa3$cLdz)6 z6aSuyH#k1gyzHf{22JrpEHl5HW2S{A(~oEu*AE z>MNOauNnQ=_Sz+7v3i_JL@{Xt8#)g_vFrlVz>AkKX8b5$3PnWAMCjt*)6)F(Z*eMZ z@A)s=hJIkKiwy4$=Io?39f-5GB;TwWnf&T-bsAugHZ_cAd=j<|jssT(MV&c&$9Pxf zX`)m79ZJHqLjcB`7~Uze7|&JKzy#4>*L-P%RV=Gu`ErRxWJ)Sn)-l$eucSJ?y6gnS zzsiR3HH!9arb*Lcb|=Q^Q=N;m;#=Q)g_knjj2KoE5G})o*DWxCD44C<8ikmr6@a| zUzr-S_6f$Q!nO~atf%Ziq&PX`^lI8Kw|D<;xH3v>Qz-GUrOBcNoB^g zG^hCFPHB#ZielagjLY6o_Ox4&I6U)V2pE|rffOyF>6PU3af^@*qqN7LcdgfLC zHNs53V<^s5`qM4n)S?Z<6BEonXX+u+=~G|)=xJ8`?Z};wFAe7H=0zV=u~%f5n%Q)0 z%;fIqn3HVTpQaGS6y7oP5a<0{>Yt-+VfS-sDu_D#FD51hsnnlh{*LLXwoA2LUE|$( zZnNvNUsqGT^1eSl(R_7so~8^(?gl(mG`( zZ70rTKHP*?*6gYq8=s{ii1!;!e-ov1ZPxHRc8sc9U&ap9DK?8~=mD`>wIvQ)mm~m`(W9W zncYCo^{##V@=D6SG#``_YxuX`#K72uaSh5Nd)k_X=-1q?fBBYT)3`vKQw@G7{iRQb zRYcnfog7aQSR)#)DEGn$o`N>>Sk;Z1wfuxn)UTv~rmC z!LHA=`8uHxDKZi*!h2a-XJm0tQ}BYR=k1{DTA5FKPYyi2-eaWMt@V(}Q7ENv)D?Z_ z`dQN_T0@4qo335pthA=VpQ+E{6v{9g`2hmXMaf;cqmJuhw9uIf?_|0gYZndVusCVtMQ{I+Si;zAESr7+wjQ49C%B)Xq3$Ym1TRLNg_X+x|#3_nEjQ-j+k0FV+aY-jYA+wp_uq^LGM*V| zb^F=e^bJ!^V|p*m|B^nCqG_9uB#!xAa_g}d7^d`>(+38Af76o`mpA0TZzQHYGkt-! zgz1f&#bPS{WR`u#{BxaG22AF!dyLCcDEFjkpJP>s6Fp&l;_S?erpyArohI-~pN@4| zSsNA0rv-EUZczFvUOr6s8(lEDPtM7Um&z}3x_RJZ`jN@IIvt@M$ve5)-r?!&lsokY zMVNX10c#kYXnr4vI}Dy$#- zC2Buy{vVb!=7ROhPxI2R?3mhdP6iAoqU`?Ig*pZn;1I=+X&RG}PAB(X(Py}NhQz&R z8lT-=AIC8Z1>LEecU$cD61?`Yo7J_dedj0=xy+l6J`X1pRHMY})*MR;<6>UDlZ?nx zA+Dx$gFLevnf{3;r|GkEmd*N-yopn6YG)MFT{g&ykyZB5MNT&pe>?Xk%`pNhRmvKg zG4|)k=%}wpn`zS=62ji+PLT_sNH7H?Q+MTf%94KNV=!7$Tqq(sss=z!2-ipM@fia)zh=M?Bbb{S1j zWS#bTt)w(FeUb5?@DjEU#9VWzQm&5^+FUO+BEPFy@5I~dGbW1i zh@N8z2`NA3X{9HSQxe%aUAa$Et&FeuQcc5S{V(e$zb{P>zD_9E_c*SLnh)n^n!Td0 z8r!4X*FM%Y`DQ#;73O( z{>)pwlzvAnQccO?s9ww_Eh3{nvXcS*w$PW7vDU&c57P|gQQ8_gJI9@@dif^>N{U5p z=Hy@*N=o^&2qmFp_7{aZtGFqbT9A$fXVbp@OzX4zd}fU}8MCXzah0C(q4+cJANu(d zwwGLYhMSFcxqPcpR_5ek5(gLcP z8q8I>P7&S7Y?!CiPupjaSPg%g0V*Nbb*R8it<3V$+7%44ZDM4>E)#>bsY4+rVRQ(b=LqT`w$V zvSxHQVZ}3+q^rAsJl`$~5uWsACxy^?)044>!q8CDtS4hloqZgtENgc$&$1xhX#A5C z1v7YH|Hc`UvRTF0Pn$MsKkR%Iw36cKIuCsY8Lt!Kv`L0hX|o*IbZpV|o6-eT)_I>4 zigYupE&4n?TzYMr$;^wI%NGSqd8_(#Qs$P{1FEl*HmXROr2NaQF&|912@bMwUy>s7 zdisl|w#+AbYIQ|lD>uboVusCmX0e!@2BFwI&CPpY+f9Kl9R-&#t~zvPx&s@)4O zS)<(j(r!&Xnqg3B$T*ctKerIQ!QrVSeJ|Y`!Q{F_MXDlH_TZ<8z-Tyc) zSc?&m$hqf1tmAmmO>R4B|2IF12b0k3RkYiAzo8`e_EytwbXmFfy;byhokn@e zEBn)Qb&qt}UC?3WK zDX+|ED*^3Qu+C|&N=n;Ub2X1gc;rGO4PdS5FMT@OYJ-dho0HbSbCaY7_Ox2XHebdE zDAGNXcdVZ4?EF$|!m@UM8g0DP4@uL#5bZy=iP{AB3r)Pz)$1^tQqBd8y&*ajvfoI{ z;-UOIW1Y#%uenb5gxBWw@2@<$lAF`a_k*E^z)n|Hrt)LHbjsX(+mzvQ|A}Cq!IAG9 z%ic7-(w8!x+`g0&Mj*I>?_Nr~7B4q@z?)ZbeFvGvsaS}vULO55BRw*_x-GN(R3PWX z#Scjh+k2YY`)sFuc+a)CCDcb9jn#}~-zulV!7DoCJUG@A(4E7p>A{_Jkd?KYH*F;E zY3vQ=$mgVn)?dN88TLb9!VezW-E;BANThEBe+|5V#69_1hO1QpH(?Y&QZzyC}B4?fIPaD`%P1 z$z^v&1l4|cqc|dm7Ur3%rO(us5|-|=3%5n5E3nHRjPJUc{u8Cb#0hsYUd875QaoO2>CR+6-+e# zWRJ`kQ?5?ho9=+`M;OfJbc@*|6r|_&SQV_!A2xk9&BORXpJ%1pfnUpXZqwwO`pnu@ zbYaI8|1Yz+`wc%|Jn@_B+|#DEuMJ%y!wz>{G*ZxoNv1s>^~#TqO=?ld2A=lN^mIWm z!{A(2I5x{kC-@z?`kgoQ69H`z&8j_a-c}2(N7~bU9FleG{D1US4ZAL&PzvaCbo2ZQ zxXhEjI(N^zxYLaVm}wmX|$VZB6r&`DJH#4Md3v*<3}80aY<5WhY`((K6ljk76EO??a- zrV#1P(@=I6Zgz|NC5An9G99eFCEjpvBBpaucABGs(*5rGF1xi3gD>>BL@~g2HJTLs zxcw5NR+!x6#fv7s&z(SyHFvOWHC8^WBJ9_ zNOy`cawWaC2CSw5ir6h*-_sNBuN?WIcby{WZb)|id4qD>C+}|3Q|a2jJ`a^pQAkC9BTR{tYYE@!@Z88-Oaj!6Q z9I0*u%3OcsA?D?>Qe-A;I^5cxv%eeR$?vGPe~WkY%Umj`pXbWAJ2^deW!BN#Zrzg; z+gt};R5k(a5{AdX*CQM2Nrhv=vjr$qipO!Z+Xh_2MpAf}JPNAzHWJP&z;%QJxr{W5 zS&a`-%bfx_xe|=23!u8Dbx2{3v<(Y-M~-xP+Eviqj(&k8>Z~?`T&sl6MwWI%d0HO8 zbEkZrkPB?4)?Ft=2d&`}Z&HcRoRB_Hc9lz_|BjzXtOIVHlnL(Jb6Dr;pz9B`yq+g}yej3s( zrLN`<6Q%#8|Dyu7C#jN3s&jA5OiStk;#Fct>RBv;Lj$ zlbxfsJt=R>*1(oPw)N3T(o-PeSMJvO6QfrF)X7HuZBD`zT1~oh0Cz-fBLmQ{IjMtv zT%>k6s8ID4Lb*|HgmX%j1K=!MhXqt)0S6=t2u{S;MHAK_%O;ST%jdunCv9w~W!MQH znRKBe`v47tEJ>YXPwZ0U+t;vU+bl}@ zQ>fd3ZbGJl-0Fy~_OLfYAxYAjU>!=cCr@-$`hiAB>LG8_cq15ruB243TG)#SSArNU z>jMO71u0GqHsX>Pu4swMfD|gN)j@w zM0UVevU@-^ceigQ?Wo9iM~8aul}VCf(Lii^qKT$O`&E=v-cKmmM~vj}0%R{tN~Pl~ zd%Ld4laj}-TO$(IMj3ZGbQ+_xC&){z)-~pb2>+1qr@KDeV)c%1g;GYKY?N~L>l223 zn5cX(a%w(BnxLrV641ipoFHexupRnqk+xo<;KpwWcLee_+d6HemK3nov)2>k%mnOP z%U~=nTq8+1_1A+)H~Z$tw|2M^oE@;sXGX@mY_i20fLn~ThiE$q_m$lES!P%)UoEjy zOi6_9p^k*VaZI>Epcs$dLrG>_MJunytMwyw71pWXjS^B(zhMvogn}~j=5<%irM&F~ z|Cv&yr^U7SX19yH-C9@v(!fHrg&+zRO*Qm*10f08QI`#8UX+cbbP@7I}jkPKcC7m2D78PVrFTq8>s&GO9GvQXwrYp!}jGwO(oOBljj% zq@83^^v!1fghq?^BuWUc^zoc{Sm8JDHe_QYiWsFz-2EZ6qgwVn*( z94W+h6}0m0TwjT1vUXn=XmN}bV$=1Z0KmHbk1n`U$o?|<1x`JaCwZ{WW4adQw9DgU zLNm-0iJ|fTj22_((ne=+Z!;(9U7dx zLpg`~zmi*QIIS}B{96;%4RH9(NuD37hj)mGfHy?I#R^5&J?&9{{TCr;gkLQrwH%<= zUw5^)sNZ|E$#t-*JXN?qfXJY2N=&E%zMmXi;26M(-27DVa9LWV=Xrs~Ol`O))QKT= zFxq?2lTswAE3hmDcyF%CcsT+nCB2?}`i6k$Wak}BpW9#i7cLoc+-uVP?msU|G6luB zn)bQ9AXjt)ef zkg_J|(9H_+zYDjx6#=O>kg5Qr@rlQtriY@VKi{{B?Z$2AvDi=gr!6PT{ts8z9f(!m z{twz)r9>!7(jY>%N@-Z7$d;9CDTR#csgzKUQ8H5^h3q{l5fUoy%v)v|*?ax2>)baz z@9+HeKE1bd&i8w+@3pVbXG+taf>~NpzuZHclz?*(@ZQc^ZlGtq{^W_dqGROZ3ez@! zM#6gQGlZ=(+5%9&V<$VB7a!e@Pdq*klDk^CDmC1iEPf#9GsC)hcWdQ1WQ3G2PE+!(NSLb zD#u)Rg{O~L_RaptnlvabnNV)Z`}0lub1BDV)&+L;2aUs@-0)b#ykUXxKY~w<_ng?j z%kI>cnS`4x$4%Cq4!Un#RdVOdZ7<`4zA^tiu8lO;I1ynIk$vLaz3we51cU~-R|&4L zx%0SG@PloZ%IM5biJc$nb4SJPGbe*{!&F$#I+X_wN{w!ale_bV?7Ms)=X1v0DIva zOsnHm*zuoKH!H9zXu!!?MPZnH4DNXci(Rh~&5#~7m)VI!lrYW6yop6fQNmk7I5*ClKRNz-ZeN44hmj==Xoh8UM@=sCVzAtR%Pb`n1i=5 zmwl`-MW*N{u=s4c<^l>I@^M*tlUe-=ZbJ%{T`N0278?0TZ-8;aOZ711d)N`Ot@-I9 zUr$~;`R&WsjlC;=_qx#@L7c5(Mom$u)zV1hhi1dv2vfX|5HU6MO{Lr^$D5%EICy1e zT2*GYAs@-JUK0RG={TL{fI;7q?ZUAW>;}=@sT{L503SN`@8|& zafIvez!A1D(>Suy|8uq50R*5ykJvZ&@hRZ{b6pD)J)CtDaF9}Ms4}U;uQ+Fw;p4Rr z7KUDtEc1BcCYMU(qL$m4YVdF;zK|U(c`a#3ow3bSTnF}*h6^ylL^wCYjIyAmj1Bpx zi}HWXGc8C_3${Ny(*Lazh z-L?k@XP(6mf^q){s3S9X;>Ci>kO`)O66FM}Qwc?dgQiKFfP;nogE!%Ryk+p{Q*~!v z?g2;Y?6>lPlXugeF$8ot%75NA9r)4nalt^_#k)rt@~@A5W*}Asm9rE1Z^yG4R5>QI zzk7MS%gYOjc$8u^K7gXM+^3v<{i(v)-o&|22q|i{-Z>;Pfx~ zX-jNg$Z+N>&~)W@IZu?93j#dGE~fbMlybXc;}2yY@HPTSjoTOJnVH_%+@UM*g-6ug z>e-Jy6k#uRd+AI0EeZKFynZ+fH;9SGF%ojROF)E@fw6aGwoDAsr_=QrZuX=%6hq5% zY1X>GySO0Zf-Ivevpc|#*ZbWCN9BQ*(}Faqp54h$oEd_T~Z>4VYbKF%mPGw_k!5n(ysMA zn=Ii!@LKLkfOiBf2`kQgh3RwIz6lT^nV~g(NSz}rEX>sV%82Sk5nm|=ei&Y=H#gaXcWa23da+nAb z`!4;tV|=itBN~ugU|Ns8mb2Z-0kS$UBDjLQ+bOgCUk|67Tr~L|KYVGfw_5I_KL@4f za@p~@Rlj`svfYy60+YpeGVf-Dy5%!0E=V*fh5z72ND9Y>QE-kO&76_K0ZjH-v*%%L zIDX+C5+RfI)qfAU@?KORq!AR+csL9pB}eCky|i2I!Mao05Xe9p<=U6YJDZ5m@+81} z5>Fn656-KrzJ;h4nM+vl$LSAb6f))$#P>i#P*oE>rTnhdvQvGk6gQCPMS5WtZY^KU z_8UT?#=bEP(7&GboR=y8}&)UYWp>mbh9;!gGwaF&V{P9kEFvO8uK1|o z1D1TvBst>1)kG26?NqHyimphuzkpRg!BzJjGg^%ybZ*P6?fxSTlG=`VL=k^;$5_ zg)@vyy%~@xxRW>nh$7&0fg3L+7%XLt6URUwX5J(X=rWXwYRFdRfr#QfA`HQD)lR?* zANjtMv(8eKJ7qz7(0`BU{8zh}H?S*DsBZ!%S)aXeh8wNShDpq*)g}!>R)7-JG>p^A zW)|hc-JrRg$iwvDgyBr;<=BD^P0Hm4^d8gbRM))vTV9fmc|#W%iTr3h`Xi5gt{XQE z<8UG;K=1^F#m4ln5+4=NCAA4RuJ5#({ha~l$b(;1>W{C0*9J#$QikZ{M zc&JOfrI?EjTA5sAZq=Ea1A0qb`FsM7#78SjkH0x*as*%z8oi``hA;gzg5i)~*Arn;tG zh^7ZXyQPF3ZR)k*ydT1E0=qG|NG}g`Bl11&G>L`86hD%x-WbJEzQ{KsmYM-&8I;5i z-v%AqkrfM4Mf#*-+r2+_cTbhxe{UTUr@50LhPQzhYD5lg09eX@LxBUg$*pg(n`(&` zBHwfawM=yv0@opk9z0=L-gI3a2l(BA!xKmchHc6vfk*pQ_wHj11 z-$~ids)s@KL@=dmlCJ#t4lCeRifqT{Hh=VN0cyhTd}mw+qVkQJhv59Q9Y6)G%I-io z4fMw2s~v&b?s=uzim48t*)boerGz2RV2fJV#P@t>jQJ5?YQ!lP7zepsJFdE3Xp#o6 z13=TtyN9(v7|%Z3khe!)GJzqTXHFCCmJ=pL(GQN&a-<`KEVfgVG^QHky+$O#uTi-^# z#qjCe9&HyTW(Qx#7cr?Q&DP7xI?Ysla=!VFcBJJ*hVBaHUOorm=oQ$K@9$x-x1}7Q zmliiB0n^|Ch{0PRF=_fW39>KoMab`tjKh=H^s`vN!|b|pKb z3aru^0;Z7piWY&$24;7}jKxwXVv(~G&J3WMeFSo&7DSxD z__>m+FQ|9gRTjx<$9^fuvSH@c5(*4WN$g%n5zmJy$O8|{%SQoudvtdtFkBOjzXCjs zMFNF)Xdx^1{7&K>mKvu_cDwmRbuUIh%F!Wr>pcoA_$FOeO>Qp3yckWq0dcb z1OW1YHX!}#6|faK1AW?ds&exY3}p!xhNdxU+Xg2 zCeeOv2?y8h2^$Avb-649nHps{bJ#{R4 z?@XN;No&CrKcq*({Vs6Y<}+Zeq$n+SI2JSMJImihpic}4BU9@ZfGpuGVLll#PWK0WoUu6%?o2;q0;!)&#D%E>N>)8 zfP1D#QX^odUOC=dmj2no|4bZaJ^SSVj5NAGg&Yz5-kp)nt1vxnjc1+aRJjTVm;Qm4 z=xe0|E+?F=DNBFQUN--qU$i%ks-{0pbE_#;Lnzs zy)ZE^iV68a)b}V^v(k6^+&Nr9^e&n+?C~>rn=VVNX{|-RvdlYKIOTX593)-NI80aJ z_5D;1oBKD>IuQc2BVN1(IoeSz@1ml3xDBZvd#+91-(DI0Eq^27zVIZi|A|*;*GUWF z&j?C7dHMdlTb{i(&!Oh()!9)o0jnZsYJ&dM&-hrcTN-=WTfV?k-zHP1@Yn83MT#F$ z9E5v@I!XJ6e{XOoCp&4Kn6>L(nZAv)J7z{l)4ZJ}p=3v22wyn!#b>p4<|Y@Nd)j?B z-<^vRW2jsWZw6A7IcLW$Ru`;JRr0Y^0$9_nG0WyNagEa}j|Mv*^OaHiS8zlHadWAI8=>^T=HMo2c$ zcbqlHj-|gbZMdy}H|#GH{de+;ms(T&BP0E@#<$JRwd}f*ZxM5hwuj52Pchgg2VIP3 zkj!a(=)j2k0O6!`j@{YSP&*~iPl6rzS*r=3&sCPYca!a$?1{wfj2!0!2MZiY{89h6 zimn&tCcj-ihUhFOg$z!$V5_f`AjotoO{T*=jygp<=+rJ`%-7waL%-8<`SRuU@n;ajt?jwj55IEu=!x>NyXGrhxu)zO<@1H#J zh_k>-zTlvZ*4o867mNSIi?B22{G-s;{v52N>V(Y*!v+k|kb(W;3<3{^Vs&YP^~5HF%$r#JDnlKAM)3PFc&8pMjgqLYEEZN}pnm zUoTgs@o;C(FW^+yW8o-EQTXllSO~dH<`nH$o|G1~7YymX7Uardtua=q!8QTcj$Km0 z{hqt&x;X#;U8o2V%#Px5khU9Zn5UO={z`p1|G>^&7M4LzX1%g6K(~Y3@cd~SI^B?P zaibaW=Rh<4JVmG1@IEVsH4Q@LFh+rPRt(>>yC)4%+;!*D269R!Wyzaf_5bG(EZlD@ zeKOOj_Fj~>g8b!RTe?Aca87fvSXAhv`k>Zz&p|crp{d3vwpMfZ%3ol^*&RhP9jLEOZ`>ci;jQLyGIJ{x`WxvzEqSowEvrALdJl*w&EAraIv z;i!Luy;a9Cc?%b8+O^Cp|KQ)@6+U4a^v_FC;wqWr+CtaZ9y1Hd?UN2M7|gw$oOC4T zzx9|HoBQbD?nB3V#`d#$nO(RD2+ZK8Swr$E?T{LDdj)kYkR2AW=9o9*pInm#b_#dJTvBB zcK4O(^mE1B_4u-~-RnS6t}^FU$6&=y^Y(b19=OT#=4PE~z&^7i_?3nRXZSXll>)sBXtMhl_srI?l?)PeCJ__!cN3>eAQd%AVMlxSglBvqEuzg zIAr7Icdy_@kuLlp$2x1=4$$re6Wc}ldA${$Tj1%ZD`>cr`O6U7*m>ofS##et$yDo1 z1VupLI>@dGUHvW$_pb#26H=N%Z=Vs>7P{sh$_$AV7J6O*Wc;pp8hT86Hpe9Cd-o$L zu{{;AhZW@I_cB28^W(hIVcc=lN9}ds2>)L*2U_Q4YMJSyMFzr<%#Arh`?%bOUllSy zHbVZ2fr{o0rVw1bs>qz;&zW%J(YnXb6!&w^n=~|0+KGDE^abpS*WA$oKkRjWHpM5D zVa^<#_tJdo>bbzZOaVRy+nfgYr7|Lz27cXU=E~p0ciz%RF5IO-g=%jjf>p*o!y%fW zZw{lW__55yTFr^q`PSC?be(sGVrf)odgDeMdA^U*7PG;f?tp@CAZG^p#9-~bvogV# z781ES9UPH0bB@T{3)BDdra@wrb_V9Qdf^Kn&!X2=^YtUeCz^}W%DCz0=fU6eb0H%Z z{xxG>>9}g)ekl^PRq};bMr$m#&5|S1E#}_(fhuU~jTebON)xZpKzsk)I9MII7L=y& z_oklXrVCeH7UhJqZ$7Uf_SHm*<6pP>P7BjTfLBd@%g#rmpK*IP&>y@-T3J%>Hk-S% zcRJlncSdP~FGAUfDprejI|BwY7IV_l;uDFO*ZWRZh*`WWSNQLjU&HL{`ov!Hq#MhR z;vG|W8Ofg#iZ4uW5Vjhy=kE9a=No~R%A$!3LF6wPJ}HrraTe0+K|^Y2mN@8Nzu1Pb zHu=r;M>$^XpAgy|2|uIMTR};TJ0v9U zL-VS*s>-a}@lsuITi2~2-l+;R@G5^32Om~CX$!! zC$2gx&wbRRQCw}G`IbLW;33QZe-Hl<)AJ(pQ#Y1g-7#H#uMf7)}lb}t~8K^T;m@c%4(y0HB@xq)-SPHrFztL@blb9QW5Q0%X?W5hXhna5Iv*_EktXXAmZPJ## z>UvI{=ki%fPJh1Iw@4}S?I6C6$j-0=U5kPoL*MRYe6|KdKT?*j$hh#WSK;~}c3Hk2 zNBYfQnFjr@{Cs$2bsTO(as<4U^Q$7Jgo8q_i-%Hkfu4Yo_E+7pZ;lb^ZxCXZ?;c$* z6&zx1OHCZG@N|1?m5GH5@>+gY+_$dXvMQg66h_s3G(l69<0)DFZB<5+T%6UK4sr;Yijvz_Sr zfV)$Jkn#g(5w!$)@hNC-sz3Vt(PqX!!=z=VYpZixsy7Rsoe-AH*m{8WOF>RAhOJa} z;XQjR$+DT@oc`PJo^P~a*7V5l^8X$wU+}s0G?Cv*buH~B`3&+8e)UiJ`H9J>E%8XC zOwu=z1$4)@KRR-Z!m=RrYAc-u}T z+Df>&H+bX|bL;P=a@gqA?rn3V?I!p|EGA$j^#aMaxjC1ox$@oY#Y)fDtq+XU zKOVOj@v)fg_3h73{e7)9qo;Cu_F!XF)Ya|M7IZ0rZ+Segz&9wVAn<>To8i0lMDIvI z+hoB770K?E`m*hVVudFqB?n!V#q`Z&#c7)t&cDdydJs5g3_jX$$+YM}&}?uVVPU&^KI^CLYasZS{cA#>Eib%~{f+mG+P{IR#$yk8-*( zX7xG9Ox+Dd5Nw0`t4-Ig_Kfp#2pI9Y@;5BI;d5`Gv%6Bfe3Lgbs?CI{!a zUCh6>e^GFK@RM2eapl_R5B78Z_i{*z_Qm)W7dGFT^8!>a0o*1=ZF4GU8|MaHcF)A* z-Z$UoJ!HS%fqH#xe7w7Pj3eQ*6r{b1NjQ$lacfQeWza_N&(AV5IFWqMp zJ8OzE7W`Lm6wM%2wS0lQr0)FY_xgjZ(z6ltFX-N|Y@xgTEnC{Y8VoHuLW`IvVxtS@ zU8^l6(#JEu)M`4V+3i5nOkQVBVh+arDXss*osm2ohJW`zzj0U6KWTxi1hzEDRndf= z$YNPeu>V8<)XyobwwLU8?V|;MbKg;pb}*8L%#G%@Uv5*$<~q^E|J)kgM!I~4Gz|*7 z_F}O~S9rq-Hct4@ZV>*VXq-9MZVcP+v|@P3zJCXf4xIg7Qq zbxN%VpIrRcMWwK=87Ko!u47RVxTqfVW3Sru_Lr7f+Wr0HaVHmDb(#+#H}L&9=2p>T z`iOWtXD8o|PMm7&K7}6Gl^wL5XJ+2M>ff$65a_&{e_)HCS!Rvpi*gxfX?r7ZMh?@| z{jy_RER@65mhzpOb!h(rRW7#ws-m~r&nrDZeb?IlwM+*C$LrpJ|AZ#eeHq=@^Id(Y zbJY_vZ6R@7oHS_{bh;&!TgC`Et_xg$H&|8f#)k-t=l+o{_PT2HGZb#91^L zj^$22bFjX`@W{v8iA$q*CvFc6q;g3gXWDin@Ut;*an}{yjJ;#7ykWi48E->AOZS#5 zty){@sz7L%ZX)91Si<(=+-spuxx?imxqeXxN+7#iVs;aA@qT$=lnBODM>w6DJIAvzX%Zogi zd2s&l9!y$_uua4|Ux&5rValqTtU6;=w(w?GTpp52{*HWH2;4)=Ek!;)0D_-qAPbH@ z;l9VjZi7~q#;MSTx;s@nWu@@JC@%vwj=M_%AWjPw>%Nwos4qOLp;1(DZ=F%TJ43&J z{PpdjZZqRO%ciSq)E}m06zA4-Q@)3;%!{(Ng6i_V^Y8y*Jz#4P4APDat?P#_EP>lT z^nAJMu*GWrM9Y6DPv@-1`h$3uRxvdBp;qAA+V*j;d;N=VzsbotY_I^*3@a8Gs{B5D zhb@TEQCHu99bH2`bz*p=pow%?zpbqe=cLMVp{a6{=SBf%UAqv&fmj=GAC@u`)`v~YLpiYj2>JZV7P$p2 zo9116k5$O{*ybzWPuYDxrSK6uP@r+uNYA1hdMk!Ht4L0(1JI$^6(4o_)mW+i%vvNQ zKn!(crbUJ#eVb0l{VN#Z|4xSiCd7g#1qnyvenFFwUKbwsEfL&-x;)vL)e8*pjS05Nqu9i*B=m;n_HU!Xha_Ru4LOH}5 zE~^DYH%siKF}#Jl!*TXeE`Hw{B_d7aDaL!djnKDFG`X%pB(7@_0g& zZ8pp_Tsm#7dm!C;^p73RqvFIe_8VXmpt5+IU&L)UcHd*$$YCHHK|~7RYtZA>48v&W zS8&N>&p3XUj{B2gH9ndL!_0Qrx%U|Q@Xx_a-M%n%ASxKzDt1{5mm~!fIxXuhX|J_K zV1VMR*bd;7ZQb-OyO#ysuLxW}{EoWk!&~N4Tu-1=@Gv>Ix?3}G8xT*-?DCeK8H;}N zX1D2hU91~)a6#)J67U-Rsn0-aJ^Aub>9nWU>d&nigV85kMAVZu+==8}ESkzh+^edE z_yyqtleSpwLd^&?9Q_r1?#d=H-#h1j?A6UI0LCdpxNAR>fkB7=IvBp%qaNtE&#WRG zJCizZeO?*GxTAK^3}rMteaNostZB{Cc!w4AB(kbu$)&MwM~PTF5ZT{r2tsX2dsNugzWCd(cD^u?p$tcwkEy z7mG@O3H6&2Mn!1K>K-ccu0sMhXq1t?w_0Xw3pNM-fGPI-y6UgT0NRHY?+X)@JCtR{ zTRoPnyMdv~vTb#Qt;BO?x}%qz+b*LVsz&^H%TE{MhsDMb7s^9PkpnffjtcWsVAf-P zn6Qw1*~qU49dgww3-H}OE$$VXI_xMkc{F`zKKwUaayvdQ9y#VylPMn}Y*}&GF zN)T+r$7j}(e9h3SNY0tVAy}VBj1C$sDIrhiJX06q)K3!yd8%CdOsK{Jf zdD$ju_uZxW7hOp4TbjRJc?>W%!1#XLi#zknpthfAisqZgAvLQbXU<~jE$*Ufr=S-d zeh61`t|I4-KG08SD&0?W)7{l)V69o&YQ)}KoOZoQ`=wl$x%DR-N6`M4Ihmm3QgNEL zu!pzW*@~@nk9?h1DOM-j*AQ_c=!t?kA|GVQ3l7+oSej1_e=9WpfEv(d8)H9bw8&pE zKdLN>)wnnZm{YN6|Hl3@z;#L8K@i}EkO`|x4?q1({*@Xb6*z7G`pR0m#8w;{mr57E zJ7x1C7_f=tmg45(YpX63diF>=iu>`>{1or^b1tE#@M5tYYwz)$lsC2y=?k*QvA(8amn{PflP-|h^TUQ7fRzV#6O!4;v}nHdY*U#rc3(2F|-c9q6F&UnVl z!ft*#NLPFO_seS+#-sY1UY~5v-8j2JR^rOB?kxMX>*z&l7ti=!$Cr}JQV%R$(B!wY z1pf>EyRs&xbLBX!&8XqZc(vsDdZ;E>hVV{<)bKe<_?hcTcv*9#4czs7eQ9K6) zvd^|DpRaV(Mh)+==iwv$Snv&|ueY$x&p4{5#(pssdgRh;uN@HA$Vv?xIXX3#yw#Bk zJwt433Ep00eMVMi?4p%{G0CG`-@tuim3F%PfJ0K$TcR^sJ#G!$eaq?r>W;me+Qc{4 z&r6Qq)5OI0`yIHhnb_$#Hy^Bw6w-VMlW$wN-!D-gFon5IJ2)0aXvu&&NCl}vK#4rp z$CgE)M-xEz5E)~4pL-krgVb{z!3_Dcs)3)k6Wu$|1%WGBk=K`+Ym_L*&~!#(-C)3* zy`P|ONVRA|(<(!p0)vqRc`K_Pbqjxg|NhR`@ke_bbL<;u{WbLNty4a*6*f(4_M`@P z<&?n5D?UNMosEn{$V>vO{E|V6!@%-+h-_Kj9?!bm*0*5;t}}I`&<5uWxYyc0D4aatm6^eMW_? zI?Lffau&zs&nw^GyO0H(e!aJby1UOMSikO4)1PtX8>9OC*s)jIH1F5xz|RWzXs<=o zU6!MACS0q!bF*95x1=}O5WLdUBVad`CZJJ!BlGN%M$r|&y@491!^Ohfy!nCf7Z30) zD7`_&#+`XjzxM6BLe&PHqI|7n{pMy+A}{^sC~Tc&{{gnb)AlTQsP> zPW3~6e}KMr^}k@6!Fln*7R3%HT!z-kh-pA}y>EOzwBCNX%>7xXKhrn6=_$p_Qgxk{ zuG4RG3`aRK*S9wAyo&*>0b@Q#K1}>Zq^62;i?03!p40*8?zL|m#alyf?6aCan}*>% zd2Deu<2lH1h7FM76#SZS?wlEI5Br*CCsj=z!xw<-c14c;k*V3JRo(-MQ(QN(_AB?y ze`6N0%m!!^mEv4rAoz~{s zd>bO%ioZbfy+U`LBxi2lpk0k$#y*?kr`bJ04t@IwVj(Y4&+z%F$m^N%l`x>(MG;uE zlFe^0H*cyL-&a%{0C?$# z8Sla;`;0Ed;d8?uF5CEMPp&*SbI7g|LnEckEt7c(#`Iz`XeC2!*U+4ui-&rcS9?ox zx6fFeoigd~JO^U>f^ESywO5Muqs`RB%&W0W^T7#tLf9_u1Ki)C+T?R&)ybbC^ps) zj_h8TNKdRe^YhL(x4gdF0ziPplWGx$DFNVz>awsn2QAL*Eug%LGmhd~E{)D^&b@j$ zR&j%IZ>OK{Tl$#`D5YeSiMP7(_*Y_X^DRCM8G|!K4f5TCM|1#J<#Ujj0C(yt76tiW zFdmvcSHV3N%b=<5J(A+j)H3TFtxe-!AH!f_HV2NDtA5 zId@+RY3Gs87l9$!(KIPfEO#L!mI!LEfgqQ-6w7#;(w^*M0 zkp~X%gRhp@Xb&`aNR=GRm~WFiZmKN82=Drk>-plI4R?pBJ54|9bH?w{;^>Xl+4x(L zS18cqGVi)qmw8R|M(xy{t6$I(exS$#PPX>fwW&^Adxj=XX{XlY z4p0k})>2H4;Hzq#TT)s!3v$vB=9!{5?+c*MhZb&b*M6!2ZA zXY*u@udMyMldq1O2J(`civBs zIwn7(Y^@B5Gv$rKv2g3V&>Zk(7=n}H6lk_L$)SStotCM-aRE9BNsaN!QOY4~Ik_OZ z!61T=aoNV?KKm?DDl2W%>v?QownsagE6a-iK>_pIz|iCnr{Ke>6u0Nx+bvzwz;jpG zS_|I6qhZ%82#)bWp!G?n zW%uRR?O=BSy0dcgygL9fQuk{ZGJ0*~o#aG^Ozkxu?Vn3I@!jke$|@@nrRAJ%gZBK= z19O|FG&MIdC!Dpt3MxmlM+AuLjzykkW`0y`ELs;2`T*&l+jTmCW0Wn2Rw43x!@KHu zmq%gxqr4T6hEJ7$?H*_5wW3k6*cv)hc#W!F|wDNL}Y{fxbI=LF`l{dO?!mz#jbkHWukE&AXn8eaU~Je>IPa;kfCXn0Wbz?>%Lw-pa*=l+DcTb&tv^9LAnsYw%Etn z;7mfJbFWBdD$dJf3&8EWt?Qk1;cAEA>r- zy)lHm8|El^^Ja0b8@L^9MsilpN+H|ZelyiC!!W#K|44au`f!-G@Gc1za2n#6k@LC*i^60fk4HVGv&ybhcgLZ zB)Z;=4Lr`<46*iw@72|XIJbcAFfu^8l?T8F!#TS>F*d*?s1%p7?Hooas>jAHx20Y2 z$CzAAIqWHT$7C0lJPfI53eEs&EZ7+y2t$LWu;NMmw^4`K+T1`!-sh}5{7&0dWW}uYxQm9Kqsf`GXWMir0N~UD z`(ZI1x^i>|2t(5}w_souuDbbiy%4}LV&D$fk%t~rE{#%wZ5Jq{@!St$(Fzz59_82D zg_#q^Uo_nDbzz@0XPvP+@aifgm+fHQG%fliOs~KRW#&1WY-R(uaX(aYfhQxj)PeCo z;h(BjNl9WCLsZCqh}BSzw_p+hVRB&D|FOrILX#Nx)8Lu9b7NxQA!C{r6K-&L?4@6w z;m7PSZ`2egB+JBm(K(dsdNqH-KiyJXFK~vIxIPMr>rEgwQ-GJ{4dlshD~t2AYcGL? zDagOUgzWSWApe&d9e_NUFq+skYISWEj6s1c_-turZut5=k$dWd<~QZzLle_9O*lC; z<&J517+2h(2S6laNKOsqggVQwHXrhP1HRqZ#n0ai85kc(^=%!Yy3KB&*nLwHtD-(X zKPL9*SOE}oYVFr0x4vSa=9qOCDifo**cVbTNh^pba*k+y0C-SmK}R9$H4;~Q0^H9Y z#8dkLLv&pqam2AkwY_3@0wqlE?B3s`;!aaY2YK#`59uKW!`M^;n?_?u9eP(ipK0;_Nsfr1bM4F|3( zv#$0Y033m4Kq~NH*`>ZdiyYaIczfS?<9$Zfc+*z zC$#hge;sM2gJCqbzfHhR9EHyCF^19=FO3fwrEZsK6J)qHucGre+^@+fgHHuRo?xzo z8PZpt*tQnxAKc)AL8x+Bf&nVO`gQ=1R)DnTU6go% zOKo_AWCfPuZmQ{^Wt!uG+O*X>Xb;V^h!&s?TV~#VK zo<{Ce$ThrqqJkeJ{KbJM87BPmg)|WI-qhWt1j#`ZS0q^-p^jd__lN!T_F!{*wzf4+ynh>KQpZf07v!lS>X zs0jQlo{*8BC-HWv`bSo+a~GS(JobB-xcfr^CZFct9B0v+5r+>LUJJm1-H6BnI3BE| zOnCorU_Ah;4oZz1f!NstQH(01RKmt4D0!S}FBR_r)Kaop`9^qBxZn2oOPVA?E1a8GO0G}bp8WAndBQY`Y&4>JzOz(hH`FK4%62USR z!em?wfhf8kF*~8SqLbV~<~DwpzzO;5-Yst%{Lv2eN3#8Zj5}CCX+MBW1&-2=^?g{~ zB9=FX3={ z%fD$!uU#jNHxkMgfXGR@{uOZISTBTJQOA-aR-=5R299C8lz?bz8z!t+X&>uDuOq-c zwLp5w8yU?Uf!+0a`E=vLob7c_aigk7Y7AIO^4=wz|k{_{Rk zKMZ~rZpoXS%rgSc^N)^+@Hk@qkt3-geIC(q*osG9TD)P9)+|lza(?-hloB)>!q><8 z(t$I%1x8vu0ntv(I`j9-0}yy{2P#?%ugGru-gM{N4UKp`4v4Pxr|R;iwb2VX>cz%_ zl+-}X`}Tfw+S`N}(s}8_ zB;fePJ+Z6ZTpN0dOrSF?CDt)B0}=IM%x56D#z*8qN5o3Rx^aMi;N3we6gVur-SH)a z9T<;wq2?n6(dI@lW}a}icbl7=-yiowMbT+8WUReSGr+@G)8WxC^LeWXTK8RJ|2az91D7bXn^N70DpVR9ifbgB7V7VfG3&JuHAQZpz0T?ZhxZ2xD zmSRbGPyju#3*8NmmGcIJVe?X`wB_x5*mUB!&|O~J64GxzMm({SfPxDtd~mkKv8@0( z$&s-7l%8I0nP6Xl+AVhF#d?5;hUiXYVH*HWH}fcXKLCbu@kW5?HI&hXhY^=l|3*S) zfrhKTD`64K1YM4W+XzMVxvc?oNEN_zx&K7U@e&C#7b*?ot_zy>P&(r%;3i|&0V111 zMoAFzP3tvu?2Z5;!}24}ak!?UXWQ#8`L`9n;ne>d8y&j0`Q?b{cBlf>&aEtX_*W&5 zGT^be%g7TiB}lKBo_YwqT90D2vm^JVzgRKmk!Ycf8D| z5CIRP1zU3M9Wt>e$DumTzRq?JYJA!QwAs07^vH)TFCN7tuQ_P`Q zogutl9W$k@n6I+@IL&*1WAvWV^G|L0v58CWryryZYoj3dQv|hV1Xx2R?gA`RLd0i_ zZ3htfu4fKfe1j)KW{FN(wQ2)~^390$x|r*_;J?K$?&ZUSLaGHLS-no1Ypvm5-+x=+&FGsT1lLM#}uiGWjKD z*d>U@Pfq4yajFgktAFFM)Q39_2UE#1m6Zy3O(4n zXh=Q?8p+KT2D=6~yBIV7MrJ1CQyz{1d&)gLjd>c?}?#$N{z+ z^&Y0$&CJ*27_CL>Lz-CoZA8-hJDkY!}Ss(y+Er4S_ixdkPz67sV!;x28NH$CE6 zQc`007<;RGZq7Mva@qmAOJx{>PmoPs2N?7HUg$d1Z2tmw<^aT`7``LS=STdKXf)oO zONjW;B5O z6*V^&HjX}EWtN@#xf*r7h3FJJ^P>}y&8YVgb$p*;fd`VP*Mkv=J!4mQ`NK*vNVNTk zi^mp|A8p{xtv|zkx825B{gDarAFZ2w26~S)Q$Yhph?4EBKbH{SUT%XtJAjZjE67fq z%7*I3$GvygVv@HoZ>lt}0HHtx@}@3%jsS%9W3txp+*^Xby*w-|YFV8R*tT79IU}`( zk3sj!-HX{>ehJ7M=w1}~9fcQ5$$}*~QA}3V-(RU2Ve=BWd2Lsy*zy2fPR#)A^QkM> zN)uEAI93Ai$Vb;INQ~{KawKWr=Ru_Tb-iNSi@?SyA1V;8VZ%%(i(IT^pCE!$^_}s=_&u z3$jPx7*t$=jI-~9Au2+r1Owsl(VbVI>%|KoY-af!u!Cix|31d_j}j*0|Ko@+n;vg! z_v=_gC}WG69GEsHs}iVc7($3qH(WaX^DY-Bnq%x3>4z>11tle=>rh_9`gLJBz%3)P zd1{6NYzBsG@RtLpT!Z#o*QaB}DWMb|%qPB-$6ZV<5Wej^kxKaOftpmM_KF3{WG$Xt zO9BWnqR?QjqNZpisQ6HbC&s{q+l*!t^Cl1nvOpV8C6w}5B`%wh$QamafS8rw$eKCi zLBkB*1KpMJ>k?M)(Zyda)h9>3N%+cW)SL1D@$kvkHWoWWi0pdw9TS#^4@G|ajVP-C zbFwq$_3Jc?0rT8$K-P|R5I8{{%^l6T1{mW{T|Oh282YlLg$ga&Y_EtoWC$yb%IfKL zbVWCkVKZQ)mc_KET0#cV?&s}|qM6lsZnM}Pr=7tKF8%vTU#pA~W1-hYQNnJrDQm* zy(cd^0m5c8V6j?_>_el4IO3TOJx{9|(PvQ%65RvIxlIDueTRH~g21F>#dYR)*v!t? z({(Wbp1d32Grs<+1#v_;4y(5N@DWdV{^)GyFG-rccZTxv`AHLpcjrk7C)_2-(Bsk% zfP#Y{6KcEAW|lDqQQ#&tHGp)KIpehNP+on41jQ|F$u=?=~jFx^_%gyBwKvS!S~@H~bm8 zrGFr3G3BxcOt2$)uG3nV!$3Xk!afjFu0gb8;B@C~Xo&i5RiC~Oh#2aAZ6$CUu@CP^ zG!)mvhpw$QvJWY-UqVEET^PN9wk>9_?*~Thf$pX^ZA;1TcU2DH)(|_X0AJ-A#CTmy zd1VXj*caVeKD|&Ibpp8bA{jDJTSwA@flKk|OiqmUQd^z){qG<59}WW}mn5+e3DvPR1>d9ud@r8bbv6&57o?+AdCn#yeJF zQ$;B_n?VcR*q2X;impsgflmNkT|!VTuWfY#U%ACXe^N`Y*Aa?F3Xtf3s-qA1H=l#W zh2uweFZ_L30_|Y*t5-GVvDw*DfS@Ki>jk2)ze(do89MBL)yoaY#i<4zE)_N>V`6t$ z`@@raGq#~@#`4Zo*9iSn_kDj;_1H}bD79HQxPVK9wmG{o2^)916N*G9pIB8@ZBT;N zOFaNUJxakI9Lx^y(tuAar)@ZwFRQ2>aJ048Ton{a=10OYKhkxrJ@5jC$2R-N*qOC; z<01IM?4=zd8Dgs{X3ZeMdgSa`|E1x{G0+7OQ8NrR`1P&1MuiXV!HJD79xmc?%ic1& zCjiW(EcQPgrNF*~VZ5S6YL4niaCgNQ{^bQdA)mN=vb;Eo%yVslv}wfow>G7(@~%)Y zp^S#SaMOhXD7IoVQdQSKcd)ku64d%Zq(0Mq=qpb9xs@CLx^1Ve45s-L*EXn zqZXH~zP>nK8F})tdK~0-!iU7Ut?d2D90>}YdqDB}eJVlFUvg&Oa!5opl+LI*CW{Yt zl>0!^Sz_(I0`;F%C|W@}2191d@L>8=BX@x1r~U~rT-g=fPH+SxfK*^13SBP;_GTsd zfZ_@|-v5A57E_%v*~k_c8dubZ^OLM=<%_W$jvpAP=$pjJt zxs@rP=nJ7cp}vF#T!-YX(?4m%LJm6pbY^e@vjEPPHnN4yi@ot_-^ zft4Nw%z3S>-9KJ}RY<8B2IqX^&rwsV<lUUv@`bsKlY5sT?)J81-0BuB{&!CLIJ0$Yf1rzqB6lX}H@n5m*lBtVH`c6V^L5(k`GUc1Hdo=WZ|jaW`Z?exWcC~fm|HSOLU1sUFrb#Zog-Tren-rXzR{Gn$1&n zrDYg2LcgdPu3kY1XePcW9!_0Pgvz?P>HzGgR~%G?g?Sa9RFtszd*fnxm7bpIo5T*T z$}Z4Mo?t~1n?|FCfT|^~xNAmsQ1k=^*CHnY>ilFDC~Y-jXFw`+gLosl>Eo@tcU3v2rZRtAnu>r;x3J4X#BauKoR z7OTj=frtcN(Y^Yy@(!M$j9hR(5*(~r!hFh(aR2+LxOs+M>}*kOidD;Cfgf+Yn3=Lf zkMKHzL)TTtOX0XAq<6U=jTH%O1#Kx5_(08&?;>;(mBl@Noc3jWVO?f2BUy$ceUZrRcW(t>EXb7}n7lRB#s3Y8yLh?3Y|DCnE}-qs#T=|=z??D@ z#=^}Y06w2Lgc<9?r~{eJiCG2&mcgyM$WkAI1Pq_$JW~t3c z)R&5GGjy?POr=L$X6n@pP46+Y#=MoNKaWI4UV5`N<*wBw{`n)vqk?9yKq)r$1V>$_ z3dG3%5?Y4!>2_FP0t*kYf!GXBv+&MUJ2&;G+<5it-_QC>u30HHrqWN(37v$+ou=$> zX`LjX1-B>z95cov(^P1@gJL13uOOcu<>7y@B~`>REj9H@;Vc{?78aJ+(+Y9e$B)7K za|=i}Y3M-HdaU*uSXED>Oasr1{W1Pko&I4-aTXkb5Ch_s{IBH>;sR;a!`s(6B=5?b zsETiX`(c$QggX=1DT1}z0_?{JTtt4uD{nI(w_r-q-UTJ6Z&Od6f#4}Zr~ZAS_NtO15NHs%Ur{NJE8zm8L63iFgyYNiNM(OPHEEWH#=%-2F}VbxM%k{ z8NtAaF}IMXo|H%c2`@AXiz5K6FBl4zXR#<4mtsIGUwUpFSg`DzC% zqn}Vbfb$<3bYdd-_Q#76CloYm3O|{yvORL-$mQP9yz;>Se=D**#@8`dw&yX0y*1*^ z=Z@`!ghZHXx7?i-o7Q4sqy@=zOI0Kj|H_ z5+|@!DG5la)xT{zv7**VLon7Q4aDS4Y~ zfXp19aB_;+wp7vZ@IUEO-m}_eGqbDdPMzF1n0J|mix&Q(o3iLA>yKl%rdIHlB(J-fLW9}CC*zaKuhT?m2z?8D!M;T&a&q!7{)+}_ zE^3ev-vB1oiY&0oWu~KnW@7`#5YdO|6A{z%3BF$DxZT<204_+`4<2AY6mYRsU2K~Q z#P(#p@x+ z9J7fAcukF9d`c9TAeOlxE)J?5*tjO#z{VFL&X+(ESe1ALO6y4XxZC#dTP@U9^&7BM zgv)NXZR3k;e2!z)5|=bJTYl+EbCXU36Ke{C&0a3JlvAc-JMAH(4v^xEyGq`DLDwZZbIISP}EeW;os< zJhnSLOWp}-oZq?rYBqwmfD$gH_=JiWC=`~PK-@qU?gj`j&X6<({~-?@6H+utWmtEA z3jKV0;bXgq8WiY6qnrR~G-=^*`O0?L-S^iiQTN&3S|tZ5knpJ@G5$>Cy^g%t+Ka1J-NoG@%$x+CS=3pbgzGx^T&I~v3+Xl>W9?MZ6%t7K{(Sg z#0>m$JQ9?N{KYbZfOxH!<@cUYJQ-%yP#}!vE^HdB7Mmccw;1gDHhD0E1z#Fw~YoAacUMwL1&`xr@6E zo?BjcpPFjMH<+GYWyZH6vu*>^r$pw1l~9sPUO#2KN7ZwUwIDR7v2PJ|S(tOza%uf=Cua!Ct*{U_L0;@+#kfE7 z@64a+`^ihS?+7FRmuY`DIr3aRm_g79!K$lSe4)o>;UL1+_s?FBYadSgq5VRmzi@&! zAHu*JFiqSwvR}R0zy0u)ssV~t{K-ZBkViCYnY)+Ym@wz$krpc=JCGPn<#Fvdw6O5L znxbC_$5<9^PRlA6A+zkns3jR-9EM~Abk^P%72~GBo}(&YgYXlk)fbnE^l81>GPJ^hzk!#e~*f?85x;o zVB&)IYHlBd=n7?uKZNCk$7{7FD}f7)31Yno5A>_VlDd{Rh~qAo+LzyYD(qkj(<)Xt ztp{f3ukmp(^G_t~q!i9{FGim@8vZNrC;QU;G-OKE`f#dmWxGy1A`99;WuXOBWKjhc zBP7Sm-yf5>vpVIc@0Xk4@o!aZ^LfgmJ$ySNX7Y4Ho~N|N@xfc`Jl}r>}f;+?`lFS zvO(bRauC+9e|uFgb31(D_$!9sLLvCO`9{4isz9q_}r$RdKpjd>uo`z zQcR@Q+DmT~*eKT_sh8>b@!jT%C^U+w>I_P=^1Oo9-`1Z%AxiRSED5^1ArJK zV3^>nhSq}4)vpJdt!reD8B{#i@_q(y=>7ZmV|{|~YP>J9*9;KoTzCQo^W(8>@HPPA z!+*eZ9SU&x(Op3AifbMW_S)I2YItk#9h3%$*#o5J1=NE{`>!Yo1Xio8%>q*H5Y5x_ z-U%^^?LS}OTX>^=!%XWoeC^q~JCABK2ouv+R!>>gU>fZ$!%~v1D&6b-TvJ!-m@C^x<#%@>2KxB z?F1tZMlmI}J}+Z`PBKk3qQ0A7(A}oRybY9qu^MZ~%Ar#Y6K=nW#qe_>!h*g65+6kQ z?1gPnaRfD-Vq9y8>pKWfK*N*Am*q~eSpon`;$6-Cy?-YMQDTID`b%Xtm{qWAtj(hA zhW?2*G)k>lR>Xn+%CCI^rqShB?yNazYmJN-t$ghe=Lk8OK{Q71lE>@p{j*@|cBym<7l_@CWRtZ9EQuc!#=QOd@-(lsO>unSb& z+E-2hk0pL}omd+d^@iYCk+0DK4FH;kMi9q?O!{?hD=^hNq0s*rE*>p{>DX_B<~tjJ>{`V(o4T8>4;Z&YwzE*Gh|^f>UyOeZ(qPTU%mN878+M916QvUL25=|3 z7&INa8jxwcy4!cP>-uf6OK`gNvm19>220saU%!NP2Jk91r^TYnhMmVF2kyWURg7W4 zdcz06(fQtP_{I$1i;Y3CEwR$iIRIF7ke}1BR~PP=Ni~zXr2M6x7*F-c;PP>z>??DU zCIh`NC|{530~;(1Kf7_6g8}O)@t2gV>^?u-8Etosp~@O%!Pg{hh)htS z&ZM&1$qxBx*rf;CUhD!yEv5qX@&s80TQP&~HT&x}c)JS2?{CDtW`phWMhrtzX8RH9 zh<#9H_g!V1elSSNHkT+bD=Fl{S+N_X{qVg0IRta0qP@7(mW~>sHx;<}P`$W1~!19{(`VO_sCAKy59(Ct906WJmG$8=5g*{k0 zcN3MT0c-fY-MFVipp{;TC z!_O`z7aeh_^{r%cmUVb>DDSTWns1BtO+M-%|xK$*NW&kj#3)O>5Gc|@GfNtME zyBG3~%0kRLAp(rC48T7eQ#E2IrQ1<0d|)pNl6}g-s(8qCU14QrX)M zvl+n^SR*{xIty*`J+W{Pj*hb5jg6$XkXoru$I!s`Mg5&7jZe1GnAa#N5^wnk6e}Fk zG=W1uf~hd}D1?w%b8kCT2&X=7a^5To|4+0O-{jc7g6MoKGW&}j=k|}!4<+DCSMCSo z(ONkH$K#1ovQ2p3zm$ERwQDBKReAa-0VELt{Q|Vtr?0E*OQ4@?y5j;g0W1c840`0n zb$K*jfCcL1*I#Qr_7^!*OHdlV|hHqemrC;lP{_*5tiPk8k`U)?XBm=6Gx0w=2_>-W7ymnKefr0$FoM8O#Klr! z2d*F;+M5!@mQ{L`CZptO0>MM%ru)jaiP$5FUsXECUrrrMFe7>7FP%#Sd)CEfe*H!} zuPs-a{F?YJYA%v^a2laQk!%N41LJLQU6JOc-S3A#vZi+>3$5F>T!pmmGABo`BdJ?5 z5#BuJgzE^gTu82lJDU8d5Xj^j*+g=N3}MnV{@67K06 z>1^cnwE6g*@PfL!6b~F0B$fl!@kjDS^C2k#zrUsa4bsFezp?QLYmF@$(7zGxlJcFd zvBo7BF~q!5c(J@p10RhhG(WFo_rAg)gBMYHKp}a^%8RCDscroq0m`aOhPCU7D3<{z z5jg2beIPEqe0KuUd|ElDLZn*P5bS%!rH6^CdJ-QU2}8b=>bROmei@kH3X*mHq~m!G z$PZ)MlrMR57Ehdl<+-s(?=qAm398BRV@Qk8Wc>RG_KE`>W;}(`Rp;@hmi&#PRlj-1 z$KoZICL}4#=X3%&Tf-ef%m4f)Ns+^Df9A6dU)i#`Gye^y?!x*x1l_ln{H?^4Q-4}L z@>*t+1)qygd2d9Ue}3>HanXzlC+uwrQbgEnvnEihiA|H#kUm4o-^lcI`7e93FS6gc zmM-v}q2~nB&84@H60ERruZzGL)c)C}b9b2PeNWaS+%8a^jhS9NL0=EPh{F@fM$M`4 zB}6cNgPFbqJ&f)SpYa1)H!5_+R4F(?RZ12)e2c`tT`n z3QC8_`;d5;j8{=c!mT2IAn;5(G8-0#h8K8=C zxD_v7z3LPW$0rawo(9%Od3CrD%bN{Lln{@6cI{j1sCuJ1397ptl0#bgOhu)x6{-Y36ZV9cYpJJ_K_PwQirj^wy>hkv*flS z2W=2ER=4GaR5PD5_Bv?7!kUfg}FihHCEIDDytiXXg5qS%(aY8V>|3N zXuF4U!dOX6Xh=f)&O_e0^XWd)T(gOZZo#`V+ulHGg`akBT(?A%2wY_cg38cp279lW zIzks7546K+YHG6IKx@Ys?dgUrG3+95S;n1iZN_{|M;tlvz_VcnrtB~KU-%lVd#iSw zzJ0S{KYSOg6C^=udSjbfU<@JM6ob;+kOu1FTm&iag%=9FX9s8k?GgM~ba&iCge3RUG!bJ(&pDgGTxJO#;BEzV|`KOE*IM_raN zob!ih+E?>JsW}7GBOQ0w^SGggas-AIrPhsRn@@J+TyHmE@VV0Pr zCoH_XLDTRK==es!&`DShgcHg2L_ov%>?rNY_&`UVx&h~fsnRPMqoEliA2tHsrl}?`?LIWT+n;(3MDR$aHGY{~JYKSAdOeXTel`g z2&%0f8%+DzBA>VYQ0o=dXzFEL?Jo_qB71n%AS6aOmsxhg+jWHPm*9zD+BsGGT4Won zts%Y*%`we2F6nf$<_?2qpFbkw4%#2OJOaH^fw#+C=TlxI#c>g&3b^w6PC8Bd9$Qq!!NxISvBirtcYrK@;#e##F2ha)%Wd&Lozzkz?8?prf ze{^#*KbOCyOY@kKLl4WTTQ{DAu9fh5f?cM}RujLtU%kv#BfN5?aa5p8fe6CjObqYJ znx>nZU_eDHxEHoNC#0tGA7f29=P(+w9KS3r^Xe7<5?HZg#HA3-34UN~J|2HsE3xONG z6|Ig=15BP|SpBl`!yT){p56_A4S$JjM?xIYe-fyk9nc8c6T3#EMPY6pGE`gz6-Ot@;PtW&fAJePl(R+*JYWNr)&o_I%^Lsh^K8>9Kr+6YdXqKI!-!l=lMuUvb;QU>j6h92^`l4^48M9)-rocK|or zrv<4p8fxjFjUqs{*w+kR8g3KsA$^6^^d$^Cti(iQondlv4Dj3?016DL4f^bVBl!pT#Y#Q6v^uyEUJc@J;-mTdVR`{{DJkvxm1EX)ForApMi zyy|hX-o|Z5G{$YM8Qk?ye^yS#G8H)%1;3SZg2YRz=0Z`Pi?O}q^t~0c)(LuviJoyo z>MGHt#NCiwjStm*>?mJh)#Z8Bv{~aZW5e4+1E*+6h8rniF>j9Ipu-pOg6p$GO+8l4 z>0{%^m53*Xd%i1uxcRhsK~-|Nm6OAZUjV5@EK+Tx`ak(!5-N7pXj2=j{Lr+WS->QW zdQ|pZBpU=Jho@XqhTTRH(*zhjhT{QOq_axsn4Wk@?YA4MIVI>Gb=ykQ;n@-&CN^fz zt>o9cv*g1Wd0JJHuB-vWJl6*lJ6y4v8sm5t2`_R^Wlt~1ln3SZAQj2~R8Bw9%E@z5 ze=#{M1*eVJx}{)0dTZ#7j>Jvm*OfH^Lhgm54Ak3GQqC#3A-d=@Vp;uYO<}&{oqde> zCy_n?0TLq?I`Q2`^0{-Ph~?+zpv&Q}&i$b(NrKNtZ8xvbJ25it{n(?E{jr;RPrUp2 z#1G6z-fA&NDHg=03mg#9ei8W)*rvCrgDad9*NIySE-Q0u8gQWAN{;2WxWRjPs#n%c^9!ok1OQ~@0Me%L7pZRr+9O1Mt>?L zHk`)e3&wSI9VtFnga1xShT(sPJEAXuSA9TEB*;@f$HH1eXy9EzVvELMm56ip=|aQE2${wQ2)X-XX>WeARD@|IiuZBG5YG@=;l`3z8BRfE2l9*`?tvhi zlLEzvF{Sn%5O~2GXJE&`TS<8buBDQE6jL$=YKED`#~L!XJ-Tk`y2k>TBI*E5(5U*n zlEg}+U9c%=?dSCgQO@eVlSE5kK5*f2cE1myjRxNt7`Y9lSCF3ErDUOzPaZK@`-Uip z1kG8sYE)6jlf<>Zd|%Od;tfzn#Wh-WU3tBIfIJ^fW82cEacRHx%(s<9tjbED9@zR# zmvmG4XG)31^`@1=@N^Vk0COIOLrdq9g2nMm^F?O-=TjQ@75#Te9p#p$*c+A@plDsE zUB1oU)cSZw_wH%^a%vgc5X>p&CufK>o$A#ux%ZAt5br1y{En`_ud|Aax)1fsMz02V zg{EC+#Y)gUyb+~LNwF5`n$yGY?3djB_GU7~=$h<+ky*~qHQvLUTVhm-r5N6m)8;?F z?(@oPB+|F#^~|Ya!=A}Y@45^iR52J=r^Q>LWgQT%L)0BP0U|BTA8-3wRiT?3tlEE}Q{r?#eg@)0!**ziagL^2m3NHKp zmen^-qK>ru42cZE@#BZXWo?;L6b`Gr*-H6cS2xp7?MaByEzM`nTK(O9-OI3ARjAsy z89l|ZaA{ISBy?FVT}*8L3mdpWa`fR1Jzv5z5>s=#l1t2WZI`e`vCo`*3Z49f5rOj3 zBOcJGdM5JaplO&LgZnb5{^nq6Kbd{-ItJ^@HxElE_rKSagfzNQti}^wA`5kUbKjB= zrLFN_<&=K|Hg}VWbAO1;N&EkuTd9sb-_5?BO}es-%h>zIRDUYZyyvll@jr_nrnzxs zRAh((R5e$*$Ww+Z;#Trnza8g=p(3OBr6G&dPX-B9C+OhN!nP2!YS;xi37E=;W@esX ze<*HZVuD9M139=qHU7o_cp0!X(FWYd{TRV$^Uz!tanHmODB;mp~M5f*5l^z zR~d^7v+3&~E}bZkys|MS+sa0c9=+kfU;*eO7;R3Kfq)8)UiXLGyo)F$shrJ{bY*FG zV3PZ`S0&Y7c1nHr?1~%#N|jVJ4Pvhh_?k|X(m|@5H?Y1sP5ZI^`kA5Lpf?p(W7Y}W zm4BdOihS}8V2C^xo@m^UHe^#Ei`o4UiUu1s@nR9b#?%JXM3(VGAb&_`1xS2bn}6N| z_lLXHar0H+*w6|2ofp!9u;F$AybVSuegi%MwPXOe)rI%HG-*ro-d$HSAXJ$&$R{+J z1C?3J!fmPr*B|cQj`5nyY`TjFz~JtVJou1Zwd9w^{;DD&zxegfEIsU-h)4>~EP0NU z5zY}Hjp=E@8UW3qH?YWNl&PYDcgq83A@5=C-fXjLb`mVYb@l438CJ6hDgh(-FypZF1!GqZ9n!1xlvv1$zP$`bHPp2e>Tz3b&3zuQ}X$8E6Rm=O?YVv|@u9`284gsX$6mmt84{8E|s_oPe**pk5 zm~?nuhlyV4z;WD#24h&K1Q%r~o*)k#R+Ksd%@9ac9ms;jcGbk3hk|mJ*Wh4IfOHgc z;2a0k+uV_p``Bf^!Nn6ggJ))05J7fq>A^6P#@l5Q!j|u_gr>D|_pZ+(+1qsms1_l1 zh-!ESkHYv*d1SfL!3}GW4F$E%=Y-}NEjq&&#t1oN?cq6cD3l7o(9s+FPrD{hhP24sF+L}{6px|r%U9Cl7FS>q9b=3!oF4Q(!udI+~G2|%r*Vr;RpD$ z+tSr1opLokef)f0_#%-bBv>(O+&qJYea(+;X5gV*z3r(J$g)|mAP5AKLzVyr78S$j zp<6k3S=)6GXlgqG#lQ=d6hKkhjHObf3=BWJ-K@EJ3XRtBF;Wk+z$FdOK9g*$W=jRs zUO-)hinqRr(D<}R{~?~@5Q+-8RgiuKE^2cH=zvf7$fV2SB;lbCeWyE5gijMyZWX;i z0^x*R=#1)dpkX&HK=C*;KoCSemZ3TZV~5SibPCbY)fm1QjQuDsYCe(KzJEN-!GeP9EL8--Zts%ayT2Q@+S)G^3E$j zVh7m{T_j+<*i``CKQJ#xkyIlzWH;7SQAQ65bWSAHnQ+YA62JE-AI3vWHk133uvAFT z?&VpGhdpxnExi4#Bgr&FJsU1y!!4gHAo$EcqX~MfICP7$U8GZ5WQitHf9dimB?983%Zn! z_Sz=_I6)<5Di7i{uIoyAd<6!D+@rqqa4AsHkE*d`DGH(S2^8dQz&W`X?97wvi7F`F zMU1=X`78G?>>#pM_!cIKn7`E=r5v7OoV6S@-taY0l;RARafax!N{pI{EhMNokzs;) zc>0?|Y0Mm^)FXK27nCm-gi=V_spJVa&nJ%;YK2(%C*s}5(oi+XdUfr;9U1~W{Z{9jV;>rXi%>!ToWaMGV z|LmSNkeUH_Jdg zan6ecaD$~fpM5+mg`4BQ+}t+G7*bRDZN4&3PxCPFMZtqp+hr-fsRLpWhs9D2bj-oC z_D5NC@Ad8Xad^OoAQ*P{0Ue;cj({S8A31wySC1A~sXQ13xeEGJM*T%v4j}V_9yPsf zehxG;adAp+e|%bvk+ggFZsLeT)c&C8w3N8`&s&)%dn5kQfx|DA8>g}1x~8{q)3Ui< z*QpsctcfR>GGV=2IRZFoGu$-S`lb8iMG+ke|RC* z=Z&U3e%3e1IDQ=X@^U8qIzMCDo7I@t;U@yJeWoHxtcOIEC(XdU-U)mEusv$wQh5k` zl}jIr%z_X8-8c*nz!1w&)Af6>-BqEa21{O9VW4F+juZP0rZT$WP7^WL@8fkmqbR|V zIqkbVPW%CYr#rv%(zN>`Do_IJ=H0jOToTINlYrMZ1(CbSUs+>w%uei77P9faHn+T{Rlg z(8UC{=WN=Kcr7qb5r?>McDoLQqgZFLW>(oF;&{9N4=(-#FUr;0ZgH}c>=+J*<7|e{ zyykSV`ruPj_m67ZkF6%La>A>zMp`a#sF;y`JV=(CAFNg1k)gyj_N1I^2#zJS>Gjw}S zpWFz(peN^kf6h)bYyEI)JGa_^T7tU&W)`n7Dill@5#PsvM_cX$6j%vhj8b*FMb$eTQR8YG%_SUepXpT}XURg7mUDdz}^ zy`$Bw!p%X}oB!=uB^J&}2OYpgGt|+xCKC zJ*7i$qRaQ&K!g*&3K2M&F?hY1v-FdxQoen z?TGL%1}W8A97DfHLOg_=55te(qaae5TfaT=L&~v{fjw8U>}S{1J<@>cAZtmO z>-r}2!4(#HhGrF)B;5~ zO>!$ln(@&q(aLfJa{958)9E$n;0gRTZ!7>~8mgLw!HjFNWJ(oNADiZx?9WTdh5~(J zPKe`-g&N>&(O{79@7cgk5KJJs!V|l?zFx)01dlm19x&(om>wU`4Qq}84P5lf0t=Zf zK5QANpLdxUI$e>FmCLd?%j0L3EXI2H`uZoEX%C#aD}6V4{{@!$y(-@$S>vVYBFwh2 zG^$)$r}EwT{F%~pE@PimOU_h(zV=T+p__fh&YpE8{rzrLa^=^Y$=NlsUyqYBt%5Qq zPltOKpSG?zWmPd7CT`V}TRHGYYd89bAdrEn8>WpAg{wrtNeOuOIT@ai-l>f(RB-r> z2k+ZDbve?NP4pyJSfiIaKnUG5)fNtvb;5cWRczo36RTy1tWjud@>I~qSUC|l%__zy z$un!RKC+obFn;^3gtG-cW9On2|4jCm29uuO1^-c+K~H!vw0M%KmMxW zN+ZKMy)sE10uiKoD*C_BIwbX4S>*bfoR(2)?x?_+3i#`hOw-W^mP|tsuLV#I;>H}{ z;?{8nl+aMjsrGn}TB1#emEPMO@d!s#`;|n7;e{g)8KyJNy`WA-VTQ|_t+@>-CPY*x z0kNIOZPaB1L)C7Th?E{?@K9c2LHEir-AcfPQA;f(R1L$3*)4A$nhY|0zv}e*Q*K(N zJs#L@dq|E$Xw z&n)t(7r9pxDIIl4tA@J>u@3&F*nY`#aS6}Y=I=Jj0OU*Q-(R8UuOctw>k6BqnB+)2 zx|=P|`_q#MkPOCX(h7}9-fCv2wd#$TV305eVj_c_GW=$yr|_IXmF%+|2)@Tq!S@Iu zqrb8O=}A2GM|aSX#H^rOL=T~v1!+!4vFL)Otm;|gmB=^-Md>k&Ye2M+V26`QthCmI zt?zwlmv77OWx+!PkK&U>PmP^)op<>tLzh8=jYgKqXlZ2gIJ;9elTd*!MAZXeqb^`% zlG56RH>t3Kd#!5KkmP6Tn;=zfs=M`DnY};d7QDFw57y?x<_EnmSOM9@T^)o4@&&jA z(Tb^`ofZ`GM8Jh=5DlwxzUtQ2uq+4sW~E2oJ7#h;K5evL4*UD}(Vb}kw!gq4_~b?; zLy#=q?c#CssF;i7`7s+#DH0d^(fkI*&&l`g2USB!Z-5{B2P{il-M z_)z#w5VyRz5+#j4g2^-#xwj`+rZMj^R%uvIL6DWS_ji`j=GzFaHvn8jFjvq@1co`* zDj=W+5KL6YAuY)gZC;Ur0jZ683nsO$(i}T!nqkV6h-~_{RB@bn)3vhQURWip+0{vS?T1_7J+Q-UK0F#Ed#2MoDSD9a(iZ(kb(P+T!bx{1{*FibVhZ=04 z<>1E8tBVRWB?`32=@&!{LdA(;AieQt>UJ663Mv;*s+wg~mn?(INrVoBESV^<2D6iZ zjK1iQv|!SQuE{N1kQ9Q7HE37T*~zka+p+(0xH}3wz^h_lg310kP|&a+A$s710RzQt zs%GGkTRd%LNNzVsYKnnZza60!Gmq79`G{!W2iB0_F?d8}Ojk#ZrAUYmb(e=U z#IgP^4LH;ZMr&SZ?ugd0Apg}sJ4kqc5(NNbs-`#4Z$bM;EH-ok!OR0;#3YyiZoML7 z+1J%6G7WBSZo(uOiR};_#1CTTOA3~go~fkc9s!LPXRiH#-$>a(t)Ynw##Rmb*K_25 zM!Z?VH;2#u)^g%R&Ix?nnpV5|*=#vhmL@+puAp z8$5h68(27)&+X0wB{9@J0LAkLbp150b}Esh5aJu{fGjdlC?TFDm@#NA22wK@2nh^y z&7!!SGY7b)vil|pz!%wu5a^|I@!{4#b|E?}^e01U59}0aUOL`C+GL%EUBVv4I9M>w zdhhXh&r94m=^DLJNoMy}e$VwP(XdqTwtYdvX0gz1(UG{&pV)!mIr{U0HSBl2%^4|2 z&BO}^67%+)FsOJ8w_)C#21TI)@aNKj{O2(k1nPA*p!4RrhZ{X1Te6rd?Yc!Y7tOXE zEJ_4Az)e@={H^X`+*s{T6Us2>L#b&b52>_ zc)#l3^amGjeK%FEY}4W>EX;EfG@qK=tDHkU8hEq0!*^P!e7^_alabT~Ai#oLlg<#1 zcr-gJf{vtJQx$f(^a!S+J4X%c&4T*t?c7UDIRFS%-&Z6!TMo$f+SLpq!3$gpIM7_g z{a>D3M&Rh$ke;sFbA{=zaugm1YS?@(q6}u$SL0_^vM2AQzx16rDufBSEmeYLy;5ff23v4=$6Di@Ir>wdQpoYmgg>%04o`}h!ss}V`+cKPBl2~Fxd7_A` zQF>KoJU^y>oK-Ui><}86H;dzX)1K>K>_k5_lpkT6L8LpSUvH=55}vm!dp8`|(0Y8= zX`^qE1V<4D|Kr%NB`$!LTR1eivqaU*P!Yyg{(G+<2@)waF!^&yU*b#+mGd+6Qt9)y zrzbAu6~PVcE4r@}unx8_qb>-Y>M%Ghg6NtVQF`RyqHGYC`YQzvadB%VTCX?1j;ITV zx}etqR0d8VX&3S$okEJ};ZI4AaZQFrgAHXMT}3$SkCHUxr5cXPmEp;B3!pg-z$b`- zLTf={E5SM`(iicWvA<)v*B}=|Gh@hV=Rebq$lH#V58s0|0^ngOkE!7hc5&UmVB(@0 zM@b^^CshLXbp&S;Gw)TlzFvB9oXO?<*U z_ws~7(w=CHLLq#4-H07h!GUcAx&w&pLpCgC0YupsNy13%Bm{l1qzkZBFnAfFK?w)L zIutSfr{0Yv2b6Q7rI!x+5ugPl%#JHPs(;~A3*}rHcq}N>bovN%p@Sd5r%E7aCx6`r zg2KTMPWVhPGne&L*$nU-t_ziawFj5>fH`YML?3mPJNX1YH{tg?N_y^l4R)~rzj!-J zkS<(8nL*1yUayA^-9HKA8tH^wSIxH?Vv@)B++_>I#`1t%Xf1ScETmKAT>%> zcyLj(!B;Na@l*GmOu=zMPk9#{VOA{qk0WUo4gvR9V;k>g&JZnY=sa zGwTrREuHV1f%3{FK|0BXhET&qI5=~}v)(yT1w<5tMwa*n?Z~LEK-tF6?{`2riZ2OU zS$3d#6!_fdwnpJE@!r2^Hu`2RQEingUkl~&BP@(h^`(UYx%5*s!R>&k?fF)0m*+C| z(1kEohp0wr_!j>C%r>+71&hhS2em&1ci;CvEI}PyWnUOv%5syYF8Jri!4FJ_2*I#A z2Z-Ah%6BjY(&VS6{&D-5)cN~wWjW>J%&@W`meU>QN0D@V4H zT<^hMMT4Xo?&>0YiY3!;^c+U|K3bk&oLTsi^B~@ga7nEdXP-aQX;#L?o-xj(wu;XV zr){Sq9OuIGo^IW*zUDyIh3tQ45$0v`m>4OAkZzWm3c_~C`g^pi3@W@kiO>@E+^ap( z_|C4G=-Tbro_DIJYHDW8sq-HPugBLzE>4@3=;_RPeeQVsdBVNTY4FQae%o2#%VYs9 zZ0S`WfrBQ#C#(F?ihRzsc+j1i4%_r%C%QQyKz8gmbCS(px4{h6s;3B`sZL}T;|YYK z_{wj1?bw9K>LvxXTi;I({Lblo`+3q!CyBv?ynf4;V@Jb19eJ|rlBC`^*_)eNlECs*R|;SeH=>e`3Yik1c&1PnSf_PM6Bgq(2kn zX?YH!+LPRVJ`|y&|4v}|Ye2v<0_vB7*Px9lXJ52sT_;?=RZR&Q^D7#Q?T186VuVhFpFeE1^Ec34utDE zAn*(YvIlu0f5oN(0HZs>nA-#5sQN!_cu!+jrME}OMLF_ZuYuwg{sivRPmzxK-Lo5m z`R>xEX|Cvk0uQGDBR4n9FvGw&KI5ma47mDi3AyjQUkAeL2WEuxA8?gNyur2?@zWWG zP4G<$Yo5K)J@`xuR#8UIvKnygyxQG_%zJ&Egt`~exeFLsgLOC`zCUa){`1c?WO>X7 z7cb0l{`H}cw;h3XY%zn56oi4Ytg0!7I<7 zU<55lHxE6-%kO@KoRtuQplSsR;VAN=%nPN9MbO;ii9G1aKgW`(H+>MqrUw0u8AO{} zV|o(1&)+N76ydgto{^oHbeZyJU+oom`G@s4whz{xZEDc@bZ_klkhzj85{Vb~e#et{ z1Fh!ErA8^WTQC`Z=+ayxk#Hamzq;V*j;cF!4S?{d&6MePGkNgtSx4l$FFaD!9M3EaD{eDTSm+AXy=Wwh9elsm?{up#sqwm13j;Qv);e-JW zHJhCuc40w7S^^mbi~g9fBe>&593D44Py_H7y{phVrsdaWRFc6CjdQkKdUO3Gtc#+9 zq>JYi3-mR{kwOw>nWXo1Z7E_vH=& za}D$v9CswDj5&dvx_k!4M@FDdZHHq4;&QS>rANb%{Wx?~F9V}rwq1ZC>HS5zY>5gm zyfM7MN$|oGSnVWm&w2mLnzbLx0=YdZorbI|tIn(`1kk^Kng~A(w@zy$M>|NI`AiME zO9P_EZLRcHx^hdxAa8}cE(hHl13}LM%WZGy_z+!FWnn;k8Yae`YS>7!_v z%pXUy_8=*p(Sunu1t$l5e5Gpckxh4YKBVlCtfY%|ve1}`(AJ>v9qLEDHk+sNpgnm1 zRU|ryrTeDeig}1oUPP3l_;Nx}syINp8SNEHz6IRi^FTbkM>@)P0vg5PB1Pya2~ts0 zJ}JE#RwBkzIx7|I{3Xw`Ym16;}D2u`o?W*e$)&E3|9ffxt#XbImvbh$lz}f_kJE zm{FG30@O*0*n73|?J?j%i_#8qOnq1fKY~x`rMH%G@nJyb+G(_bU{~+c9;P)k#|R5! zd_XrCfv(_*=Qe8A0qY|FI=S~6{Aom(&I0C<1b@=%8l{fbra_W9J!wcgl;&c>4d@8}ttz#!$ z+-CuYo&K3Ny2W|$JZSB2O!$-wt>RRR@wdgayUKdA(is)UmQ)c+3h}Tgt-g1gvQO8o zKVMm~f>h-|n{N$gg>vX>Cv7k^i1!*at4bFT#rR8MlSr(g7I)@P*-6{w8#tW0k<@UR zC*%X;v*=kU=C?t#+YIDdggmIv0fmQ_{zl`KPT8{VZZ-IJdBUf)WC<-~uN5phf*=N|Nr;&XGScUy*BC@kSs11AKzmfXk zoI430eETyIvZhvjz+`V&IRYB_ap~;kkO&@)pFU2TU&yp3667YPcz>;}xpir|tDXG9kllC;^5pVQx%3C+ zkYP93Ph^fyl&*qn^?yb?m^PscT(v!5)~%&!XXxX4tL_<-3(hMoJ4RbJPqo0&<+lxT zbdth;&i*s6tc+NWIo73CJPYx|EYRQ?BXEEEbro>> zbW+q1q+k`91Xww%me=>LR3Ku?*9F7*Ix^~>Ixm z{rf(489`xM@F)wURcfh!7!PY~AU(0C{7s~myM0v*l$*CEX0=?x*^eLBTmFjmj>5Ki zyW?!lFBiO_ zPmcb_(nF6k`tW0D#VV|HZ6Qh-(BnL@yClSP$6XAb|p0zuquN={aF?l%kz$dqTL4s4RG{X$CsY9 z-WSU!|Jkr!6w$OV7((*=xaE4IK3Plqd*IaRAvgj{F5uBd5~KenU}ipj53Gi9%<#kE z@gg-8yuQ4-c#PF)Ns(dHq1o#v)fy2cqLy4Dvf6BN>FDr}y3$z}bfS8P6B&+UgjFcw z5V3xv5dQQ)jb!gL%jwXl|2-8UWffB6U)M;kwN%wzu$oBF+h?tpek)Le4F7ZbsaBa6 zq14000Oi?p)IJRGdq2SV=q2TD0BL-6WngW7iB+nN5BL7eOI7JBNs_{pXLw^n9~^94 z!agvQZg)kRneterdsCV+H9m#uiSPbY3o(NbWimZch(4p@(=80alju9I|9ty__f0Vx zJ7tM9c43!X-)Y~4vF{^ah}PxDYy*%DZVAHwKe=^=3s=d3^Cn-r-of6 zqt8jl6nG>sC_OsiwQ$S7zdvp~Er? z$RY8uwn?t5RFaGFJvR+WQ645ge6||57gt8FEzP$V^($Oq0>=pi3D8`r+)82{q%0@a7Z;57{RyMV{OO_<4HFwb zVz;8}ZF%6-A&QaL@JA6bY?yRZUplPvf{4VSI&OYEF0>3JxV$U=v$@0=Z0YX~Jfh3D z9JR4#Dtd+_KKmJ;pCu)@DkH*&4mP=Idq$E1H<~R#6Z9hJi^PDy9~u)-t+7xCPz3#p zb;0amoCnTW*9)~`vN!grl>!-L8F%yLS{H9islpA*;|LNfF1Qpxza3brBH(ZA=>)b0 zqm3Foj95!{{H4p{(djKJvJsjVFsZ1ypm*HsFncZ}-(s6#tTsZSZs#GDx7ggX02Nbk z)FaOq64}ex12d`3d6uA*qX9Q$?>VhR&SuXRjy@p7$M}qXstKgV*$`yl9Ou1{#Xmx( z0Zo7$=1+iRVabh!-X_vl2$$^8J_T`nwz!znh=|5|_^le`Q+oZQPxg*6F+0J&U- zoAW=9gB&6n8X-n%jUH?x&GWq|rK8MlpeCZSXMI79q79ZJMk)>`{ zTm7yMs`0~q_cDx)B-Z~7I8s=pAi4}6Ajas_U6N-sN>1gDr3+tQuaF57w5%4Fy6+ZH&}uW zVQaYB?B{?K`IJ13I@f?^VTh5$Z8z71et~n-;fr@PZ0eMc0m>Gu@hTX~5+APQIXlTF zeuoM^GVAe42(<`!`EuX2%JVVECm@$MewgVDmo zLmqteut<;9$Sqs=LWan@KWf{Lf?vqn*dJ|lK!Ctb*ysU*eVyX$;4aoLF1dYnKL# z>2}*}D6BoX4BOVvwcR6 z{64d*Ecjn6PHOz&-%9h!JWv?t0>3}8&(Nyt1unt`K!K0f$E!0&DH_F9S>(9%Z9N-( z2<>{Y(+gxft%HE7dwL)Ugx;m`6J}5oUGjf<4rNhGFi?PXb^?w4G{X{sbcROu=*)`Z zpvuHoqF7)=B<>g_{3pAg>gpusO!SW!2nq`701!iTGlG4irE>&pR*ukH?{VAwkeyFi z7uO{K6~yv<)`n~I`og}9C*q!qls&~Y(pdO?nvZ?@_j_hCHDJ{*x$u*jZV(lOkjZn` zCunA0odWY9v$-ZkcE6ZDM(Zwc_0&HMT_MN-g>*kf&b%PqqHXtnmTAe;Grg}Y;Rm)3 z%_zLXCV>_*gXuUwh=#v#$7*x^s(J25pj~Xvy2T6PfQq8b5gjiH?gdO*hq-6ye8ZDB zH<}v=v|$CCajngs{iQ)$NDF-|;ofcBj>1~nnYrr-*#JD5)mAm=xcVby^uF5b7#dQq z9b_9n0bce(ya$Tv{1428*3a8+`_jUDKx6Po<2R(6Kp)qkiKkf4LF(WRK*C>IS)`Qn zTLMg3xJKmn-{#)4=*N*X>;_P3fi0A=^bs4v zR1juCRpI=Y_stdT9UMP~nu{S9?4(o!DHgr!7paR4e0nK~$G+)(^PCGsa?3?hy znSiC`9_|9%PGSVmnz{1ypNm1o@fw*FTcg(?{Bm!ATUIzCvd8E!_xI6;Gl#+3#pzen z)719ysqybMIt^xJv%jcW%r`MSu0S3qKu-h*mpgz|=>euvSv60F1Ia`)M67~6IkyoV zqu9ct*9G8Rptd$!xEsf@#g-f|-|!v#Qb0RJ`>o9TNs65g|i zX~mz+bxNx!Z>0S7m0HI^Y5pJ5l%VcWz*dxZ0*M4UDv11{KMOVq9{I7!<;ql$^AGF` zeD+0E*8*10P?hMeVFK$p30%=^GV>HT3SiQFcGrjthTiONTTlGG#04mdedr>9>AMd6 zcFUd=;4R#S)7(UH6U=Px9i-+fYFwMaMd!-zrqYbbzOHSj7%BJ2`%10Hg*nD9#G3XU zY~Un7RepmE3%k(m?~tc9chc{i1e0jJufcqWuuDt2;0p{AusyuF_cV0*C4cGSI&tS< zc%_{XbXxCtz-;cOlXS&rfX@S+<%IWGwK+{H6BYGdahZf$EdNwE&PBP068RU1L6@qmio0hM`Y+}ZdN*4g)f?-#OXZ8BXT?m;cB@>npM_(Jp8 zcV+X5A4c7e4s1vLHn!_XFUI;mUo51ktf$Osx&srhk*2B{TU#^Up!x|u?@r~sPtZF- zJwqYcy15QJY==1IT^|J<#v^PqiOg?7<<-Kl(UP-T7Qx^DG)O#Ds!hDWjUGiAwhkBN zZKA3{i(Egr0L^C;E?^F-q|JU^H*kiD&-&ViFRIy+?E)*2 z4>_c)ryx}4XASpUabZ(p<8*hBYA7>>us24<6{B2r1jS<_@4p_YWz{^jsHUy=M3^Z zjHo)Es>+!YNOtH6&2~9D1>X8GrK!wy!F(oJEu!F^&ZLZ~g1XS3Dq-EyJ!F-i&@7WW zf)K!;i(7jl)g}PcRA+*jh+O<~#FfLgSx!J$iLqpR@)hFg*1-j1`FGgtIJ;#Ltl^c$ zXFR*X0J-0GF^#O!z1IXbSYwX+MMf!QV8$|kxmDF?^Y0I;tubQfsTXp*7!MJl5vehr z$aC8nc7QtNHL;5_snV994IOzN_-3*F;|Jx#ng^X}+RMio8ez8Pn4m?j7#(jF*SEP6 z9`Xh+^@?DowuQwB?@hl>9e=R#YmiNt-tb$Gbd_}F3n zemK}{$N>k6CWd$FX3$H`X?N`3t?J;UdHC$ zr=Sgtu@Y)#ths~A3wG8N;s3;wuDEYAA$K;-G8U)iIq+29>CPFIbG+UBhD(_M)*vp9 zsi${kHX7{KfZ2)T9b-UybKON~oF^SRw=Wf3n*^0sllq&)B<_1S8*oKqq18j0vN=AdT)E%+ixzV=fL0#(p@MxM9l;98(wPa)5vK`&Gb zRZ<_IDhgPm*}~DU1w&e31$039e0buiqsae}^&W6J{@?%jRaw~?MX9KiqL7w0qM<>P z3L)B4MDzBxDjF)GotCyVwb2mLQfa5qQc2qDf6jFmpYQK~Jsv$C)O}y$b)DCl&+|O& zSo-xuZlmX(%A8jp_CA{3pi1L1Tp@h2%6d8Vx)o1|7Gca7LM2vgC-z_Oy83%n5e^N9 zmnG%cpOghV3b0LqpQ~%HI>e_nhQQ=Dtft#LeuT}BJxTHwE8!Xx!2wb6Mx!;XCF+T0 zdo|;j$qNw1$`F3@KemoAS+xP)REj;#XLL0?A?&=59x+E-kUFAD5J8DoO$AL=_v-MM zmb--sXW}jq6OVMx_S(7z(iK4@qK4rIyi%m!1Exze&6ATDq)eb89PI~Y#_ZYw1f{_i z%Ia%~oj(nvf{&YLLjd{ndfKy1FDIS9dYE-!VDP-(joE0gVwo$I&f{fOjJ4r3dEF3V zR!pxU!khBiiRZx$0VyfHqxg8&jck%*8um1prR?lKo^m?(Q{fSn;^{T-tLxfXh?*m? zY3uliTbZzTEb%t+tU)yMTSH(>+3^3-ON+G_Z}^m zG8bgEc6$ClHADqwfg@)g+j8_`Js#y?0eeH!a2`U;$=7<6WP%oA@s}T z)*w_=9Uc?1A$5Zx!dLBaASCkEd)~}nqd~!uNLVH9(`PkLPD+~Iocw#TDe+ttDFRzF zz%|5?AP}_=jb$S*33M3lt$WS~ue>Knf9owLiJWsx3x-->Y&31Vgz}mvP)Ol%|DVo}T{*r(JWHNqqG8rJ0p_ zRW^&FyUDD@k^f>ydyZn0@1EX^5c!81YQF~}crK*Y1Jbq9q6|u zm=(t9B?3$D?=8r#%S=el;loxxWP<1LD>q+FlL9T*By9xt7DG7fg}gM#NdZU_N5sLx zjH!1>U7*s}2F{Y1E$dVmw9nb)7HZRU0Nse?__(G~S~j>0oqOjx_c{cBbOO?RBqmjl zjOQ}~_Z$;NTC?K!nf7`C@w-)qR8R#@!j5-wo(co93HzzS1alD;LTiU$+?nZ!3mv(A3BK;KN~tZwKZ1mF z+g>kMa~~flu&79GU|N^tD&Bdg+hLxrG12v2pc_2t5wUFq)EOJs_YL$uSyM~#o7tw> zglfLEy>YKh-7hfL*MQ(toTU|P%vSd4FJ%`-`|4WR#&523+72S${@Gky3~Xrhqc`2` zCeZFv5U!;cac%eGg%k{Dk71FC)>Toigu-$ozdGGreYk%@2x||!(GL{?H0>&d?SiZI zcOM37g2vfD!2or1%uxlc^%7H@^3uN_BC&0*lqJAdZQx&`&Ram?8)$ge9*)Uc2C1>Q zOeUwh3od04pTpX`;{dw-j??VHxf4{pl`*=aQ>2DZc}8YzP)hd`G_%bb2}n5da7l!( zUwxSNjsn+VjuUq-B#N}@Ce}s9b~kW5j=q2D*9m2YB!T8Bv-=5J0{m_w7ml32(PNS^ zD%(f9(x29o_V8htEOhs{+`c6~T;E=%b=%Grv5u>b4cvJ0)aY_(gIQ9(Hjd;NdAfDZ zpwhmr-F_r*EF*<=d=8N+JFmdxo=Yv$Jb`H%Qjjzx32^};Qz~T%!;LVnWp{NwJSD|R zp_Y(5RlQjHd0Rg3mGtBV1ToLF6Ji|za@V?JGOLNu?EsM2w(+@}H*dz=qnrZ`{{0Jx{CZh_39#xWz5sI4$n1@AuUq#kQmc(F`v3bq1 z4mY>>5_5v0UrPiZXu8_F2`HPM{(6G#w{z1&?de-#qNLE*{eDl={3O9-k`DnvU73_6 z^xcv1H3l8e%0bgK-S<9~qXrzvWc3YxL2QYrqv=rfjVaI4O^{cMqkjvx!XQL+E99RY zdcqDw8B@0ha!{#h7(MBk!KRhjvF4Px1L-xOl(t~v7wM3?*z6JM0*a9l#uymh=Z1$c zmJU0%Z>JXBi+K_P3$l_OxHEnKBlRVerQihpR-v<2#R-U~y$N?#Xe7Zd%Lg~+vFl>! zMx|rmwOPP7o3~7RLq<2|Om1DKdE*w zqG_|6|M>eA#@=EE2L}&>+uDy0Z5B7~%?t)Y--kd|{7#srBN*X2X>2qb^j;VoYJpMU z7u#U^@Kns%d7SM&J_i|eq0y)nvF=~G z?yZ(^y;s~5jwF4on!U^T)^18?{15^QmzL><#M8B(`=LSCp=BBq2BL8G7a#)@t?jd| z6W~r69v8vq)U3bSBsynFu;zlw@voqCS2d(6)b&9jYXLsk%-6C^xK+6ty6oG$9i zlcypL8cK7(&%02ceQ3(x=KN}XNZNHhW$3yKf>bSem41ka9uyQ5>>qLkw&gAmJFE8@ zU~t-ild0^<`1t5(38brG(0kUKjt+wvxS|U(wREvH)YfjCAG4Zg9CB#L)fL(b3QBuV z;Eyx$%R2s=ywyA@;+g6mAu+;ybi}tHVqaC})YMcb)C0DTKLKoKG;c!zL^Ngju5j;N zcm0}AXXtujzR(g{m2A8b>sblJL^i;QL6w6~)dw9F4xIkJDc8d6@001a5-p1AKNS<9 zz_Go13FT(y*r0u(W6Ly7Sj*>an1xoA1B0`q=-IYjPH5;KPW5))Q!qPVCHhJ_}`yc&81#SG@E(E%rM63lm6T%dRD2chyxW$32lOIGMpsPxzS87Rl;O13kFl z;4J#7U_?d#1d=2JkU{8TtBrg81^cX$foa#qn|ISnoW;Tk7_f9k70{(VQbF7s8LBmu z#s-KrMJUh&vClW7A=Lz)3+N0C!jo8mb;_njk;l{VBRDnHRc6@m)79qso;Mbnv$nx6 zGT%Vleqr+W_l<1!NQVYV^kGJ2ND5TF5;tKo;ZBJS{@JBYV?dsr*b-N_rYI!p$%Tkl zx+4y>#5VwLRgEEml&9l-oz6K{oHKVMc@+Af)xP*R)}J;K{-&Gs=gwZI9Y{)V`KC(% z=2=gCR}CL+m*Lg)}Qzo@N~BeGz;p*n|MDnW&YS zt-Y(?kF?=Gn=;HkPQ$>|4y*vM*d}RD;t0X)o@e*DB?rldDd6Kaek}*r87K?nWnj<% znt6MjnZG-RKG7>F3WpNh#y8&3(7*(QO>^00`jD$f?u2ozGu@c%LkwUS+en<6GoOQ_ ze97CXTy#-4E6K|Lbs^I++#J58`eD{8=nR8Go zZ`1krmS%>&ctUc6QKN>Ge11Gk{ zV2#ekyD`&3FRxo_$Q=O1^9pu@5NAlY!L++l1f~z#fcY~~2Ap&CtF+%K^HVA44#_+J zx9;R8@P+Bm>A;GP)hXV8r@R0yAc#D15N~^5b>5@ImwpuO?}^KaCyCxp-#CZwLC=E? z*sdq4MNHPro(oh z1}jXMDQ2klZE>-8VSN$V(4hEPDj9P&r3|MuAp=?7WQCPi`-EpZB+|t=u!X2O)8alf z0&zeW>1LQ37V=rR8=>~U*3DNvkFB!92H4lHU(`3^ z)gmu*+9+i69mN^%Ik`iP<)N{yD~JPuSZ77k3?%&1$ep5+`{|@S>t@kbI}ONw$C@{(9Xw53x3Bx3l`U;jo$_!BT-FgN0;Mozpre<>*blYjD3z z!gQV;EAPB{F5@Y#mOEQyNVX-_s)&|=Dv&|^EVJz=?3ER6(BFtidHnmDgFJBh*0OG< z);ON89@7T6)Z{^~3aNs%V1@{)VAf|R*StENHDx*%y_KBa2JTT8Qc_~+H0~1_Ekf2| ztD5An9F|(vghE>v`xAF6f=jsDND7+Se?m&b23NJv>K5gEd$q&&X1KRhk2QC+5v11X+JB(Rzobwh?;Q)+pqQXC2 zK%thvORP&D0jn>YrNl-AY+Hzbzv{9QgIv5TDUpks+4|ltA!D;=$3m7jHL|q*x_kXC zOPkLqu7m8or|PO>jg6Mg7F6${XvOdNi@P`bxjsIJ!qN^yXk;S;4+k}hAy~GmyzlFk zjWt5#)Ky$XFlKX~9CnDuZcp%k_VG9!_!|ZEMAj?VD9@4rdkR;O^SF9iT(*<2KKg%F z{v>>spvTVwtTwam2A(ZkZ|7QKdJL2$9uKy^5YM#rAgrVNMwbxp(hS>4YAuSTVTJ#q zs3aY2Wm|qc(x6FQAZ8AQ-WX6WS{kZZc4M@ z%DA}&+;f#s;f38%;lM@pW8l+1jseQ4u^%rHw>A`1oj+ z@XS6Zc4!jzk)i6p$FJIF)ZbRbU&6zT7@pK_R@|Lc^4~H809-GCpWNJdzYDD?qJEVi z)<@7>=ZK@~e^g2EMM_J8o*OrZ1E6l;e{lE&TxuA8q%K70pqMRuirAo(DsX(c0t5r6 z7L#^v=FAiclYvZ4CFw-%OCWp;z$`bn&`qlbbA=az23ffk394KwbT7Uu{Qb=K@jXX2 zGVI?8zujz4y)1A51xBaYY}SYpy-j-J)c3bRsbKGckZ}3Mx2gVtJF)3tLRRmB5mR1x zh%^&H1_r51iw=XralL^FC6eK3VJRrLSMpxF95XxW?^~F1OKa62^|I?39v;=s@C&d6 z1ViVIMZ1W9+s+Z=FSPg!x>wf}ZRF!Ir%85D`MW5TmNY{pIl0q+?@dEnBK5+Xl^uah zn@P=w?*8@&!{aaQJm7uVU$ZayZ^1&y$$b_yP8dkfXjZRTW&n3hAsux1_;}yeJ#w`! zF=#&VpnQJ0g0K%%e*+G7!=`_yjZ}@SfpghFUz@%3lZw$f){-{5H60I3tQY zQTj_`LV(NsbA>MNdE(T<=D|&~Abz|%=WUAyF*Mn={u@LXF|bBw8GkD)_a};;(7`3eV>`#Q&_hIat%#Ls z8_^PV2y%1_P)>td!^4Y9cy`UDjE%dw^?g6b|F6hLRGCaG9M~!q{cWg!Fn;Nx$gI~6 zd7%C#<43&aLQDYH@o~Jmxu|&eYv6zQpF4DO(_MDlC?wPVO6rq+#2!fOqYB3R@;PxY zX@{Sz8gHX~%&o;eu%3aL!oz7pXI*EulJHp^Ct0Yen%y-P{`c}LXgbPwkxnnP0N}Z7 zD+76t#Q6I;8|LVt!ofpMPLBW9)rP}dt3F@mHzBeEO75>DWSgnTKoH81jJwLTQqhL& zPuFTM>h3$iK{u4d*#FTSN+ej@yo|1v#B$IZ?iTz(KYqii+Exa7r!PECHE5L*N zH*HYoDoK8nAmv;5e5lA3MHWiNLM(%S;?i_mt9SHrjjsqXg!+X%;LNq!5)tZeifv2o z7Q>mfKRFPAR!D6Pc$AYv{X;|E&?k{`odZ5j8Bdvg8> z-{TKJHsZu_3*B~@G!EOBKYN|_o@}ZCk-fbP-T}1iI#Rc#*m4o8wrzJ#nwlVXL=0+3 zf=>_$9-jZjEpP`cf&Jg$%gycir5C@%-#2_~)_pVU7RgOsxxAp_n0!-#^R!$0y(S71 zzpj6Y7+$$5Glpw5p=0`2LLS1r%vyg~JyPajmdjf3T(5p^hQ5pDPEsj{=kK&2*b@Kg z%N3LD?wdDiFYXff1`MkH+-&smNj3EwO@2Ey?)o1uXKY!Xu$U~^j_Y~&jjToe22tX; z7VIy)7M8R7B4@l^qt(j|AQ?nZJ~fztW8CI{dreX9zdgs{U#GeUmi5QcrDT#}n;76z zR%K9^9G6Y9cBiHE)O)i`)77QAP;1j-dc6t{}RL_Lprt&^N#$Vs1Rlg-g+T zXx?hPkC(^Met81pLOz<@-KR2Y>n)GpxlLoRAeF&%#{>2>c4s=|vtij}SuK8Dc3P>0 z(EppZf@V{-mUz$)greLbO|9cb8~M1+39_I@K4~z-Jo_QJBvr`d^2)3VTxVni{%DL@ ze#*5A)&4rlU^m+a^cF;TJp)6=YA{SHkfXwA9&-iVvd}P!IWAbTLm9vbvYML~zTRU_ z-(c9g-JONLzLpJ=*6+-x}WiFN8}pc_R8>q=B%p$ss2Y=v}b zdua3B!$ny7z~pnP^Yqwio+a?bcXx#~?*55dL9`dRT+z4v5NT8D;n?Ns+%-5+ex*5Z zA7o7MNEZd8csyrY9A+=@)IYGt7>To?f|A;u8L|GC$L8H+k0Ok3zbv)`z9T!`pMECl zX&z8qejU8gSu*jf!F9civyJ>M@|B<WfE-+fHg6K1}XbW z_R~jpbUP`0|z|uHfV0`y15|5KKAxQlLZ+m6o%*AIArY*7_Kw|b3BAj1&{f4p-a$M)mW|dw-oqLeg-cR_!3(da=}bjV|Lymnlu-P@(Guf9oPATsp*D`e3QVJ)>oLTFYMeX$MZem}t2Vg^BGw4dyb%Crq(H0#P ze99g4^-#yxER)wLLpe{?q_@=QS?UuLWtEm@UtZxNfe^M{8V(szykQbXhy zo61dq6<$w#dYH;gk)J+dHgv2*d!rco6-`g0>jtm>>Ax)WQ@_%px$eakJTtuK+=MuI zje*?lrb%p4(cG({v#WU{@#$&Q>n7!E=ihI)Cig1?!#%cr!fS)2cZRy&7*CLHh)JSb zLuza|hxo0Tp<*Rq#1;Oo3${q>Bh@o`7dWbZ7p5zTjeL8{Vw=o#md#Bmqu%H5g+FjT zZ#v(q5xwcs>CNS^iCZ?nWdWEpCWAL-QE9a0%s{aHwymqyHP35>#cF$BKR=ydwPC?a zQZ?xM?!LK}8gzUMAgsMU_m6r_;!{x){g0PqPbHr7Zr8JWN8W5M^S%WbKzgC+vUa+? zcBhtFA3O?n481Tt$VP+*=#ImgX?@@+qU^``gRn6 zI90yN9cB~M-{e+a@c##5V^)|Rh7>~D3T-_^y3wTkNS#Xz{oikoss0?-XD~2A$6U`HoO1AWj+zQyv=_D< zw`Q!$cwAj*zEM91slte-iMKY25Dk3{d(GQh z|9#f*p$31{iqDtho;)LS8`}%1-r4pDRXw>F8+Si8WT7MqAk0>(~}P2g5PGF z!p5llH2CxZUtvOC&b%onf!>e$Sy{(8dP42Fe+HTKC?6 z)}*SJtFn`4(31^Uzv<1*GdJ(*iRI`TN13R6aosr8B*_TOJAtK5F zv|PFojg{<0R?It+$FXRd>laLDi}bFoEzLZ0>*StI7YffZtS2av!>+Cmda=R>ZkKRYI=?OgUg0TZ$Sb#%{sM6fF(PZRi4U#~QS5^sEbgsbm&*-L$4F(o9 z-iwxAmhF^%$f;BxNn&Q$Y_NG`=+@;wr9o?Zz32NI*4-b^H@U_sPe+8Wp(hT!LEaf; zXu^(OWI+1)DnImBN-AW$t|JFM0Il4iJ}kh&f!sq_H|fGboDF$Dgx7>15f)9-=mYV0Y*K5C3BhJLl6f=RdG-hXh>d194vWs0rS6YR zi9J*cU3-=ur`O3kVuShxoD>V!E;9lIKHfy+*_5G4_v_z3cq+PZTqr&WIAInf?#C8h zfxKUDaBf7J(|cTNpZAGd^WD8*Q!Y5kltG;&(2fdmH|f2Gq$bQ~h91e7w$MX&8#EUc zBT)$SzS=-hqs)s{qIC7lu?MUFc#R)u>&mifXTu~ZlJLzzHg8+vjQFfs5d(kaJtXZK*FdB2zM_?il}kwkPCLlfUh=uH}3g+$xL0 z|Mhk3ISk^noZ2IqAzrH&w6K6ip&Iqr*O}(T{F^*9GeH-xB%Cm4YeNhN&TWA|Ls(w2MRN*q5_x02kC|PdI^J|^S;sa9$Y^&$d$}VJeOby)*rx}ye@)6ia?EU; zHEHMd^s+(ckO+|us10(p0Wn-zrR&_tWho0-I7(@6qDqv>i#A){>fuF4yhr0Trgi_0`WW0)`|FCOla2gaTvW#@sDskc(G3G)dLM8p@8g(|XgOt31mj?^p&MIZ z=H})Wx%0q{G;hrj&a`Z0*2^?^M=q>k*i^@ov{}Z39q&=t0q`?Xbx(Q|fZgR`0%`QH z8VUPk4$tCgEbyS)yr{43!luI<_7~W6cQvl9J|84n=rSK?QrvKVC+O69smeVQ?+4UkgcE5lF`AHDv#G&xASJ3?Mvd9K?d|FN-34BogSn50K|hX ziE$Z=B;km|5$mlEb_&~!a0W47`xGw8|Euc{x#~Yn|Tln_YE3g;RbHmVryP9I}D-2sQB;76wwS0pTt=?G&L+NXZ>GQOxt~)SkgtrEPbU=QC2A`Jpj| zJ#UH!y^AWY3&E51dICFLJ`O4+{nfnJ>dl>a`x!3yr$lGvSI&;HTr^etEnJrRxnCFj zu$)I=^7Wxg?s&M+@t*5FOGlV7!n}z3LZ17(XB>fcgM^F&{-Hn&5Zq(*H0!{VNGOSg zSv+^okj*&Eye4$ka>cUIO^Z3Y?GoNrZK0zpSbKlbjo+W2y}9%xpNK$y;?gZdxCBHg z#W=(Sc}wzRFWJAV8X9$wB1cS*0~iVBv~CO(!Iwog3Lt9=yYLdpKhyAWR!H|c*8YGe zCboQ1-=+9x3=%Jkac+3->iWc+(WBFaE~jQ(yF)jOoD+@Q(Vc+h)gC3Pg960=&Xz1I z=NVVtnfU#XR z?6WI%Or|C4?e~z7jmThVrnB&ZqBFzFI3!LK%AvzM0Ot*+^S~54&EyJ!6t6E_Y zuk#0r(pactc-{ULN;`F(WLm?(DgXO7_Jl#^&x=0I`15qd&U7D+Ji8LcDS~WWoDH?3x{A}pANE6LJ6oXc4;;kx&xTD zl$GdtqY|YUo)zmqvHyQmkT)dFYyCBrP&R|NXvag-v26l-nAFlN<%$6hCHUmBonxh- z&=Bz32a(AX*-u|qKjl&vCf4aLpyh+wNY+M>-=_Yne_d&@e0@B(6B45~YJoNxzUAkF_gOD#wwsl@Mr zMc?PR$TsPH`>LpE7Fcen=wk1!&ozVg(c=jT!Z1>IvzSGIx`)4fu8<%&+ovF0+NYg; z4P=sf?HXX=B)?9Pe7Q+!!{Um*%T-E}sxMqw{=v5S?EVtJ`1&LVSOxMPfSCMP{w$~j zllwedo5}pcz{LuzHu*#!w)@H_=oi38NPb~EN5NZwjdQF@tXVSpf(P+p96X`jpc0CJ zJ2X=Iy_Ylwfy-(iSPq@O`y&Keq8K5jLt%9I@c(-f4(leNXh`~l$WW4T84JhE3Pn1{ zK?#FK!Ga>JYo&4gxyICs@`<_`d@CJiBh+_o8heTaFyUK|HA}83tMljFbkrVX~`OCVfe&oSn&*z*KM^4%O`vo8mL4=|`i z0q?a-DfO%1nJ6Gv}ef;ga# z#yKYp!wDTjKG>2872$w7nCstO9NoB%_jF;(G5*CM+=yQbEp3UFin!<*>2y3usTF zX6&hwdVLAcZp@SaT^${$MLFtWV>Swk^?yc_eTKFXdL|+8#7P-;Va<2%QEsNVuX{4vs;CDpUV#S6ssFl*t zbvL83xMAM$h~!wy2To?!RZD~Rh-$p@caqAvd~gH2cN54hq&R)w?Kmejb3Fd-t!&`5 z9PdJa4+2rx9C{+a>H?;V>@5YQQo4G6ZJ5PGBCchXC2Rt@vUQsADuEao!@+C@&py|q zH(oY5KSY;0*xh{Wwkzjt*B~;kIs(SV5MVpVkSZ0?{PiyFD+Y!-Q(=;U8xfq<&yEg1 zN^#nWzClSCSaMNnnKk}}dVuNj!rg+d% z_VI~6;oHa0V@|N8e@7z)N66QgdhDJ-?2Z1TTl{=Eb~leHmB2pL&IgNe@?bxWaT1yz z^eK?WR9@&8`295NTIYaNXwZaKVAD#3f|g);8<}^(o$P^hJnU+8A<>_Q?n@kshZI^z z!IQK}j=1vRsvg)tq5jSx-63l)S_5#QzjYDP!aB4(N5pOR!fuJkZ}AZ9-tx zs0UJ!2WtVIf|J_-)-Hzlll@1E-rmYNGTzWXdi_ted>3qRmT~4t;nnM`W>|Nxcfwml z3k}S!T7Bzr~(wH2B0~oDA`tO6R zOT66n-^%TpeK7tdKScwicHCuXyc6Ds7XUp(`+ITmWRHyQG$-1GpD(5~#>PjIa$mCT z7+2!G7L`o(s$khfAZ3lTlsMlE@`Ey#>%};@&F5ODjjSA(y8?srJkDWs8qaO_gctck z`ZS!IVsmQcPExPn&D%v*7c5sb!=T^5jo4=cT@l4Vi`0cX5KwPYG;PC8&OCxm7w>(N zfQbJT3?{>ASEv%Wr4Qigekc^QC}s8XgEPEt5yDwDC!VAra`d!i^KoijxhjNY0YoH2 zJF;JCs7Y-`?sXObI{tj_SrEC@v25kap;@RGFqYt$Ld0F_+m`Rd2CPey&@T%PSOys> z(LIW9t-=3;esc^oOw&<*XiCbFD!Q5Z+hEQpnOz0a&n<{*XtDjkZv*g`5m;_5ae&DEd`Hg*^&hAK z;cp6Qk7H;~S+kJt^nn<}(gX;cVaB-?Zf>R-%!m?`glqvx!-&yNL-H90hH8*-aL+se zvA7TE3$WwZU#VR81fEs==#CPv4|b2+LJesk(SB2j9}rdS3kkX;^`RHrO+=GhVxZ8; zl|?#!`~0+_j|9ikLwq9Ce-cl^9M8shL@_2S*l8s9=4(^sq0xtX@b{21I__sa=D{lx zMHW2lc3$0xzx6pGI>@0SnE%~wG0v;{1P`a9T21JWmclOCNj0C8+YXM4HNzh1ka|L2 zp*o;>&;vZakkL#UVxJ;4ZT9W#y`=NC%l?19f{<56?N7wMk{G2Nb<{xxfCelBlXfgW z1quZ~-T0a6ql)V>S#qcx&i}q?P0?Q@tFaYaw8c}2moX}#O?1KC!0ChdY9rh1VZ0qR z(e}!S-#-eF97F$HT*v-&f^_+m3z%%6fD2v|nrdL`KJr<9@<^h-KpA#|P)jwGPxTFc zU>u+Q-FDh(QIB3}QlSlJ&TxYJ=yrf}dO{Ck7zORA%7-YyO zy;9Xc5?~#>>$sIk4G&##wI*hAP|JDGjSY!M_Zk8_=&Wx>u57uM?i58(h zLKV=CZKqxumP=>V^^aylXQ|*5%&&)!>})ZADxfK_IWpL~+Bsa^0%U?bsFWMPMCS5Qnh~3_(H;j!N!c4U4f>ZhsV1SYJLcm*?H-WSgPeoo7W505P;y#rEct zd*=EE!1kU5djQaD?}{K%BQY$1$#(O~F{N-FFma}5p)BXiY^4?u!t<}H6WKwJpfc>( z4xtHzf~p^bME7D-o3kz@%c7YP^ic&_za)C}%l{Q0jjcQkn~&^2UlZBqNk=ulwm2UW zfbyB$;}MJ~Hg=rfG+2-v9Qg0#m2)gdbn+)w7&CY+N;HKbhCXTxpp(S5p zSN0k*ZQlJ6*nOFheFCuO7b`8G6o-5+$WcZ-1AoSO}kY1+iVP*&L} zBQRB!I$YW~yC!I%-0Zu7!-5?er8oClfd2j5GNs-0{={?pp|EPNtt)BQSuOq4iPkEd zb@O4p-5_mcFCDs$+cb#|xkE|@5wJ)-_ zdP|pmQ7ZWT0}R#To9Y`^)s!MJK#@{SODsCVStq5 zx2$76EZ@;PEg^oWbY7}k`7-y@k6bNpchawX$A5I?saKkE>Gd9u9pav4$e3@|iEo)9#&H@R;67;^i490(qniP-K_ z{;|<$Od7UC+fc*qlz>LZdfl|~Cm$0tr2ALl?I|8CeBjp8ujuM98Ym$W)y9p#gi!5S ztzgvAWC<<`b$F#|7h*XosV^GtO|>p^GEg}S?6KQ~i@6w0yZ zL@>MiZo(1ZOn115mZNjwdiYiV)a5(ep#; z&E6ygbDdD2EjrT)WHu(_>+uu6Kj`jK`QrLq=F`+8x-NXcromS4pKcoiqS*zgs*Up0 zPM64j$49@L3hP=K*D^@Dd$O^-k31ZGh013}ty0`(mrtu(jD)I4s9P*lx|w$z31t6% z+pGrnLkSmE@m59UFLUTx4%Z!(wOQr`a;F(KgXG|0 zEVZ>}MnM;>pvhNQ4rUJO_31ZHY&Qwi1ZSEWDl~s0nwn! z;YZ-a{dRHjx@*+C>ak?ip~)^-Ss z$;U_!i9Yetu6XWNT-J@o@j>s@a?`$rd#TFb^svHPX(uTCfNEKI6}$2201yN0PPwxO zp}XxO5aO7Q|017G_2xQXZo1`rL)k~VwbU)HJk!0e$Mz-AGzk9+0a2D}0-mDyM6TQB@pg>G4Syy__}rVA(bV9v{b-0bjo4|q%rt*^yyONgz)bIY7J6+R z=b5Ci z85^g5BX6OWPhR_J4B#_x)I@riyKp5D+lEKRbuyoRxa`OU zBvJD|4)`#|Db-7bZO_l+*UomW{rfJe?WQYCyg`0AIpR?}Z2}Ab7>D{q>d$@ecgb5x zc9aK+T3L3z!%K>*mB*DE8ptkIe?|JzXN=?A`Cf%QtC1tJxr^W?#84X}jS_H~59Eft z7ZMcQVCC4{+$4lRH=@I4)wJJoO2`|`9>cThnuY`r0xy&{e!Yyhk@-x6edm{U02Zf9BjW-2ir_3+57{fcWB3R?@g>BrZLkdl zg@iU?rw?RXC5KbXjuc_T$$D_#EgyJ!W!l`vYllR*zYRFAO-G`OI4^2!eLxx?f?}ze zVy{h`{q93%#S%&a>)0Ha9cbl!d~h(ktCJiBymqZLc~(rKZG#dgPO@J(YgGuN2m`^! z%CsmBtb9bb{Hv$L3#Jv+)#o%!h+JESfVjZlvRF zHuk6cCGy5xrY(|K43QNSD{@RMHA#S-99R3vWAYB*f`$HW$6l9&lmcgCrh)&e6dgu%9x*9WRdr(Znl(pX1zX&8f->vVOtgAc5565w z+LwE0wmjBMzVz=M$d@gptje?2Gr17tl2O~nP7rA@;%oz?qIx#cwD(HB+VHEZj?zEs zpscD|itRC&`t5=NTo!fKVOu_Y_FwY=PA)sP=a%nsIu%WVO=~eA_J8O7L;jWf$|7MD zh?OW1pIIh6f0iHW;BifSScxuH52H$A#+$@tK`V%%1!_`a`%Y5XJMfh=MJLb}fhz*@ zosN!a(p=B69;)3Q6%UYJ>cv>R7)_eSmS2o_6%=DP`|$tHu{esF^)QibhO~eKY-lB9 zEf21Ens@3;nE88c{3{+c>RHx-EU+)MQ0<1==2A0AAu;cG6l>3}nqCwT<8?GOGselZ z*30OiMxM0rYugLkO^EB%RtIS|Cs?p$!DrZ-7 zuO__X|1PB_@yYu#AMpXkh;8y-0CQ=7ON%mz1sx{8cxeT9)a-!@4x0J01m(>_W5GLj z5aHcK1OGRwlkf8%8ezW8;~hV2H=ff=sy{shWv0f(tBaen2GQz0c|i;Lxm2^4fz`&; z=kMYE9XVO8p~^P;eBr&2@0s+$ngE~-u5sBH&1GcS5@e#;PIqYshZ)B_ix!+d+?sli z+xOh|U8k~?0(*$+s65GaxVKc{zLVvZ=-`rd65omq{z>)8{ue8Yj%r&j$bwk8z2Bkt(8sXWH9?WJt+N`R zr}drqt{c@L{8t3>dEcu^&^Q^-<%x}jM~HoYI$a#3CLuKCz-O|CiVURu7k};4(nfBN zZ`U5cTd;2el6!+|(Es&KZSI>|%8ln z9H_rz->oW7Z+OE^TjW>gASZcszw5}m>n$%XU%?-Jn~_^E?ueDWZ10)inqAbj*~PJ( zr&~T66ap?t32f>^bG>16yh^n{1!XOZ)l?l%$Q6 zn}1;LZsL~A#4XKfha8^q-Rtp%e>=_VPjIuWnofKA(%G&|E^j_wqEqJ64OQ-i(^gH2 zr%=po8Z3emh~U?<;4vn^UXithwHWOfs)b|{&s@51$6h!W(Q5uWPsvbt)V{S({=#*0 z!5~OH;n8!Q?;Wbbqi;=BXu(M_hOV*`yAQuiTCo-H{o9=*zS=~W->6BGTnGL0 zK$|3p~v}oRw#DcBN(BvsbxXzgPfDigDAl^bb;S_$kvK41Gga;X5ZO-hA}l0XYEW>C%x8|TK3r(=#4^!JJn zjI+Lr8u+?@QPn;cIah~a?9?^6MUO=4 z`DrnTWOyf2KQBlN^(v17PnqB0a{2Cabhv#;TuSxE59zo}i99pDx-shW@A6Xp;LUiW zF;g8A{o9|#wo=8z!2aH##QLy<@DPT$>(#dvqO^9^@78K(--4Z^h1705EQI?l=KIRp|{4R;`bA5t4#27~$Yi zn`R!k_YrKC4SAdJj2^KIVJT4+95HvpeNbo7MoPt9Jw-|16n$;o4vp`&FH=(Z;3X_- z41(3v*hTHxw0vodW*$`<40Kro=K1qNf#qCvl{Mrv7U;5bLNA>V*Q!}r1bC-ws+tFw z*HG^yB=N`gM*TQ{2*c7;QRFek!NY(V ztdDOxt+fg~#iD704Y4fRZw=h9-TW_szoHnjvS?CWQJ2L0{xv)ix0mxDiMb2!l?~$_ zJSZmMa2-Ervebaa^6xo`9)nx6<$Q$qgMYUPJ)Ey_?nxvq}qiO~6>O_xW2*^ziBp-6p zNewJDz(!mdzr{YY-NE6d^P|&a!}xDMGNcb@SzVzfVkIj1chA7}XkQ+c$$I7cYgOX4 zrd3M_18p!#@pJcUZ(xrLj6}0(y!7}|%{6W3kDpQ9$|lsk&07*;whQDmwOm(Ox$aq3 zY;d*P!tKbJ40VU<@Rn?qA7pRW&)}`QmV5NzSKG5m0Tp7P#n~nDR)(KVi5-jG?9A26 z1Yg?jz0$=;i1qRdnaP9Robe07_)Exy(PtpZzw1bfJ_96O{Le<7iBVTQMf0V=iCkp? zih7)XQ<(Ojhf(L?EEMe*Yn6Cd0>ct%A)E2*e_RN^I`vaxc&7BXp3dign6PWFl4A;UH200^`# zeV3QG^}Zik!JDax_Nsxva&MQZq)O+``Ez*&XC?b7vB^?#o9ptF-WWYTMqz>2alwV^ zF*t%Q)O=;Dcj&wBs-s|qminoGR0ISoZ258I}#nd zhelEh!{c4dmsrJ5#A)*VVJ9CsZ8bcyIR`Ogm>}v^oFFjiqVHIC*Z3El`J<3)bP#A4nJS89+zGztWjK35jHJkmBcn&u-nSpXz!VA%lSjY z-aIELmj||ldF*YSI?*y&HFhe^go`^NBUb-h=JQQZNX_V&p#cHQ*>VUVHZg|<@QxT0Z`HiM`{NYNgw5NF8pA1~iJt4`$2>Hf z=m_8GHdvPFLl17pWI*mc{D|zSDDHENW3i$Yj z%5%eV3JcirKZ5yN`2gsxljI1=2G0c#-q15J@8IYQXALtmyJvyAdXS`Znd--FhVtG!iXgb?jWk=Fklxm+WiDTPA;v zeJSXV+ic5N5yrH8t?s5u=O1mud7NWrwJT`e9q9k^tvYO`H0?rzoUrud+v)C2rtBdn z;8}E&0_}`09V5N5s#f1+3L6=ptDLERY_Xf3DW-y9G2p4v67haew!F~R2xaR)oBi9s zis8Kt@-y`wJBK55lHF#PP3sCBCYoLg?mD_JMcu2=p(J(KqidaqT5Gm|wv^;H*lApr zM%~%)GOJ8Ac+Ec^k0gzLj$RFKjIW>H0WDsh-8A|K3zxfBsjy*@io=?Dj)HswbxB&xX7P zjr=kreD5R;w*&@C;dRuv{qB}70DgjM^Ovq;dd#ADN=8xmD?}pO=kd>!auZb(vwtq~aiCo$RI4r7)|wNq(tptm*in`l{!1 zH@@$B#Nlh$Vy}v7DJkICbsg&C`aZAkOSSx9{Bx${>x<*#x<1*oFRs>_YoR&sA!qr> z>YPfmG5lna*d~VAd^>+g3ex3ErC!V%J~7loeM!BL1Bj+NO&){w%QH*cot>|?6u3-p z{Mvq5Sd&KVt&er}NSUW(J5NFbCm20{t~4;a?=l^Zp#v@Z!d#zK7ayW+$9a%uh} zIT{0S62eDoR*;c2Jb#e4^F@`J52NF9D{D_OFg$!A%TGTlG)zgzaQLH{w}qfQ+m%JG zRMNgjZ{8ne4zi)ywd_N*o$t*8!){rxPs366#P(N0KlrJBiUIez+>1x_?anxSZFgI? zn}}^_9kgJ|tFeGAn04zMH$mYbElSQ|;X5iXOw3D{ZVyYmscr~5$$hZ>X}In_!p95F zwoM=RT~R1Fjiu*YdOv+`=64{nTKQD8Vg16zd>;WwmgqSF>!Yo>oO14kkIM3`J(x%O zEdb7s$QWvlefiC7EsWlts!?s0oRgZz6DksfhJUsFa%VsKT`^2s;8Ew+>9xfkx0p&m zg>0D?_<0c+Ye~)?T;j@eA5tx5+JIqWS$qBdHjrCVOu+3z}rL{IIjC zPAmBi-m2PovenrvVd;6l(cyXL{^W_G4_@v%vwg4QMWK4_M$MK~t%N(ye8@=jNP?Xi z+D2{=bm-uCnQn7^kKeTqYoZvG?s)fJj`jT=*_?SraPHd`8PCer8H1cP!1}rsojgji z&#~(b$8-rcBlkenm*JwPmv)@Q7yI3m_v68+>Sc{nI+!Ond&j z#O}vR!yjjtT_|~dztcV}caN%mfjx^nBK#=pCqP$Rdrvuw@%*8aX~5R6&$_*Ld-|WUeDlfO)M@a?@~-^C z8=4qO`>@d%guf^)D|L4i6VBI1i#N`B|*N(XJ6b35|^!E(=aIgSfEx#qLk^o|eRhpj%5_V~+fbe%q)(Z1LA zIEm*{yzkdWYti;X;arH@6~L;U*o8DYPQAy^dBBB5ut&MBFLZZ3l<3F-2`~!SB=7g5 zln1~y`RWd5#bZeJmLNP82a0L3>1fUQtfkU*ZQx5O)$hzy|?_A@)k<{D_{@qM98X!>cO2zJ0@URI6JoW zZ6OIR#eb7*Qiu`7kr*~WdzNloJoy4h{>T|MI0Yc9U^L05PD`hPdCt@AI!w6lj891R z$jbZ9Prfo3L&^jVQdY0s;Au>P4NW=uW%u(E%GEoepuw8;#1%lEWrRBUcfluIL z#bYbS?A|q*84krdmX2brG`O|T#06A8GtQ+eir#gNn0!vR{D7HbL-EJyL>l7VauA!y zBmhSsC6pL67)Nof~cYa z1~o5WW7a9T5;_t*0d#qOrnv}C!4)2cNv-?qu8mxn9vc{b`8a>i+#j`hA)q~asGExo zB;!CuHteC3#{uxKP~BXJgiTl8(?nxr_iU*%=J+kgY;%utoJzD6Q4FP_-hsZg1eZcHokSS%f9NCsq zZd90IZ%KL7?6t%NO9UgZ9ia5J6^OMb;y`NE<6%uGL!)!B?0I=cfzVb*ZKmG#8-Ar#O3l9Jm}Txa_)+S=Nd zPU9@72}IXl|GMg2c5?<9bO_SjUDDm%T%=RFzd88+f8SZl^}YyRX3os) z+41b>p;d~z1?CfiWY2=Vd@EJ5)xBy6u-c|S^m2uTNrvrHI}K*s6M zK_!6l-nAq`eRTtqtAO{T?F=jf1;jX*(2fl=&dMnIpzw^`OV?!OEB(4Y6bLk=vl`;) z%u^Mvx}?m$SN`J+y@G;oV{uvNP5Jh-PlDl9uN@ZPq&Nr1z^A2j-=qzkCXL4j-bE)! zkfrFkEh13{05K%Xc2~`#RH8dA5Qw1kwRr>BRbh}?kmmKKN(X?6H+F!Z+iN(>ZM?{Z zn5%yn^*ZlE5=0QS1M%L*&Q9on$4Tiyj!J#bPtMb6(?W=6aT)MDhC?)IYA(-CPk4sS7pIvJgiR~FFOn> z05&x9`BBGeB%&h#7)VVt=`B-e-CfkIGj z=JD-QY_G5)aAF`5c*D9iNGlBL&VX72M9p6SygbzTf7hLy5pOXKcc;8P>wp7!mr%$y z%3toB0G)C!U@uRd>Vbq4ByVALcG{&0ZZmOk0Z-KL+Pl^nf(E1m=;s7MA&}OBGDY#d z=`j=}3Nc^pjj?j_*ouWUHzb|)M3a*j@);Yy##{WA8TYCjKgtdk)U~jSKX+vS@=>{v zhyATRLF|ijFu&ARqV(A25F_|Ia370sq-CdxXFT7IFbTbJ?wYt~IJ1QUx`dwztsn6)}@6GOwf(926_{r9Y?Vj8y6RZ?Y{n6rhI`pS2;fjS~0fy z!=%$XT4^cDaaxFS zY)$sKIUx)QqkWr+SR`o)^XMnxNYod>3%-VS=hiO*+^pk{sYK6BUIZGDb)#8#+F_ z2T4%(?*W(RA=g2OA-|ridwDm2sdK}B^+7E>EtEI=376-9G8Gqq9f))RSbapZaANBY z&hB}$=GkBU!mI9lG<>|RQbp+7*A?nk$SHu?PBbD~}d8V}m6D$|E2_~sA7&ep&rsz85lX1!*<^4ZYU&$OD}98Va((1t>2D{ZktoJ^S66REr)%8^ftbeZHi_Rq!}lt_=e91HpsSgiEB( zVBpxg9Zjz?CfpYGSSB7^TscQMExZj2xn2AII&HSojE7AMEN$NpnArCror$lENbUlx zf*eEp*IO0aAwn0UOr`UuTmE~bp64ZL@T_OAZHXyhcI9QOq`m4ZawdD@KkdLoo5;pq zs^Ker<`RP9C%OzMOkjxwFn=I|a2|46cR9BgCiU$6MgGXf#zt&0lputf_p`=^d5Q(z zLTX0R(%a5@d(D8l*%FWxDs1gRjnTl_)eoPb1!fnJxVxELBdj#%V73(7Qq@WhevBMD z%gt43Lslv5%?r2qCWWj`YK(A(j4@>whg`qWo5(+Ry6eo|U$gFNJ+~`2R}{SgWpIxF)sh`KTJ;ti@xOvX;4FV>!g`-R+5Nda!tuciGSFoHHop;YDsuzL zja7CUFIn4;*E8zF1GJu1%ngpGX-pfro#0(*%WW?0IR;sRX7bVs5UeKL#;U`2WvC&) zLku|d*3Ok+h{Brs_D&if5V^Q6;<+C>nGH8XH#w+otxN;PT>u(WSAp{2Ty!g&-A+(Mx2b=!oL3AIJ7X_KuZ# zg{e6iR^PM1y(^pv!bKV6#g0(f_i&+`wFc=+5J1OCWlNcUpW|JlsNW4m`;x(-P=`d6v$ARW|_<%cG5Eb z0;Hy=pY)(Nh1afzVX_)T0{XNcno+8UgwB!Uwf1yS-z1AldB`f!J*z`K&2;>zFVAB0 zcMxDJ$zUsZVxG6C&dACVyK8aXXK;R>X5V`3W$F{|yPytd4~IpR3UKYY+0k zAUQJPy>p-vl_0rb9J4c(2&80UkKI9gRKJtJzyRjs>@Gsf9J2VbAxmbE1<6z@NA~Jp z1J#*6VXYHrKpqu3RnM+r!V$kz5GL!y=6?}%6YfIp;VMIJb=ntXLq)^6lWefp`S2$_ z*kN8*rhNr3yl9|i5jIUB(Bb}a=N2e+1_3ONOZWsNMehXk&XP7B#j&!o;(*tcaFFyo zc@Btvu)~jm>?0cuEv+6P#g7d|NKsPz=&YxZ9?m1Fm$p*F#0Mw#wC+V z({wsQIJk)XAznSlND69(Mq^Eu*A}4$B;cuvLTgCdVO&O_{H93jtuU-GHUVKTgRCWu*Wj_Ij}mHmN#!N5TL9NbHNbbe_cb50{`fk@}}44WZz|=yHx;rQTrn z$D2qU%Fi=_k+7(IAg7oRMp%@dP|lwb9J~5r>Rk(E6K#OJZfCyz)_9-OHPCV$D7&4S zZUjn@FLxS0l!h{HflW?%_v>ZKYY?r1FB#*Mm6|`4>u?KtB(^ZacmwmO=Co5PLHZrk zVwZoK*QyN@!SH?2o7y;HhuxB#MZhoDE+|pMV*(%nMzFIHo9=eDmZ^g~!qYM!KQ~!! zy4shDN^bWqLysGXXBpNtfaV;C{Z<#iE(h$$B?PZ?=J#p8CcVNh?k5 zqji;$+6VeSJ(U7vd(Hk;L` zHDyObLs!)npD6$hcKSEpBtc~ofD~?CPp(|^3?2bN;^gemMLr+g)X^+}kCG(pvNA-x zo?>W1F^oF;L3=6o2eLx$n-t=XxA0-~Pw_-hA!juwP9Cx9CwkMkvN{dOprcaG5Zuo2 zd-U{v5=hqwa+=xj|HQ!#d)xsAuL1G&8rBA!H)+%kfa+s@Qo|v!uSu5)$%ElFNSK) z*2{DC)>?O?1T3I*-gO%4@8>E5mLrcjGNEI0odrFTZI@VAILx7p8Q{2$AP^*{!dm|yCK1~Vh%k}R&!e98^uwp3E zurm4V;CI?z`+Z^%=>w

@asXK&atrJWH;0=w&`naEEw@-qw06o@d2goLl#?=WVhp z97#))#~k?Q;}#U5Tvy<%mSVPKhvdemD8TGQd}$ z;L@26X-2efy?*_giMRux1%c?8UigF|sUhFW(p2BL1Vu8bFk6N~&f<`hC+9_MZF zDaX(_TTcz!mp9)kh&L0^K{O@QK4m`h6{>pmT2@ zY9ET$u#sH72HbQG)8XM^VeP;KMLXZF46LsojfuF+*@cD1x2sPt>^K&L{LD91n>LJ) zuHgQ92~VCS(c3cniagyjKpIM%EY&dSJ|J+~YCmRA9D-89s+22X$)lUvOc{8=fTOpy z8?Z&e(AE%jus??d+c;Z{-VLa)SRfaWn24J*4_i232>di)zf2>V~3QRpTQqJdK7bT zVFowz=jX4Lb+rJP-!MQbQl5XSmQP4cO>MrFe03l&#M4gOgELg4h$rC~+SVDs(A1YT zM!m^&b8M(@rxJ4HtR*aX?hMav&&83<>;hR^J^iOzjWbPVVN9_` z zHz0aDcSfQMGReoq*@)gsd=&3Kulu~^ywGH9VMI+#QW z)zW$u1uo zkEOlDxPyHNGyi$gI{ik-`9aC*($v2p=Fd-086zyNmOq1SFA8{tEhVegw584mRFZuN zmYe?=7SXlg`GY(`CHycfyFGPY%VRqQ`9=j1W=xVRc-(l%@4M(#TAiJ7WFu5xf$NBU zTT(2wu_lzpq^=tN2ZP!{R?Ka;!DhDN(yMq)vw+$z_P8AGx zofEjJGi1BwjBDjGF2k)%wR~{A$p7wd^BzHySTrtZ)^m1 zb#)17TDFyLwL+Fw85JN}Ej0O(5>Js~D`W30Tep%v1TSPugh-1YsZgy(ow~hp$;LlO zxHdT$LsheVObWyQSgsjFYgv7D?zt9u=X_Y5Ztjer`kd;QD1&;dVxVJwmN-x20@Ttk z++7lv`R+59*2z{lx046}32d~1l8Y~N4nggLP18~d=9KZ+ymcF#K@j;=pnCD`R0C#H z4~Rcse|`XJEq8Nss|=6s`SXa3thdhduc4it-E_{}9~&MN6qIQes&6^b?Nqggtd0|G zg)dN0$x{bIE}R6Y+JU`FuM|Q-z3xUXi%#Yu8DWdMS_o_qyk%B=@EUX8aeV2xN^iy~ zkMsv3qE~fJ@0NS_z&C+I8tPPzEsDS>S6!>3!nw3{Re^9BvDRKwnw=uhyWyaWvfT7p ze@VxP_J3yRqkzMw;a%_ZLp>|2)z|uK*oIsZ0ObO{5}`47%n{;kAS9aQrckWCEftqw zoHCtF@BVaH1)J-)uzMVBko%C2m38QwwVm2m4l2rlf{~;ds7wIFv^7_+A;3D6)SVLq z^fwOy@rl9eb)*m!U4k;t_KEcZULxGm;!+l{Trh1}Zv1@>?_~=&``{^7V(j#MnQy_u zIJqa;S~bDBU59B0Z*k+QZYTzXZvk5k5$m=|_N_S9tA|OkLjjMIWx1W7_g5cfsMcGb zHmU#$HFBr@C)TU69iSaSh~)M|tNUq%wWup+krfM2JD8Xe2nn+vaGVg&`!KhwBW*hW zS)x6bmdX5-B}M0dHmh!{AT(w*#iyG0W~!qtR)UfRE}(AV!J_+TC;OBfhn2mI4t!Rb z^z^R&TdW0qPme!4#h=PJF7vxIt2O?zNk-c|!i0r+!)%O!nme0jvPB68MoUWz_&@W6 zov;3e6M+MmDa2!Hrn$*7%1Y{{St$hZSIX z-E|1ZmUR^;bL>oA&kqO%olFdTWnLQ7AYEcuH=hIBH@oiT?01+1Uqdtqu66T4{|zl4 z%SjgPJ7@m1U*8Wr#d#v(%+9?ZZk@?VQatl^fB!m-boD@q?t(6p@4quJ*B!Xr*8C<} zOY|zkUyx}$GUUGv8OOe_wta+A7~V$>$6OFPE^`iYAk!G9JCwH_*+jY*Y2^e3uXfRD z0`cHGhORSno=H0#gQS#B=d3sfht3WBl*$uKd6_U+ALtmcF-~?ri9NUggn()vJHFy+d9!tD*S}rs^U+QJHv* z52%S83=yi!KqS%ci1uNJZJO|RO*IH)M)PnC2 z-8&#p2Ws8=EWh1)PHQF%jD7^R59kvN z>N6v(E2ho#Ojfqya;GjJwvSakn31mmr*OYmE+ZC^Bp;_b!05j-OXqx{4@$O_hmim4 zqBLm|w&wQji)dy}`C0hh91-Q^>c?90ka0!kHs=@I{Qa)YOGAM1$l1PxAJvOC<1Zfs zE`I#6{DGV(GgpzBi7^3?rJfMT&275m)9uIT0d!Ql zFB)Q+*f~v`|4F^!(P|++NlH~ z?zh<9IG)JaQA z&NH{W*U=Yc`ztf^vK~`ZRB!31EAGbNAZ59TE-1@rw_Qc-n9g+D`{VCOtm{Am(B6Ib zbZX6F!jdU+%FnG4Gb(4%V7Df4ovVY=-#C||c@8)OW_*5^^V8V!zZ(k+C7nftlwmYf zcTXJm6_2GK1}z>Ac+QC!VR#Yx>6w{n+1Xu7CqT(b2ZZV#e78U$EWsk$B*4DRA@s!c z{8f>lgQ)0kNr-jU(ablRx~fuq3DX&!is>i!5r@<4IwjFtrecTg%O_vBSXKr*nV+KZ zm+m}Lt7Sr}BppT1B???{+Pgv7z_rTVmL8U4v_zgiU`v?T7FAAFMDV7 zn2^~vs;v#SwRT?aWT^Eg>(acdu*J1Hs>(zps8R+4T^XD3h?MaG>~8cpI5K268sSWX z;1h+R>7^coA!t*5%S%Wg+XhE(=_ECksxhgts%moM1pHlN(t=`Id2VqrPG4VNKuE|@ z&p9b6>Co`-vK?ji-TX+l(3{G4#Q7UG)&pj~{VqRiAz-ua|NiI^6K9^g^NW)o9N063 zE&6Sd>On>4ZJe@>jnfeR&8M{BiAg?-umDYwO0#l%}>y&-amR^b% zftyWw$O#ZIdsdHPq4m3{uI-%OaF_b5TGgvm;3s-}^C_^W}ul2zf}(K zPVNgw(~iYJ)Bc>63%x8+ig@m4jRAD)fHGlVy_(u| z){>^DphKE~g}l7{8_C#5c&-6PK#f@Jjq#19k}39hLmd(2s?t(mpBS~DCn}%Dn4g4T zKV{lDa?)5EV0o(WkmG3(8uD&YGUt9jOH}|+kym0O`=afq#=7@lX1i1`&OfE)$^6f_?-qf1Qjr0NNJT!TwD{DYZN<^3Ldio z0kb+0>#e=0H@2`BdknV53)m+rOSQu^LX~ewei4>&sBJsx+TtYHrtxAypAH_$$XC1b z&pSqZqCcxu^%6K(A9+O0{w1troZDqEKFatY@_LxSD}Q)<;px8vLbXtOSsecAp+**L zyW=a%VF&cq+2>hd(xTtWwVM%**h&0n`1ts)3H9e{9beSc){*qYfz&%aS(_D`?0CtlUYfqw}7@b78e-sChm&o zjSTc#n#KMYATN&O{+2RdDj5k?My@IvKi+J-{wrJIGM$h@^~ZEe%HHt5VUkc@O-Vd~ zHv#=Lu(4QNx4VIryTbx#-HkPU$f!ua3peu;)HH}ZcuoQNRicGfja~MLl}$>%YVq%l z6TsQ^+l=$_s!lu&XTj|-bi^GLEfABFqXXz3wgWE3J^i;S@hmjIc&CP$5%>NmqtpEuK%yK2#ix1cq@aKqcVgilo~X>S2+Nbw3wTU5`de${#I19#hNT0+F%#-E4%J| zWeJ4nQJcR%UH>A}jpC(0eG=#V@juf^^PrY;E&W~%A`8Yt$c_v-b--9~B&PwXYJ$Z= zqo+_%P>`ET|J9WnnV{R`h9IOGE;q1YitY=E-8<9__+gT|dCY^Ay91d;iXWJ%H8X zHW9=OKZ9P>-$&4CFeWA@=HALHP1rpIn39X51kcNvg#-(r!HzaOGUDzc>j{ZMCR%_L z-KqS?k2|G@O7Gt;^pzA|qMB6uSyX@uid9U5hI~ z-Lv0S4LU}jJPH-}pMftgTY>LitZ3ZO0I?L%63ace286#}%gaYhtTE8hHGziK7nzs* zAP@Sr=Z|J`aDceV*tE~(LVruDkXg%YM?+JHf8`?TfLkb$;}0ppd&JVe_?^T3A}>V8 z+Obf;m5eBfpMK3F0|HuKVPbV1`3`C%c*N_3I@HKJLBG2_z2vB zT_Z;95SLxz?jd-ykkEo=;u=Uxw}CwdRv(O2IA7V-J_(OjR`}t)%v%8<(WaT0wvgyJ z9|#a@{xeL37(h@HC8p0Hd_d=AEU0;Lap&KV5)%gk62dvS?Zb#I!QR~8-I)%HX-H#P z##8Qw8T0I!xL4nkZh+ z8U_<$5wycUJe#F$)8_g&ouO8pLp_+P6{st9DBm3|{&sMVkbO}poM746*|MkA8yWFM zj(eKnVU30Z6tmE7I+c`>A?FBq&H*4RKzA)`#QkJv#vjPvAUj~wJeo4&goM~SdwOhZ z7J#HI3XrosISA|&I3F`VTR6o^?J={h8ffn3zb9Qp>u}Z<(uG{{UUYAql|x&cw^d zm$-WhAUYzsV>NCX*^nyt{&Mh(WuO6#bvjj~g9NPD{$_3=6+8QAI=rI1Tn7-^oB_s) z#9c1e6SFG-HF3!86I~IM$3GZx#Hx88^D zc9b@i(=HBa?jBVtn#^=EE;Qq(_EOcZrpzF z6;|LhrltTi8wn(|DSK*cYT5!Zp#xD$3SVDe*;6KPb^tERXDnAGt-gM4qXFcSqKIDLQ;jtq9 zETs*3T~)#;Qd8J>4u_?T=+otaWTIMkEqVOn@)WGMH)Z5&*XNA0wNJ3Q>g$LOJu3+S z&n9+ve9hJ1axv{6Q`6!=kNlh0(2T(|taECLtR0r{&o{vX22uW=@4Ti1@c@{;d!48Asz;~yiqq1Mxresg2cWvq_YTa7RYo+3>mPYsv zu0k=2%%plBRrXf?@-S!O#9=_b4EXQXZ0GarkB_J>;!F}^`@KE&80?vU?lw9DILjcu zY#vU3YyEenOa64Ar{}e%W>Ux6TN#-)(BzUbu_Ykr_kI>IYh`6+HCck&O#al|+`J8J zi(+fIc=*66Xt7==+5Uo0fyPWpD=?Ce2YU650Y1Lmsrc3p?ix{+$^Y6L^vS4QANbVnP6|}0J zKMWz{^SJ02F>}_YPd#d$@uxo)yT`;?D?yO=-xTSpiV*MKmi#{Cu6WCum@t44+7BeG zm(C909(-~J1~h<0F9c-$8WZ*M1OOBfwy1D_k`&+#SOD*|PGgc!fFFb9ro*LRg6cYX z{Kx6Y)7j#S>W|d(7DS)d9DnFaSR)D68A`tM_e%GuXNYqx+T2K_v)uHP!GA(@PdW@u zL{^t>SCyCegSDS9S42R7Y{zFa=y-0X9X%E{CLUF3_Na;AaERNlH1F77|HOtkhaWEK zF3%g>iqs9w8aykcH`}RJ&tSa~N_Pi)0JId60NX$gWull{SCp)f6$ZB`j}ONZ(N40ZU?=awsS)OCqi)ueTx&rZ zJKGmNE}DVA8sp|;L&47Ld?lrCrAbPas@-O-f47jC-(BA!O!8JCvRrPE(HHCqXLh02 z^K$!_r&H`U9FMtE&r|5VgBSN0Xpe5x7L;8L^;4~s}l3J<+FAnufoTUvA&_!{%Y(tryAR+L#r z9Nj00ZpX%tyA8_mdKFXF3+m2J?x$$ayFw@`1f&YZ!HF)xd-YSkyQAT=sHg&0gAfhm zT6GS5r|7j|SC?}~D-S>Pz_64wdedfJ@p$jGn~otp*84KuWDE?XhBJHm{&!r?g~pogo-X@S(ScVB?*!ni1d(ovjRW zgRBJzQ|?PuUlMpRaRL&q`_Dzx5S)tYKlL&1&;~VO@P)Gh`*Qa@6>$(MC|Xtf=Q{@Q z|G6<@hyHmeMjmXN9D~*Xg!U zDx2~!@#db^kHsxLOyE0hc!IDMdEwyhU6F#Rls@PipSS#(N>{R=i{CsQP9H?|ydu!v zd?r-+JEsFO6z1MNb|nAh&CoUP{6g>nh&}{f^?Hfgk*D5sqPZ2zL8MyKTXwE7%7Gy< z4>bf|5Uad+S$hR|knah$VjAXUb?JWntuTlb#V4T?v6<>E8uCFVbhP zIii`|gL{g5bnU=Mc;pMsWz?}>>K%W!K>7D#a4?q_VEgNrR{BwQ6R`c~yUM(4=Czh( zcHf>ZQ!L%L9&<(JYjVMDFFaWi zBi{seuBjd+K%Z8(Bng|Go~UdU>k&7606O-^(WX5++rB~H1JAFHi7k){`<%wHW319AngxT0khfm>;g#RMYi+%% z|IdE>>Rs(1i1?lE{qRC`6hs7OJi&7cRC{+w2qR z3btC?>lpH4lS4X~<3BH4S2pRKRch4^1@TSnwfLVt|16vCMHkdrXwh*K$z-(7QvI<_ zG5_lm0h)WI-+o7saMb-SrVDx~CcJ%1>{Y*4F~3ufr!H2!chWF3=vb@#%wO$^W1&1e zhAxQv-B3`z#Flm`5=tl{xW%-^6=JmdCv?hEQmauPv!lO9nrkp|F(k45)rec!v zzx-jSb3FUB^HUo3dWF6EyP;u$ZF{l;MJiT}tzlMZfddemL5-16ea~?%Q0>_`xdrQa|U!0dp&jY{AJ;M5+0(@+_^*FR=~ttRxG;hWKHD zl8%@I+3K$^s5Qnb=^3(kf-kaKcHuIEbe{t5%P;+{mW&~!Bw5dhhz=nnZD25IYVKBE zzigNFWMR|kJfjbN;UIL=OtJo7*as)SReaa0cH8#`3&$`Y$KNaQZ$Pusg=q#}zT&7uJm- zjP8|f>I)wE`Y=N*x+^F{wzP%7f!a>$%hr2}WW}7IE#4vvcV;P4f6X=8N_-t-Wp?WxhoHh4L)0HUxX``L$ zd7e=ldEwq`_l|7A#CBOW@D_@XjmVY%w8E#hR(Y>O2*q$ZNNe8BkNPH!%-7<-L|{eX z_(p9vnBzhO+uobPy{9uc;C}1RlD8Qv{V?S_#)G_??DCnA%LPF%5X84s^vR-iSTe_k zokxmeJCQPRj+T@9hx+FbylnL~sVdTg*~R5Kou#>%@oKQGa1f<_gZq`zEbZE|eMCnL zP7U~B(NnairWQr!QvMr0kub-+{KlR%$b|3R)G(4fK7xpsNWSoQP2@zAb@m>*dUVC* z2lq!_*433(A)H!FhC8I$ckX!JmfU+=ntE{AV@UPP=8US&Cona@PZn=;My7?(ek_;Z z&4Y=*_N1`FJ;Bcl9ttdGc}M5u>8i2h{EoME4LPo-l~6f4`!5 z%6hZyZ3BQD1BO0}6KT-Bf`d!}@`&JpdtcU<(J<2LI_sq>@84HeCM}E}ttPqInHV;2 zRuOBVg*msFm8Vq|jAVA;i>2h0qYmuRwH@+FeQeNj%R*U`32qxumKFJ~xii9v{2QFk zs>5UVb(Rkjvp2`Z;u^Pmd;9Y>Z2{OL4`!KzsCcE7uRguS(VY3XdqgH+&iTHQ_+aON zCVJ-2j;L#}Oe?Ch(%Iv}?mw3xXjNWqU7Cp2r+y;6HFhpAW`QC_YQ|jwKl>U~-%m$? zSfYy=6M@e=Xi+*ARy*HI&U(c+N$M&~#i8KOH_!zeyo{T)%R)&e%W41F%^BUlpjW(P z6=ixEMu0_qcd-hAi`CMf&~$HsdRvd=V-d4Hw|vW7`{Q~|c0msNIIGL8%dd_lU>z^J z)%S-!o8-k%1UG7N4d|r2!57;Wod4oz%V=Hq6OSp=mlXdcvF-yC>0qwMPoyz&`@(9l zsN;D1kb)=BURhGU+5@T`snbGS7$Hb)%-RG$GyPA zqjF@xzYo;4)~{cm^(d91dee#rV>;8STc>7YXc3ITg~b>*r>|@262$3WmuX^#DhL*- ze!N|_caRsoolYl7e?ZLYlEA}*K9L;DtMl3-ifOLuAibW>l+3wq5g3~BhB6|{IcGwH zXW01+3_(;ieVlF|-iKG7B(;Kd!+Oo^Jvf6}xZ{~1=gNdtvoX3w@Cf%Wg>hrV$zGu* z{|gRq3AGE;NBNSd&IfQg20Mvl6x)mH98T2Y1GWCe36=D^O-74XH}-1Be>_n14lo?&8Lmba93&--frDVd)jbLlW{o%d;CMx=7l3cjuc zXOAKn^N&mzQI_56cCXRZLfZ(dz!SSg=XE25$%j#hHdANS1+aY&i)S7;H&6T*+#3bQ z1L8I3gB>TBNM6p53Ee1;n6$<(M8QGkKQs6XI^siuRPoyut~0aOlor;lGk;zp{8W4P zfTXRd;^#ob{F<1AKMsS4-&1lHuIVs#_dOhS87iqw^6)3^zBxLBA%!ewl!APlc4mi% z-n{Jf71)-u4y#SN#KLe_wq(U>i+rWY%m`o3_LgVVeBWJ~t!!==*C zqMvAFlHK3HZYa3M=m=VOZT-UpuXR_N>ygB zzTZPBO<6IgTME~=<YTld2H=E~!@L4&#` z2?$)wabM`IQMf!_Bf3!TtrpBTzP(7^3lmIs(@AizyYmz!vHm;sUbJ|~eF*`72zu`2 zFXH5RJOBPeSrCH;;~pCQqwMwFTiv`C$8tv?5bTY6fXfJr)VfjChvb7b3gq{MJgV24 z)-9g;SWxja8m&dSxpHzF+Ot?Kjn@q7E>^qAjja-=38CW_Y=V!4Pd?&l&>FpnG$6z zd#cE`b)e>cOu|3Dl<`$<%p?P`fd}dn=>D0tC`QecVEYsXyR%eGi*X$+Y~`Y^cRyXCc54`$@|4 zg0~|P^27=Q^CZT6(lwP>!gN}GZW{jgI`!B@I+ROWUL60`rMHsjw8r}I@2CBisZOshonv3von1(k9so?*RL zRw4UvF^9C54w>BY5-;xxUXZRpWx)DCCPqPx*1&PKPpKC-~e? z#7!p8Zp&!lm{cF%{(DRymSXVWG7%gZ?)}oo53spIpK4^bc5idfR`O$@>5%xp6=BqG zmj86|^AtN22pw)~ec>Ll3Nv_O)Sk4gJQ83|jt?jg9!4ZQ0sDh{elYNN9F~7FWu{^$vVQ9qZK(vE z$LrI>pW3M@*TOHjWQ_HQn6EFH>)h8qWSMgCfclKDYgBhA{VlQOiQmLCSk@a!N2MKkCK6)zDE+n%~0UQ=0}ZQn0g%K_MN4 zefup_fmtRyB0VX>)zUPN`%{{~_0m1>3p&`^>Y)US{g**a{@q*{2!oj2C174)RY!1N zS&OT+7BS3%#EH{pu&$fKF9Yr75U?Thdc#`uh5Be=i^Hc8kI%YaLD&4#4`c|C%SM7K z&8)mfYD4K~S@%1rr1_a@?#9){H#0C&`^5!A>7dr|h0Z@Ki)fu6qDH~dIQZSKpy6r2 z;9)DtiBBQTFZ59{6YchFliLBGDq$LmU``vCXq9J(BB~SJRaAlcA(Gex3Ll{0@!b@{w99Xaa)GPNVm_w!bLM3 zsdH2Bo1N`GZ4eyylI23(VT}8jj4uq$0AHFP4W>>EbBIktw^T5UPr3G|LGk)Hu7zn= zG{0GtdE;QY$-dNoT;0iJNqq1KoTZ}tB8tYdMHa95rWlQfUqP+I7!9RYCa~%E(HnM$ zxOWp4Hjkd--+Mfs(%idJgv0nEj6)uOXxf}ufxL9?d8+9bvj8JPow7+k-z?3mn$dLM zo(h6->aAPB7Nx_;;=;O5qx(PKySdh(El^n6YzcztXxNHx3Lm$OY`nLT4ja-lP?-EG zBN5GBWjW&%YhYAZ5Y zHtJR81HrtCMY0^a2IdI}y7s{-dj@>{Die>F1qsR9DRz&J{|^f=bgCeM zrBb0IVJ#4}$vdQD$CN;eckh?@=GVlBL2nIcg)I1SJ?meaZSN#gnK1pCssu!(*LyAomat2p^Q1Mr%cW!uC|1?>7>bDe@9$8FB z-A%i;`|`smOV)$a=IokJ3|2)Vpn)b0>UJ@k;i8KcD5Q-rdTB#tIvOeoLKHTr@IM=J;6_8Bs zV}^3WPVSC81s`KJ?Y=UxY6Nefp*)Wx6Id2)0O5AkW#9F>ou2(}GYPNska?JEddbR!S9V(@RAgQnOlQ6>s$-72{E7qMouWjG*ax3;@^QL3LbsEMym?2F zi6Ph-zpR-0fo5jU8qE^X9;LX5Ol?ocULn@(=%@CEzl3$ghDYcX)E~YP`~KRG@c9Db z@<^)JMPPSiDoKdRxBj?NtGnt$Bg;3J=m@|F4?QA#`Km&XZ8-IHk(}ohI+eEraXN)&4=sDbICo=scw% z|BOqS$Edp<1CNCeANgrv%<^&hoTjS3E7wZ3hJfAEIRjG7>yvweJgTAFt?vq_+2qTQ zRllmwdjl9zUCGwH@r8zm#VDaF9cCLZ;Sq9w4?sLo7H)OL3KY--Z3wccw^6rN?{ z;O>ux$~d!cVeza$^J~b0mf%S4Vk`(g3%G2HpEdTw^&QDmEP z{Vb@bn8Da8Ht=|PWB2EI;d~^YjB=ib1rZ3T>rJA&Ogh+R!j>XmkCDyTF1}IX3ws}W zGw0TJ#LaJG%n2fD&BVeH{Wi?o8!S`?HBg58cn^YhjScMljyvz-UT-V@RZuYZCAxvW zuYo%XP7#Eaa~{#vdBGoemgmAGy8?eUqWX$N$ zQTPsjSfs$*va?PJ@LSxnIV zsk#WkhtX48+>T*q=&49jYpt!khrp5bLwx53AejfQ+XhBcEUVnk36ol%t?L&tR$uQB zj2F(sD!SxZu-?Ww3A{4Eje>VLEqLq;-%JJGGq`AxZVut4e)ovHW9fpCdzPnEia zkKqy3gjtxJT9l@(v5gCUz{$&w2y4MK@g>_Bs#o%P5gWzw%Uj3Os%>O{Zvy~loeud1 z7$`@qzP%*=AH3Fik#FFI5O>H4POe?# zdu|NFXby*;AjFA3G{qrE{heGG7kXAS?@Q*f0WTsxSN@Q8sBK{Un#h5WYtc6`y~+)o z1c#;fbbk;*S$aRS&sT3$>Tj!&UJa<|LiujKO9qg&N5{^OL-EyUQW3*EJ9?OF_I7MM zt-ycxMN*WPR$iRn_lCXE`0&wXxX-+jF7564jwgo3v>ZJV3&*_InC-WRdhd{6yPlU` zLh*zTpZ_Zxt$6;cXCU)Lww0n;fue@Rb9<0Lo~gh!dy&_2;8&1>5pm(uWg@{M+lP^1 z!b=1)N5x}o4>J^9+(LR)1t@NGusq5Sim=ti;l#O&|H?_uvdnmo@mv_+)pY+xZ(`O% zUOY(8?g>e*vxkxHeRxp*+uHuOHsp_7!E@oCEySD3?bHW{=T_~K>uKW-lHCcM7KKpv zgM%}4hF0icO`s;=X6Lo!caTz4f#e(i5&MCn6-a~q=g`~-mz4oCKW_oMeXMm)?gDBJ z@d_&GVNMZiA;VzbW1+JXCp>0X3zd|35y6vIi`-9F+YfSzR7+W0&3J@G960 zg`9m(E@$8YSu@oH9N#JWB|)AWd&3Nn=l8jF-+Ksd{+0@V6MR)cCPHw;VP4BMSRggJ z6={oyBXf^LXNw zniuZ8mivkViaPBIvbsho@pth8ZmJC*Y!;M$KxIsNd~rMT>$10#Qi zRcc`W7<$u9FB(RH@{>FKJG#REZ8kZi*d%4Fr27;L@0<1uk($*ICJmy;4?m`T51p#U zw;}#v(57vy+?#dD41#%AN2cG&mH10NsVJ2LQ4cekdw;R~67$#IKkNP+nSWN0H?;!? z@Jc0+#XZXUD$L~rS*E9=0N0+Xa?0fXoFrME*=tF6THF@)m_*z#j>E`^M+L{$Z+(1# z2NCQIFbJ{15~`)aj`@;Uq7-sT*YN=!v#sF*sp;y{&MpteFUVmRg9s2B zZnk;yHtu1N$pw#I-x#Z+^2R^#D%t;5UU)Sk$06@(OZI)m(SunB5JZ5g6clYj2|w#T zVtTv+q>5i4y*l>;8n<^PVo@0l-1r$8Y&ROrYU345E-%(sNpA0GW{YwB|FLx);9PzG z|Js$1RAiPiA|!h&iR`4v%$B|P`1CDgDH>*Q084mPyI!p&v8u>LeN2D+<3gq~0IqLj zF6`Z}O~y^a#<*}z^uiuyy_-l>hJE?g;@NJz-3Prda-HR9vG0kRJK-~_m3ACkhc{t= z5udxma{bc4*-s#1i&-Lr=wbbw+x4bSZawGM7*h!)aQyUYyhIZ|RGZ_Oem+yi_}!co zeE6{Xqllqcp@s~0RPgD=<4c@#x)vvA5JX%A|gDu#}}=8Rb7{e!V)5&7zqnT9@!jQ&0Bh z0R}?|vivKu2$cAMdV?ys;1tGZ^nNoWW4OR%&vQOsZ6X4pVG_&D|9mc6rkYdjvVYP< z365euG7fp!bMFGQRZy%zaAbApI(%#&EAg%0rLC!kYDR|IDoXYGdPROjrSRof8SquMk6CdOt4mb~ zz&y73c4^qM_sjLCg&+`8+FXHu*(lVyN`_W5`YJ(4kJlo|Ap`bJV&#BDuajILO}l51 zK}~!;?bYFSc+ptVG0TdRKwZ=Zz!=g2$gipF#f}D;Q)172w~ig&8JgOc=O$Bn?3R;J z(a*o#Pno(a=m=hy%jx!=B^VtyNqF*OWIwRs95M^P7iVrSo1L%MtnhxKLO|st8Dr`) zGFzm%KK3j9Ti55EjPGyctK7MT8OkEWm^Lr!y{e>j--G6H%Coc3h5cBC&u89Vz>C$= z8RgDhrg?olQpE--aoRM0AEmE<^Fmwo=Cd~0`@j*QMI^~_z^td8|6O=icD#F2;82yY zYDBLf0q|VmkvKaZizWjJLU%I;*jySvEvx%}Tq(KE<`;qcT21ep0!j)Rf1*qTR`wP~ zoxaQq%oZMbY%jABmQIe%ywrf{D}Xhr2Cr%lN&~zy_enXpz0zeEDz}xJavmdyn5r1x7S# z7dziO_dQ>VjKx0Mbm^h2THDLfZ27}OuHrKH6)k-b)u(OO&Ha=)bT_A18l<{wJutwn zl&QuxyuzX=KlT(W1LvEpF)?RC?|Yf&5dajeFltV|x;*jDOIxn$(SzmTuwHZg+uZv| z6OG;?Nz)ZR*Z(1#8f+JauZw>S@8Ht&SRbcUV%dkS^4!Y#3{-jBctu{9j+Ip@06Yep zG>-S*@9@!M{~%5?xixk7&CA2%Jw@iJVk3k9r1x7NovjaQmHakZNK+klqX0ze3F3L; z1w9n86>04*U|$23b$HCGhXba`;IpLu1Ek`c6z4KukdxruZe+v5>_JHe5ni=dOL^vV zE7uu@iiU;{@dOppgPSbZ-`gHo+S9_t6+kLEw>-;061!RQe0BLF;DhS= z|8~8CZ>a5!$IN=cCHz<@aRMrO!A)^?5Ef!LA628Zl~OUKzli<9-59$yhWxdk zAsua9yqBiX_wH0)=Ac#e9ODf-1IWR>J0;58437OfD9fE%ZR~S9g7uCndAq6@}CBuv{e+E<5Tax!GFY0 z0$}fFe?}0)uYTWb1OiS0jZTx*oNtK)df3Y6Nt<%hzo7FVx^^*Ge$vdB@7{d#@(#x> zkZ9X`wW8y0C&2ylX#j9CALna&?uO7>-m@3%OtAYHN+~?C)21@8Gr;Yt+~GM$jd9q8 ztA}|ZL0P+Tc;ULAAWi1WdXXxA>i96JsA~{#ZB;%Hd)g$|Tw~$KexAFB@W%nUVwPPy z@Tt;uDGG@r%BReFXZki-QHp&_NB4V4WQ*l|JYT-!buhjS!g@gKd^a5Rh$}H*-HI`) zTLyLeM%{ZG8(=3@-r6d6Q;Oo8=nVx&~LJO#_Rc~g43Dk51FDSiE zB#6P%6(hdRBojyoV#;@Bm68V^gGvv$5*8#B+|8njSYsm)Gg)ywE6Wx^JQH3X9y7M% zlFFt|W0WbE#YCbmTZ1}>g3;`70b3@VC9QX!b~ADhfe!}Cr(P8JxoLB7f&CWS^Tvn= z*1)ics@ki90k2Yi1HbRqbrNjOZ5C5fqvMkGj8}cFnc42kA&Bjf8G~zg^=2oC!Jah| zt44G2o#PL+O#%^k>x@X^pr;%Y8iU6_>E=M#yl!t~npb52H>B1}vf>=TJCZ)L8j@>6 zld`}+8B2fODz`*+1C%sfNqM;JgVG&-AOkzZyUn z(ZRZWT+eK%bGT$}+MIqLME^|ffqQz{fZp@Ea0btpqh3_Vk#SZNwJH~Zazv~xV2^0SKXAKu9(&`qbEZ=P6NX7N5b3SWvn0;MFs;la{tg8WbVpo0Z~W)&gB@n7oRIUy#UyTI0*miq$S9=*A`G2@oWXkd#7BM4CvNYb!Aj~ zUCGlA!r4cam~G}FUXfj>$xC;&2UmNfqZwM?KmsH3-Qzv5xC;x#%&?|eq8HL;qAm6R=e#dPc5RM-EY*dPMMyDJ6G$Sg(L8}?16UI<9u6} z!p_a;50(e!o998i(W5o9*#}hUG}eKV-qJ(28%haClOophX)A1K9mXExyvYYoNCSIq&kNRpRe_SI z8gkBHqO?~1JU^H@K!DUL=c`$KX+}G#@P{Vs{7sdc#FoWO(ik0sYVQ`KRIeJll*b7j zWmEjb>7jiAqKP+4R9bAU{i)e9G!Q?+%%{SN;z2czLcqm{TxXEK6umxAP;xNsM_XQ5 zHXPSt&&V$Gy8c-knf1_wzmecUHKpKzRi#Az`Nxf`duE0@#^w2#`U#Jjr#{AB@SQvR zDPf5sQ+cwZ$zaToRIV1dLizSl#DEu#585lM>qS_Qep=zXc>{#ErZG`fChP`u-bBNN zi^)xvbE8$OX|4_J`SEKQ3^$YR5W*DF9mD`XO!ovUY zY+=)%aRr|>AM8XoilsSLdi2q%?|*loX8Uk4>&ZlgonQSX?<;ls7cB>Rpdw(wGL9xL zZ2-8*cD6wx_{izdHN&NP9h?(eGq<`_S_?jbmKc3bJ9QTW z6s&|_p$conR(CL9%2EyX2RY&ooVFn6bPeRSQ&+uS;UKM>qH?zqD`wBNJ50j`0fl*8 zct;gR)|WsK4+!J;NnL}QH)B=XETJ`I?jJM*#GUK?L_o%DMT9wdf?>vRT;VB2nyNEy z9Y=M()EDvjJAA4l8T_CK6WGT1(jHLi#et2X(5R0tgwt1Oz%JjAjZh9s;5l!MbF`Ph zcL5t?uH$;}*)t7>l>)9x(8)*2(J#<7%#01Y0>N{)UvN`D(xwghkc*jPVf10?DGn{U zO#1uDQJ$Dra0;Me`z8pkSV=qM(ruSg-V9rYHSt>391|p+M2!|~v?h<7DT;>ZG z=N(e$XX3-L2$P=^$;*_ME(kR`05?s3%6weOX3kH0Lh?%8Zu7rO;8P}TX?GSmPJ4og zVs$MoB0qg2UKLj8);N=Tp)G4`qwiJj6`}r2!(`pvd=cXbI^l|j>Urz=Yuv7W%) zQ!RC7K-PO2$6w8VtNmP;)O=^#0i?TE7f3h$lY!tMglVXEM@NU+E3-$@1Z<>@mc_N} z?!5rl=iVJENQ?e<8^oWd&cswN25CmV28AddyPx~#r4UPRiF(H3c$#Ufa?7KxB!fzu z8XE4)p9@Dee|*k+@_ltSk?&*3Md7{HNyNQ`8i4b>hdef4&$XwA?(B!xQ@YdN()%vz z*kqKudmFjYOwvLcN>V~(7Di#wS4_Z;0300FG%AD(?WnjPbtFp}qVRCpyAsbUW$I%H zdEm>{PYN3vuc`f781QXD{hIfF8x3`q7S|2xsw!7{>f?Om;`Y(iN1q(0e|p}#e6;xi zMB@Q!X$ECA4g$DhP;pFT$XP5l1ojKE&8Xc&6wEE*YdDG7`|r)y;2OP?@2J~-;Mn5sMcylKjkBBpI7K>jd7kM0a6C@67}6)2i5WFN<*&*&u-v(r%X9oEne&PJsl?N^KI+i{9q&YSlw*_O-5{~ z!I5P@IC;%B;_B5U-a&uv-UZ9$wcF}~%*5FXOx5FQ+}%Y{!Q`pcz<)n@VetKJ=o+ju zK|Vf+=-G{`QnxoZf@~FCxj>iAlXC%BUs&6oVQmNm`FRd+&og*srg9g-KdZCe(_aGT z@+Fx~UCUAL9rBI{Ap_O261XFVo+5w^_LcR)ziVSzHXJ$j9XCM= zLBh_&f~$!ybsT2eiTxyymH8Y`=&_S=K|df%XzNf9)3WKkEgTw}r7CC85@g2kyZd>i zEn6xlyBr4q#o1hcK~2-ybWV?>4VB@1#+JGLg9kT4&K6HbHx^rU+=Q`1Vau6_^T1KN z*hoA`EK)^X!HG8%*gLr$Mm!0mOi_7&J30v&HBUIu1d8^vmGPdV9V0;myXAC}$Y zxC#NH?D_I#tm85Y%X>PL=P=`+y;qfd{GLv_aN2Ejf;Vun#wYozp+xyUxwTsi$#~IxA;VWc3fqXhA4N9g{#i1)v<(2 zS8uyQ#S4AapiiSf@@>$)BTJ3qj<0bggry~(guzSUZuKyE*mc0joPf;5``2pIvH&?T zDK13Hb{A62etJMPtAi4OAQi1n?{PsMl@TMu5uI>jPPY8Ht*2!s4dq5NkHx#^aK|L% zW0q$Rr4!$7qd190wp-_QM-eiD ztL=>gyju%D?;RZq;7+X6SeE}nW|3uC44>ia*9wSptG8RtTP|k3qTI_m$fTP7LASmz zQehhxG#eeZ9WWa1o`^X9R`GhZjHZO8l_jg@218r@+(3XBs!izT#xJ2Ewn5eX?{FF$Ab7C0a@<+^*gcS-Z*p>Ux}rkqut&;u zcB^SptVj#hx#?Z!H4#GNChod8WH{N%5F1c07dN``?fCU!D6gO}Wszns2ci6V3rDk5 zCEp^N0a6Q*uWaN22GPP*wjFp%i{uMK8>2g!3twY~CTPlMBtQ4LF0gn{=vweyT5n3X z`ZcVWVYVi;7HH;{Yx5e2#A0<;5&S!!Pl{yd7o=Pp+Zy+^$_b z#D3cJ&X2Y#zNDG(Ngs~&wzzCLf5Mti6=FW$gT<{ZmtRm0?{_}z-|RLC-I+DX@(mic z(x-H>zfKLPogNTyZ0>))dm=LT6WQR+2V_>-h=VP+o}Ch!@*9yY2GKEUftyE9S!zAM zIh)z-&SpQ;v9^ux8oDM1_5kHJ=~ymMXHykqGqpvL)n{#@#2PBa&c{DC`i3y&*$*ot zQ%1tfE^a9Y=1{3zhZJfTZ{K4i+53{iv>2=Xrvf$=5+&-sx!PI+F*%vpT^ijed@KeyOL^_(mzqkFkmo_2f34p$_Qa(-5m)%n%zVzeYv!&g&tk)DO~DyIE%N zPss@Auv?q;?P$0c4|L=#GCu&k9X#V)Yh$DT$=MkqTHqtR}TI+<+GS#o3s!gxgB`9!4Cjw;` zkB^BIHv-#@(1d#-w@-%+U4T$h)yC^hBRn$wawGk`8a4L@ozcz0Am>M&(8?NUPhb+T zBw#Z4##}ID4P~AcLV#p832>Zfb~T?5BG|5{IcQO?t9<8-?iwFoM9^nqwb-waT$KCC zI(>JP(&jsD0|af98YlBW5Hj((YKurtX?gG4%3r;X_RZ0_V+3}(LsG;Pi20}BXiac9 zCtZQm*T>a8%Yv5KZ;4o$KPQGR;dhxQdNU<)^?mbZ7q&8BU9a-kROQP;36YJutv@(u zPtSU5=2piJo-XEGE_o?Py+@Q6gQ^pM2`}|vH-H4}ok{)5(3EMSAkmjpq3?!38>uSc5D`2&rr4YAX>1fdoD90y;}z= z{*p|3Drt*n^jICVXE`!U5|=3GO&JJ~11Wu+5ZEG7wnyZU<`qcp3o`|RVx(xszU)I@ ze@SAG<4TRGp#7e!v`5f0iWbL(?p?>7DN|S~@Z@h=$nzH)-T}%{o$-LX_&gZqXzToD zy~rU2ThQ`xvd2|F96_2}-)(X}T)=|b=izg}ONSLH2H6UqK`K})4@>hfiXC0xF42HT z6w_};ajI*ST~JZK44FR?Xcf&XECf_&KCoUxPi3ctP4HsXeq7~9Zl`3WTRE26T-JK01}PFAR6AV2L6}TGuYK zBNU_0UbPd7_Hkx;&J3TSu3-9z0-?+aF(}q}MUkpLH+hh-JF#tTUb5fXF~~9(*O6z_ zv?^4!J`MAqoIq)DlfCJ>0xmMhhEpnnLw9V~n9^=kdW7idv-7pNF!!BRfpF zxuBwyw*<)J(MiL}IJY@9tK(Ih)$RdLIg4cG7PbNuG;G8mMyoOlDY27LS41y8_Q z3(Uq5=)KK;0VR*4Dz>Z)J5EU5xB!E9RAZ`?ADrnJiPk1)js#ge1~T5EG+$oR-TQvb zCTvbL@-3`(Mm+QBVbVToufSLco%!^eG@Rqk&^I$VPaCVnWM5`Rd?^zH9EU7SLbIPx zHW9Jj6oZm#LifLn-&T5pi|8Y-JzIEXpi_#y^~;izGyl;lDb3;rxAVjIcz4|oSM&Im z^lb3ZLZTo#ZGG!U;#)Z(-K-wSGWJ{!uu%<9*G3;;K?;m!FCk6lI)n!5CkdyV=~HoI z$op|w|@k3=#j~leVxJ0}#z#eDMrQeK$X=)5s_?R3a;JC1S*Su!U>1fu%FhG7I;Grco|IW>?hi4_!l@0%<(G6T*wOr6z(S_@A4c z1440z013F2Jujzo&TJ#Pz`mSVZ0BId(B5GovWOW@$$6+H3aB` zAex2Nbt+~5m8d0S6tByI<^{P>0CNo4Uek}PMYk9fkaj3I*Z2pNgFDuHXsX>qpsy3>S$U_-M2{L%cD`nvqfmPbL%a5wEe$UZm7sP@dGOa zeW8ObYVBZ;YwlA_0AMxBBM$XFM0jC1D<7plmr&iy$%?(a+o1) za}#^EIJHbep_SpUkR`Kkd$ILbX)NTlVof^X!qNtO^eDoAGtnGEkZ zM2sEB@3>DqUX55f4;}YY5Y_+?9)p6rhy>@Va+v{R0_L$ITKZ%L8?kO#8Hzjh z#_-i-!e%~v1V19Hs}XnXJz5)~(G;nP@&y}Ujev^PNv*~T4|tfzjK?}^xfr|CAC*0K zvI0t_C+AhOvbb;%YD#bLI%6UiTk$$Cj~rNUVT}0@FIItfn^FPEoPa{FU?FwBgQ;j1 zbb&S^*D3&gu-U`$@4VCs3uHqTrl*sbl!XGY6e7)FPX`CKFgi zOWRXVU}8K58+5N}y5M03;PNjTGw~FBTtjX|U*>Ubq$#S30MA?5oAY%b> z`)QL^OTWSbI4`2T6}%c@KbKA)XAe{oP`VvD-faoAv~n>dP;0dT0rJrh&|P&BXc^D3 zQ(}&hMi%Z}b0uoV0~itJ@^eeA46St@&QmgijuYz5tXXwg-zs_Y9qynUnvM!_*o$P~ z?UCjmfn3+rtuT>^ot_w@V!C1g9H(@lTO{y*iTwOh-!AiNI%pK0*$xet{S4DOKyj0| zIQ|;goe>+|78HtclqEpIG^cynn)p@m$^w9>;0RdI`?`B>AaSR*ZJ5-?;>1k(tFc z(Hsp~Qva;7p?BGS(zWW-CPd~S#7DK>6nHAnI~kKH{f5QPXH9zua!QrcjSn4G#;K|Ic9!kd{3ithB#dSt(Ffg%oY3)W`O)xdIp;3meE_fN z13xE=vvDEs%wtni(_&P|&l})QqoPa{r0(0g47hhqPn8Oa7maLr>#^A`1>SHm#=PIi zdtG|aLk*a--j4k^Mg=U(%-8adVeRFc&?ffXy04Mr$CEsAL|N^QWJMR;_X$y$7AD}p z+GD(>A_-t_XBVsqF|zk-NGA^tbU4XFN!?tXOD+-D;t!!Vr}C`ovt6%m&g1PdS&i&i zmLK?1t-j7K7Tik@4Oh2m>*`vqcMzr`q7)&`^GmlHsr*ztiCl6#&fFhb`|@K~A7kv< zq2KX=qwB9MU9*xt;CN8Rk_9@9+@W@$9Ht@`$A>7E;K|aakxSTYdui-{@;^SJ>Z>z-H5hryLm#9cGu8UF7B%$x*etp*4j08m__d8V+&!As5~i*?5R#be zHnpObtgoYgc%mT+l=yke6ph)TXcM{qS>WUg$!UPYr_DAq4S!B}AMf@}Hgc>J6R-Nk zm9QO+rORvD@~%bI8-V}H&aNFOnI7KS=$~6(-9B1$E6J4SK8h;~to1$)%C>i=VCzhV zWdM4MUmeIbgDo^ORg$=qJ6gqYv~Uy>gF46JJpHun#M&991M}#x&qLkd4l0|sfC>?r%jY8T6Q|C+w>~EU1DP!U1bXcD}8BF!2<|<79^k6+N@PFxHt-KO?O;rYbXVc5Dq}v9_yHESBR_Fo>fI=H3|Q`o?V2SA7A_)tz~~$lf@)$N>Oji|gk#k-EieIEWqj@$ zLd34^nQYZ8yY7TBI#_LtZ2?{&^&`Y=+E(m3Q@GPYG;;d@OaY=u`7lI-H=7(79O*tRp8b@RcfPkUa@tEvmcGojt1lRf(9$fB= zuX!G3e%*EYRwG$KAn^GK%GoiaOKsK|fFn4vDZCz%?bBff@E?#2=#nb4;p69#lvHm$ zj@}JTw5zZWddM!p1W7}$A>UYAAA}h*>KY0cFk@b>RcRf}@zk^(N4ZQekMg^8m=FdL z)x)abc1A{R+tI4fDiAVO?eH&llSl7%v?`B(?zkLpp>{fNw5e~Din-uTlF$^h|439k zXr>vZB8n6A=rGZ8F>*La*rp0-vNvziZ343rB`pJLZ>Kw`ivOs!s#JhlkbVDsTh;bY zpB+yJ4I16*O(X88)d3gz8aDTzN4!?%tDj9OkHZdER~@uy;woL3+&4!>$ncp><~5aB z!Y3F|ws+ijdX#G|JjUPch*TXcDj902myYgKMom0%pz@P<-TL%VLsertQmW+A@yL8u zAdO4)tDVu~iQJvhqY1U#UX^14iiPYtP`Ni3#<8}GHlI#3)L6n{an~s@n-?Bm&-@3AxFl#y z2E}8cJerOi_xhDGGBV1iY(N`p&~oR-#CMEE5M`(zUwsEmLDok#P0%>r;V!j+n{aG| zM(ONcsP!!XHT)~8Nxi-RI=OVr1MJKgO500L>=vrn%$6-8+V2a3szE@_#_Vlo@^V)M zzl4h4S)Q{VwG_%4tPnaHt8&vH-UYU4IX41?R(4f1OazZ--1V$^&C9F}yP2lnzTN2x zs^G3X+8HRe_@(Z;zcK8$^!!%%#2D%u5W0&+8YMRXZm8>{smfXE-uUjfG@`{^zd2cL zH92KOIU;hgK8bV!4({#;w$uO(Yqu@XuIw|vMNnS|K3~q}o;aGE(OIGu^RC7!fQ1-D zR!Tg39A~FYGcvd@9`1hG1beM+OSY!CFpMHqUP4hHuT_-@Rjy9ut+pf^PK-a9(bX>? zp6>Ll(vo11nCNA8c;Hb0N_XOR8~bWvf5F_>Lp+ywWCClNK*Z+# zs0`R5h}23?=ce!>Nw!Z}tSk4DvoSxMPyhjq$)v*stLmwS^}bLL=AP+TbzJ0fnGg}# zlM%FZ<&Jf?7p7%B|CAaSVL1K+RwVJD#>1^XbhR~Mf1Db2WovbrpOVIX`m$ADNLyV+eQWK)gkRfr2lHjW8zDDV*T8){l0r*D_N+^M z+-O7~&CDiDL{3BXmV(}Eax2}w4oG|D7T6MxU+RL+zYfH)(nCN-0c0$0&`zZ0t*_QZ z?Am3!EV&v0_YIJ=n!#|gyTmWf#o(o}!S%|6*@)&os+6ZXDVlzu{DpZ^L!y2X2sOnv zO`Ow_M_&Wdb9+9l$)RSt4A4zveQSO~tVn~}LD*_s-O^zE`#u-9dJqM@_vEzllB@8A zeK@u?=tJ{V}*7njTXGWdee$M~=b_Ss96I6`lzIn(~7k9kN!CofE=wOt> zhT2Gq>UA4YsJKE?Z09ktU%|7=+_}3k@?urvE?2(P=`!(K8V|{{ z+V0|r$S$+l_k8va^tpud80Hl^>)Yv7sy+gQOM&30)fEoiA$!}ES?ZayP?xido%@pd z2)C3c%_O#JhXO%rV-WbNXs!dCC!1YiyuDQnes)l5+@s4Khc~Qjj~jlH)_I0a3J}^J zmozF@+0lnXE5P|7J(xLi+zyyrU83OesA3%|VS#@tXY@m&G+i8Zil;d`hq4E+7HJji zMyNcfp~xDcuqd{-knV$n0<{Xa!a20^qOH;jFDaG+Fz{?^bQKHWm__$*mTHt#b3I&)Z5$}F@Fw#FN9bsoEHcv9r?-%ugZDN2+H~xgb5+Og9a_oH4c}-JHz&- z&g@;Ak?(F}EVv5L2&|ohEMU|EP(b3E^T%;>qAzF^lJXve`l44Oom$ndPGdsxeXx@i z95G^c1~MFhhGmAK=()w+Kn*9*$f{imwyUDsSFff_cLsL_awx)6ndxTY!$xpub`}Gy zb7Daa*2p7WK235w$3u{CLjvzxJ<;e28cc=L50uo@;q{T=QHb=(Ekhc-6eCG6%WY&u`wX@#}D74XS}U&gk=ttI)_^N)y9j+ z5nJSl?3&TTfe5h_7#<@~xy;_)R|_XGe89h;w$u-Kar!@;g@63rj-;)8ZKRnoe;MxB z!y5yegkRR#m9hnGQWhM`WS?hOBR^q3q{9eV3i4+SBE7h=at4)k>)$|qHsC}Y4Fv2zC~B|mCkPykB})y z#BihsOE&n9owGiBphpGu7Q@dWAAS`UF|Ho~I}9Q5dzc35F_<(suRZl$8ej$td>w{> zN%p4mew5U=cWJxUnc0i-BO6uE;v;YnHeb*#3Bo?DkBPlotHo3Z;{_NdegsHh>;KZ6 z36N*S*_di&Zg0SQ?RokKos_D`0XPK(Z6w{MG5Dw-1+%RvbK3O6 zBm|-gr<6B$ponDsdJbZsJC2Hr8Tv{QJe->;uL9y-5JGmubs(_0*LgrcAtDn8{HER4 zm~Mafqf{>eQrin~awnQ)Y@Qbys5j@%)ynifQh_M-KXncRf{gUZhM54*0BSGO^k|8d z=`C@0<=rCe<9H6^^7yAcl!MM?sZgArX?CwOU^70S8%szweVVE~WEkNdW)r6+_7V8jSuyX*7`)25BAVnR=Fzm;P znxN@4!b#I3t_A{9N-z^Q3@?4+#zq)kN$8OLh|-Yg#C>rYxw{ty4o`kh^fMckCxo&- zM455}Q3A1Mih*Z-BD+3)bwtDNPM`Z00mQ000zUh)N8fm~JuCz{xq{>f=8NF33S>QU zz{NqJ@?3J*wq0QC);w&zP*Rg))p^E>(C}wDGM#8CFwSxE+s>kh2WQXxe){wdgNUQF z>HK;Enk<>{`?PjZ39FM9f)};{KJu1}4od7Pu*)7PsbC9~@vi}RRdOjRRP!#;3M313n=g{uW+8_9L5+>$aI&HCHtvG>LlTdpvmY#GEq(Qcd4fA zvgx&s9f?sFPJsBLCzrrz(5(KxgQ?%4Kw+(b`Rs-q{44HoX)Mb+j4{FW8iNvW2RcKh zXFju42~hM!0~3;{NX@q(bfVcw{%Bi;RjYH+=w6As?{eAVSI7DB+#S$K-e*6#wRSb4 z)-F3UOd13g(GCD}_TXjx%PsIL;LDV_htexz?O%ZcfJUHj6An43FWZkrGJSbvy$J$jh)+u+DYK5!rUpBZkax%0Mo(bbszvzy^7x^$Vta zlM1;nfyzO}ok`=Nzy zScRi6#<#|GuQbpvpoCTL)MtR5Mt4_O*cH;Joa0D1{K7Z(l1{V_{6M_)Qzl^DIm{u# zzm~3quh@a{Xfvpi2?*wteNgJ0G(N<05f@SY3dCeiE`&-ow&~zI;DLTB3|OrZY&8 ze0P7~{MNbgcVNp%k;>rQ(rvreJ4R{@7eM^JN|k_e49&p%(hR@F7$)(hA2ki4pXZa4 z*m5z7BW`1;zyEvtxzCYSP_d~nkjisnFpRk$K`BcO$&pXEefq*?SN_lB6Qj*;UYnf$ z{9&>t^f~MA3KGckuCS`S?cwm6YP6b)tXtKW4sBSwpIoAkyP06iAFm99Jq1P*V4ZHz z0?tz$&3>1IS-jv1>v{CW_*SY8OZIs-gFKv7JGng-6WKL~g*>}nHU5tX_yPtRfw9Zy zOn_aOPFAQF1&B?7h#`lu8~UmZw$rt!Yr3Tl6r1!l*w%jX59%hV`q{ss^J|~Z46>*F zXK`RtZ(f@hwThMUg4G2`C%|+AE``{p@#j8uDJ)CH69@y3jrg4M>}!l6lfEEL=q507 zIiWBQDDZ|PVEJT;2!{wm!;&f(3%q~D7R))IVx${pBeWNT_#Poi2E|5d%D82}+12`o zV%mCC{Vn{*Q8W3WkN*;xgB>QakBwh$X|JSRb`1fNFaWk~@P+s|ypI+KS4YbRi^-nqQ2`HyCWqgjm0#Hnv3m17KEmGgR?$1-A_mu9Q zhoS<2)1m`f;zIGk^bbRD5kqiD|M#VE={YwPZX-$Ba0v*sGkWhkYi41YG3dlWgwP{| zrZ4`v88kPhE0YwhHN6Bl#1}U8o*y_NL7}RPpf=5Cxyy)N8WNa1l}BINF5EFnuY?n! z|2?#%(5gvN5-CX)y*7rWo}(t=pTR93F+Imc5J&*g{eGbC8rFe(@==PyFb9#_3RIN@yyp%WBFB}H=0EaHrh4L;HEU>((u=?T$P7o96 zr1%q{4Kx&t4+aH06IaG2Ie;KifO*GUJrzcr$C-LO?MjWGsJ@k-I&a#tpeRLNmVpT3 ziGpvJJiWa(Sl_762qv%}n!sG_@9#i@d1L`^LMweJ5Fr|;1PhKb_QDubCr8*s7hhBX zyNh-!6;wcu_CX)p36N>(V=y}oIFtOBCA5`(42Wa?;A?((6`10abR%PiPlp}>l9(8T z3sft)Wsi8gz0vR=O~x;Z>0klfW_gb_3IS-5l!0~S_edFHAjEPPAh~kq2aUO~e}KLe zE`*+cQuaIx2ZGemmhl|3EY=D@sA1V=Nhy$h-9MU#tNK-vb)zM`Sf7){3M){c>fa1(xK&HXtOm204^{>Wz1iF2S}J~7!FElGZRfHZe2tM`v0?l zFn9rv1Ft3E|IzVAAqkC`fanZ{VXCF9;utyqSpGX+zk2TfLqjuKacHN1+@O~k z4gyvoc7RHzXt6VTNsdq>f|89OxdT9qlM8WhFako+J!^@w+!d>XLaU`>WgLSYT91pt z|DTvFBNyELglCWJ&j@mb7-Ctj_5FDknws`%e76%(q!qQdx$iZyZ^oPgqx($ zmX|qPI@jV$>?{}XLs>NXB;P@-4nx;Z^>+I@T%H?TleSFfrYtUW-rid-(~?x`w`f2(O@7>e&?J#`Yle6#>Mx9T!c*>e^kg8IpstHUI) zZK?}WfB%=?jGk+9C_g;)Dr`MLpzuMTyzIu#MTo8RzJ_nN2~c4)YV~($_iIxeO-?KBRya^M6?eZu#%VInohKB zpS&_=z#)s3Q~&VPpU6-9k_MYzw54N~0SZ>)fs8Dh>CP@E0kZY;>1h1&5kT9XXppSn zd<iBOw}Qi4bj2D~5y?rUJO{2E?-@YZ%&7s$ zmjfkfzwt)jM>1J*2=xWP2Unt4ayV-A=bD1cdJ$P5;|)|=YD54Q63DIeMdY9VhccU9 zPW`xfsw=bDBY+(_G1a7pt{hHBeVgf##s;J*mf=uIY?%N>>vB%zDVx)^Cb9FwDM$lfx@28n$lY=3*F5V;v(U+#}pGlB!6F-%+s89`eCPrzmG9g z%0~^s1B(BWB%$zsXbB!T;retLgR797mB(K_far}VIb9CZH%%c;O|zN^kn|CO_0&I0Yv<=s280ZRO_>JWO9(L5PV@It8hIc?YyAMD zo?gFsCbaPq##ri{9}eOPC)9NOmy>U2cY3}z*9I^z8azCLaE)bvWJ9PBL9AlLJ z%P#*cQLi5wZvPAIg44?%W}z+AJesIXpt|1PY*~6Ea*|^n5AkHmBVpk$Rs!QRz_p%` z2E$8y*k0R-#DWiBs%Ai2@!!|RwHxsI(7;c_5KIX$-kcvNlw9o4sLlE3F46kGG46Id zAh2<<8onSJ67E_a@foA|HpVF{wBIH9OE1H_+AzVUnmeV1!)TA^@0@xN@XX*EGk9iL zmJe!j=RCt*Z_9!Ts8iJ?Ixof7qWm*?0T_6WbBZz06LPB`3DD+^4cg3+*oH52O z;UHnDL|@3`Hq;^B^QWk7tm9!D3b z?sKqh9V8pgFm`+SGCqVYQ($kD z4JObvUX>c)%i5UJgp8=;L4W0T5w7-Ti=7w_-xpWHl!Dxu?lNaG}0%3Hb z{~v9gir%{pLLo<6+kn<>)iP}pj|Z2cq1(qmK2NSYrp{R){6~gn8`aEbO+q+3$Mg^> z8OFlhf7PNS8UqCO34Ahwijml3!GC=eGFCAlx4(zbw2)WM+N3Dls&8*s_;eN-@s~Xj z#L6MJf$unhp0Hzu&@R{r>S59-hlM~l984tZKiigl1wAcLdM%(V z99maT!B4PXAwUqn_oiP6@2A!uR%c z8~zcLFXuJEhUviTPkDpZjux{+m-nr45hmlbr__$8nuSr#uiv-Dx?+qe7ZKGU$585V ztKuJiZyW^e8kPOgM=5V^@nHe~j$(h$CX@8<)-*gCh1s7L4k*!0#elr!s^Vyt`aH*3 zK-ZHCQK-<>29!`O%qt3KLtFsA{;XvYu*r1LI5nTaL6xU;kou_j0&^uS#>G052c13p zGZN!#Sha@Uu^PU|UK-0A&-|Cmf~8qH#&FgF3Qs{h>P*+0jM-n_SMKB(CjD29>!Wq% zU7+FQNrOA*CB_SaRnYDTvBow8Pp;RiO z%rlj#WXe?LkeNI4%)6hrxwW?MdAIM6_uIDj`(1ymEbjZf&f%Dk{Wwk++i_y9dfG61 zR9kI*+5Vi7ioQK2x3!ph;UsB0ekJATk7i81f3X68{&&0ampV`i7l z=@4bamiUOWKat!Wkj)pTb0TO!8HFYzPsq#(#PUt#smPDg$#gxu6UQ+0zNj%3hA-Pp zr61;t_Rh6WsK%ycqXVvdbn2~(R@vGjsNbUbFz39F9V29wJkcB(&P*JvYpOdK7OsDH zY}{0-qA@A?qW$oGL53a9<3yx2hd=x5=q}*P2UsZMiKGz;VIuqW)%`8h${QXcCdu0} zcQU&R=-$yS3fpUKZGD$ba7(fy2S*MrXsvV**|N{Rb<=$BJDf7LcTRDi)q2%o{x3&a zC+NNK=FOWGA7*mgT_^35h^sSCE%!)=3q;2Pu;3z0$EPzs2lA;WCvNb4vhdOA%Lh(d z_53nu{mk`9LDw7rw1Kj#_@BzxzMgluyezin2dZ-5&R^TOxVYMe20KynPDy!rc``Z9 zBcANXeGl6^9}yEeEcEL^clk{5rBW+QtM(6ZQ!zf-9h)84%N9eMhFj3w*v6Ie*da?u zv9Yt?4Yca;Yw5Bc>UytN5_QH}udBJ_{e`?Y3ZWNH7UPn0KJ(7Th{4{5%D?Aq*{{%) zTKMkFp3SOpJ6Blz{-6+NVH)%M;~W|Bwq!Paa%uMhvVpkCH4*jdt1HqGZ(6qPY-x-s zxf=A0ns?Ko<^urupB^VD(80RYeNhOS%LSZX=Idd6s=tL}$ROZ1O{6E=(P|Nk%GERd zo%%z@xC#2{-o*|vp*jW0ssnkdNqwbVagVoZ9JJ`KJ^Ai3gO9Vg691k)r^1%YbHA|)Xl3*12;NdmC|NhW z#HEqlX6MW2v#DslF;2%S4Sxv!Ovpo_va@sJT<)P-_}bO5=~B6V13}go z$T`P%+r?{{?uc>)87AS%Z{|nJ#)=nGF{>R%i4?i)jcI7jw&s{2FeDPvQ6n}nz zGMnSh*8Rn%H6AUvnVr8_Q%!AU^;cJBKlwn1x*Xr|TG}(wj?T_xLh32(hKCM$2=n7A zY8FM8ByzR6yP&=UA(k%>H>s`DRG&nOs zrjP2j+P`>We(&xdqzzf+82NfxnQcB5vi`70Q%Ja|NdNComHxpQcY-s7Hw8pDM=8Wy zH8^eF6iV({ZZwJKRtifjjx-;cm}y^HTKdwf zjz)7dr^O2DMb*6|43X18R^}HFwK1;EgBJ4aoXzPV$pa-P`lgJY2mb93k_^tKPBj$j z1logZZ|dOUT$W98{#R3e)0FZqggzEA(d)0`61OeuwlC9)FwT2(^8KZsA5V9L`3&DB zYhck8U1l%iE|3%+*YUO+7uSpV|JIizd{1OW%Xf80av{3<$N$Wd5f8rFQh~*_TyvRs zPf1joId}1R3@LR(cKHoAhY?kvWiI__i#;wHj{fPE#uL9YuEkzI@iCwJ}l<{I%KQ$l~-qHNx-o3p2tOG1;3JSSX6DMd?%Nwi&dXXkfy#)4wwB3*;jRkzr) zgb2-8)F1b{5OF^H*aWb^Ho$`o3c zsj8}~MVous#m|ZxWS;Eci|Y&xOnR{4_(36kFs(t|i$?;dgU=@2xe6&E{d(rg)z3UH zPI)&jzOlBIK>K*>c64+kFV~nS#XZI)Z{!ce`27A1QA~kAGe(vvS za}O}BeR}KQt7+vjiqEKtK`60N^TJ!#k`UarYu5(E#Oq)AR6MiWa-q)Et2>d4RZKPV zvc}H7#$ayI;Mt`^gIy^`Uog@k0YHo{H14%^AWC{x@|X{34y+Fx*aE82c-VcZ_OMQ_4qt z4J~xuzTT3xhl&5R;pcUa)(S=ch-2FMTf)guq~!SlXI3#)s&Q!$Z%yWF&gZt5wsY@h)Lz;YEHo-KN4-3*~H31b>t5`q$G2L zx9?J(5C*e27OL#J8Kx+4cy+bGuZ&(^R=srwS-WPg6Y9IWE#tOXY+PB5eoV{0{&rt+ znajppMUjS@pK6qqmDin|GXMU%*%OU?9N~jq)KV>J2ot^Ten?IkV`CE&lP6azY#9su z6@xi{^mx=Kv8Z0`?#CRtv9#M}&%6UB1Q5k~1BP7}Z*I}S?n*|lcqlAsvq7j^RxuXJ zD*F7>CKxRN&ks_o>uouyg5q(N8#29Q#Nf|zfpt;#yC-mE_K$uES53D!OzQ6ws-o3`f!4(XsCB)8iIBX{rwLDyA=fx|z0BKRm&h;C^hn zQOTY$`xcWU7HnY#WHy@^kGfOir3@{(n&=PET9x{P)%vUfLXGb}RX~eue!bd8FfUk= zL5+EWIzEtR^a9l-^pHYf29#Xs?;gk+rs5_DpVNiMS z&0pm*pE;@MaoWc;4)R`jK8L#M2TirzLS-Ly6#_ClFK_X{z(AjJn;sKoJE`1oCS0BArFv{{(f}mD9%7F42xW@(HHr*c;J)?u7Co(1H91zsP^o2JecKGwRA^<7 z&XuJH#@1W2QNnk+7%A_$r9yDZWAp)cGcBX`>*$n8I9YmG)z>|Kr=jc=`!p{`Up8@Y zu$cPY3~XYE$G)dUsQ+gYi+CWM?6AD(oy&P6xgVgIWd)}VWgsStFH1vvJd(}6W(rYO zS?BAu;(c3JQxQv1xIV}GHf{02L+lYA(QA&y)X$qYFS)ZRS}Bf)dXU~XgOZ&=V@JfL zRB(7gA<5;Xn^y<9(2B~+IEuoVLM>F+J9ja%{s`wumtd!ar5ehfG0e+qF0sFU(r4ep zwvy@T8QOB1Cv{JmT3RyZz!vi+}Uv|o?}K->w!GDlGI7APgKZq zhVsr(6Iv=3`5v@>e~Wse{jzN@f3^ipNq|YO-5sOoakAB3 z-(n3hk6tze#C8^T=lY7B+`acLzd=Rfj+R7bXRo%#;LPNNgoGk1PYuPp9O7a)>rOZa*h9k_0~u9*84eo8Gbv!m6UTtd?3urak+>< zhEUBDLh3F&sw+Tf)Oz}Cy}nw8jW0*Pnf-+5 z$UJRA;yR1J+%8ZOUt9Ow`S2aX!>-?2Emuvau`OD~KF=obZ>lf@9Lp+Z?K@QIygS&? zEl+VeQAHMw>Kt~l=3N4(yOiQPlnnZs!lmBIZF;@cCb?eGtxU=a-4jNhs^fDkiS$H- zILmmRNaMSknQ4DfwBpEM?b=X950B<-DGqx_i>ftzyu4YLN+N4K+3Z+&9FF?TeK@mF zO7y6#{CKz-Lz3tP#u4xTeKWJKx7VqF_sKT5ydR(C0#%lC4F0~Q4*q8>h#eZBIl}Z4 znI~N9?X+>~QqRqK)6~i&$0J74Z$8Z7XI_qY#12>&O))j1H0^GSoR>16b-qU!sORvX zWTeD9a*rE)n9h=z|5k}Dz+K4jeE;uT;&^|_2p-Mh5@2q}EXPI9d?-=Zcz7ey)h^}ImW;y)CFZjl4 zHQ44QXkqo0FJ-N$^;)_e3G&$P@y?>ZB_$jXpXE&w&RKWeyJoxJBRM;e|F}2ge@@Wn0988 z<#2&D5F%nec9h%W%C`fIUV+Nd0(Ctwr=jo^Ej`X*gXzPyWr~+wQr6ekC%*Md8F#s3 z8q`eAv}4n3CPZJxqe+F|5Fdbn>Bg_) zr!Vc=iGyb>SZ-GPv?XCGQ=)lUUnz)4%iiqoqLQ!n;}NSZVDaLTf3ty%1?z9XKkxD1&Ew(59 z%mWcAdUA&ZB zU=~NTf0M3+ZK53!;ODo=WwYW!O%EeEGMc5B0^9Xn^#axhw5Ae{c_A zNElYD}!S;=ulbrv)$MzM}iVSF-o6J2~UtVbKpwdexI6ZR@XLhr@z4+iePr z3Hs@#q!+o)xViX;Q`=yh_|P_&Ey{(L(rE*ww9qR5t&EI}Nhjr%7b7Y%RCq}_R>e`@ zvO$S>Fhm-hQq1pt7tqZ!x&(=Fll85#VLCrCo}0RQq!FFG^ z0K~G6SH!esh?EC^>EyC*5en2*ax!HzTshR|IMnU*$~(Niw7mNEw&3cPFXMS zQl1}C%{dlF$Aaj`&`AP(@Ef%v&VRbeNDodSP-56LK;}%wT*}T~Omo|uRQ7 zuoF=e7?fv^mrAZ2!=+@pQUeI)LHu-DnTZ!csr2ZP1?f*UTc8Kr2<4R-!E7-o(hX1gcwTcd`2 z#)e|z2Y+&VUUb+Ky5h`RrQq{2{n;D?M=LH^iceglNvy&jG(?DQM>lYFRs}!Y~9&s9ASTA*FQoLbA)-2a94AFjn z`PY|-o@#gX{_Ym;A8j}%dyf9{nFb(f5;T(ToTgRG_F}q`$epKr?R;H(x zxQ}P)*_7vIE^1TW(Z*8@co&J>A`PW6D^6hRu9xF>!nb2GRKPNB{B1Y~b>IMeIG(Zi z#rQY#oDWeGu#u@gOSF3fu8izGwAwMeb48m#fjr}r+mx_~;as#+{VY9u<$p<~IUO1gA1*bG8VPog5tF8=367`1ba#uhi~>B? zCuHo-~r9Q~eCNWg>`-HM6(xpxvIqH|(W^?)MGyMN6b zVOOAh$7Yy!a?CtKBK5&}w0RC6voc>Hm^PY=CZroN0nvdG9!St>`VH6BoQaWZuDs%j zdDjinm!fqhF$wW*K@YDzL&f~v$90O$!EGkk*kOE-Q$48m*0{TFW9&U@BH-M&PU5fR zO_=2F;ko$kZ-}}zM(UX4s0avMGzl)zx91*D&_s;fc&s){*~u=wu!f5Z;sW z=&wD?jRhx(>1jq|Tk_g-?c0V)mexpW`O8FkV-PBNon=%vl1+x@4W0IMl4Bb_ytZS9 z8u-V-1S>fVacU#m|60y3bmu#zITNH+lLS4-Mu*`9)pH-781kE#%hu4~K8$edpHWH5 zJLr@+gTlD0y3+BAt~@=CDnMrjztRf#$|W_nW0D1DQF@<_Zg?1KhATD3^;+r+7d;{p zPLS4K)Wehd29xE$O8Jp^Hzlj6=%;^GdFj|}s-88CVH&Ust0G-f?@2mkIsIrAJC@8e z#szhw^lM&pmG<)U)dNHa~3Zuy`cf);K{AX)%oj zEg%gx=>R36pE>$UDl(N0>!XWtxdyIDJ38DVKm+@7soHP-_%ulbcbul_3w$^sr6xt! zDRf|#MxK&|;l**OBw?PFF$#;ru2tW}tm%)?=?`vnMSwt8Oi{yTrH$LLn5FmPSqNjl@_)ufHH;tH46ZzLdCoa70F3@0 zz7vKov6u-CFBXPreOoC!>s%>fH)-VEnP+3Uka6^nva?HvRaOFsPfqCr$M5rE@i0sq$QW`3{=6pEJxmT-;2F({+JWyz5PGKl8C(S!lo-zE}a=K%Uvq4 zH3w(wy@kFfesbmVJA22!iWh1vqR%8xt~@7Tf}XrCU(SAO$U=3`aF~ruHcw71)cr;8 zqOlj_+vQ$=(U0QPwd{a#J5TL*j2Yx+#{y!GDc(3tZD~9_ynOt3?!%|^=z^0>cjM(L zm)<5k9^*;1i23z^*9e~jR@YW=fMD@J5 zQ?2>qWZRF$3_ohW=fX9x=^Z6X4)%hbLSs{WaMK?&_r@7PK#Un$Ay$!YaeB7SUOpz)bg_eSJE zH=|?kxa0Ccx}*6aodAW0MM2fHa{mdOfN!pJ9Hv|SOU7^ zN_46pRM1;1(kGRWReJ{la(G~)s>k;YDxUM*DAvhnUo$6?X?Wfgm2hcwE?P1SFF0gf z+u^0Hq7JOvRxf#Cc9Fq%jCAqwrH{!(4k~r>Y&+XLYma-WdEU?tZcayzlUcT-qfs{< zPfWE5K4*e1xR>V>PStMG4ekCJA1jj4!{a=2z&yp_qMhGRjdn{}&0**W z`?vPkG&io@_8MnUzY1rdrjQ!6dC;giq+346V(b&AJOjw_`|*=kjXe_lb>J^=u_IZhl3?!uX@L z;p5p6?Kl3*wf8p=SAwqf$A0Vm;@lT}^pB%md;f;)DC3NMlydsl=wS6ea=N0Ei9`A`-O70~Y3=)0=MbxzZi9`_9jCK;GNag@ zn`$Go>JVF?q(v#7}>+{{0KY2!T&I z`Fvf2Ah+PRk0~;I^}xAR|Kuqfm(@_@fVC$~c#Q<>K?F5k*-aYsUtdmLI!~Y~bTu|% z0Lo?|QTgM~fphc&n!M{0(w}!LfPX?K@sG{gbFi_7t=;hf{)Gvow@=xTX9+^uJbCg9 z71tB;qPqbT2l#`pAfAbH_}|4dFWH8FNUfK{MH2}V-XOuc`+slS*0C}?sgJ`VmrSBL z4E4`B(nb4Z6%w-O4D1oQEjIpkrz}F&bSrr5mlDzoh=id#H)FqCX}j5(7|fHI1%Lhr zT|+t3Ibbqz{L3e28IrinWPbL3@t55{)Wzk`-7lePZ9Yt*=jho@8w3AElY{rH1YXkJ^0f`{t>sE;S*fNYIA1tPOd%br@^P$o4Be( z{j(z1qAT!!wU+PcV_k0JR2Xk5J_x@@3H141cMCF%~>S3aJT6Kl40vK9-1~~ z?1d5+Hf4&e6EjL1vMnwBFjU&*dF4uf+UJx-*6SfJggV${XT`?GwnUc=Y-x_|DvcN# z>{Cy3;m&q%oAn{}{u%(NGH&m+TS73^l_5EYb;`#LU`nm~ae={=%>xN{BYs&A^?6&B zJ!tW%5V5O~bkVRqj3fJXlC1saGhbgWl7A%`(aj3)RuXJHL80jNvn@dONpT2VTrQQw6W1O0 zSjhBrg)>4HLU27p{G~W7w-a~=uutvxXrVwpekZjVDlt3sB7WX{ETDUefy>{8QEqSbs+$XO5(%osxbmzbA?sfM~ySeI`?~Utk<7DPYkFh~zw<=_y)n zIgfqEd})`>w#ZDrx5){Ax#!lrq`fT4i$q05(@9sX@h9OOoTO790jy_N?f%FzBSsHp zFD<~trc7npIiHlVeDxF+;RG_Zsi}!i8@mfobtMWw9L0xvG7V}xOp<{Dzf42iE--02 z%W2+=Q@;Z~Dz?J9zvVo~BnhUb0Mmi{Cjoi{1Oyc8AbX#g2+UAL3C*g@rYkLIGr_JP z6V7!OP>IL_%tQ!?Ex}i9avuO&S}K3qV6T@B@}*k8ak>+pn@kM6vSy@4i9p4=+>-2A zQV3Fijg$j>ZYGs&m}GEXgY08g$+5g#ETHk_K{p^2E7t70TifM^rF4H_vXU*p`7bvq zUVv%P40V5fd1z3m?aSXSIbog@^$D)v`cOjK>W-o==IQo=rAwJP4=w#BMqr*i);(#F z1;rL^>F+f&Jy$j5%r_Iv+XIK|pl(xPXk-Hc002Jw?p`cG zjxH6qvWRa0ikqa;7X`_?z6Apai-`1{RsuKNT_GCvfooh2Va%l}pfqhGBO~-3?<*?S zAvG3@!peYDSjM7!icBWN+O`$J-*PSXQ_N|zyaDv37fiWW0#uO+PD+!(9&;qT%Ooaw$JM~*nfy8kTyaNQt#FH6$TPq)f~@=Hrs z5KQq;XO~I4ROB_{ z_ML91t-VdqTYpf11Q~*3s5_;&1E^Hdxs zSS>bAoB;*u*`WI)Xr0MGmGhCqQA5C;7#7SFR^3G49hH!?mR>qU9^IJ3BJc-GNJ2I) zEPSsng?hN5)YxhdnuX@KZF8>-0WPzyL_8F*_jPeN=FUg~zxjcC?j~_n6ey-EmqDWwq^IbfjqyM}RW?V{nhkXa`+MGB{1G(6Yb*;%w!&s;KX&l2 zrlw|dF9f2K*UzR#zAT}%S3urviEaNTR!~?}ROzCmcVLD5B&m4s$gk-SGRjb*Qrt0% znRBi9r=lO~-i9vO1@VI&-?1-VI;sQp@|Ep5NA&-gdADX$x)_xp4#0K62h|>F+8}Ga8MQwm!ePrPUHtg(aLjh6JCnoVH z7S>-hArc1$i_2zF-hX)l$G-3PR|e{NwJ8A`w-K;$4P$+FSs5Eem$|~G*}9UX7K`<= z1I(UkPYq1`07^pW*dcTCzSHq_FWp%?YfkNh*uA6aWf`X3$03G}wT(Y=LIyT)SaSg? zzf+&0?90))XY3WgU1zdY30ZVs3U;I;trDYERsSJspIKH%W%3b1pYSsOT zW8d5J^DQJ3t3Jb4MsZGDCJwnW;o4OF9@DpSb|~ZGD)VY3kbke^nL44T?k*Pzn*}}a zCK)H2^_M59qabJT+O!nCmfB)=iN?^FYzT8)<7|k7HOMF=xXRwW?w^K_L*!bobVKUb!!JZr8=GA0fDPuF6irZJTiM~)3z)j_qxs^eaD#`7Vk1c z3G6Bk>?-(&B#BXms<=X6w#6O$rX}=s(Hvp-{8Axb*C+^3CU7&W0#fZ%Hf@pwkv&Vk z$SLFYAi6X!?_vL3eND$}89z3Y64oom#+{L!wnr>hlXB8Onf?Quv=@dzYF7o&P*c#e zEKI*ltejtCt_=;QNCdE;eW%@l|0Wd~e+XQ)cZKejRQZrQEbsQtPJzCqGF=WPF>6eK zK~r@E1A~v(IC-3@$?zDKOW8hBTt)FK%)6THrME;rFYAEWCk*o`KVh=|m1SbKx%RED zwsz@nHv(aEl&TppP4^NP*Nbin``B6E*vS6djaa270}!xwa7q>% zt(~YKY`&0<+77rW0p-UxWQq@2e7o9ygGD7(*$V^{6nh-DKO1XY4a&!!L=O^!YO)8L zb?a0x6P5J{)$ZF&27n?z7&S!Kc!L2ZvFJcB@om&xRUGJp8MAG?U`?Jg2PRS!2jgjO zKglN~9jKwV2;w_c*&68Sv)Jncou%+bn$4u7qz-wBiGBv1PI%z{AFNAcK62M}n`UQp zDO4jd;hkbW9!96@Y1_DTp$dWCm6>2^AD&hbM!BiDM0L<8#DbaNmw$rzv zrxS)lBl(q(W~VrMvu>U3ZLb>$fKX0xv}*U+-E}(JShu+s=4=Zoh<<85Nr)v_6FbRI z&M%2Tjf-JuDKdkRc+SO(_y1&ij{=9sNw(0R!+il@!@~(+2|^HK!qX0y`9a}}M=Gp7 z`|RsY1|X$vVc|#bDfNZ)29Wu_dHOQVCksfK$E}#j-$f(HsV@Xj*V_$1r@MJNvF2bJ z?5rn` z(-$n;Wng?2BfFUpg?z6V)H?^IQ6|lVJuAmsjQ~OJ~itog#rzeWE2? z6IM;7J5EoxD%*(})>sxlbdNtNDTxnfvwq{o3t1(T zM!7d@PJ%@6CGc$u_V~U+8w$BnND&)pxd6fveBYTTuWAork^(d3EUh%wHk2sCxg26K zA4DfvCK8;denm6b^se8q!4{I2_vXCitkAYX=Sl_#`YKh2I#eq&L}+)99~N4NGP6KQ zQ&ZCroq{dkv=t8@K5XeL8xq^NX;VW-Gm0se0W5#~_`pQC0OFEdWUkpLC#Bs`PxNPg%71%vY<8wFA0uvssR}~h5RMz}GH|N@-NLvzx+`+vW z@6LR}jerBX4<0_$=vY4C{WjEA%EMyasT*tE27zmY0)T0^#7;Rx&ZNM@j73m|-%BJ}4@| zOJP#@4`%S9_mkx|MQu1cjx-zIqGO4Z@D=#w^V`$aCTt&m+`nK>!sOrFTfO9uY~0Gd zoBxcF-ua&iP29ErvpaPESs@+^K?aI@m+xVZvnb(H?KUk6)Adn}w=%80Z9%Hbb8~Yo ze%3&MWk20>Yv+||)FM{mSj;&;k6Kyu6=qVWRVkc{S8v{Y z*&{_&xq(tr?}O*A4>BRkGxof4ggQ)yiP;Le6_R~In?${!O!5DBl)2vzB8KALtEfoY znKaE2*Dr}OI&tDe)zdYty6JBGN0pTaZg_?3776rrG(5WHfQoK)7!8*{z;Qa~4#z1~ zfUHlqnsMuUgUaOZ;reAPRw{CGF1Pfk)R`diduz~7B*SFR^RI~3u)v`2{g~O;(ZI4v zKHw`BEb){NHhH94HAMxb$4na2mPo(JPd^0KO^OJG79zg4L019Qg zQAHB>yN$=PPTI5tg;rKl$V#%(9noMDd*9XCrQlv4hop0Ae5h>$iL+mkF^l$ubgQD#Pn!A>_B{g z?Ix`RvbvI)sM*WsS}KxSK%U9^R&DMIXr_YrU-`Yzb?ep{6dR-@5!asHx9P$0!=KOi zl0)cOhX(&>9}fW+rx0sq6ob$oak;Oyr3+RferreS-yowa5MQ)+a&ppwOMa!Pkl$fv zYiccO-k)6hIExSMvX=6lm3;H){4X}@p7jke$i5qaufoE@1j=Mk^%it%h1q(m-W;!F z#P7GpRg!9VWKIOO#C2D2HqNEAw%oaMr?q!5I8%%b;s38XOjN?ty!`xRR2-j0V;54b zOH4mfu8bmEgH&t7+@n%S5Z#6a=R`jrrB-^l<;1L#Vz6m{^ZK>zue3)ghMA%)c1yVL z!20GxQK@T-Wm8eO<58b|N$9?!UL0YN{pO_bAg6=HRI1fiwwkeL2K9RxFeTdvHE=LDoa`rXpWGLIPfaO+{j>(t@kwKVBliyS<7FsOB(aus%t zv497&vKD~7H2#gwV#Wlk&;O3fccw@_Gg2c zszrS`cvee&wHRXZwTn8VrQ0MqCs`YOinD<_BM%V9zxS9Qk~~t%mli5o>H6bLrMS* zKqx67j*_)$JG58h2>Lg*6aDGP<#}~ADQu19qnOtaPNSULN*fh1siU=?l6+jU`7SqUJ%p#Cebi!%{$|7heSgIFRy5cw0e( zE*R$2%hMTTnEZ`p;DbeXNFTh#@~4jmG8yf=yL1653tWzr&uuZwUP;18Z{BRAXG`Iv z?CdVTPWogdid@jqsl2l(;5PCJ0yi1i@=wGQGejaEltoMs`D4cxlCpNvu__ykvICW? zJ_u5ge9!kNBOPMctDwyKDjG2~Sk|B`lDK4FXA?PL#X7|}1}a_J@CkJOoeRMOq3SS8 z5=dR*@A40%30`6p!_*mx^qN+5lQ>>Ok7-w;<;z_dQfu=&nu>_?y#U^Vo@^#1(RTF2 zi7TnW2n(hlZ+9=R3+5Ud`tY5TE2F4+dKi=hAq0D3rIs6=@K=qG`%HVwBs80PF8wr} z?eZdO|1IKplafiU{JHEqcuCViw3)LFwD`3tJI=CCn1(h3$NT%@hs;SiW|&^dDNReb zKs$S?ocX|eW?d>AgkIuD>7^g0iw!3)#t;_IT_$w-+*d@HqOQ~(3lx#EXI)IXfW`Ov z#os9#Xg0a!Pcm8k=rQKtHPEQZSicNcZeb(sX%;miJ$i^G+dg~ttQHac_QoIER8X#O z5pF1pS!`1`o zeH^HWG)_x=bJFjbzyIc(uy_faMcv8uZOKo;W!@Sa=&n(E2|iHaAkw_wUkIHCD&ME9 z@awuI?6qOjCObmIH<>s*6$Ih8UqxRq)+@wz%j)l_%i*H8G()zVmB^VRVm)i&H&?!N z*ZX3kGZRwPrrI}>P`GdhtxOyZ%L1+r4RlqK7GnF-c31~s*#=!DCZq=6=lS!s?~O@w z2E0L_K31Ho41L`ZySWyC9wuY>oV^lOZIr0G~{!yKyL&s$dG+qCbe0s5X@ym zLYa8s%R|l&4Gz#*G7v3$?$YC6-vZ?WRfvq)J`p!Zj~~xjOCuYx zeKD94@0KCFd;0R{b+-ISbI{lxPN$P*S`wUw-=;*VZ*503J_#Y?d8R6-PO)0I30mho z*FTJQ8--!I=BaH=V%;lAqL9;)L^HhKR{@6tfr-@SmKF<$q4&UQ+@(E&O8$Y|5G9sL zcIYOlT~BO7BM@<6#ODz`N4k!)@{`QRTa@-nK^xjYdc5%DpHk&&Po#E%uR z-zCy#E@?wzTl4GJucIm|o)5$O+UuARkvrtC2%AB!l*n?e^~1~A1f%NUP9ARV^ja07 z@?9^2MX8zUP(mxGB494PlSBB5mRy-QScN(B5s#{8UKcs8dTIKKs&=0|dD5b{&exV- zIodeARu5y$zh6SOM2)^BYUuH3Tf_C_(r%0aI%m$bd`H4B&u@UPv8y*0Z<3QlzVob1 zyw$+gI1yW-!fsw9q&qW*uEMrUA?9OSGj+z?)cQW7>5}M7b6BoyCiP7l4F4XSNMiA% zrwq|PTJUN~^zO@-FT_N|@>c*@kY?hCq73L_>f3%y`$i23yzfNQA47P+=dOg~owrk) zWA4ww>=%gUhrO{MBcZ`SVU_`c|FpgmYf66S=wJXbyo z3rh-L3Oh4e#$F~z2g$*V{Ceima7sdYEqU*5@?O7}FF7Hc+!YJ~s@Q8_V6d+%jYJ7D z**exi!nq_7N}Q?-zz9;k9twsCh@TI=r4nnl&XZOcx+(19kJZl^Y?i12+rs!J5Qbfz zpL`1G0(oubirWUmk4WL*pC-Rlgkb9euqdd3^(s*%^rlT+9{k#?RhSrw7)2LT?5jwaC6Ict8nChVN9=%!AdLl5r?-85I zgCKPPY1!|Oc3mK-mtbfJ<&Tu2%PGkx1umqhXw7d4*9?K zI|3sQQCY<&AbCF1)~fGlPZL+fK+U!Rovc4W1dt;-Wo;@2tR&IRmYHiGSZQmNDg@3s z^U_onoZNFSLi;m%VNo(?LKZ%87OOY&4G?3X=KU%)r`eMTFA@RHG&#!VJaHBl34;f! z3Si)n>p&^mllv*(TETmv|I$N(_`6 zA4bYrNVY=!!i5WGzdb(yhvlJyAlf+876hs$(})oJ^(8On{tOrk`+enl^dOode*|kD zsW631GW;fWYu@sOnGN;Kl-A&21<&B>!@_mXcc8mqCD!BE+S*zRY!}S_b?|tYIjs8) zNDo+0#6r@Z3IY06Bt1rUEw*{63~h{;!t#hg=NtpH(a`J($4=hIPVS$Bi7xUay-~VQ7m|MqT`vEScLUL;)mk8Z< z#Gi&hJir=jNa&WNFS0x=k37ZO+6~~ww5~Eqg^w-1n+}yfvRHsu~t00~w z;;?hx??eaMb6PT?H*NX%?%mtsr#i5a$l_PwJGAzYjJi98|aoc?DV4AF7o2mDznn=op|xEJH&WG-Wz-1M2M>fS!tm<*!FP* z3zaTd#vW_daUn>=&dyF9$JB!6qsd35mY>udKwHTQSY%p3T?{rZyFhzYZa9tEML-cQ zs!VZogfGUG&&VdQnWQ2)O^<`DxuwOb?K7Pr)V)Z^FH6G6(x)CN3y_L3Ew@Igkg};> zh}y5qLf# zLiMw$_0xzL$fDDJXLAV~fMB-)7~p>&0F6K(cm)lCg?W$Ya@`_>Es_(GuKE+5yz)Bi zUn3Emet<*lJDBJja0->T#QV>jmBF*~cfwSm`oBiTpHH0HaGXyC0p1}?vNk_duY~kn zc#v#zuj}FpE9Ei34 zXBkmN`thO!MCaeJ3LF0Mp^NDnFC6eaJz_$!)&j_IWM^PNKt}H^5m+Vm=$^-!->o*2 zN=@|Mb^RGm#g-o#t&F3Bl!PG{G}vrc5NuEltP^|dUSDg>9+o{FtLYa@gd6V*?b1{( zA}-zO;u6`WSHac5<9xlq)DamkW;umo|9WrLo`so^hhFacAcK#L%HZv>NJJ+C>(t;M z4aoSwl$#(^oRvB`d#Oq!;6+|Ml z(;DI}h-m$SJPu023248yboDFcftN^-Id8>jZucPBFP!v3P>ih+fm|V_{p*#VxDy!a z%>K5R`$veV=b@Vuq+{B`%rdLKCjU59MMc-ED)QE-cp=fNt8s`lu^VAnIu)jZ3bVGu z8DJ^v%@2PDi{X7U>8M69p$H0H&i%oG{qXLQ?wj<2rLfW}fLuun?j1x-X<_EAxyzhj zs@Z%D!&xS_0fPDK6*HRQflqCAbHW=-HiykriEdN&u+i7%TQ=#a+6fs}OBxt74+REd z>U1A-coBgv{10KG-;WaeuK51!UXNWzUv|>UI7mY8tUZ%4Wt03Jvc19-$77f~i<13| z2=!IY2>eu%gx{8^+GoN;Z;Ao2s(5;9#T~h~r+&Q(9+Jk!r^_3<3bq~?KLTPxJ#cYZ z(MnpUwm=%J+N2*3qIeIBdynTM7nkG%TpkY|hC`12v_{9yg_-6Z^$&dxV^u3h$#iR1 ze_Lh>U>QsE^73qrV22x%=33eC8Q6_F_mZ`FB0e^HKvT{iE5(T2yV3zhWYzu z;Mwg`IIMTlhWeDrVviWQk4TU6gx>a`(XU=b4*{(`G^xq-^13R9CUO2TbEuHH@S)$d zx$7U<@$)})5jC4gklRE=xuUH+K`)ZTl&ujIpPjF#*+$_jwfB57oanTn70|X%3{1JQ zgl>b^lCV`p56Gedcw)V8g7S!f5!>}_`hR9IyS2-}^#=nUt}sPsM0HrcLiLE^FCt={ zh+XfW#OPXz9#wQh-v}{)v*c8TVPg4Y)YIkpQ=v?@o|VK)A9nkIut-ANc_#(ZSBujU zGStgn$!s>J&zVh8F~srTPQaVJLYx;`U` z#6pRWaa6No4PMl))7-W%fQW_xx@haUN6Chfi#8h{`M&DflmhOK0=-d zlkD3v;e8s9l$XH97q9Apq9X>ROlv-nzbrrp300Xot`H@fN{9aHny@0hVV#A5fe;Du zvKx_%Avx0Zgx`4q;N1lXzEBHhy)K^wQrqX{(dfq-d18<3q?^+JLFzD~ z{*B*49n$fi+ymfK>I$7soN8Ns2s=B(s0HemBWggZ6rxRN8K0G4ED-}YAR`KG-nJqp z<#e4S`iO%Pv=@6(*8xy-5{fd^;WXJAK_@tXLbrTLOEb(>JWsTT*p039fb4a;NwS~3 z2SSN%kS9Z}x?~R!a}@nJx$yX;twBaK2fgMPcX<-AwgOX;{?Fj!#dGHf!^_vf(B2YM&c8wm3iL3$`q zp+~CrFo~WBG~u{fer-nA9O^k{nKQ5VX&P}b(Hhhaj37cn$F+b~#L|dSO*&4)!p`&7 z_wWL+4*nSVD;(>;`1GF=H%~P0X};!ZRjOP)`+-wyDjX8s%U$j9c^E?Rrb_) z={rRe;-+T^;E!K#DNCg&ndg}Md!XWXz%3y?S&i~}kZwV1W6u`z#ful?Pg6MR5m%5? zQetBh)blTByl;yFj~ys3u)-fG8RBEo?R>2ZP&q3L2=}%ws)@#BV7reUJ-UE|Ng*gT zIy_+3(-SlpR?%`MrR9noNChHmw&*oEbQ>$LiC#{5OAz8CTF%CW*er{t5NnI>oO0&J zTMv;xv#93FW}BwS7Uc9QZPL|rp} zL<2Se)j{HJ62x}1Nrpu<5>m1wB{(EHiYsH*IN&mgyUk0tYsr%EB#He;^tYzDN9>_i zzNLRI-`|!vR)`3zw^n^77r#h?klY*X$$k;}fnJz&6M9-`1b$byg}6_OG=>><1tcBOij_bw7nU%Ku5A@In` zGF^~r5MoO7L?G!FtBzPx3&8ZrFwNL#IP{AEXd-a4oa8BCBWOW7!jjqdXp8bQgr>3~ zgO~2Oq{fbtB2v|`4-<~FUQXHUArU=$l6ItEjTK%^j!9xQ<4d{^WJ>85UTJx z?76L+l3nOtd+n@S$u|y$a`L~Naq-{<1DytkIe%^Zn80hZSy=DYgFC737|Z9j#b`AS z^*j>N40&Sc<^Hqnz*WP5ZC$hq2U@Znhs2$w|Gw>Zy$25-NCuxz z@9f!zxYzE2wCJufYjHSgkIpVCOUE3`mG zdi0<4V2A+f4K_O27mjBN4)VDn#o(z83`#&nG10idSYsLj$=t%mF6i5^pr7B9H9) z842WHJR5k`5^S^(#=UM$E{wt+y++tJIrsH(wy!hhu`eYi%18Uzfv_7|VC(sRxCk9V zZc+OW+lXAeac&gaDXT`pV$gW!zY;fVT2WP*he_!&;Mnwd`v5L+z2x3bGOHxZ_o0!f zW8ebE$2mJb4k~FKqoShjnjUAR^pX4~H-60sMsOkp<*E-Z`LvVdB(XFZ&m&(#S6M&z z4KGOI=@?%x`i>B9aJ7s!wG(k;oT<|FAE=_>z$WdFI2v^teY>;aYs?6KecU%0KP=Q6 zssC8?_b53?T+?8qx)6ztGH!BHbMOCwG)6J-(v0WfI@u#^&Z)Hi2L8rMOgpx(VlZ2~ z2WZw_m(~o=#(VzUQT;J{a}gD>p=8iJQ?%<`%m-s~K>!@+|FFHtL4WV9=Sk7xvw(mt zA4ZV46061+l7$R(1>&J!9}7NY_>KDF;8K-7G%)7?HvR5j`YGOP;L-I3h@JAtLXCT z;Pjp#Ts}+iU_8<+$b-z;T21=P|E)Vbh|Tk5qvCpzY#76(;}HXbtIxtSTNX^rCbDnS zir9AmTj0e9%tXprg#2fPjS!^Mi4(OW{6)?50~x*Y_s7QFVE7GGL?uc!GasuWz&k6f zXUGy)C$*r2CwI+xT%!fZ! zM86q{_+tb{qcsBjU%6~X!tgq%=|S)#FyiOOOe=Qo_#n_jD(1-zF4qx>hXGE zZlgQD{b+hU_2YyfiTEJ3J1g`g^G zYDV6ABQJ*BuSCbGx-|;OYKWlx&l@uOCpghw&&vut{L(vXMy#PLl(wHZG#DvxM^;m-6q^Gqx z3&7{T`-2oNV2R^Isy04ZNV_BbU*WTIT2))W!LmrATV3pORVoq88JQ($8}S4#2uZX* z5s#J)VzkjgQVdzk@!@30XWVEwI0XL2_LYVE)Pt^(nh=SgF=5uKg#Z{Iw$)Nh71dJ7UK>!tg4l`_OoUcN z?m+ZjaN^HQp}I4z2MvMh=2kBaRE?+KU;4`Df3qAPixyjZ%~ENzYFBLy zp*aybmFBecqH|ik%4n!8#Zr^;a(X$()kc=|A`WSL*^{D~Hod5!)gU74RHTEv%xqmE zCgQ?4zk8m?j4$Ww`IHYemzw|cJpbqZ-!H%Wci(r?^SlVkf`jNooiS+g1ZCy6fGIM( zUnE4P?)V-KqHc4**K5}4rcB3Q$Pr_X9`j>;6hyvso|Wsqw+3#S#InVl#Wa2^|5vk$ zfzzwpde*|;*8Hn z_3_bqq{Vkh^Fk3D=8qPStoRnH z9|AzMIFlRYcReS@L#xS@*kQiAqW~ahO`%x1wcDkyYV^WC=r4>@VmxVDM&$2eo8S)T z=aPx>l*4w)yL72+;I!Z?=(JzW7R?cM8u>F94&Gqa(exQ{Dez+*50vi&&k9+91KvHY z7z|dHPQ)lx5D0631eySQg~7X?$Z8Z*JuUq51*Z^L zN-ot<;QKhjG9}IRr2-!SYg?+S3lxnTgWRFsP7i{72lV1<$^p)`>Lw{!B_;E1sC)3hU*g2Qh zI(*yUrq{7)dmc<)FZsEv3N$@Rm{GxM3kr`D&xGCM6XkAsX~p4x*F~?4*vl-_e3_?v z<1qGbDXA5b;*Pcxericl#zpTlQ!ucy@}wpftt$wc3%%R>lwbrPUObQurcefu@)4vT z3nPdB1ydtcVs4+<)0@3fiKFfcWf+y*39Ywm+^{ zO{W+rCTzwk8gR1)#3(W)G((suoz?}z$er$#D)FvNoLI-BN9S(Y%m7yiZj%EiG$i49 zU2;O9AwFxQ9c(+>D@R!{bymp{M~oOPWUjklvQZIx z2PS1vP^Y!G4f-*!wK6>poU!sxb}U7godDLfBqY?`*&9Zkg@`}04@@p0?DRF{4CnRc z0wyh?Sw5gkJzV(=95gTF$UI~$+OYUx;>B6pF3t*{Q>j90gE>T|v$vZO4_%P&`HK&#LOH@bc4xqLCn= zpQ68&j)vAY)fD@{Bjlf_5=(n_FaVjx0wa=m?_WDqJW$HWVf&Z_C{r zIB$G+wt926wV^+)3AUgsj^=ky3qh1MaT53lU4FZYH+|Ob)?PeipjOCh)$k&Py|15e z)gi)N%-5QWbTM*rP?&r;N|6h>u0hy|yAhTon8W2d&YK73Pri4kQ&a=Z42;;{NQ0zt zYPsq#Fu?e3lbFS3yBhj4pW8;|v+UyqV{Q)l?Q|#ka9@Mv&Xiodzu$oZC|nyJ-PrmB z28By0mkdcyc{f(}0`IZvpTma{u9Z-oIfc9ZnKUyS79l)J1h*JI(ig&5m}*tW9Ohy+ zZu(~kL2kxRjVQNd9vT%EGupK2X$3Te)yvuj~ zJO{$a!*oq8O$}Zl(#l;E$5x?ZBJK#DuxbL)+YM%F`WTHz@lK{~+; zf(rm@L0Cn-CwP!ff~8B=QP51BKuA<6h2mKwLqRkjn5J7=IfwMGRT0}9+0oWh!le2p z`9nEkv}KsF=RjU+60CcB2P=6tZbv@a%xO?GY3qX-9a z3QBP#Fu##%} zGO}2x@uz?2&3P4O+V(dzX(;dA)D<*!g$oDX$ICq!3msTV`AR7MDi{lG0RWAo6#OR+ zu52RF>`&pa{E3H6&B#zgUzB13TPu$75lnuY+qkba5oFB4ST`9^POY31Ux2ug*YOr- zZMItL>uZUK;2Nw#j1+XAQZyc!4A8TxVKlhWtGwg{s0}+fg3tV;z#OJoZ|d++c$Z|i zsThVpMS_Kp7quj}oib6>z<}^g?AbDbfYPlz3YZC-Ask^uv=`9e_o6=t*TH zoAC8b8>-1#x}TNQ!#Y>VBY+%NIEkhrxIwV#Cje^l!RHpDz|K@eO|i(U(Sd3k)Sj&2 zZ7eqcz0H;?@+YlzG)GAN!!;}P5sLufcAruMzlBk7WRv3 z6vhXqnXwz+sfJteNC;e@23gNPTxZ28ML8N7aV#PmzAJF*7h{JgvuIKvAOfvXsodNg z?8NyR1{R4wm|!&ucCG-j)!Kp%5A`ZF!BmvegGkwXT)uxB@db^a#J|7|egG(^1v=v^ z4}0d0vp?2(s2(lU(x!`XbYd3g zUAdBolCV#**KDIko~B80Gc}RE((ZZ8g{>v}8!o11_zat-ZL%$c)VdH~r==bBp iZs_;o|129nj*M5@ZCh9P*?VntELi5V^s1--f&T)W_VBj= literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-25_02-59-27/plots/error_x.png b/tuning logs/2025-02-25_02-59-27/plots/error_x.png new file mode 100644 index 0000000000000000000000000000000000000000..dd60d61b8923eff7cfff37fe51d8beb6832a3032 GIT binary patch literal 221104 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_uc_H?*ISz)sUGaw1>S_XwYXTIFCE!QYD=Ls=_mVE(L1j9XN=akcjJy&l;* zYFx2zPn_1?xJYL_Gh?)5`Enyb#rDU(E2CNw%m4_vm**^f)cK}QC-Qq4fZ2*NV3SVZ zCzPzWo@XL|2AFcKh=D;+PW*vg@_UJeg@qqbW4@JtsqsNsdHe56fbzJbJc>dhBkT+( zd8%;0MqIsl^JaHME~3C~sH16+fQMv=BGG|UcO5iQD|8997z@aDDlGqj)Mv=c*`a=B zW6Wy+P-~pJ*pbpW9q}d!c7qTNzL36A$M#wrIAK7$ya8$uBs4S(1XoG49{=ahpAm1V z2bz$|>h5k|_p4eL4$WLoz}}JCE5Jh`)&RGA_K1%E(!z~vyQ;?%JRg7AFFkq{enuTY z0hisq+}-~GoJ7Km85Bs_AalHh2yR8C!$M+MH`pgK6Q`4|cgszJ>aUgkQ| zVnCpdRhy7^+DbO^S7Fc+iTVSfPTRYO+3;(?W47%;v@S1WJNNDrIGHmooro6JZ!4JA zE1AcJL`T%Jx^V^N0*7oSkKM^Wzp$%7|L^?RD5+$ z;Djx~PrD!+zc){~U~maG*XCrSva_&B`0`aG`cWIIUc1r}k z23}AJiSG;6poKb9wp+o+>_h03l+;vnm(&Fh>C7CK?lV!zInaZOqCep=EPFZ*fLb>4 zTGIB7J@mmlvJR2%dw60NDb)wwOT0Mol^v3H*+{l}p-!Y+Rte@6 zq09w9Mv#5mmD+HQL;ig?TQ&53gf@Ezwt%Oxvu{TqH>M_vBfW?;3Xhb904(l#!chWX zqY|(Z$2JKSKQU2do8?^=nSYQj9!)W25eSqQ`*ufMg-YYAc*k~D!Y zcMG<>jeO2E$jC=s=8E0<8oJ~(d*)YKNN#=9{R zUc4Lr&ePp2R*}MHH!QvzgfFOeWt1XCrl%_)5+Y%Ca+e>N1pvt8%qEFblsY_>3HC%b zXND1yhxZ)?3G|mFjWCYZrbQ1p$vzH&yY?j&UD3K-c0;%vtC3vMS)ryqqD5o>+2-4k znVlU9qD*X-EQ9kLcN}>`IKeLeDh&!iN zx&H;r`x(4|_D8yQ0x#e67eMGcb8>;Kf*+cV5xz6{6i{YGA0at{bR^IjI3d>@s(_QS zMowQq)@}~u@&%-ufI&XDfR02WF|h~vNRXbnN8DUCbKVLXaBR0x0Rtm_&d0~c>Vg}o zqylF^uis3nzr&U8fvV$=-Q`FPDoZI{B9S-MAQSLdhN3t7B5;0y)802c4)`7Z&>_gD#V* zEIy6=#-$^bn;>O`)mB}|0EtsgJzEVYI2b+%J2yaE&z6o(O4>|>kx(wfP%X#C+=oxM z5EA)-YWdsc=RU{?OQI+~=v36yh$isIo;>jB0g}Vk@MCk3bq)hf6}!u9kf{>;nuR>_ z5%>^bk$HCR-H?aD@Suq2aXRRxx=~7 z-$t}wFc_9_&0$s+e;SJM%$A?A8G7v}*Ng z_2?)J0ckb*sbU|@^12~W;y689c#pDtG=J^zRV^5L55y_5E}b3*0;f)58OwHNave{6 zR&I&Dd;kN?Rw4C)fdN9q3(KxpULt=Px^}z0{lFICGuAJrFDFb^>$P`e<_KQ7uX3~G zfwQ+{-XM^bI@ztat__ZK1xa7!=_EFZOcIpFOXu2tY)PV zn(O&o)ZX4awY=NeBjm@ZAUXUtP$quY5OL(d4ao(L^(2n{k3#_ZZOK7-w8%S|juhBls{;oPY=b); zioNfMhYyLJhQBu0U)ABljTH0A?mXrC`ufi1hcQaPuZQ(2Yv}3e=~_LX(h0^`ff89* z01uS9Z^M^h#*svVkqg45rmoI~x(^>{m*uddB;>Xz7;c)iOP?^`<{FHyUuz?=MDWjt zBVeQxB9al-2Nhrdx`btGCAK*^ojZjrDrkeF)rPM5`DJ4e$OiuLhfC*2b(VRX%5}&b zZ%p)CKt;#I_`tB=FS^nD=Tsrn1C15BO*QGR$l3K?t_!lOy@YbeJy%QZAD? zW%(Zv48sX7UH3s!i-m$#>L4%>X=J0r zfLQ9hE9$(mxw-iW+Smzhy=+vR1?~Sj@M5N@C(6w-;Uhnp>w61C%U4|+P%}S|aGN6% z-9-M4gk&euxlZ3*%*@Qx1566;?CN}IFtW<5V^e4kD{ZlM2bS1qY_@!nNNwGt_oZpQ zPe~t;dk{fvD+vF^4JF*F@^lm)N(4E5e{I(qn={*fr1$++jw~Y|xsnqu4FO#pf{W!{ zXxU(SGD4O8Cav_lF7%xe)UZ8-n6T6Dfc=oS7sc8o=(H^8a4ghS)pm7Wh^o7ogsV@j z*bZIt%C<1L2P&D)Iw;pp}6f2*;rZ0*OjzIJdAcHbjYssKG*vx zsvt5Znh;g2zc|13jKPw=H*en5X7gKmcDVE=dPc7q!On68>%nkHvbp zgFf1E*m?Qhtfl_Cr(RLtAWrLrsCGC?x@W6wtx@Y@a?%UF)3KB7q}uVa(faxFV3ek@ zyw10U>Z7Q*Sw!+6&GjkD8K97;BV_vsdK%(p&yKRJNh4ovKYaL1uzDG?S0HGfdIYPK z*We*|q(IfoN$)YBUn|*rXP50;@tjQOzAEm4fxJ4+d`P}ZbA%+Se&b3DeD_%=oqOf= zq1?M|M7w2ZnR7d4$2Z$cSRw7BZZ6ocHlgdYHxWeD%Cn{BJE0+KF+7zHjN)lZ2eRKSTx@i6(sdi+Eb0aLBZDo=9}@##>C8 zGKFz81!yL3J(ajPi+3)@MRnVCU(q+YxgHzdNiQZ6WtrM@uo6{Tgp|7>DN^*?$l?u1 zZVJIiKJC<^Q}f1lWz>GN%~%};CWyj1^XbF+E4@-tz*vW~74odMb86~ZZ@*>rV){ja zc)%nRV6iu7D`Q^>pq%;;Be*C=04DNAEnY;-Fln!^i^2OtENru0m2HjCcWAl`q-EWf z9H*g*ns=|tF-7k$Hw@_Ne86qK)mx_Fx=}z@dT{Wy6Na0LXTJ(hXb3Png1sc`YWv2!=I;(5xwEjXlxvs5 zSv0i9lLS=oD3lsRAzw1>35#)D!qqO3)9};kq|ygebZzn^ct9?Nw zb_hc@NFA%mgQOy$hO)s=DF}mK{9HUo`;B$rjK<)X@c@|gm&B)C+s|Ev0**}NMguNH z$d8_c+vitM2H=J`iaB0-mUMB@zj0g~-fK&YS=`?vyOovefX{Ll9{w~{O;`8UGkfGU zu0KnZ@7U)mWo&G0javr&tWnoQ@cJC-g+!53K$l4wZXt{rIN33tB|IXf!`Dq zEAh%33!6~b*CIKkGE|8%vnHnvAO^E>x%CB}a}9l@CI|kBkiyW%{7|q!X=$CMv%ib4 zI-`Sh+e*M&1i*1@4fM-8BeUM7!sUQn+#qH}*kA9AmQ$0m!J9Jei(#Rmi@Y~AT=&f} ziO|tS-Xd)C5#Wv&sRjCJ7sifgMfErrZbTYt&+$s+wCDD81-b*Pb?@|s4w&8}fS4ZF z=}V~d_Q3XhHnL^pj2vFNBmYLzeZ#|z3O>k2WU@e4PCdGgSKg9o!w?q0A! z`xVw9IUWbKR&~iWBNo~XdoE(%D*@2(y2QpH<)OU#3l}bk+kgM^ATrXk!>Lh5$k2B& zjNn>PQPI)1n$fi&b^9pYbmwY;yeoY9x**5)OECQP!?)SC3D_2?F%D`;rw^qQI1|Z# zd&1jZ2v`Xp7D~RYy;s59G*?~gtofZ-%iA$e!#S?Q(A?sS%mjBsWAT%50#~&>Q0~zi z9RG+rU$G^^M2XG_(_74DV!k^uKVNAGOawGY}P zJVIhn{_AyU)$KTkMyaJN2E~jn{V#>H5m?kFwL~i`mno<-eTs;PASQ42<_4VOU}pW< z0djIBMyzxS5t#R<;HziBxCkScrIG~}Ov}<% zhiIDg%i=o*WKMDB$Z<$>(`BQxZROW`d-9=?knwaOTc_e@+bfaWvLIaKv2Y(=2E+qa zMNWt!ewGnHe_AaE{lD0lz?o+V2NsKbI|keis0$JfsRWonT*a|tLDnAIDixn6?>4U{ zaSI7CasOiCg)gHA2A?k2MPjUk=7@*02fqD7j)eeb2UAsM<{8RzCeAKy0)MB1H4 z-pLNIjCB}F9>~Pr+>|>8%F@y5^}~hIglP~f?q1O*F!FsM0u-rmU^P~gMPj|5uaJd3 zjwZ^&;ta)}81F+96bV|xwUz7-w8IFJ(N4grDjN>IY_tVGvdeItaE^~lcNl=c+fg5~ z1RI$>ulp*oMWH~{q;GWAhMwe6?3Cuf*7H{e1qTb0bGVdBh);O#b;a2PdKWv9Z7&oc zrs33?s^wC40L6)8zcvpTI!7E#vjb5u9IqY7CL__a(i;W?;hiQqc&k&&wM)txwSj$``I9g{h83t?OX`)C?c=;`>KR`<^ia_T;pyDpy5{HxV zC4KC>9>G^XgzS9^a>ubK>LCZ=7?B!l4UPH5#l<8B+m1Li6!;W1Of-VL{v~UQKydgK z?jANH70d*i0v-+y4wAE67{eHOh!e0HPav{npb|pw-CMSM_ip0a0Iumzq=MLWxK8tl zMSJn0p)ax-6P-=wer;|x|%@R*O7 zA|r>9RiS8^6$tN8)3%OyTv*zSR-Ek^y;G5o84v_8KDU{n3hC zk(f4+XG!XO_$uY$y`4LAfGm9No?rR!A>7n zr}y7F5R_eT#ci)v3i=;EQS<`~Kr&b3SI87C06EC>`I1x;0JtKurk8a3^(o`mj{qc< zZcnH~y04d3fsJk>fDp+Dnk25r?ft&9Gk!b<7VWQFXUdP0c$F<)69;1?Gex)93 z+*AzVr!@{gnoeg%lWjJSpGZV*R-E|+s|?$g282CfYGpODH^^;Bg<>6QMX!mkb_HOS zWOGP%vVvG~@N5x%x<-?XrR%P#hU770m+9fO;d;>=RX$S@I?MPGlM$wls5yANZB^jfAcy+4P=LUiTIOGvS2BAmTh|K=3gaVDypEqM_z zGct&exv`40qG#dGw4J}b|4-sNk{(+*Leo{EBM^r8G#uL`#WU*VmVo1p81u1nmf&x5 zAcJJ!5uo{|R{BA$61@&skV#@hE2){qAr33}l57W2WJlbxV~MNqV$9#2XyZH zw@&RoS7iw|wi2WhYJLyjL=&$QXdA~2b7YW+NhgE(M0Y+Ov2o9j^Xl*)#x-||!kByV z;{*H+{#9tn=QLK%U&Q!-pZsq$hzyKflgY-)x5yT~*Crl3oE2};6n!v!BdPvs3rJrK zUy^1~k464J6W{Sh&znDgySaHAx4!7Qb>4_J8$%YIGKUf%=^N1$;sRj@HWwXHRIYPi zprnU4$8~OY7|YWM#h~S z(Kmb5qEZskJ&1@He9?kllT1)U$RaA_u5~KThdXCBn-VG1wWO#U4dhiDOZhi$hb88) zquXQS@6=W>%+8F|d+4W)O#O|hS9XKt{qr~O>J z#sRC45g2&I-~7>#8$;?E=6jM%v{KTC!gT$aDMh|7jlVZ;c0PNT=1fEtaU#FJF0U+E zxF}QoTE!{iEgWC+tG7?R_lzowlPg_{SmfBm+x|X#wmyj!C#?VO9Eb2e{HPw>GMA!u zZWv4Xj(3iBEb`u7v^(VP?|z_Z_KCjMJlp9w7X8Mro;o7cgF4I6oc9I4+u@ByPaT_W z^kBb_AH4p%88=M|P&z}k@7vGwQnfkY_KE%!a34q^AW!?|fDEs%zrXP5n!koq_FS7n zEx9$}Z6#&1GjfEr7MxYxymo8xH+!6$u;+kAvCHQkgvB@qT7D|^DdYE`lA=^JlkZy# z(v)X_ZHv0{ZvOb;>Wn^<4wNR$&dAz6g*O5x*`J=+alQ(sghNve5yabM{pzZ{_aweZ zoNRR2uYwT}Tb?wirJmd5W4;Waxs^;7L1B#OF1 zhX3b&8Tv^x_Tu%|7&hTpNb-Kbi$6|G66?x_p9&My$kKo<`KR zQ&#ijj|Y;!c?a5r$QWvej&I)o_%h>pYWzdVlC;zfXAYE(WVPhh4BLb?u3A^53NN&2 zEJ^d@w{x5CN{tFA9D1}&@?^!eXPZ1c$oCVbMdZ)XnhpH5y;-hq&O-$BZ!;Ft=f7X35bd$R>Qar+5o@H|fUyOl45il2^|-PSo}& zw7q*(d11g_Z3V{hvfb}vHTP&wLm=BF^LEM5E_dr?ORO z_)Qmb?JaLyvXJSN`15JI1Kh53G6&KsPk)>HsFoI@sPlnWEqDL!!;fZgRw%OQeNP|fk9Lfmj!rv&K*N>!Q{iZDhO`>m{7Cc1vCv}!zvPZEc9NW` z-uCCH*Axx$vrzB3S&YaQ*UxJ-vQ>>q_Hc+BUCc4PKR@T)rF5C^#UD;QbvR`}QG=?# z55?sObp>klxvR6zo*Vs*d+wNS7mzj&<~hloD$7SvVcRDBdKuHVg&Xb zE?<89ob}V0g;)=-F8%jm@q5S@?i0SS9Wp3HChhy;-*O*2cYX}lq~cZRQ>a(o6YkK+ zR8~$uAMLS;;UPx>T} zisYr@XHJ3gx0u+E%{|PYUQG6^MR>E~guXqF;Kp;%{{KGbBVCCh1^=14`}$0i4!AMq zw9Su9k<`Q~3ZhQ3;vHuuwl%_`W%Ax_VoHc21NEPm=TQl!(L9*2`kyZvuq2i7>;H(_o236kI2))>D`reOuO}8{ znA=XnWXRV3I#f&U5b5;rBb`i~D7fvchU8f;6Xy>yl00eWANR6;k{5&nBtCH+e+=iP zR%7fRPyFKkF{;vH(y7%dzD2E>L>f2)_bxxto31tw;zp~SuyQ_x^U{^J#W9xK1S#S) zKF3@};hu@wN9`axvmsej69n~=sTd_)PTn$ceX2>Wm~?%HMh38E%$TfM$HkZu%qLk4 zmrU0)9U@aK{JS<;^oEU#rn7dEsk~(Rp01=rZV{Y#ON0wk<-v;-bu?$O&@XbVxCpIU z%Qea9Z@ce8=Qk%Wnb`Fe{PQv}t&$tKZQ zLxEz<`$UP@c8)3I!#W~z6Xh}VHS4Emo8jWf2zCC_J!-C+Bo9;N38D!mu9QWa*_l5* zgC&?~KeqX5jFiSrrUEamcsR&KV<&B%psyi#Bh;h{iqrTil`z?gaC;mfOpRI3iPFf< zM%^SWUN~VE1NKlBj4%E(y=;po7rGPcnG*I*qKn+vMq)_Uw?c$}UbJn#frC@5K1^ox z+#;S&Gh~@WMQ$rLgoD+wI4)e~Rx0RE8}f;AE4 z-@Cc3sMU4M&P}{yg$(g8MX-K;UOSaEY*-o2k^RK3NBpq)SAO@`IE^(doyUZ9=kMK^ zMl_ilS#3YBC1Dn0?%>t`JZ0RtP8@L=BxZhkMtqI`G>W((GmYV(_{laf{W6A2LL>Oc6y?&1LlvP_oFe|_qysnkBtt40mS>_EYgA2V_!VpZvug^a{lA15|g@qXbYOlce$>xmN=62Wk|7%OIikWVL01O$L4JE7J4Y@4TMtR4BU zPMdBzcT5NW=Pi+ZtQnI@6zc(E#~I=21O>vRasN51;bbpaaTCuX0m}sGB+sJ8qrnLh zO@k>VVtZqPq=mE=iH--<6U2%}OeuML(C_+X`U4pFb@L{X+K`iCW3J%x-vynScmz); zlk<@0nB&PLOz~p~WwClIMLqr^&hd*Ji!iAmN+gzaq9DBwuc6O?tga_f^3Q80<4N3P z5+|CBeFuA3J~7PC1Oa2-%sy^nCoC1ktJB9L#fby&3!}_WY~RF3@pY%G5x4R`U%(56 zulqNA-PcCH`MS(+;3hHL{|Re|iQ!L)PS6S=B#km=t|zuui>#iE;NKnEx$m1cPNQ90 zh=uU|`qZBTMO~&n-a=JMPGTxqeKpYW$%gPfT%j?gd)zRRgHm)5a%_!dAUA=oBZWq$ z@fERPfy_d&q!EyRq%1L3e$mgj9=%UoVxnkao(*H30^dXMwY5N$yAc3ZX9f#LCistd z30NF3v@BA)bMD-^Sd^(|uGa5#m;RQ)QiqZhFVsWJ5{$H6u1@vbwlj{Abe>(L2CB}n zW=OyCOoe&pli-mxI0vQNb_Av1Mkp;|fM$oP`_jr#4W!g`=V!An$2@*M?NjL2ms==` z$A+{_9OnuGmuOjO-xx^1i3#BEAO&c82I_vsC=-$+IA`#9*;WGlPIoZ}F0&I)mXiPe zk548j)WalZrw^cdSi}1DQvXa+Q2FxZ%jA(Hh0#tQ>zC|O1jRH5)hKSj^~lKgCFWD=E%$<9`o%1((1^#^f_90!QP2P6=i2#TEC8lT!`P7qmHs(`j~*46xT z5=R?EgYJspuYr~Hc0=V#_>TK~Yp_dDH`Ad14*{H?W8R`+EE0;4{@3LaxJ|1XoxK1YS+px4sxToM~=dqGghmgCPKZc1M0YFkC;by6wl| zbWlXtcMbN&rwanF++x-}w4VTfLH^?gV2SO4KEbu94fPK5k>3o$nh)`E(aG&e1SEA5 z9I%#-KOP2rgm*;5E~@h4If@c%fFg1=hJ0ENHr>wwEK;UqM^ku?kmDKxtW=fl+*Z>E z{Bd$E4t(usI)C`*Q(o!)8${gwGgh8b6h$%oLV~umLzS@bMS)X039cB26AOU)i2zLr z280L%sn%>Q8HtE+CsPxPqPy&=3jNRJgVX4LU%ZI=jdyM+@IRgT6c{*f4&XJd3wABf zx>+;afQoUYSsWZWU~Dh~kl#9YZ9J(5lC3>oBRukThxO+R+}WDxgT?wI;y)WIVrD$P zV4)@dOf5la9xo|^Tmw9}x9s;*yyanZ(kf8SBUeA?GbAHzBCyQVA5Dct8YJr*+>I zO3v{+S`&@NaFzzyyxSzcabsLXdt81lLcog@_z;qb8qEXSUp2$l23G4ADk zqi;>*xd?tXDOwA1po==9ryaj+cx`g*zj3?&og7C_qs5?#Q~%9$HxAb>ZtH=zhbL<8 z?;AG_m*c{`H?JaSLsC{^1U#X*v~*eFkSl7XJwY33m1#>#AWGdNHGoETBn2HENeypS z$9SR|^;xG7x31Ne6x@vuNu?4B+$5`i2|P~4K8&nwIUD7D*0ra--!fi)j?~Brz2WZX zCbjoD_3?>#_0trxqb-wC*n_BcilxCk&C)n{dsR1H(2~1jjJpv7I^pJ_)W09?GIvc*rwqG?FWp^4}j%=W{UfYs3nq08ys20am) zr2eADmO#xz*W}7o|DscR59Vq{`S80A98&GjV&vY4N3iG!s2e(?&!*xr{~ReV!eP&G zEj>h~?1jDxYCB7?&Zw%eAFU=LID~dmKTHf~cc2j!W5#GO(bIWV_DV=u*q% zwr4<^H4gpM+ltLXAI0X$oayO(6312kcn(F=wJ%_?dkzb@L-z@Q^=i_ugObs!Bz*;d zf=QW-TumPq@L8y~&&Dy9fck?T=3|#L)4z=ru}$@MUA$=a%~XT@j_KII$9#!i2WhRF z89@1xGnRj36fc&x5DdFPZy@S#1y>)WTmDn>ppvWm(yjX+-tQT`hwY#()U0oR zk-C{o3DAM@UAWqs2u_aEsiP?NdTQwiYOYSb7@yOU|2BhqrS`F@yW8a|n}>8u!X~-Y z<=DD|y+|>{;4F^50otz>w~pqc7G09q=4i8q{NS4S5g(w-qf0xIJJQnHep!s+5e@>B ztILO!>oR6FLDgK?0*BwEk0WT`L=z_LS}@TG-7VbMhf3?DmY&j-1_@{O8$Qte(WT(m z=ZAmNTrv8yahF3QnpLP2`kg-$zIS-L`3TXaAHC|}D2>g14 ztbFtle}{F3on+a%+Ty~#OH*v_<)m?qI4mHI&VI7@z6+%rr#~ztOHp;_YQ$LTszI|v zTn%WwYcWp7w?IV@b~;q93zQtEQ{_=qlNNmVj-1lw#hz2?{pV_OtUg|H>s8hj^gh&+ z;o&m)JdDFT-C(2Wy}d%MLj!ons5T-<9hVV1-QJfPokf0vM$Q5vo0925Q$01+m&Mhk z3&<>g=i1j|RGXnZqQID{FVRT5G4`l3>=2V=r;?H>j9YlL86kf#jqmg3s6(mN?Uo*v z+0r2$COpS|{&_boCC<1{p6~2v?qEVsWqkI-d+i%aapc_Z}Fj0oPXGXT^DZkY7f|==~0jkx{8` z?8wzYrSO!(rgIW{lTr!dIKnKN`0kBsM6pO&&mh!lP2UF3xSX9PtoqgJI%hKNbK5

>R43BkQ=AVmZyY>|I5B0tESlsxQ=Yl#zU5p%* zSV8mf@1MH`?VrjdCT79T&dw-{G1fYxcNWxc1lGT!>44)gl$OTA`HwbZ%@BQtn#+Ei zk6hj7j0*3rD+=gDHq3yjwaUo zKmM+n?rx&V&+|CGD`g9pXkQIGRd?|OD^I+9Pq->Ma0xaXjN`YUNQfLs?FU?eR6V8z z8-XxEFQ((&rX7V~q7qCehWaEuB7#)d89h@lx+}<;mwv5dDo2~=fO>out*@J+vB{oe zwryRp*rlr|Xhe{WGL7cqjE}0CzhUZ`%)f4={loH!-Y7Sl3aOE`q~4q5E7Z6vIJ;Q& znLE0yc-9|j_)OOFy^4m0kuximeLY9fP%e zJc6yJQ?p+~kjfzWKOErOpQGT7vQJC+8~P5%Q&83{aDl4_n*!PX^pSlsehSr>{;XBC zNzjf`pg*Z{mo^OED|XL$zh^8BE)XNzeaQC+b;GF~F&#r!1I)wH>iUE%a%zO6 z#gFY-rQ~c$8J?U4+A|Fe(Lr$I5jRX+n)8vA!?DKRIegFQMjh>8OIEiyexOI3u`PaI zEXT58mS`yRxlbZ1u2k}bxrLll`lI{Rl&cA*Zsp1fVGS<}8Rc>me!v9!a05tHn<&=bQ&s% ztY|ttBY4M0<_yAUK*E;`HI3)F_PSMAB%8+v$5*u3!QN{2kMN52#5l=2q<*jnagE^b zG;Db#-DsQR-JM2dG$(>czzC6k@<`=|6_1uHr&bwAo^?ED*PkRB`Qju+liSq&=w+R4 zjLh+;_nE{_l}J;xQ2T1i@IX*P)2LfV)s^l*&D3U-+E?t%p~j8&=VZ^nWST>PbbKD65<^t+NIQeDSCf-^f?=pAQkJK9}N zel;=}eRj3Bn_GBp?XG=-j@or@{r=}DgRX$m$QPc5J#D&&ka3__&Wq=;my0g#lUhU8 zi0?-cRVrZ}l2-dPFu~jSX0cg=UnYk{5ymmOkJpUWijFQKggBgek#;!O`H&=^a{iOc&fvvJN9#Qd-n& zywlSgJO9Y8aVjg9eo(dM=t)D_w&PxPO~EmJ9W1L(;3>gFPt|K9Vruw>>B+*GFJ%_| zy*_#jTIj126FeHYhhP|u0e|FbBD5E(@a}W<)gKl!V$)lW?TL#6icJMjvq}nd+k3je zx03K}lWh0V*rgW>4Kz_$w}W zvQx%|ubMm4Q+ux`eDV!5YN_k$%($w$y>Am!b)QRvBl%BT*Yy#BHW4z08U3%wjB|@| zQq*o#rDVTCg|m@iUA9Z|mn+J(s`PGE&6IX%7%LLE@jUlbYPlflba=Q9Og#DuHP6g- zKHD5>5+b$EpKWOCE36ddTzcZTvxHsiqi_3Ey|!_}YsA##`>N_W+RKH(VnRE#;o5vj zdCFI9@xz>ZUK?VM*S)m}&WqmVs8_M}(|bkID#O#KrqCpy{SNp&F{EAkPBLTba0bNu zn4u9+BqSit+aVVAL8kdZnBU0oMTOzRW350=1g&_S+~1Rvy;>?tcrZaZbxZe<xA|#*dd+}(=j!_wyQ^6f z=B~}4sC{}I<_2zenQyWf5cKh`{iUNxv-^m5B#G~#924zu0t(*iQb7yj zUOG}@IdU)s|K!ID^QSMr^{BOx(7ViHJNICI9FG+g)|w&vhsEwj-ka`Sc6@o~hJ|FU zoQaTdV`}Y%P7Vb-Sqn$29j$gJRt}!q(mj=4(A$}>5a7|F5V!bvWtN3P$sXe=dBETC znAmt!{gI>4Fo(&I+W8M3^{$ZEBZ~6$aq*T&ODdP5Xm3#Yx4XlAb+nuEy2PVdEiP@P zE^Fn#{mJ2JsPwP}i^*F%YQeeZLEO_&TFlv3X`_00VI`7`_8;?+8q2&6!t*cHV&UGK z69jh%R#w-U1ot;^)W*}BOYU@T)?+7Qq|p_qf4eSyC$hR%j$XQGI|K6$1DM#;_c;CR zCO+ioBXYIG6vLfKvdLpzl4(}UI*`Nkhbat(alSR}0r}iI6s*RzN)XPu!+i$FTaf`y zeB`)wzQmL6oWv}PSpHEaiqsq500B_PdZW8w~>cqjcYq>V$KL}al>+& z&14u7Cl9Kg>?z#3k4o=V+)o{8v-BZk3Mb}o9%)7*L#wxo5aC^@8v2{x;!tnbwFb63 z$5rksygQDa1X^=|!J2l(kW!&|@sj8ps~E3gMmN#XwVS@DtKDAvo}y$gQeyjd2M@e8 zsr7eh@(-;skk35xZc}4s@W{vD?Wy`vu2nb{!}w!<4DuC!w1XX}gb=6rr5?MR$aFkF z%WpVvuPWL7jEH!^_DOqfZD7piq|32PhF6wOrFFH=W+m^-RtnlWx_&x#GTuZSTr~Uo zv{HRX^I@pOBd3#dEf2}HL_VnnQJnXh9n#UQpnZFMvaS;ayMkEq^o`v^`XFt|b#WnN zd7L{0#Jh+7xF*3*28`w`6@O?C)h|`kUn^Z-c5WswKeY^pu8?;=@N@CrI@(M+d~GQ; z%l8e=vJ)oUS*JG#!e}9LSxd4?;o;$&c_&jys?7S$%KK{^^FZAq*F8ii7Ib^NkRUtz zweNg{S^YFhl!$|(ao$;nt%8UTE-u9ynpuSL zFNbNWfSB))GvTzcbZ*hf)wcoR4ST(Q#)geVC|B<1r?otFAWCQ&wIaS~Y1*ECZYrdp^)2)6&xAIL5JWaK zH29^qlV}sFWmsj8s;ZCavAPy>OGh1~43|2N)U=|?-OI=6%VKLpJ{zgJCJ#}JilcC5+A#)C}wKCN)}jKZkMkQ)@mIli(^ z3|=yG3O6GwYXOs?VPq9@pk$wC{?-Ul=O*PkWrM-}sPMPgwjs9zw0b9sPCPZHcag&N z6@5uCKu16{854~3XkBM+`f%=$t&cM=VPfd?i%&65Z)a)!7!WSY^eHY|l%fnzy|pc1 z&S*Op#%KYjSLUF1(HWqH@l{IqRestO2yX;RI(T#lj{;$_!6r~jt1Wnn$Fj+A3E(Nn zl9abyX>#?`RteC$xy~naYc^gA3JStRDC*LN+I4!9I9$G+Q+q-&T`)b?WUed7&}3RR z9>=FLLk-Z56sxmjjE_N)!=;M8$C(n_C~6rB8^rvCu!};N>rNu^^s$9(LiNAVOq+}S zfLCzjr*l11oEXaLMZDs~&0pT@qX>W9~2+o;Ou#q3r z5Lh%HFEKpw7AFp$<)7iWxnV_>lAD?QkjoM{| zUDGiv07*9VBP*;BseF$PZ z8>G@VJx+~tx4_<3bW(E!!+>5|9(1U;nlN8Lfu2fl;8-K7NgaY8L>)MIg5}$u+_~$i zdEx(zm8U9RyTdkS^lw(_WE>iV(T}f{IQLwH(3x_+ZQ$*&%aPg5O?kU9B)7vp-;rUV zdy_~Gop2aR!&j=qHjEFrCd5l(41_`2PPS4QjA&AoR$JGsSrciOzb3bqaDLU{0o9L2 zc`}6JPO;LsiFAZKF5sv2IVti`Vgj~gN+H!N!I9F&5^8| zV!t3BrV!tt+4VuLqXQSJO-`Ix#n=WUVagvJEW;j3sSCne7{A@8XX9~+J!37}w(pL^ z2`XW{Y{Xb{r|cKetNqZx8-31E^RF0dIdz8#dnpXRRPcnhz3t=rYT?C9|McN{n9iAh z%S%2o!Mq1tTJ02Aw3ro2{nGmmjwAY*8qfLT9bcR3QqC6)y-qv9MX@~yA^9jmDkF`Z zxQpxcQ}ule2Cf-gB7;wuB5!+6Z%sb9xa}Vc>y_p&72x&p2EFM_R!oK+ptkQer`nfU zj2kB9=DEQHQ27)Sf1rpkv7kKKnIyN#x?alX)ywGDkx3)edH4)mlJKHHJbcOR={h>A+6>OrE6b z;nHZgDKH<hgdMGzvL=E%Ds2#cH`;aLi9L}J-Z~cRguYFV1R8P((c8$v3D%yEDJ&6p~ z-Mi^(Y?NW-M&cJ!Lx$^AS*&t-uRspgASDgD-a@h)()>ZQ`J3sFH9 z##7$1Qg+&YMjhjYSH7CfgZc-#(as0!88?|p&gG{i6YUw|-mtmpA`?TSLX{0|AFISs zym5D3M=@Ejt5h%pAzuQ#;*{3mUh2WU#7wqN4r`C(`7&1ALFJm1QsMEtwC+ZacezT3 zqL!ADL7`gD4d9M5PdJ|n++IQ%)<~Rct!_CnHiHGb*{Q}&+pr7rdLe$h?^IqU^(_?r zr4H*FpvH#y>pWBmns*`h)JbeaF#MtK%}d*>av6S@#<8i~WPvEO!4V2=C??0cm8%-tsc(9Q%LAmp( zc4AdB?lkodc1|@&Sv*?d)wje_pzP|I-0$MlJTfb|BJKt!r1>+XEI<&!^iu!juPT~) zXOir~qkz%=!Q{F(F;yGlI?GjZbEtiBNe73D5r~J2r|;f8s)@f zc$2hgzwFZ@kIZu~`gSGXV0Ya|ebVCV5n#{QKAZ(Bj-lFiWK`<00K@AdPAFtcqCl$t zERiiZ2Wxw0@SfGi3+AoMZ%7Tgi^MLx)F}NU%!h!(Vkl+GS9kRe#>%Glcq4#XSjXs0 z{Y*-yf)TwwZsvfib%Wsh?-J|ntGi(bWv51_eOb2d{p-{>MD`avXHv3TfAj>(j*+T4 zK0YU8LKLqNzh1bjZ0oTj&dHm)t(j;hxm;BHzw1x#Q%sN%I|{qT7hqJl0F$A_LKqkE zGizt3Gxc-3G*8(o%te*y`Gut}e!7sAbcRRx+!wY_e=S4Qzmlwd-&0b$&O`4Jv6a!W6v;2ZT;3CV@ZGg zpkgOQE&j)(D~LQA;}_$i@RX^{QHG+eGK=g*Gs+a~nHer1!!KpYNI%=FTvwqJ>?tGs zkvDZzM1S-zmb&h|iz2|@BytLwok5S zzjJna#Mm8Xdcs8Q|8fFZV#bm$z?78qojS?EN*VrT$B;Vk;YPXl6y8QqjqI z6fO3$ag*!v`xbK;qny3t2$NM&OLYqqb$~Q4gLNm2Jkf5nOR;9+QA`O{C+2PBqC_+> zMnpN2Q6f?{idd+e2;(wEoabCQf2?^myUZBYA&-^Xd9A)I)jw&=n4=^dK6SYMrxq4t zx-#a<8y;!Z-ZPWR#~W#}|E#7e$93O&zAw_1F$`11kTot52`Z(mZ9bYp85T9j9MA77 zRDlB_w(fh}zqWd}Io<2kSvL`iy1EroY{(qPcbvbUnA(gl*U8x2)rcuwB*9XdAG?du ztV7QBe!X9S5@yVhA@dzc>a4@~kZnHB^r`6{hQ#x#Qtj-tA6dZtu9wrEY5JqPV|sM@ z`?m!`Eere^>vI2F(cUZ3mhq4OItC!SnrbA~Ue8eQ6cw3<5ND0`2(d$p&=fHy#@exM z)81o7Sr9)z_DVTb*)r}%^Y#oPYx1vkL|68+WayCzxXxOoudskCxZ}PKS}L};Ih@IG z+}YcW+{Eh^2nLDMDBASPmDCy{9bAW9!u^K>ZyY=bJw;2w(08@YWlaA;Jq7p^OkA+i z8^J6 ziRs_?B#yG$mbrS}(3|v;zOALtYK`+1#MZft#9G&Kw*0+G0zFc+@kssB0R@v`x66Wh z_fs%t_bJOMlG(ZvG!H7bH4gqvuvvw7RzmwT^G-j7f#m*A+#POzs+@<*Hlxd)k9Jdw zX#?u?c2{MT7LPUQuCIxXekwzXjfq%sg-A%;%E6BR9O1Oj?FkL{hAx7ro7%Sq6S&Xi z7w7k`zBjAYvQ8!#PNAt-V;P@YX7e=LbqpbN{U>ndRzWNSp0va)SU83d?B|yqcl0*( z*szWVV2tH#_pz&#-8N-luV|WepV5yS_c~B^N!R9!VPVH8-Ge#96(N#ePQ1A>~ zt@*)iuXvlo$4!kOCt253Pf`}~d{dxPUP0B|GPx>3ZhkcQU7%evW*5Y7TyqWdZ1DDY zSrX0r=1}s2g1=ZPD&s4bmpM_cH0!H;WBv{WdqQOP@@}Fc{(2k7*BSiI<@hY4JWI_Z zS1}S|4qbt9jlE3=556a>1?%pIUx-=xSNM~rVu9HVHf*hRHc4IL()c94tyG$L6^61W zgALqugv*8chD|Nv)t|@9%Li{P*^_$(s^n&5(3xXT#;whL3>-l(N90+E;$hwIG=)ii z)w|DibjZ5#nO$(0lL5?EC zyixmR+n4kbK{!AHf{gQ<+p;cZnt508^vQ4LK5J3I+d&`hs~cS&RNmOZ!N!Tu>n+lo zR(=?%py5v+5~Uke(>Z@w8KZ4kHQu>NP^(>0cCDHIFd?OVeV<*F}9%ZtOD> z_3kq#%VNIx&9El3(!Ur&R&HY9B4Ux~>bTH|XvNN}#f6gJY;EGslMYf3Me{$pg#XlW z?$=+(esH}{MwBPfvbyWgVWaq)T8E8TsDYzBahlJ5ojSPz6mgR5TDX`>Q75jEQv0QWyDzfkYcp78@bgoz zmOo{ZR#j#U|D!?dc$kqMjRjepPol!VbhK)(S!ai)w|;cGpYZ>OnVEM>Wwxa3$Osu3k+^SJm5?nv%E;cE-*H~IUhmKMcmMHz zd_J#S*L9x9cplH=ILC3<&D3Ff@pCy1Hu-gDSIc@?M|x&yunWgnN-lKZ8d4&;WyonM zvw@$dVahMAsbbM33#!A!Wq|MhBaPN5Af^&P`8BcBkbk2>CMy@gY*pF6j zh2n0D;yUHsyC~f>`~D+heIdvX^iHKbQO7e!> z9E&X&dDRMHBOUxXa-Tnjttlx;jM?RuS{O#GH7rO#W-~lBBa1>7;Z5J32UFXk8m%T` z1H~r3X$K-sxd~G*O46mb7Kn%D44#P-Qz^6JmMoT-o3ajh}NH_!^ZaN z%)`I7NCK=XPSf$0y{)kIY^rH}r;_^Wo3Hp$!0kYRqZHZ!1JK#~do$LI8-5r0Rr z&v-1i9YHX|9g;{j|Kq24=B0%5WLUaA2Lz|Oe&+`C_0%HMppq3lVLh9YjtCzMM9GVo zTk~g~_Oo7PCbqan6T;InNmt_0B{wLFt2Bk3z&v77)8v9Yt8D1Oh}H$aS_&e z@~*Ic>iCXUV1@Z+_EB};W+tHT9gg%4+L*Bce28L(kADK9DkBGDiO*L?K|maW0OLZ~ z3G~;*#>N_ljQ@%^SkmKH;*Ti7URVdT8RI@_-93Z=5R@`FeRCsmh!3PsF`*OJbl8Zp z9RqFZV4B>(O7YsnxAn_#lDTT${}1c+PD3J0*daoC&Y=YFnml8JMSZiZwKnM6L==UD zw7ar?7e!uaa##0BSL5uog_Q===E|~4cuLB0y!4g`1!K%ZG!)XRxZL|e zSOTy>wTBQq6mn&~o3P;t~Ts zA&b}e2ztm1A3G#{m%8K`pX@UhASb2y)3hTGapYI4wo_ zHMU9E8`Ve|6BwE+%8rRoUa5JmM%kiV>3yZ;y3+ua*-4(+hvN>Ojcqk7xW>02E4$|f zzRaG%3rL9<^j!W6i^copAz0yr4=+4$iCNXP6}t%HRmq9j+(wS+3( zqeSGNZODxf3Yc+s((BuUYB`ONCsfz|r->nVJb2)_#fgi70#H9uC7YlD6RvX`T-itYR)-yQq7nSy3A0*;w3TF!p%#k+gHb2>)di z?*|WY42SlQDN4pIp4?%97S%yF#Q!?9U&@-8?B`^$llqnM z<)*a`ph6T%<@I#sD_Sr9RXL7^K$wXa9QtD@3whf67TC?DEmEU+U1mYHYw;IT!OF0& ztoJTPMqYUzljY8}<@Zvn<2g(6l90Yan^a6&1B}h%Ut|hza7KX%`^#?zhinf@kN$Y| zI>@zhrL8xDzlag45VlFZkOMbS?p;V-TT}F0Vq+g~mZ=U4C z`>}BKM+Mk(@=LStwRj#7AKLhjnFFcG*=O}%rr;-Sc~W-orig8Bm0nuqAI3ax4xn$I z2ZN)O`dH%Sj&dLi0GL)-DfJGNdq9h7qUe2m2|try55UNY^3?|(oI+QiMwE1CAqXrv z=>X^-eo4Njmm$lL=Y;x60K(@@>>dNwT)myM-9abHH$k@j(g?Dkw8jHX>V`d=i0`ey zba`!ef#gwyfQpL%io~~E9zd4*Lv6d6(U&~O$ZRse$9MoBC@TDgg|1@SF1I8mkcnd$ zadMD1ZK$!34$7#w6>gP53u>aamgcPZQ~iU3*KmS&?pq@+9e60dUd^}(H%vVo95=Ch z*~^;d-&pxk5eWl?j^YEZbuLtg1AQ@*dZ(aD)NpC2sWjSbynbR-%SY0-bMd!! zd4!rZe3Z!7ra;=|YTd>fX{&hP07qxh*}|AiRKww`pm zTf%~*(dzkM=2J`JO-_gq;GbCc)rINB8_kq3i_531(K2WLCliBzwERRyhr$xdhZwr- z=M;j)y9SjJaeW5K3qew?(0h68Lf1YRMw@myO2nU`yHnwpdVZkgZ@vXB|>^a_~7k3`N&W)w=}!eDf5#Ie-S8u zea!nGv#3L6^v3}1ZyXm!7h ziBQe2+v|xqHp{0KLqN+i*l=I1iT_DX$6j@-0rL%5+&bM%evKfr(!p*2I-wvIT7JN> zSr|47an>!ojcaD`f>PJCWzNMn*ND2|CqQ^W5JD*#J_VhJ8=b^p4I>R-j;LuIoOvMA zN!P4ZagHtFfea6p;jUwZXNG{f3vUF68vjFGkY6<;7G*Y!5<*z(j_0C5OXP}D{a4R9 z_DEvt0T2buC>lG9qx+n~4zSxgCU!7f6~sDK@!8oLP<6vP*V@GQ-rht>8j2EVnT)X>t22kGo} zsTk4W$;T%`IY&Ud7-ryAxX#3oE?ZLc<2Yt6p8DqfIbSn94``**8CWIdEV9*Do>;qi z^VF$S6S3Xl61nDlDSJf3F~T-jpQ80(Yayq&NbM|iBh;9su$3F0nRl47JEPHrvWUyt)~J;kvgdV!l@9M zREr5L=_g z+VgR}fZ*&xc|c4AuRmihSq&Oicxr2T=KI=uv32KJ0W9bvA`#!R{9#g8H6*j%4D};V zA=}D;*z8LxJ+Y*nXl{_{ESD#`_r^&RDOYAuLk8i@JwRz+eCd#we+)&qTouqjl+Vo>n>q#G+sgr zu)ac31nCGY1gt*3f|3~`j+nM)q%jpC@fNjG$g!IniP0`)7uKY07k~AhjKB|kXy5a` zyvaV7bI2E*k_LsP7l0Y!m|{+Yn!?*1zzKfpNXldF)&?Ip5&6E>W6RmA`+F3Pab6ozJL+x7lbrn`xr&K2AOfMNsKpLq>|Qs6>o$kJzcp0E8O!<4ABo6 zOk6Ft?UdXBu?nckv(^+!ee2)!A?yV`1X_f%$mjJsLWOXe8klN)V+(BGUK`+dE!*TX z`_9d6>GO_jxb<%{5)z^M6ph;))$jpoj9^$_HBHlv=MUI;wq_datX7oSxr$+wy#NcC z_MvbFBiZK;MK_nY9XikZaMG!5A3*Gj=uppjkcM~&w2u=h;?*1@oIv`ZsHK0ij;@K` zCe_3H*dCJW$jC`Hd}V?q$onR~tf18RQ<(-Mzi)j9pT~)3cb9;3z3FdN(5F)4r-^$d zJud@CUI)6)C|U=WrJYHaYH1At<(L)a#FDR6=`n|r zM*f^^`_Vi&+q=XtvhSM#dY)`QO><)lVG|j{a0E$p;a6L&ZjW_=&5v%aIzgB{qKkUf zXN07L6;@Kx{mdC&v3_%NRlrN3kPEztHlT{Y?bp;j67ItcsjG&CI7%3ddcljyH6kPA zb6=p_9#B&_^nAYVU0aU_gKaSX+H6$2`B4}4I()eaUetm?r$h+&a=1k_IftXWE}FuMvY7?9WjcJv-(##9UOb(Mck z&JQ?_2aM%#O-XrAv5;G@7_d{2`}V9Y=l42#N!D;3#2**gSqaCo4p787cw;;8==jDY zRsD2jp{J!Rn+@pgY8$h~%4+<#lL0JYKFb!d|K|;9UuyM$9XTyoF3kZnT`>?O!ks>a?Ok$AbY{Cw1GVFM9pz`|ZA2^HMhj>^wy^(2u>>KQCI zQqUwdsbjAu^?2}-on$9d@UQ{PVjf7q_Ql6RkkN+)jO_S^W5@gFy*qZIhhta@VG#?# zXbbWIzl87-8}MY7Z3l|Hx}KfngiNSh1HO9%pr%_IQnUWMIMD#nu-)BP347W9J=t3I zOA=E(gCAI>^j>12*hWkV21DGv@?C_j=SR-F*THQgZTFzS{@dtp z0uAwK+XmP>#-qUfM&T}c3@byKKH986))a-$9fKShw)zRd7G8uZNq44c2$i`Qc~mEw zQ78I1dV<(9?Pwjc&bcG607H7F8ze8KfNDM;sS|u9u1VG;gQ-4O=bh+ggGmsy65eN5 zc{g>Ur(p+#V`?*6oBm-i0+yo9VJ8oLvA+3Bl&g}w?L6mJd3%E%xRzg@d&To4UsIB1 z%h2aP}91_y)T{x&t)K=DF#uq42{wWnE zd@RttwfE`=JEj9b?}VhW2$oT(`d;EwYa9OX8=c8PR)O}F;!EYXT<~WkxF8)ImFdXt zH^rw7GNaIN^85h908;l5FXU+(E$AusOSyLh`*Cnkh1=ftkl zisM^Cbk06ac+9i^X7K6C_)JHxpvY2}%lm?Rzt2A{Z4T(lnp0RI=51`7DyngZquR65 zq%KKlsBOp@+H`TPUrVGm=0xIsu>7Nl`9I&$!HohFn9YpHm3_^P#jlANX3Zh=72dMmAeUx;`^wIzzcswpx5pXTJ0Nu3SM+MjBjx>TI?oPeHgg> zEBuyy#&#@&z3&$d!NLyy9?KA1jKDIWPD*Y1)c+yaYN^;2-#q}}=0LH|OIeJ@+20e(BP}VxaJ5_^xg? z(>_lzJM~E#EXvZfVs3No@q=jaWGP=RZk(49@FhiUbtY@BK^mlW>mp@g{9oK;q&+tF zQ|8JcI!XF<0>X!cR@UE5FnQ@#0^K7Tz`ESxSTy}vAsJ7h_~*zH^KK2DX5#Kl@qOsc=+m3vMyi1w33k7N|3yyt7p*m+}tGmzuy91@D2q-tpF%FesS*mP|pL5y-g|aobam#{eHCR^=KCmK29a*fU@m3pai52_Uix z0(bfl?RIRXzH9z^X7^Y$dPXT^BVf?6;+Q)S(=Z8>P?2e5-s4U;XE&SJVNia6m^auE ztEIRY&dJZQs&OR#BWjA%;$jLer>(AAmK$0k8h@M)Jc&&p(K+2_A0V98Zgza!G~?*A z$g9`_a_-VJ`r$2-8;;m1-HSOO}T6EDBtOQglEF)fv*I{?>hYe3eA{{%M8{mDzVU+J0muO-u`f^wcQ^LEsj zuzVF<1_vU$E_!EcBr{m21nQoo{Y|ca*v6jnMe`$um~oYkd*hU#`r5AHD_VP)CpKi$7lYXuyD;5dQ|^ZxH`U6rgV;C~Q(svbYVR-f4A^O<-Ix2G>;sRePI z70R1$ce-vGdJ&FWu$}lf`kcq$CB-*sI=_d{6WB4rRE~4`cwzNAoU198); zGrV?l3Ve;}?Ni_lFM0YIV{!8=oxH*0DI^0zP-2}5kpKLTA84qoN;Zm>fRVSzA_?uP z*Jq_Cb3ix{z7*}zojGmgjurnu>@r8`|+55`Q~0?L4?Rdm;_CyXTAJj*Gjd`U_+14U2#|W zakq~{w=3!k>|~#;*7B#HZZ`8iwp_4*4EyB1%6JS#LK_>}~8}l+E z=7c2fz1i(I$4cT>i{O3Z>aE>a(Lar9AdOx_V83}ieh{e7oW<25AMGU|G60D_`CZ$DN;-i9^t4h{2c4J?t@>q zVBxed>w6>I2$4f@gYUYX%Q5mH?wvPAcG)6{&21o~_Y1%9en|2PM-`&|WGfu8w(vWl ze^XblR$etls0HDWe;D~HSl#~-Y4a5n3om5tl8+vy2}XMbU%=%DF`j)s9>BHi!x+t=NI^=H{XE&D^y?#nNzsh zSRLuwXp8_8M|O7buaC$LV&~hmgCL<6*>prjlDBYZyWB-{PPp1mLr?|EE9O7C+r^zi zEQDVua8nt-{ojP^Ao!CL*c=~L83VdV1>R!v*f+3l4r0GI5>24izJss?*9@L>&ZaUz z%4Mn#X2ERlz6KIfaICobHg5kg(`#SyBpc97?;(d!zRyOar3mI6zFtDC-yB`YT7>7X zabNQ#U|}BH{~4FMB@X)5XwNa>e4obfunk_*gLm@ucV?h9hjsN>CKD*z|C#CoS+FQ% ztBH(u*gD{wv%Z+{D0wxc1Xqk&bAmzgt!~DtX}#z*>T$ydm>&{WyuC3EXG>c$yQT1|1mF>4SD|qve+=bmJ_0v z-2lJKg|A`r@n)`_*Gcr4dY2q*9vXO%{rxT2D*Rl;uS680Tww=Vj#D~klX3sbYsBXs z4f;CFW^^q)RjU&ZMf@_#kZl_#6xzF82t7!&k$?vqLx7rK9%!XS>D(`x?oR4cNWB3& zsxspq)RETGto+slu?)jls_y4H7o~jgxt;rM%%+dlWH;mfmc#=L@;3V75q4~~DAXj( zd#r*a%`R_cI_*kDtg5G}>C`!ULu4Cw>P9r;FZq&s=zFIql*};p=s}Y)ssk8SFS4yN z^-QPYykz=(*qXu*{lWV+(vpP(El-^O-0y#GxDU&ifB-8?A$P*Qe?(mzq{8Emp)!FI z5w{HSV#fO>_-^FEfxDseN8+c2R!67mf(!fdxl@4>Nf=TQ)*ts9=AGnx|Rm!cc#JUpb?^d&)LA7O;PP zFa)|Yn)uM;Yc~IA*gyu^*f5bgI|d_3c#LIPyiVD|dmR1^+to-@LhtYW>P7KgZ74y8 zM9>r_xWIg$i!f~OQaci_jLZ{$<`0WJ#3W(1hjID)NnnZ3n`42Hr3hacHqn4&;p`2^ z4dlZ0IC^rr11{|b)1XY?Pj>j9>?EM>d{@M=f-kh#)*D&Xo$JWR5_{nR4K27U9@Wm- zgw&ttVLSjPxg)YC^68mQOi5aro-7-={^}CY)pxgxv>5qC7Wi6B60ki=fPUPFMP#bd zV339UFQS)aY@-|>+JTPR0vc3vmmWuWSO2&k8%A~(U&SIYnclVfb^5kew0dQ?`6)Ev z?r9j-=>Lo;7aa=#X1xWI3^6yrVgho%wq02M;j?sl@d+dh7pG|^ka(4jc;!*Ky}1u0 zDD#sXaM>g%#pAk*W$StUs#QY)(>`4gTzp_Gf8@&IPuI?bEx65YeH4|02Q1vkV_Rjs zPv?JuWRfB>i(#nLM`>37Y%`k)=Pcsw07h|N9{~c^cGTVVx;+5NIf^>3WIslLL*To) zfy{FY=y^k+hG*6NF0T^z9aCYMUwk5#f@hjQj14FP50ZS2pbM6^Zcp z+|I7uV`E+3KCc_mQ)Cw-!8m#{_fY_wz^foYfIAf|uaYvx-@_(WFw2;jxCgCXUTX_N z@=u~#2DiS$8GG&pCpUYv5b)1=ljoVU5O9!BZ3E4+p1cXGpkLJlWk05m0lgcQTQFGv z=B%G7do^;3e$vw@8_q98z2iOBaYBXzM*=v>m`7V}wC!{6Svb zucVu3=2_xAXlPNB<rCjvfw>n32>oqt;IUY98gkR2-oQHDZp)%k;7 ziWAAxkwWv7k5oaOq?!gi91I9aXOujF3OmaY}O zoNuRgA;L$0ppBNZ?Tq4TUvT1_&)+K-1tY6)`wJTQdGSvt>@wYttj^C;w0sv@$szD9 zauvD03j{}1ahfNDum0js-|RD2t<@g7I+5;kaAh3+C(`q`-okwxC47hOmfY=NgV09t zN{!uJmt6{9z+@A+pvY-)dON06IwhnKu`;rx=;gCWOIrNpWLdjsT^vONjla|pTCRgk z!^FvNf^o{gNACMjG#Iqgywal8kKM?8%QS6t# zfc-c;Jak`GFd{~`4A#SEk7h#(hUzJ`7Iq;XCqaKW=S}{49jo4gyWj8Zo&uf{YLaqZp)7CSb-!= zONA0R_~NMY<}yH8Hy+XuQw-0Fft`?9$HVp*Ki__AsbJMaDiK)-QJ$`geeb^i;Pk3E zWo}e4bMsvv9Hk5c`9RBkd6dLxmY@e~QB# z$*&-LOpps$3O?--wY9w{1MlhqR*Q1 zpsUYt_~$Me%KQrHOxY8@b#VQ&m*xhDz!XsbK@TJC-N}g=Jh2L9-@?GXUY#iPm&Agz zcR;?5PR3wm;^(cyS?Q6+lBbIcQ-CTHLR!0HitZoxLc++fn1Jup(z69c4=KsKSkRyxw;cz zKL$AZHtTaRZ@@BM#gYORY?ByL@fn=Z!D_9v2X%Cz=AX-m2 z+sc!>$MB!J+3vVLzmgp=`6-j|ZimST0&zm40s28E`_4;M^+Xu4(blWU}XCZ=%`Z5x-11Tv-PH zdBxLp}9v60WCJKJD zX~EkWqVi?`c})*gSu^mG)s2C>AZPUQ`?2)o>Ou6^1iKfNSGV^0)T6TLItE%n+zL~M zBJM*$%8|HKo#_ZoyfIukmTM~_LtJjp(EhJfoop&M)pZHJ zsX2|&1`k1`M<1AMC44!a1>)4LoyqiHMs98J`a0IKZb=$W_V#CwRG}zBp&t$!?6OG# zzK3C;=NHk|PGNSN@d(>m>2*I~5xq8uPn9C^FhbVpP{+M682%j{1rj0L1|aoy+9U;W z1&AP~6F3o@B1SovjFDMhu&Ux4l-E62mzIqfCvFKIbij+Vt)K~c|JIyZ$B*5nxQ*mC z0_~Ffd;-34eccBT+_tEj*t-Q%yimqPvzei?fvpLDpx`f5wSE8Ndk(cU-Ird~bzcJK zXW9|@+aw>(&gmcCi)kK-zkiA1yD1Sg-9Nu0co4xq5jvA$KaOB?29*(CKFvqkgS7HM ze||W85{sqyIPdQtGiWRZK3?`+e-VVl=LU@_Gp}391qkbD+y8~#Jf1j1v`$7mf{u=; zpJ`iP77&>(_9%I-6IRvE4#5yDDJwZhb3G`-2RxL{pgEZaUnB0e6r-6Laaw=1BX*4_M z4^XD2>TW%%fMuM3!P4EOEO%c38iSvfKW-WgMP_4tYJ1_+05TRA!IqyQndh_yILfU5 zwW}J^cr}LW-AXi!;+F=F(z>4zWh2~gI1jdKgQHV?ZA=6AI0@65GzV2j6?r zWTZ)P`j9@>yQWk07cq>o7hsWjy-+ZG4cH?GQls@T{9Bdq|H=tKnYhrIm8!cOpM{Mk z))Ir~TrKCT$NwLtHaFmQBZtG`<<`{yCh-3kW-CO^mXZ?~)?^H00@Y`n1>wm4)9Oi; z4N|>^faFHiIKqLOECmQ}f-Lilw1+;LaY&!WvJ5Uj@c*=$E%^E(g=zG(24LfOK~_8z zwi~11!2i4+TVLoeFhcc6dm8kgwT*SlKD>&2a35-5`CKVfE#P(;GKO~-|H)lax~2o! z;X{glhDAKMUx@$p2e9UVI(evA_pydQVgIMplQ0<+p#B+wn?Vab9!)wI1LP_3>}K^K zGjafM#uP4dH~d&>>?Z|kEG93(k5kVDH+Dx5hO~z{EbX=;ID%jKV+ZG#maY%}k)j9` zNhHqM`ANcgNgMVqe}VPrZ9-oeQBcANA&jhoubAZV^j^B884eT)goj5#GG9&zC87%Z z{=bl7CCb6r4jqLIz5qdlfJ~}gqN64SQ&>UE@le9u z{2rx*c@Zzfst$l+3R3Ys6NIup4XAQaq~VhFeGA6M@sCWE<$%19P*d{-;r!P|wmBHK ze^et1Oh6_^ZwA$FV}R_M0?2AwgE&Pzk&@~f3-EFRw0JZXTk0!&x zAD_0by+9b%*rzcbvCd2WU)WKp#WR*WowHAR2Q4}sj28dKuK6ntJ-GUDsJJ4_JAKQj zKb)cW|95+ zG#Xv`c9>)|W^M-Cm+?hOp!Rn80ldU2R0H~kAn#oElH5DbdfHKeY*^1~>ELW%=spY| z1hXMq=4gQJeR(U0zDPWZYQcD^6ctCvhiB`t2%WQIOATMA$C><3q)=hR`lS|mGmby5 zI7?u*#YWfZhwWm3d3NhKVLfAFQJ%i^%dDBca{6{ngaAsaqzdCKs#F)yWnSdus=L7c zq=i5gFwe^0$FOjAa6r7;7MC~qIcsi(ZLDbK6iVUAqd`%P%xhIY1>%v<8D!d1%2j~X zmMlI0kD44huByV5oF98{PtQLyxebL1@?fOo3F?elGmOA~ikb{-uL`{r00j`0o<(qH zUqmiJ(ecE)nu5b7PV?j<@7}Mrr_oDJ@Nd9~7B0WF7ib7fpQwn=KO`pPA2Gum(R937 zwXgz(jq6ZwZl83D#@e8V*{89tTd>}|H5FN&S!$n5Wqbyp*sfW&s=NsY3sF$W)}uYYd<6tIK5`h{~GIZ z9@?X7up3r=;%)C?IN@i{cJ|bI|F8&O0VE#H3Xs6mY~jF7u>@G1*x#IHIo{=}B?V_u zXAU4s!m*bEXz-$~LE$YX(#}o?W*n>&8)?V(&?8KR>&}3+G~`rNYrvA~RoR%4lQiO%%QD%i*8wWMBC*Ui^t+`{SSNC3XM} zwu-4@Ir|TpHTm~qY5XW`mLgf%mlsY?PStJd-?!PzvFC~I;M&UIN$z)W?88Q~JcAW| zPv&L+vGpTuy;YH%v9hA={nk}SanRgSm&NE@(}=4)`H63X!47onM5`niz{ zx>i|p!=PUc3CV_~dC&eDceN`VoX4jcK2yus;SmFY(ty_H86!6OZ7dKyN_aL6$@Du! zs3~&#ZY`lEc`X}Tt3EmxUlBE|VgNI1v%I%~0HY!tMP@tsjO47gSB2#<@&GLSfV-zY z?g1#FCWe43Rn*C~oR}=t1ioS$ZkHIc!xsIO&6`{U5j~}8{f>lhsIbUxk8j zNuJ?kuPyY?>UVbkbH0Di3cSv^*(^%(p!TjPz+m#|4iDGCZc^cNyRS9|9^Nx{0+?F6(3W#{51tf_VPo`^{A z-Ume@E97)A&`NU4*tDMPafR~XvqbMCHdmQDx08MZC3RIj;=FfYtvsH zm_f<<4^4k4&i#B)e|}HYv$T)n5l(}*Eb=pGF`i$^{?*%krZ!PV?dI3*`Ae@r3j*L> zdT53-Y8iDxd3naUoYH*J=f|x5fKt(+AabUby??R>*5HmDow`8uDSlU5g=wAqI zTQG8K{)BJk=dR^q3r_V4(sU{QFq=~?W-lxSJ3h7p&lXgeBMhMZnfT)hdoc+D5*Ti+ zkK|y&^+FUH3NCpkQQX5*;WiSU*w=QlTa%s$9ekUH!tiJH9E8V(5{ug<-B} zxNh8aZHjv?A&nEqif}>L_K%>L$@y#T$=4*b90I>6J{dyG47^zy2Uaz^ykGCfC3!id zLlm4UsBs_FkQBJPXWAC#{0K_VoL=wMf+H>lP^!u=69!f;k9afw8+Lp;se5?Zk3V|% z>gdt+C}54Y>yUGy{;LbORd(JoS{z;p4$Q!P{AGfI8%ZiW-wb4qm@+YEraaUPP~vWM zzGBDPm$$f6B<%IQx^?@2W(b`-+)EV1F3+;s_d#*?{`3fG*{4pZa4jgio}N2(E1FQk zA$O8N0eT-rheKl~jt(+6ljyzb87il9gF9tW=xsUWHSMAhuZMC49zH1d!!ErQ(UrQT zF?GeIY9qRID0soUEH-zF=s$)1?pHDbAG=ZyL{be`0P{%YFJm!A=UL%B_M<9Em z&CStb33i1aQ1160VHgw4!u9hqi2ysBkV#M?*E?9!ajbU^WvBO<>kA)cMPb%DcED-$ zxsD}z%a%4fy77u&AL*luuYXVw%suv`uZa-2H`?1u%$X|>VD6slbP@F$oQR}|msJ#Y zt1x|prwe`$6nlC3Sc<%U&?32jl?6}W8%=@@GW+TzMOS-KEs`O z^yL{8-9XkDxx<0IOiK|`aP1;Zlxkie972*5)~Mwwq1gs}j4}w<+1or`aC0~czB~fpvUNBQ1ZLUiN1g8wZyd%-T_kWQ1@aJ6W%mlrgLa$>8NZh!vgl zlWuh5fZb;9zZ)*!+YM)vj@-nrJ|ezdTBNJiBrTM{J}?e{hK_#=>#&wtW`K5oP_Xvv zd|K!}HQKNi=GlhJr^n`>QSz|x7zWLL&B2yCMtRtd2m*0GK3EET+!&k z{!LHXf3g4bpW~{33xu$+T=mY(?O?~^{Rb40?B~bi96==3L3gL-b22HcrpA7vwX?g?05QrmE9|CQ4Z@9aO&hB>h9 zI)3UlE6pgG{SrY*b>b!?<2aw#W_MLqy&VsO$eX|P#9VUNFWG&^dgqq2#Qj&e)DoX{ zCjVV6KFIUfsXt=+?ccOT&nVs+^9yU$(suoi+!sIfFL`i^AvzE!2AG!QTC#PabWYOB zoifuTvol5kt^OGH2JK)WKYm*Ir>B%v_K?D8HLq!4V@DyY9)t*Ov>Yhr)3<5lK zHWJX|EdphFD`nf@e11$H;ip23_dVUQ_#G+mP|8P95@ZRDPb@dscgCH^ zVsf)lS4sH6MnFwQ{P4{FO?GeLgu$CgVe`cA>9w6d*%;(L9G)5ijkCXX8JNAY8%q+Y zIzvrHExq7BChBY=!p;vk*U&ExaO<00!V~Q8V59NMtiQNRsCpUjM^7~jvoFTw$EvV? zUxb9J-|XdG$O_l3=iTea!M$^w(F@M2d3oGZR_J?WyJVdtk-3Q{9J++LIe(xy+02nD zni6!=!n)PYWv;k>Ti)y6S|Cb-EWGiYK*&zcXU(r^F-vtv^Y@s&tKE@C{~$C^;f4@h zYvEL+H~eytZMO;nYy*L;EDsxyEYwFl{4W-Uv9ASNqd^ zE1tK^@KzPM-T#C}^7R(nq)803?+J($llRHrmwDy9YeF-I#mFG#zyOur-8dsfC3WEP ze5{Ip(x=^>}*_ShyD`M$pp3rR2(D`a`0nW4pb?%~fhZeiUi_ds4Yt+9G z!)B6cO@Lgs%@o!%9T#l5z>b|Nxg0z;CWFT-zp&TqIrs>Tq>{EgfI2~}uMcuPeYk_yr zD~`C~(-gU3Y&1-&O!{6;N-7k~a)hFSyfVEzM$}^>UZ7m$qW$3Pk)7oK@I*;N`jU!^ zF44>kwP92`%J<@_7W8~|03N;RE-F12>w@|eTb@ha zLf$(Ku6u?FGwncoHZkXzYc1$LIc)QDU9BM z!N%_Am0zjJi~o>Psp_Xi#S@2tD0AB7Pip$k%16pZAvN7*djnd&)__a%XkdBu6u11V zEuxG`+2LM|Y+3tR(R{I2?AuEOJ68|2KW^sEbHpenxFTMyHAd*S$`CvjIa|#l7JEafW@+(THGUOBW3$m&4j6Zmc;J1{ zV+TLg7}ozMVT7Sd_wny%ZI6(W8I|tuo^P8QW@f6$RXJ5Ue(8RTV_Rf89WbWc;J$U z$bkb}-2*5#u+1+icpO2!J1awlfT8QjCoHs;=3fSS;qJAAP1D+lql&B{33E0XsvY-e=u=eDQ-^SKTM zm1FrKAgbMGc(H!*ek$VL5T^~}VNp6NA!t10?(^zTFbTw~j=fXSk@}jP^^U%tY z1NE7dcI-Rl>gpO@vCF?~V0btH^?HPMm%YCpaGK5)KH*j^r-gn9Qh%Q7qD#AjjprTTKM5@R4ton2Wlir9w?tw2zBdeQ|wsP^IRzr#4?GV;j|MMp+YTAhIBhIXnXe%wI<=lsQPNF6uE51HU zS(nTF@&*&ad*IURfVaAd<-y+5aa75BiLVbt*Oay7{?;XqEsmr(R4}Dq(}v1PqxRXB z7)eAI&VzJZXV(M1Pn|ke%_czw;00g5TL-P*@N4@~t4#fO7ef|iP+zk7mI?)CP=jx{+_(vAb;q#kk%THX;Zb?Ha`EG zCoW%R&=BQ$6F~B=R_1d7%vcyn?OfFsB(_~*$s3U^B@gjx7479+X=|t2vZiwC_Y4aJ zJ?P0D!?TS|LLfmiaxWN`>M->36R~VaVo~sPb8>Pjt&3Od4Y^?Y2>QK9F$)-E820mr zoOM9=vp;0y?&;-Rb1QG8*4EIiuw$33@jB9&Y3JlrF@LUvHV>FQ-_aXb-f>3`7|YQu z)Z~-`kAGvaIOkzuJl&f}I~{QgVH=9REbkMvqB+DYssm8NO7wq2Q>mf3mx{~37#v1& zno*0=Jt_L{{<^N*NQ`8D#;X+soucgapXJa~3FctGVC)trk;53)F4Ua~0+XOYCZ>7}2?`P&U z@^k8*%lEc0^(3dH`PF!hI!;LXOi4OGlcL%DqLdVVbQd|^6E-j~@J1!abCm!V#>8lE z_nb;B>7&gD%b;L&HqH+#iy@^IMVV;fA%+=Iqw$2kdsN-k|6oCBMs8wql1kCycrb8E zpf8Vf-tMZAn^KoUy$Ilr`HDN6=z7Zbm<4R2V=jGvwNheeAAB&gUQ@PAuwZy6xQdl} zgp>%9@zNN{$2zM@f^}_U!(EW4kl?5B&+}hY6-4(RZ-*AwrO<$i(QI`xw0A0c%`@66 z+H>;je6?#4lSS06K4!B$#Nxp^hB5Z6Xb<@phuU){=<#rO;%$We2767UdX1xjUpJ6D z%5^F4ybmv2l+Oq) z!hRAoq<^UecXV`2Kx?8>&eib;AH3|KPwXRBv1_GV5BBY>*cUCM9*<#^y#S8t(C+h+ z|KG%-VbaC z2yeQSdEW74>hN&KuzBaez_$$Kbn!3YfCw-h?G#@IHCD{l_InIo$4Ls(`F!c(%1`sQ z-0Np1&@qgSM5~s+jVZlNMs|U0cArEzpofF=ul5hVPD@)a*p43T&gpMy$Zt}tnW|Cb zM6HCa((-xAgV@=4Bb{_2zz{^BvrW}U=9yohnADb>oB775{e%C?ToaxRq{2x_pIEdj713 zKl4$)l=LE*Yu{foE)8dCEklP6wd@ZcEGFkRc)gOaxro}kc%=8zF#QCarJx#BP;v{+BFrmRB)jYR*+RKXI>bPc|oLjV^*hEUm zL~lg}G+^H&R5XA2nvYqA2x_6Sw7d!pX7f+Jvg3>*hUDDdmZ1~9_4 z`M55gR%1K^q{+G+hIvj>$yPLScG*1}`w4YgpN+%^d84Cn4{Mm!Wz<74GuTU@@B6DP z!`EFoi*%E-;y)$7E=V|6&jcGT70%Ai<}LnB0W#tm+#9T@;0+CCt}ME4wqn2eh0DvE zWFSzkCRC{R+7ix`*MbwIAgXG4T;vip39;mcq`q<|s%}Mr(T97OUANgo@&!55ExV%r zsO7vz=0@f{ElpBxbuZ^R$0AuitOir}s&Pi`gz$aHKr4rr*3h&mj}~xSz7JvI3fwx>Wz;#}0%G-8Ik{`SP#N_cI{^ z2b!9jGu@G7<}h9JD7!3zcV+-M>qWh_QOg?C;L>~b+WtZS?6fX%pl<0(hfrMDLWZoi zw$Ugc!PiL$Ru6=w4o2czZ5onaJg4e@_)xV^=n>@O+X(AZ+hX*9k

^iAO2yEAZ-u zO#m^YTQG*>$a7H}3RAaV_vsS`(i$%e%)PtR#qQF=H4CkaT3oxl%>OpL&4hk^Wzcz< zMRqvj*_NTXrvH7qJ>}4bWG9Z|5K1PXdsR8=?J_XBI(6@phQ=oEp}8h+m!Wqb z%11tQaYQfw=I!nA7YZ_Q`FY5}=0|j1-nUF7j*!T`n*U|R*=(Q=I@^qh-A%(l7 z@U1I-H}hZ0I9sBIU;cB@0nFjYaoRG8HfymM@u0opd@6x^cO&=O2mPFf6oi=l@#sU% zAh&}-VV;0G>awZpbTrgtdhf^sLju}~103LqqQcrjjjEbjC9z4%%c#)ZnPe3f9?q}5 z1#1*_KQ*~$AB65Q7w(lcR8F}Da7GSy>AdC^z$zl}BK7a6&xDbH?bx>%06bu*sd`j| zm6Ndia{!auC}8?YN@40%O=+NHXP&K&txs`RPIOLAP8o^2X!hw7pHO_Zk*LW zyz4S3Ma21UgA_Cfivw3iVFz^O+75s-(bl!<($QMvoqIEXpNWZy1Bw}_rOZ6))relk zw^X8?WqRvRhH&q6Ee6+n<{b-K8Q9&30xQo~e|K zI44H$thc&Cq7PI7BqkdLiA5&R)hZJ@9piF}*ST?be9VaVPZ~Y#2N?a4#E6}!(Hfeb zZP7v>9;1`)_~#o70t+JL4aEBQKvQFl@6n2iX`d#)y@cTXG1`3OV~%2*5y=|{-aFqL z91M+$NCA6H-Cl<&ZWr%qCapS0ciCOP{xH(DGyg;*rcEDb^h^uSJ6RTyr>_o+sgAMQ zXndV}f|5}vD=@za!&1Fq&?@Q}$8Ts17U6umdFC$3>TZS=3HskabE4fA5e_O5_Mf+i zc+QU}H%62rN_2-#@FAUG-hP~(LnG|nAKGuK378eh9f+-oUa?SIGHmyps+u6JHm@aL zTxsxyuGR%LV`KUKQMD~C2Cpso?7-D0z~;+gt(}>jo&B6(Xk2{!A;h7OF9mQaDnPcS zJ0eOYD$b{jxefB682&o#WyT}4fwtlOM4WF$2xo_6^~e0NK;14&AfYNy5e8)c^M(!^ z;)MD;Jykc?fe)QRn}!~kJpi_s80m5`0{AZKHEJ0m8Iz#?YA0${<~fsM7Ko_GM3tSl z7zZ@;e%LZTMnzKxeeIX%F%tO7J8kh0giHusdsm^od%k0TIUv@e{I%hhOcAfeX{q_{ zyXFAQ6MK9n_UumD6?0P^g&?g$v~Eb8VVAwSB;`4oH^1QMFR}FUYKli}!G~QXdnZ}- z@o4#zFXSmFz86&A$?QQ4SZJI|pdad#l}RYRgV5iSXStxLudfd!fR{(x^BvY!<|-gJ z z1sk^3h8)MUMs4Xq9?U`;7H;lgJ-+^^*?l7jbd%vW5O=PN7fZCp`Paq91`aEklnT9)?sK*CzA@ z+M}DO`OZap+ofQ|RX1bj#`9ijKd*(`^bBX!q-iUkY(rrLnOZOO?lR3$qdI+ba3jRE zIb&&A!IiIBwY81m$CY96>gdEqf~*@g=1g8M8J!DT(398!TV(j@5j<6eOA5I_&pFFb zk?ZWv4d)yh&Z(AtzE788vh}1k5FXTO%I|V!OaDh8498T0_8GoT_ALS;B8A!-L9@N! z8kj<(phcD^ba#7b2TTLXv-kIywhZ)xJBvUk^Y7_3-SxG#nO|#G!jqy#XGcpbo_}L( zUTfy;UF|AjiT1J3J;p5eV-vyNof@Eo1%id$MHZ_QctZN}e{?U9-iKI5&{* zMvRa3{RHZsVzS}n59ln{RR&zFxjzgk@s&lC;cGuWi|;Q*@E8aky_j?p)E|MXh~;*= z4?D@X(XYIYPwRMcAL$go2R(`Kc=ob9?SmwUs5!TG!;>_C`q!CQIsN)k+P$*cOmQ6 z(^DZUg+ioKMo8Ja$Et)Rdq(yyd)>ctu3O*N&mYg~ao^YV8E3rT?{kipm(i_1qmRHp z`cF+&G9|2N2n1WS(_%!77^n)jD!eN6AStQR)J8?<82f*V4DJVla|70@j;{2)ojs9E zol72H9HkUgi6|>8<9yuH(WItgoJS0WRlY<>4JXSX2=^G4v=JN75a@4LnSgTY8rX}tVou{bU;p9j}!yq~ylU-ydo^n)YUSl=lc9-HV z8`1DdFQwxLe&%cNhPD-3L}loaFzB{tv+`pr&k>_O36^TCMS!0Oezz^TEMGa>4mvr4 zQXovW^;XAi#?G3kr5go<`3v2GWo@pbdbfSv3&R+Cama(aZZmRu!E{Ga7^5Xv0{_xr zGLs?5xZ{Ru3q;-Hju7Hdc?ihrvUKWs6e00L^Nv&e1%qY z{QE!X9hP7$tQ3pX#5X#r(NwdVPOXADO*fbqI_NZ9E?B^6u+X`cabk|Ryj_T(>sXa= zym}SEuBiBMXelx90w~DuR9q|y${Wc%@-Y<*6x0d(23d1)vaQJhqxNnV38gU;w14z0 z;?J9|F~#mt3em{<_ohB&aZn%OyEEN2+jpUELO$nUAc9 zYvj+jj!tDw4H{5gA|S>{ff)JvMb<*uZOswaS<9HyT&vlDAUjiASY@`khUzO182IHdr@}`;&{22sPVqJA@ z?PPk@pIJA!XxBX48KV6C{r3ke+RPu1s#1XLU^71tk5RFgy=6_yW}6$YS#Q2QBqFb) zQ$t)_Mf7L3doE3ed||78+V>=+=e4PY(vy31u~$YUo;&(&tKOIr>-3@CDb#-ae$r1N z5BWo<#d>-6tzlwXKg~hN*0tDxEZ~bSA5Ys-l8J$~cG$~A<)e4SM1L`tgCCqDmr^A?Z+WyOyAA`%6C4DX zk`G;AtSc9exsK*J9fyClna_o7VS%s)Eut`3MpGLbN^|d$vPS#3Ucmz!sfGJL%BDqA zi?7_@aZI(FkTo9>dro;KRpJ%Z8rt`yb)T|t5zDj37fum!0j?~udh6~BdP!2pZoDwg zUkV@b@?vlN&R%xDQCiyd>o4|3qd%Jr%QM@-=k$2cd#3f|)p3pY6?ywVJ$6lzQ}o)r zFaL{+ne987f7%k3tLT2DqD{v@dTYVVsi;A1ZSBsaoDrY?nm1ap@0*U8eSakmF!{Xh z2M9x)7sksDXs{KA%--jn_R33d=bs#ZptYx&4#b)Rw;Wd39$~)qXb6~|!;bRm1IAi! z`@Js*p(fRbN6Jzc6V)y@|Pj zd(weTYcba^ODW^RudTPv8Qvm%{cE2?1%T50;EzI@&BA|<7YVcYCUeP%)Q&5iqhlc0 zH+)~|iForsNhaNDXpwjDQueX@r9Zulzo5l5C^BO<&9?9F!)TNZ2LA4ScC+p>+T*FL zy`kkLIJ35lo8opiKHmL4my2msJ7pxRmtTE#A@RA_VZ6G(t80+EU2r@F_#hL6(dh-0 zL2JoP#BQY*qH|8X?@{1fSc&N$ahdNmMDk?%L9-$VsoIBGy=*ANkOLe7wP`dPf^AV8 zEx1-gLk95ey58xn2QRJfwwJKyx;V9Osx;f>o~}z zI!#%RXZ7T@aUGC!HA?6yrHdtb-uD+2#}8%H8NXtJ$7wY5Z3ORsh`JK3%KfL+~X6V2x@=H3GUJ~g{2Vo_HN?)C*BvPV|YF$JdZ z2B{pooQtrj;r=rp?l_%*#_h4Z%>kDFQnfC__um|zCPnPN%87%27;&rvXYBFF~7=w`N2`y$-APk z7+~@3?MqV`T`&dJ7cA@B`P}W%24@BlYldl*vF$e@ue+k_HeLeHBhAbq`nFvJfuz`# zhK7EYX1=8-54re+Qz)s$xLNTBLd)%%led;`9d+4z(UGO)v;!h^lfT|MS#pSdy?l6Q z@4&#>@u}VTC>pAKC6dS`6IV|Wnf?_|h49&4jL#!E-_Ji0zaBN*+4jbuxzpk1ByF(B;Y=9pwskk|otIecfU1g$ zN(9WPACH{Q-3R&9MmU{tQ-9fKWh`E{7!FfhxV;-)Txp|8RO@JV4a`VL%AXs66Wy-w znn(?$Kni)`wj#mM_9T7jO+>PdT@FeiYA3i0E)Lc8*uzcQdUnGcqfjP6kgFC6L&wF*1f%KH`o7W zdfsMYW7Lei+n`Q+e3Sg3%Mr*iqzhzRCi+ax&Er*}62fB0>ne3V?J5?8!idW)N_L<1 zs;)aO{e#xZB;DNFmpkgFs_xN0JA~2&79BijWCr^XoR`r`3$z@;_sqA-cE7#+Vej?I zh;86pP34OjqT4ezJihvFK7cwCF!SS$^yV0~c0nI<7Ax{tzi-X&(D<(<%K<=0Fl85` z$rXW|r39~x=AVTZnkh!gD%X3l-POPaxn10E3QSH$EJdzK0V>{OZo*>xu4Lrd8~#an zs$pf=TNL^3ncSM@B0OP->mNciEye{%5wpj~OEL@dbq2@JEnRz;J>BNo1y|0ut*uSE zK99OM8lYpHwP)?!lXv+OY+}^-MgR$rt{;NG0w!wM;dfTN@fEcAfE}oA>7(8U$a^?W z>*7_HC6pjPuS619Zi+p8CbN?3?{j?5J!yby9lS?3Nw3 zK!J?k6?D7ON@;8O(GJ->95`vlRDAYwr+Gb8e{_|4%+Q}#w zGH*}}XFPx?;SC;y*CcN6)|;G~a320xwE<4Mor^~|v;?&M}Vrd%Q3dwZmN zLbBF%3OY6&BiBaBrj(9MI$wnoEvV0cpF6r?7mYtM{0CQS_iXxCCJET8`etbzj-?8C zt*=65#d54tyBErzPa-pKu+(i(3e4!7t{AWph*Urb$hJA&*UM}6PjA^}lV{*Pge%2g zuBauhnhbgU+UQAL3{5W9D{vQ~Jpx}BsNd;v*rz@as=4>laElA*eB+7+{<-01%5mR(I?EbxCLa~I&W)Sn*6ciBthUmV zmnYx0tY#cV6-l5(%fBi`mJaSjuKeA}_l^!)$ut=8j!rfdgWd&q0axtqtv@|h>*xHu zZq`te!Ni%GD{j4h`z=5eO7N5lP{{#jHT(0UePvZ1Qy~{)Q>|3tsALJGv%Z@@AW1; zUHm-#n}DY@TBgto&(xTIC2=)8-D9AeFl(jg%d9@`IMjf|SHgu26N7N=9srKRqYuNY zVGSXl^Z?|fEYq%wU!(Dx>cK5tFl+jJZr6@cucyK$rO33vU8J`kfewTs2tPiNaJXLZ z=qWD`$)|z$X8hGe)IP52HM(Ju?WZ2;oHcs3A3XkBBOkr2N2cEj83~xW_xd!=IK&FX zY+BRdcAg6L#+FAla)|f!06=`Kw|GNETcsJldd}(BLxocCYVEyYpgu(Ms|8Hi=6HUi z0I4Z2ITndmM)l2V;B+7oi_8Q7*XY-$ha@_JxeunCL+}UT?va(1l}{v{tXrJB{OoF! z#jG5kIK$X_KO}z4${E>jl%_I2sK4mAS9&C?zKK*IDt~rafrqm&JZ$?~?>eW+FhDX1 z5Qbb-Olf?#4BgxAFf}s+)8v!v&p@3rKvSGS%9Ci!Rui!qHu2R1T zV2UMybAMJ6K(D&l)jCJ>c%JRG&aT`B=q`NuGNUKQ+G8^W!N#|jn5HTF3Ohnx*P7B_ zAyF+|Mz|kY)x;QR4Rr3Bdwv9A$YvoRA7E`pJfmC}X2!=MuRl7~WRXlKBPJ`dBfGaD zbGSZvw{%iY{R2pQgRg?6kiACxY}rJyIh1>o-Mzmgz$UPL#o3d}j1!WsRBt2dG9mG>KEdT~Uzh~W!iiwqt{VXy@$Qb#!z2_s?5xhfSZ=%2ErRtgV z1Q}TYGs`pi0q0dxHu(Kj;pEAA$tH#75|)BAf`q(D1PulMCu=$dJYxnJlhb zzaD0|FHI&>q^z_1U-N6M)F^^{cst50K-j_ld%N07X&0ZgoUBzupp zuRZ>7Oka^cR<*Y%{t6J6M+g2m>7l6O~%L}%Ut!(~97G$;e` zK3-!pU|BVRDjpoI7I>pduDXw2gMTOt4>}Juw#$*hAwA*}X&o_!L*W)&q}u(|X~8{N z)TL8h5LEl2VFo2Z!euUyZ&yDt>I^5B?$PW@Lmfbr;Z~^|qtCLj(@Q4ntQcOZ`IKqR zLGXqNMP&qlpyMjk2^EfiJpmQ^`b<)c<@i{kGicS~b$5ZetG{%{g9BxgsuFo-*}vD| zUCoWliVie&kBeB$BLxnY-bOyXS_}jPQ+Qc#K%!=KbmhVib(Ip|ZNi<%mXm_iK zfG1QKDWLTCjg0sUy7w!k{Hc^I+b1*o8My&t;Hfl|wh)H4W(Rju49S)4zPgR5?B@B6 zcM(_PzcoPQ>*Ym0!Z`V`bBvitlPsPobU^XF|86|*g$oU!^R|MS62ZE=xGFbp-YgNw zXxV_gnY{cEu$V#~3p4Cs8Q^yEhlPb5Nfx9b1R!4qS-YYb9qk>zhl6tO1avwyeAcsR zqbE9Q2+qHLw-h~yB49irE#L>b;IjF^iwHtQwX_E!KZX+>X&4(oBw=1Mpe+e=$k_pY zglqg^T{PNFwR?0Oxg%0U;W0Bfc_1~5h1(6tO6lC_HyeN5Lv?u+RzM&?g<9DPG4yy^ zvbzA@mQUUGgC18d%dF15_}$<-L6~dG?V6=;CesFfQ~`T_F*QFUM3-6SaD@E8q)T8C=Y8Z0EIs`xS>RHIIkI(hJw1cyMI_1)k z@XUdsb;P%fqjVkCNDKP(3tV#=jk(PVu&*-n-QuzvlP>3x4+OEOVrHW)EpR?VWS+m_ zh6(tdL zfLOL*P^vkwl3?fGu6B+X`E1VwcsR$W!&DA+r>0{$kKn_Ez^96R!3qunHvhn$bHvu) zn66$`ATn7niX9(FNIrciRA=jwp3F>hOA9B0-kq2~iIl@9AGsIvlo&!s?ep1w#aPZh z|H`2jU<;MijbRO>N|^ZZvUuLUa8A4r@g#DeZ==-bPI5gfb<5hjGoMvFHlWmWGe217 zu z7Y~I(wt!3%A510;R5ji;E7#oSdvZTPsVu~-Ss8lTs6e6msH}3cYlvyxBYv4 z;}dA1nVu55j40C_DJh;bQ2pBb2jy>C2?q(!T?s-_3niu2kCY)_zP?k;z|8t<86V@w zcB<_!uIiRc?C<`p0C^Vp8fE5Ld3AS5seNP!v|cH@(N-T{oCyy2Z3qmk#wMHk3rKM@ z@YtI1YYD@?FTD;IKJ{*p8X6Y3mBL0mS5sUQ{u|V(o3>W8Slp=sk=(iMVmy2Ocd)I} zbA{4>5OdQ?SUf)-?AI@nz)<{CAYr=$M9eLHy^Nf;vUj1zId+HN-K%sRk)4Ig(NL#g z13F;JjG&`0>$%olNT8bQs2lHk@d1$geQVa?EZN0RbR(qtO0xigOf@w%iO$Vp zG65CGvcsld_vHkS@VSr=8D#lmLo^?>-`@j)iqyWrzYgy$DCpkSg2EvLBc)FddBx^t zFX~un{)7;~T)~*Uy@tW5e5fi2)K{0=RgIMr@b&CpH;jmI&PM3-0v3d6G~x=6#eRS9 z0^UDfm6?#WGCjk-p}${w<|%mRv8Q*%THO zym2fpeBKxJ)^-m_-JwPbB%0M|Y!&y1K*qVTtrn{#a=FsVrR-o+JGqe`y;;5TIGNwW%iE>9=qmqQy|ln(+J)#7G(wxRzszP1exv z2K+MG+i!3O_eHtcKQ8B35>&dU~V zvd(E_{?V8Sc!e{?!`Gk9lu;JS_HSBhaWjxyH4~(C$QwXmjg%vRMaQKC9^Cz1?;Mvr z9kDa(D4ij0(RVCAgX^pvl-h3k;R@Wp-GuJGy~<&mdZQ>y&5paZGi|T9^(z^~lMkc? zsX!hsh=x4W4xtWoXWHv~S2ud*&@M8RWc~j)1DRQ9@nb&qI`=%swPTyLblKWxE1hU- zRD-L%{Br9E*K=!$z>827ihG!_Iq{iC!cd$Zfn1 zsTDfS1~9HK7TOCU03zKFObY6`6{LSZy!8I++291QiVLuLd6>IHBn0s3Ix@GxSb4$37ArbR@=l}?sHUQtgTFnr0)4^ww>vt9TW%t)LOScD4>KkRN0 z(Wf^8zJ|XqeD+RS?dr~p2X24?D?W^2#fdmEGX-g$wX3RLLT!V&In+Y@EgfQrQ~S@u zxGiTCEXn>^$FE>!kM3^CN_lf>)(@`jz=i*<>5DA1C-7sg!1t37phv47w5IT8=?y(_ zq16q6LnWncL2-Lw+XEqp`d$Img)<)jZ2Nnk0>M(C6(+sxL;L?)y&x<}g);*adrU^# zUj8~b=vGaQk5336`I1O~Vx#qj?#LS(4(Xg&zisS4OOqQK4W2Jwe2p!#J*{f;Yevq7Rlp1#vg2$w74FOxO9#F6svM6Ok@EQ=($ z%MTOwRB~W!{pk@gwtGA{+3i|t23*1D$HM>0&m~NnTGAyUjb5w+;K=5O% zIgm*zkPo>T^hAf#u>)pw9TifvmN4w$LG*=KPxtH7zGi$Zd%nd| zE2^vu`zk1Csx7|lCNKY4PmS+iiwgwPFw-`uHyn-O>->#;|d!3U_HRV4gTAB*NLcx5{NBT{P5}s#YM?}+rZHfp!=<9^kkQXB39*ukP#i489b8{nl z+i1f&h{iltdX{A(NKQhlp`h!D-M1tpRGkO~I+Zfi1(cZ?HNL<0G7rYq1o4@`#6=Gl zIGwPe%;e*#?w2=-iI|9}kiwUM?sZaeQH@S@a3^kUAh;M&i8TYj*m_jcptdPBLwFz( zc*V@2_vM|KlLI2^KjjEd&96j1=1IQ2Cd@~>ds4ny1144!ACuI6L=HcKbA0KsOPlRy zTmep4fsKte0d?DkYRrl0X_f4DD1CNJy-FL2 z{YeMbxefw&aC#_-k;Vm)T;+Ad8>*D=UhG}5Zu9xUJyhXk_g9*4D8 ze!jO9Cj}WJy-^n}PKU2T<0XO~LV&-sO}eylD-ngU<`v(F7Ok7k5FWRwG5$XP3kuhL zD`DQA6XiV3vRS@=tiBDJcEJJeuroS5mTj@#xgtztJet*gKWbDme}6e(JULMNGPk_6 ze{k>tD3FRlOEh;0gDGG+eQw{ry>*cbtelbroDf;^9D`{X5vC)K7Jv0mCC26i^6bju zdyOXlG(T!DLVGI9^}glx5gPzsR0Lk;(djoqU}ZEvHJr1G;>27~H#phw?uwi)WQb%S z05s2Ll(2Rs+PGV!roU!xEc-_@;bMsl^^Z&$sGKJoQq9!m7e;o+xZm{{oOC%CE}CfO zx)O*0Q@)t?%wY_1K0U)7t$x@91m5^Q1J}bmJjb+^#>`%G;FL|iQJ+#Ei5 znI--}7_JB}bD?ny2t2vAf)3!p$#*$RIdIDI^aEV-xKOQ)>Hr}?p-FjmPq>XgkenBq zskXRLN!bJOPsD8WQL(*6P@fY-QvZFkX!Eby7W7l*69WLe^75jVV_@2W0}#gMx5w$Mw$5=~ko;3v>m!Ped#(l3WXA?hVBUme8-s zVp}SteKR9Y1sqsphg$y>)9M#w)ktl;rr_Gek-0D)qrP_F4zSk5a{o?d;+tiO(XK23 zY;Y{Qq}Fb~S@{{LL?jWHv+&HdPgHU>6GE!nh$4rcrzWM4 zTy$m+COyC+9#J5o>aVx_cZed(Bwbfivk?)n7W;AmsKdZ|1cb>@s0{$wDJ?B6&KuuO zWDVsM6v*I>L+%?(P{~jl2#|YI7u&m%U*!!`s_JKY#0n&&r?aY%$qX-#1o3i$F8^+K zcJz)rDYZWsI*R2WMrp`-x+9VKa_^FXwGVal;pBMbBNnSqF8J_=b!(Z{bddenCBTR% zKxGo@hV3vF!07bBRzZKO=Ja9V)wvmmt>laEF>|0k6bZxVG8XBX4phCMT!2O5S73B9 zvdwVNU*zSv_a#7GjQxDKQ%I`pI~1E+I^b0GH^}qllj3`L1IJ zy6+`UJ~FVRbzynlk3I=y9^grwIm4jxgB10$Qf7+A`&B5%F#BkLQWO0^rN$j zUS7a=9Re|!|Gg21s;HDfkExrjZ70i-CDV1EtQ~(XmKPU256DQIy^@eo?^rU9P6#ac zL32!{PcECCL+5u##oD?-o3^5pOx&aViV&IvzU(x$@f<=Zm}DX>>XZDSO6JHhNlAkr zgzo-LFZ7c~r_y?-r*F2NDVUmc;4zA-AD+v@lmj@RbSTDR{Fg%KDHNxxm~%@Kd${d% zf~zyFD}Ww=S?I&}Ft-9r15s-g@tf%5iS4_U=-<)brv-5<$9{(v97kDq8P1{t zv+rdHl*&s2=r zfc4@iU`j!QQyt*3DWla znRUeT#xF6&3?1dovgAp}$3Vo;I`MEA16LE_7(=%VLV7@w8XnK%2z3=X&U9 z3db}yn)tD?{XO;@o(dVCj-V{f+AYoYD#(+vE0Czz90v*gc*h;qQsV%rEsKkbf?1`8 zvd-elAF&Ysk&3hg(yUkpOjaoZwdA*O7h(*y?&5c6DEByuVK>h1_#*j`gLt08BJ+-S zX|c$pc+x4+JBBs+!Od`2;l!G}4^17<$Y)YYxE4!T-=NzH4M!CT=MCX96c6+hOA{*8 zqdYuwb90>_3-JORiT|4o#CqE5zXXb3PdF@b#nG!kl&$c2T)a+x>{BQXA? z4&Z?PxQ}?J7jLI#vWsT!&^1AhZmrcsVDc}94mv!vw;=xH_ymbV3thLG?)bfzT|Q!* zJ9J#g_W|u{`*h%JgtlCH{H1V%nI_GYL4xOB*8l)976I75D^=Q6tO*o zjxKSSrT9vyHz|Iu!uC@T8+@oeqCsrMKq!!xjF4kRgy4H>(X@!+3mB^?SSbB=$ezbM zf*?$jm{t{DAQeEgkpF@b-*Asr0iKhQcyIMtY#iy?qS)R9PIN$ z6hEyc48m(dHs}Z0(b;oBQ(NhCRe#&%iYxozTZnfymsb>)0zthTh%2&^osK_+!}k<6 z)Tr^F)=_E#*(rP~K^)Z)C@RZYiy{1{hZrnu}GapA1CCHAu9-CpI;0w_bZI zZBnIY&zJ868S{a$fE?^)2pslaj}O9*EHfQEU_!ogc((GaB24co>hSfu{QaH~fUjKCD{l)gj?&QXrWDSs}h9|1-WXlbDgcc z{HAq4u@k?@9O4Ln=y#ho>y~`srDPlF4NE zgCQg4Zp%BhM~;5%Ib}9rUst+9lvRf{L3m-a`@q=LpDov!x1wT4}g zaFQu6u`L)T-oo_xuU6E?=g+|N#)dT!mOSu%o78Cs>2N6o5~ouPmxE$lpx>*DcvNf# zyx$n~nSH~r@}e2UN5`~lRuoD}(qidvx@j(uDgD9kA~Wi3!8)gx9Ot6nh=~}&&N6L3 zb37!6OuRS2F+5xEM9Vv$e>UI7@9Br9{}H)^H)g*2Lwxh!R6Yab^#H2K-NJ(fyBH%v zI88IlOUZSu#h1Gpyo<_l3ct`EKbF|`%-OlutG=NHzy8~qIOakDhTjCC{1Cdo*77<| z)Y~^PA@ z!?)ITPH&~|c9~Cj8d;E~gOOakiRfgpX1mTdnc0$ieaWv`e>&kvrRNgIHek-1?Zi@i zLcPhpVfk70;CBe)b9Sj>@aSEQ4;eK(=VYXXt}9neohYVdVSFBA4ar>^V9Oxa!S*lb0ARxa;bg44F*Vn2)*;`%%hrsa~>mP_Pi2$$uF8K z*(`KBg(x@~q;ae4Spu6voRvSJam6Bp3EXhli(26QT~gMP=XAw6w5YryEB;8`E;$JvadOorUu+knm0R zS#aH}L9ywHYuR@2YmGn5CujNx{FuqP?y?RyQeQKAx;mmq1`_C&`8MfNa%>NInV;W2 zhH%4Tt;>z+*_}{ivGlgJp>=Eu@O`yvSuW!Fw)aPgzvs@|e47ua;)ZQ-AwM-MgME7r zp{keHGM;2;)R^gRa%eD}#C}dG=Mnu`1l4nLW2B)=;A$_;TdR_eS4p$JzrC~8TZwemYS#< zFcN$H%>|+u4EF&vb5tcpAcZbd1#uO)$8pzJ6CAWm*br9z-P7RIEz5A%)V^ezQ|O6H z-Afx(1YSh`^68*e_`b{EWqDdbqTdB=!eY67)0FLFJken=u|D%na#+oI_!6R{WB`vB zyD|RJ^N+_Q;cDf~J2XMV(&7u{ader#O?L$vnBUw?A;m@U|G8l-pU z=0ykr@nfbAl)rNqS0uxr>oo6Kcq!!C?#s3va5tBaz#tp}J!G@qQEIa>2_8@S9#8w^ zl!VADd*k5s|M$s`uSAH^zT{KMq8ka%Pz`*d5_veEW&nH5GniK!BzC95#(@FX6Obb^ zuc9^fr@agOAG|zE6BZCd4QBMbtw0(;8u_Al<7NEU-R?Bj$m6Z>(k~ZR0wx_P7q@@juXA_NH5}?0)g&w zXa{?^{p|-{DR6%m5^KAnMzlAIEnKy_;{;}7sr%*`AGiXtf6mzm!hKM}`v5-`7pm41 zhtB>l(lCAZmagMO)O_{E@nVPO?eM0a-qB$yWEbP--bYq>y3X4-kou9_OKBlX5ijs# zB+R!BGapW$oR}!COVoLplOvg(lY`Bi=H};Ls>NZK84dp6SPgzVNLc)*F47UDzLkn| zjN6=QwGvATWacb67vIM*Lm&6T87bQ?qE{{I+Lm^Axke0(Tzg{hHuj#(2 z&@`^|;hT)3=mR&F$)2a{2r&{0y-7znr)=8+n5-*qE8GKr7b7C`lGpw-v}NizYua1+ zj7+#Ob0jsnfXh`kH|I2q#8Gl5CMQe6L@bPko6-d5+Sn90+1^ChE9Q>eOn!h8@t(?O zk}nn^Ec8^G;TXfEC2r}5I?<3NsIQKvgCePP@5A;Q47GfPPfFNDR zS)vWFHh1fbEaSF*!3G^G|+})e0_MV*`uf>`Fn8@dv0>BYRW* z1&2_Sk1}}9x+-`{)=F{nIglJF>uL(Sz(91kdLGa!45;`vTC<1s& zedWPQHN*ngm>ZYz#B-#8y5wBt+O|>9wXwX@ebm(eYaTBo)Iz=tG)BP5=y%Op@=WeF zRmne_>i;m-H~cYS@fd}wp8!xum0_y^6o3P_O7R8oqWiZi9bx+V!BY88A=f#&r%~-< zs$}3+TJYn_ylt@JYY0^;jsm4|V=;tlIqXvq7+397BOze7HH6A~06;?y>21euM-gx& z$Ng;Fc;OaIZ=c(dy9Ddw%HVi^J}o&fPh+R^*f?T$pj53EN8u(f_w1SDkXU6c=0kv1 zciGI3I{n|N3zh8q`w>id7oNM_Q-=v4-Y|0)1#QCFB6<1lK0Fq5Fdp54$%?`*T>}FH zT=DTQTKPv1FP>?v@(_LdZS?u#s#^x}jbhjG+!M0~9T*BS;GHk!I@@t#ku#Jcl>j~y zG&s7R*eUoX*Xa7fyg>xpK5nQaZdo!HxDTOR6`}iMD6$Q8-QfY zakpy86sk)$;DUEJnsvARvi*|~mHGodzfwkNy`QAKQ@G7dVFBmPoT4T}rc0XPqN zsV^#Gz0eV7*DuE9&;52`@?DgeYJx)I#ef&5j}e{_3FF9{C+lDDWAMzFz)%7F6=xjy z>&p;aN^B&!?vvtHsK43_hqN*Al+!n*yB^a_^OaEklbxOY0vcL@*kru|*R89Z&@2WY z9tvJQyEfdK zq5p05C#;Hx4pEn}@>*~k^wjOkP~BgQU9sMNsPw_|Ykg2Lm41CH%#mFNs%-3?2h#bH z@b-nC=(2=bbJROy+pbbQr`FA6%_n-Cce^$vv+AVsgDPSmW`hRc?FpL8MwHvrr^c41GMK5Vq$bsrGC~S`KKfb5YV#WJ@3HR_1dc$xAWjNK^Cn z&15OYjT&WyJ^Zt{IZn*ry1TB$we&TAVA!foi}%1CX)s5 z3dXuRIyz(p99EN-fw~?RhyJvylJS2pPCe+v7eHDG+mlqcu@HqGX(146;f-KAD`n*> zj=;lFgDeeSMGL-u37zG5=pSvP6`6g7S0HDqJJQ6_5hDc+3G8Nm-VXo*^sQL_xZgM) zBQWYRO*#-wo$V$q#lufABo}I^@wLy?ZzR9%ia|llGHJUI!=*^V#4xZr!0x|-B8N}A z?)y${Aqagn2|0S(c2Dqmh0l*yo_<=VZ@usWa6_$u`FDx5Ox5(C34-j~J4@z#drd3W zlX`(MNj$lI$8MZ1s)y$J)a$#!7c9Gim2uql_S(x`4@APQgAHU)Wn z$VhIQ30y}MI%_71Eag>GZk;lreGIx3twnQ-g|_zg&1`JI1opPE7*U1iNDnA z2|pHsTg+8^Aw!+TrY{UonkrwQ5^X7IToz)Etc$L|C3a0|R+Uh*O_bdhT8z6|fyrCj zbP>OqJzCqGXprKA9okDA_eQBKbgko_Zl_Sc8Dk62T&OMJE&+h}9Lv)cg_`6o_hTYd zYy``CD-G5s3itz0%FbK^^zS?*ynfW)oC7aoF8MytAGQV17P!vWVd6m~%Wfn6Q`8$w zUu^xLoB?LwA%rbrYlVU4cScO|#%DrHhPiL)al*UE)j>1F)`_Xom7a|51ML?}o0yw9 zviIWWJyIDk8G1lwGUw>WcB{_}^MNuC;kg*SBpX>UdWNb30IgBoM^f0>F7R*Z4F2%C zc#XsBl8-ekrW19bm^=D1FD-g-xG%Y6I)uu9NT#>%UeY@F=)zxWfcGk4@Q(5GYyD)_ zyAar$M%KYqUDUjv4r{AuMM!tW-s!w!l7Hk)E2IY-gpX}+hD^$?y-Atb0CO$R&oLnl z^{N`E=&k&&z8W%<_n`Q=ZbQ*T{|69-;TtQsqk6(k9NffG$)D!!`LtJ48i+0?-wcPv zf!)+NC~wYi3jVpnN$vjdo*JOsg$8FNYJx_ChpVQZ(fjGG$L~A)CX$m7eMB=yzS+r8 zlbB-r^S?~!BhuWs7{-1+9UcR{ex<}rnPRK(klCRomEe z&Y~|&a?V1i!-Fg(;8j&BryhF@j-+J`Aw0mqz<@PMMubnx>wrZKseH2&8|`28J=Irc*F|N*(%AnJ(~*_ zfOw=NWw+OCH!}AtJ-4Z^z5CCjK*DoPg07-#REX53TSVF#I|8S4#CSavpUN}u%a9sZL1% z4ule%!a%^>0R0~uPTtGKw}v=;n~cqM5%MF?D^MbO z1LxF88voHd&a#2YIn`K*X>`mq5=_}sBb zAhhzN_2V?cvRNTKiUBeMzk)reiO@Y_#YnK%zX!N=n8pL|%qd>5*;KI`aP6lI9cv72 zD)R5_>TuT+o*9J$tCL~v2dbETSnU`+s>L6SI**7O-_P0sCq?22&@QOO+CuaTFlFiW zWpBZ z-KpNt=F4_h{Q~#-sTm-lx61$_d!Ne!h%M-d%Czbqm1F&{u;b554gPEHYXD{7aDoP` z`bA%02cOnMGo1(8>KvYo=$je#^iZCqGZTj^!5YM-rWa5BtGb*l@;-FgpYjmy!7a>u zph06MG_v0JLOXF}Y9=zV;Ep~&lWubT{l(nK$jD4AS%-c@J6zr-CJI0*bnoOxX!&A< z!JD@By=h9Kiu-_i3Ow-sO>5;`x48-6io63G%r5xFo2IZT_$#L~4Fj@*a`YdCdHbPKNY*w^5wRjLkRFw*t0#FZl2I z=i!O>zB9ENm>Jr;@efPQQ6n=w>)EvW8y9-~CTfyi5W z`*Yzd7#;`>t#ijq#d{+hf~Hp!hq+QizPCM?)U>#eT;IAMrbOk1A$Wb(>Ba4F0(LOP(pb$?xwUQSg{`w3_!WA|~@ z)?%nt@5lBgZ8~5ZMZhGnvC*fwJl=Sx2wqG1_5Ti}1sq82gff6AIaLpJrvh>U{K0#3 zqZQ&sWgiKkvtipvfgdD$#&9oE09(@aK;!`-$Hv5uPN=?WfF{SNB7^oZ{?No_7XV|% za})ij93zb@C=-Fcw{HY5ehJQvM_Go=^AJ8zP8@#t!@R$W4=E+~X@0BzuAyN`($c}3 zzY3uZn#bT^pLZ2y>5m*W&vCd3Ey+Qh^n+MYt4kR{fB|YG{nS;YMCzmHVOg)P`8}m2 z{0f9md!PJxl+MeecpZIo+hZoWj*(~dcHbVSbCR0iLU}DEPNgkqSwB667d=WV; z=3cBewSk#6YJ4VUWD%a1Ii7Gu(&p#A#RCW~?UaDsp{LQTE1+1>xg0=qZ0g7g$CGFI#$eznBF zZbbPr=o)c6Bb;qtwX&d9%f1<$jB?N(kUWz8p0Cj|Yj!ICHqiRgLZVO4BO8`DeySP) z+DL-D%CP3U$gzMsSp(W_FQ3U;!X)zpY~jZr;O5CF&oww*?Y9FhiTv~;K_Pu@0ZD^`a&$LcT7quF+K9nt#^z=noX<)$|9)_Wh=E6vSHy3^wt z)j}wLz8QXvo!=^^Z*bd^)caw$`XdauJl=*DDwMaanNp5BeCU1Okv+cM8DIT${MP0WQ_XCEH>R4|5T&1Jv&K`X7b2Im5^IY<^t4+ z(r58~nN|?tMhCGI`uWyM3$sD@d3jzWYWN!KON(T)JY!3iw!gl~eJAE4hTr4r2gloO zJW_xDY+sGL54(B1R1doBjz0`=+uhXMtl)aUxDLS{r~%bo_{qKW6Hjf&o?u+*dB*QW zXvCC3KT!ih^u70f5M!mo?&FJ_tMdEC)qASi08wsy9Z$dD=qn(WY*Rc5KG*Fh&|KbdWTGWs_5I)tKr)?yq0 zg6$cHhkdhAoChuc-;4kJcO&W!$rR&?h1FTge5(v%XsYG5ha<1RK`mA_Q??*H_?m&k zFSFL>N@HUD3hzW5mQK8sA(D~y07H5bNJn`q;`7aIQ|V}(u${%DB(@o7iFyrNPS|0) z4D3?|BB@6sP5>I(bYmikH|M6dj;szuzOjCqa@|ngeMD+3gVe5g0*P zA}<8U-$nt_$i;~E)9bLG>$mLf@d1NOY5~MCpZC5pK%6La@Z%tnPhsb`4kVm%v1fZD6Xoy7ffQ1FLZG^84NTpie7< zW~f~{?Q<8In3!_=reW5 zDW@^rXJ#!+5scc-s3N&DG!1S@ATh=+291YXo2;Ff3!&5$5QLN~MfWnHGe*}FV}Ebd zIRf%O>f3y=gJevghD-ccpj;=y>Chou#@i)tDd=N6_|BTw${crFR}im&K>EDP5N|PC z?XuW^<9`S(4@q;oST9$O8<0FNY z;Wmh=kz693CbU~1+XRQ(GKQ~g&H@kWpf+5!|hvsDCgkCB;DB;vO{ev-ebIJ zLz!%HQzoCk0LJ&Lc9*zc%#ic#{`1Maf99}e~Qky zWl`N%`$Eieh%WV)BdgLjt+VU=3CvAK7se{{yL(~HZ+(kpBfV_x{Xdn)PU08pi;_zb?w`OQr z!R}bm+*4MhV&!jO)mj}mNfTS0j>5BDN+V{h%O1 z3^m=*;`BJi<9KL|$2&_f0CH!zJ-y|%pBGB_p;hQnAO??3G+=B7cnWDgAbveEAp+a@ zTRK<6i3 z?8GL%I8mc80g8Wi3mudO!Sw2t)XKK(noXX<5c-PFyRsLrH*R_4`D z?)fSOJLP$nH;rz_i(azx>q`@mHY`!5MvgapkI&~=v|)A6R;l{_iF4U^P{*$ud#0F*iv@aWWUpUjTU0s`v^UM#~3vG%#w~vbYjQMPMeB$wz z>}`)TPQB);>>qKMvZWq=Q`361)g-a4sMQzASsD$hSyrtY$Zd;L}@n_5vw zZ~F0{RpaPXmSzH|;<&h^61V}XoE<@!UBygqGvCh3L$>Gw9lgsjDAh48A3xqcpT1RF z8hgSbQjfkzY6mwVEA!R-)v61mgHJuOqRa3xM^yv(y0(RH~LRqYJHx%A8 zJ-h6e%9lxAV#m^wn|M6pd2fz{I(#H=?wx&axXVQ$(7y%^y5&zRD0Hz>$5^|txfOcC zaet>=Uihz0>#7B6gnJr2{aijh)P3O)2Ji~5rwuB)08&NyUp zXVW%1m_G!4QBC(&F535m;wv&mo^0K36B9Ym3gqM4>rHMJ?}rbAJQe1@hG#+5I`8D~t+>Syl?FPn=_Xgzz>tR|=$#md z>H{q0F?n|LqP#rWz5#kt%Z%jysU!0&!0cryUIrd-J!W(TV^tRgwD=#E1%>{p}w$3oVapNd16(-Ec zAtNq?4GhRpFokrCpV;9j`oDaAV$^DhKcfjof?i!~L#WmFvucs`IWr@f`mE zSax27*!_t|8Y4N+BMhqvLfBMukJZ03$uZ(vMIhSvR9*RxDTWxaj|wHHUxI00x%Va< zvDUb}%~)}yu!?+Fj`+`G`046(EKri|F#WxXGE|OR{3<-HyS~!Y9baZR>Hs=rij{`o z-2!);cy=sBec<%&&i5gjg?hd+8u_MhNlx$_B6Jf@)}juA6Y|rk{GHo5cs+lne<3OC=E_p{_i!Ge&xgJ6 zBy3OWI#i!rJ=4%D)lB z1RROGY4f*{c(0gq>Fw4vUPZ`Nd5cU$cMOQ98vXV+mgdAooVGHxKoE!XXRgz|lh%M| zP|logHSxwqMY+s>2(2$D@OY<{RaB;2cwzi`^5yo*uS-xO?Y1N2L|-$AsMGC)^`t3u z#+8TOj(|siz1?AaV8L0;1l?94GK}C!wMzrOemE7X z0@F+vGp}EbI7LsW@y`oz`dGA0Km1jd*ou=ovC%4>bw8LA!eRTqD>H)M{=vQ<>S=Id zym9m1o5&CKdS$y!WE<_K2=B z>&Af9uwe=+9GanhR-qO_1O0yBJuU6%Ya+Megh$?U*9SHMQ>ac`%Ao4sh z0=<&(&8Dz^7iQGN$oK)E+8fgkDagNp#{+5ac0ru|H7G6K-80caZL8XbqX|j!555%gM#%i`5cryfQ8> zfsg96S)Q`#ioCu4Aws=jV8O}-idb1k$VBt|e1o;=Hq-{!m6%LKs1l|^XWP#$j2{Dc zQ?lcSDAnd`eTi5ojVMG$3{w%dP05QJM?ra#J~i-Ex)&EuA~YH~C<=~0_8~S)0VM3@ zbX$=`nwvOu8Ts<4=TC2{Aevn%U#4b2?ip0Fsa0x2V7L`9!i>m55-{9UP*I0vSN-U7 z=tLqd%(dTrbai(8_ZZG=RRW$mj>f@#hYWB?2_!%VnWM!Bn_AeI^BVodt~JrnJn@=Z z=6)v~=4}+8l`;rY@_?|V4+Ag^#AYml4EY|T`CT2>>Fge}K_0BwOyaV%2pC_gow$Xe z*UR?XfqTAYiIxZq+(EQa?`W;ht&njrY<|MaUnLeut7=%9Nmr>!br^KdVVwYH7n6ZT z=49c-eadpT&C)*TnVGh7che#n{GfS8@DcRK%wT6Cx-JEI8ttuKBVYtz3PZ%dEzhwl z3M%<(ig81h5=^#m9&aHdi3gLmr{_)J*L$S4?N}=b^@1)yS@gQS{-|m8u^(|8M{#U= zrWI-c&qB*BLZOtSw@_rTaB>Gk2xG4W-S#&RO=%|P{g+3`UEtpV34w4+Cu5BSjc=f) z%M!ve9M0pUY-~X2ijK)2{d$QOD*}w0;uN`*R6ql4Zu`Gl+yOn{QwuTsNCL*Jl_lbdYziEB!v>&<)b`C^| z5iS0tpccO))?drisK6X1|7j#%o8D27OQ?NTBQF=z296uOv$nG$IgKwntL z{bVFBl{$EV)X5VTcL}HbCW}?%zBgH3xw02Ke6Xu0yR~DucG(S?eh}0QU)WuR@V#SC z({s4>CxROak?X0T!$#h6(mAEcn}jgL0CA?%%eeaGN#RLA82nTBS)$@s6@GerY#2)= znld$hAMX>-`KhYrgkaC+BRW1HHHyxilo!xt)&iu_`8+obamMJUsWaVZmJc{B zlzuQDq*;2Z0GKav_R4tI8C3gE7Hryd!v$CIfDmfAfrIn_A-M@-5BWm-5=e*cXz|B{Bne$kM$IUDLb$xZ#rgua1fW&gHqz(B)6?<8&Bmoh*-3Y=i22}E z?*{P14fEF!DH zck>X)mtK}hD3CQKP)o392*Y*NPg7ih+uPT-1b{+0u_qLatKU=UHpOl!N;9ZVwK0WC3C-XbbT+ z0ro3WUW7<#`t|FIE>KgAz1*J5D+4I4CD7vj65>;6k37&JdG%{U^zqMdAB&5NI|DRS zJfSbnu(%is6|ry|vi(hl6yT|bqlwPf4;JrhhSyzIC10m~shRb@Ea{jY1ewpYfTk4i zPWFN0goz$n+6`Uvg|MGOw2%FitsWy#-x=t8s_wrXcy5D`KfU9!U21+{@ znIBc2abC{yN&F8Ki;#W&HrF^$xcU_HQnRaO*bo2?g>x%7Drs7w^aQcEo6togrO4Z6-THg5$&l2z72@quHF?ZLe*VQHJp6w}Yjhh& znkm)W3T60v+rAB4Sw*oI2%!Vt2K<#;aDP}JY`4rAva%s*KKIXLBUC}>Lp~Cf7BQ=J zQfX9kP5OH3RMf3!gRIpt2%)rWZ4FeO@LxX zZBAj#b>vwT7GPhoS>4#Om9}sou|;-6k<42wP1sJ`EM!iEPpk;AHH^hKid&zqte9wlRg@y5mplxzTjZ1S|I{ z_;2h;Er1l02=P~!f)}?09U>MEj@E^yI1`n{AJ*w4w?5QFb8udIfwSO8C7>V;9K z10D0OpW49{vbkBn-U)4zc9{80hWvue$OPa`|3PAJBQPEz5nGaP{FBi#R9qr6l|1w9 zzRdX!n3}+g7cEYxW=;oLbZUTNxc>?&e5{F%$yOFjXxak5e`%bwUa@V?Vcy(3N!xD>Y(s0>N2&XR&!y2*fy|6U0?Eayp zxt}1ID@!+kJK_4#F6W^i_%|W4(DQ;N=$o&*^kz zUT6gc)RkbcXioA*VdEFD1arCH{NX&1i1Rwu)@*I#E-}aR0ls#5E0nKwi~+16ceV(2 zv=*$Wo_jGzLU{kD(-6R_ATlY1v+ViuHfbJ^FCudJy1>6!5G4I4^OlYg@H@MZ)e1W~ zurYV!d&&k#=+1zLxE*pvtp`>~P3mdv>OjT@q?5+}XaP59DA=iUB+CNp)W9Us#OV#S zkM0jg!;VMTpxV*~wS`{`v6rC9nlE|<)S!^wigkg5mDLk@8ObCuIOxV#u0-*)Cqs)% z3BsLWXAQVDACXKIr^OfgwetE)A&41ImV`4-b95Fmy41`96R=Fa5GBO`P z`^(@g1pj5$>9_XSHHNQq>|3eko_n$fvfUyW%S`8od((|39+(pV;v1q0tR`2Zt%ItjhNbylArpXlmCXYwSR4#X8@1 zErk_fQ#&^-b!^LhfW+2oUxNcS)8~g6Ye9goCHum8e zqCx$pbe8IMS)Kx~7qd8!OzC(y156eyNL7mNwcG3xJTYSaM^9(f@~XkBL>-x&_f0PaDS_y`p76yeO`Ej?SMX_2q4<` zbY|`XQ+FUl^80D$<(VrjQfnb~Fq8)0PB_PeCl65bf`&7{b!kmjoVsY6w(+Owg%~(r zgjOo~1*d;Nh4-t|<+oZFMn5gv3@FbZj^a)KgNh@eL&*$R(VG|g|6~0>b)Y@^XQtBg zIH08DBL5E!VnBO867iQ6mZ=sn+)EHerZ*nu=0sU*ktQEZ)n856>Mgpnr-_<8n;V8o zCtej%Fj;x-z~LLYm7J(7=Fz4Hd5>hdD^9eK84b7zaT@t5pX}9fHFJVD)_jphk@q2l zUfcG*xKFYuAg+7;StU>jd%*=Jy&bvcq5tUeHKid*%QLx|g?i}Y1-6YXa;_!h+RHi2_IW6PYGm1)s1oz7C+40k_#v)w_W5a4zx10@`SLw0 z6lw+H+4tuFnuJ7Zb^sJarqkRG9rbG?axTBWkPnjj@SH;<=F=mc*-{G$+x|XkE>VTY z&ftA`M)4|wIJt$04p2}~=!9y)&@_D4oRPHxnFA6!tvzH^z%14cIscgOn`@N&f39RA z`!`cFk+^{PhQ&M{LhUS^d;U8Mbekee)O#o=|7SzQt(Z>Z4DqL4*l-|ozpNl(h3>y z?78>AA_#5~aZy5wx*o@B8bdP4uhPHcU9SYG4;F)-E&F6SfUV^=ehAPD+#*N$_=zv{ zecS{=?FGoW{PMy#xHis7y^sus6Oj8|yQSsQ-y9SGk@T}+4vOqeKf{|zbMrU`21m4q zNCgB*{MgW63>~#|R3}QMpWBv9cTWu-oFLhuGttN;yU-AXZeCAX&HtR=x2LCw>( zS)@wdl`$aieemRm#J?#)Y?h=PBiop`1K5Z*A#5;V*>Mt71ui`tI(;1;=KAC2QZ}D% zefk0Js$3KG`9Av?C_F8#&kklNZXhDH9$EvJBIE(2K`g2=e%K1 z;L!t?h;OuTL+*hxV1L^U38PTwPB@ak%2B10+cwSuf_OE+<%RqEq8e|!7`~M5W!*4b z`K$}7aOD-L$!I+GI3>BYX!qDp{e)|Br@OMujIiD&1PRJEzAT!I{je))5=>NuWeEk_ z4C<}5+q@p)bkpI})D*7}%R@$;a(1)Ab=%7Y2BFV1Ktnn?ocsR^;+ohOD|!lVI~&UF zGaTYzIFX>I+t@j}$lQdxwsYl0d?2}Gy=>(!Iz>HSV8yE*X?o-6UFmrbj#PuoRiGYn z*nA2}cmRwW8x(cv;<@z?L+J%H5h+$7HH1|40W<};DNzUhJz|S_kDAI2>QkDCR zyk4KGRdi{u|Ac#f)jxv?gt7e2IozzrWoxuW*u|Qm%Raf*@#)hQoj(9+KtA}iNK2H( z$U6$blcxLL^7^W#tp(>#ZbUg+KZWCo6cqX*o%=n94u%yLMBow`!)rw&YXN1R;0-2) z>b&{7Q3iYw@dYkTEx$1>@y;5QG5%BT)0@HP6H}=K^`lsEmXYwlc)@?D z@PY-Dy6VrgUiE!&tw2SRAS9pu#VQs0gGyScHyE%Df2Tk}6niYli9Voo%|jB<-B>Ne z2>^%_d-pBv3P^zIe2kFyv_pwQ!Twb6rsVy7!dh($6B(nE_qPe}gy_IDwWi@|@Y`lc z#PF#1cn`5QPk_xLB0X>$SR82c<>d>J2LgG>$xh>9l2HIVq|30d8;6= zYI+V6oLn_%w;61iMkiF^U`RLRl^ z1WL%StQGF|4*L^F8b-RkxilG({}P1UJ_sd9l6vfUc0BR1<)b5Z@JY6fJtA3Nv3233 z7jwk|eE9?CT;_<`+@K;pflP_n6exqPV*yl(w-#4L2=Sp0bi}(Y686Q8=Ja@i1Rb|1 zF=%8&x@{S|1@acg!|r*g%FO;EQ#$b6-mfe${`gjUd!=WdTg#I%p7t5L?>+T4mfJ*j z6BNCg$~A;|Kl-+m%j!v2S5bt!qw%?nj~sc17E`@R83&Af`X7MTjh$v#@F~dCVeqg> z)h3g1kc@v9QLu{WxV0mvWZ_rUn|6^)=p#C|Ug;NbA(Ndw*PAbq9z10K5xng^km%V2=@DN0W|Ejo9AI@u_33auVxDSLMVP^W|zLMu?IuOkDuL1qlU|4 zP~wpwETNP^xgIy|LTnv@X_ChNp16G&XCm7@re@DryDJbk7x#eyj11LgrRliD#1387 zgBL4*mWO^NT{e~-abIPJq3x2Cr4Hzia&23l((;(p5@jYe} z4e=OZM-~d14e@i{jI&X!@Gclj3>}PP0)3B}uG&P!7C+L_v88u7+G2B|2|`zsn_%*O z1q-!09k)H7^sy~LqZk5sZi|~65U)M^3CiO!p9GPE zXq~(auoJmS=>J=8VSAnMSuDw-CMw z)=f{=mjLQOsz>1^sQ#C#djJuwZb1U?$tSxJ!TQ3J4XqrqI=OFoszT~88Za!mzTPBF zazzbal7uD*#Iukq&3F|}t3UNV2yS0pf>zZiT-YyxFhHRXj^{TX@x?1QLT58uoSBz= zur8Bd`FlsDvK2@t_y@L7_B^e()Rbns4#FB>-l0WcN6Sh3L`^Tqjit9aTSO?p>BiH0 z0(32HJ|V{?mFceG`e)9?r7f!djZQHnj!Lcz`25WVYfCugWd@;ov%CJ57U!ZGAvGU9 zF$dJUI27py@=wG;9NK`n1Gmw;BX7N9iuXCsm1~n#eo3vWXTno+o#b3)*(?7i#9KVq z$SZJ|oxV%GzAv-GWQ~@_xR#SQfX4tk)|BGcCR^QK7_FHdSxpd@?H)4Y%2g3fTbE#< zfQ^myzOeoJe`(=kg;=f+yW1Z^g}#T--GmL*gHY`Z@qqGw^^jv1KWJ99Gm*=z$Jd+{j9ftLvM!54oWPQOuw&bT*J4A<#5j2l|XPhTw!2 z_hqiVHJ#ng0nHcP-5W>GuN!Ruq=%WA64|z%Y8v9*o(YqxGfU-JXZ=y*8O}d6SG5qc zd=GMDe+ioA@5|uY-iFRbi%w`Mb5;3g2Ale@wB^RhK@e3Y?h16H zjnR%Yd%#|O)I3LHm^}#Fa6&~=>0D4FJc;<`fj5tZ0X`H7XrPyH#ut02!?(~bHI~RQ zBPb8nqun?mR%!{Bm6WF5K%v{sLq?ysNSw8Xwj2YHP%O1L>Pv)Eg4@(9PD3rn2pk4^>-V$Zw)uC=f4c@nZ1v9 z!Slrb1d{QaBbN`4=l!%sJF-vuWWJm;;8{mZG$Zan#=`j5u9S#HO8{4?*wq0;UBz`; z1{_#xL>ORlA`$AaT=OG&9yuNKf)839TllY4g-h@0LM>?W3!LFHYklZUgLMnpYlo@q zs*rAU40sat5`ob)zWpA7y`Zyk#v{m+t6|BTG z^^PXc-0kk}p~6WD$A;P8oe~kj!xUnYm?(BU> z;NL>gkXcR0CBG-LniSSr^X)13MEGLLm@pA=Wk;oD%W4Q|p(#v4Nmhc4r1sKutiAP- z-7}48#(H)l?Q+NS-N5efE>$6y+5QyUA(`s%DU*6sqt_lY7=mhu3qNEtxK-pnJ_fST zQ-W4!skwn|{%miCPHjx*`qvl&M0JV<=l2O8qp?8p&#a5>M@8Hj*T6aS9weajg6%ep-saDSHIw|%DqEh zbCI_l|MR`cc#h+?%PGYT$Yy!(RbvGhrpr*^dJkfb|Om<42<?vhfOZ=%Ih`FsqPM`Ac6f&7VUR4FR%NA(9umZvdPM zJrNI;xj&1ZH$pl+Z{$51c{_7sp@ze^xM;cI`;np7F585TLelWzT2+zO_mH+0xk82NyAHhRCIghRCNtfYYX#P~#)JH0Nv7btQW>`9qZR-k4Aq?I z!s&q)v-$up@gr8}Gw8e?)b3vY+iY`^)FJXpXgFLRnz8qb%+rIHy0#33ORodIzL%s> zm76zSB~OV;$^j`AEq$W#|Gco1!fkJybl2W_{7tf_rYby2=ye8zVF=vTL0zzlwG+?5 z48lJJd?tM{);6HfsmU%H0L<$APh-PSX-cseN{({^T;!U45b@O1o>nH(g|!XwcPxyp zZx}jg8NeiE%aObCWrQQ!AgAv^uG6eU7wiOu(;{`Mq0^0L(J}PaFPX7dry_hJq&|u*U2A$6WrD}zoCvEw0qdifoe7g>TgRI6|5@$X;X{pSo7;nMvXfxlomGn6C9iad0 zujis!`Q7&`3~cd+IOjo5gBZ-p+~X59t@`2Up{C)jB5XwD!)E#l{$M6Fj>^8II1|yo z-mEO2ytx~niGNpKDxcX0QI*`t);ePFsTF)~g1!dP)eMva-gWvAF@2 zWA+!}iNst|NF8B`Cw_esA&?2+b57dgYlaT;O1Acp3Ay|~AgZb#)RxZ#jb! zE__4k?&z2&8C8v(lw1vb_4qGKgZhD7E;zWswV*}`7Fs-McfPkYjhpwuRo76pB!*WE zA=yjK!oWsZEuW-qmpTAdz!fLhxp(`Zie*4!EImqPlO|nRoXhBWutiHjt`$Imi3S7I&%9da#YFMtKC|Lu|z-wpx zk%-e?H*?uE>hDgb##B(H-&tMI7cVjVFz5elCASmwUkCJqat)|Cox+*Imio+6)#InL zD`s%NNuIpR!#3%>s|wu8nOcCP;HNQ!Cs1Alru;$gO|I#PH0;WW-Kq39l|gP`^J()d z3OB-^)zzI2J?faXqBjnh44opg{ba^_*C7u_0HJf$$d1GVKY!juTUfLROw(1-&4RxB z`!}=0OYrJ#B2@GYXrcE3k1zl6Gb~HxfpA0yfu$f#PgcL@HvTY`V|1h!G;%#nP@^G; zARq6r(F! ziTmWbNvn6SFsI3kDL+Iz%rsS!-Um{xP(*!3jD}t^3kt={e^QTA7y=l`a9#M4LM~bX zYsA#x4$U>3wz#D94q=%lEdR-E+g45Fm^x?x zuyHG%HGZ?v@M%EkmM@$k(+A?AxrTGywe3@b21zaF8_DZKbKuX4~=q#T)EvHZ8G4Lzi=#c_gd@X$QN^%yhk7V zuDt0XH^&l_UxueqC*oJ+Ru9|Jjm{g)zMP53%hgehfH44Dmm(WM&!!5aw0!&Z-q4h_ zT-6qKs`Ns`t*+(s7XY4>jY=gL3F)fA@A+ByV8?7m$ob-?=+_k#ygUpgOD z9+~jY=RNTC0q3gQk20i$4>JnMeA#&Eyd3kIO`q;;q+PT3pyKJHeS2H`;^!7$aHKdK za7!3)yl^8|zvqvHL#xj8{QiGN6X$bBMzFkb-MWYLk1WWg-|6MuL;PsxcU3p|b+`;5rRu7NYXX?!)*THDl@mc@yYtlihdO`Zv};{H zdhoS5psb#6vfTG^>faMxVXH?twOXYGnRC*_%1o!;`+PipxtD|vF>Ku1TE))?Q%rJ9 z80by*{71)aoEx`rQ2%G$8bUauy?7JBL;eF0%Kme4Le+yS z&!Aqkcc70{r)mb{Yn<+;zyP`&KlOn|4hgutNm$;m_e}vnk4lkcZEfCa^IXb3q`_&} zRMBCjKWLox_#pIxYbNr@jqs;# zglXy3EvwDyr*N<$usY}ioo(gXqwo{|KQh|iS2pm%=`8m+e2^$f$ffW=dEb^H{?aTW zX`nRbJdn_sj^920a^eQOAu{+qJ{=Zes%X=51AGba%9qzgK5o{4Nsj2^Y39nS+SESoSuJ^12)og6yHzST%EP^w^ zMnbypd4T(rx_5{O{d!3b65`H&)~Ed)KCXjB$lc&xPgr0jZ{?Ww+O6);=b+F~%6Q2Q z<0!rA&mTCjat3~Fm1tW2zW?x1v(+7(__ts1F?*Ft5j-@2`Qs85-yFzY@pB?n;x@wHC)A&)W;`HwGnKlV zj~~_RQaA6wi%@G*@-yRk`|gR{f>*;2`p&*`qOwEftvQ>)BG#S}iU@2L$qOwg+ zksopcHZnTNTS5?DQK!MXFFV4&8nfjqn{@h=();!K>|)GiYe92az6}++1KS3D`s3^K zhhN}pYW?rb8VrEhtBtxc^eI*e*|{*j&o>5qpF_sQ-k0D0Lr^|^NZ%LHnKUrub?8;F zMl5hxZJo_QjX8M|4igghVF%#r%K#;Eu@` zX0_qZg!axxwV0e5e`EprTv3rOpPqWiS?Z@V?me%#m06KStG(+@hgnw{WGh1`Mx+=^zB$&3L(n*#-UbtUNF9VYcYw|ha*jK09wt>8xh1n0}l=#+>28pBPymoJ2_m01>|)`1`}ib6tWV zF!HXwOiZ+Tc7WdS)KP7J)v<=jZjIPggy~+ltE(tf=__k`9IfX4<#{ngNkr}4C=QB! zJst+gAX8*^wu@K$yi;^IFs}q2`0p1W_HdECQOHP6a-0C&5ey3#M7Fg6z_PToG>#u4 z+7BWkg**}!6)nQ?LyyG<4-T?b^VO?8iN0$7IG2aus0;1O^B&liciX)k2!uA1RhreZ zGsgx$)Hv^wN(XTvaRF5D3~_G8NP~vL_N_WtX(2onrTj!dRZtC0BQ0v6n)3>N=}BsE zRI~rvNZ10nyejy-o0D}~T}TH6giXs2q4{t5$L0I&*k4H^4?#jy zFV2@Hf2YHTe(E>T=C6Dc+5m|7n*Le=@?>mLuw@r(WUa=u0o@AlrJ~Mk`}7SafMx7p z>JPcn*va7l+kBepA3vmer}JQRWDEy&tv}9o-vrtur<+T7%>mBb8;}g_d9P~KVYc=r zjOv~VuK@yR1E`R9z4Q`zc@+U5&IvAifwr+ZE)Gle+5!bJSkP8;%Btgmhs`KB^BN0O&fz3_yY~8@J3X zY*OjnR};gtc3DAQIb2HOuc=~MRaF+% zrteRnd&mC)bmMNSomEIXzN=~Wf2M0El_Q?Dh{o{{j2LKcJMiD9Y-qpk1iCpd(EmI# zlX0p=QHuTt9EZBQyJvp%$ZSWXUvGBtx4$y6@eU;Kt&#DD7#y5C$7{F!6)>0~&;_za zZZVig)0pr!EB=>+VD2AvETeiRG0Dw>W~Zk#Op#)7*5G^H1h1ei*yq6S0ZKAlL)gax zUL3okBw<2&77S3jeSot?@0(;7yDG07J_l6ah#L*6Bllt8F<@$TY+hfGd14ZJ%tfKI zKjNf75Z|pf7y>wA`1s>fXxh{p`*vbOpj3~A!Myg4Tfd%M^+h`Sl6h!__Ul3F$K>n3 z%ifm|JD*S0e_vK@Y0e^DsPCM59}Wx5`eu#=H7p&DUR>0(>)4*QFx%ndyZ2)>`UG_W zU-uats0vCRBXeMNPyRe<55@lgeq_cm<*=ioNGxXc*$YuWo(r33#vO>|IJLu0J`^|| zxvMTgt8#gmq|>tl@!r^~&+W^FR0@Eb?W>2 z{Huf8A?*++eAa3w+Ot6@poF-OjL^CQuwWsI)&Wh1)SrNMx4<0se)Tw_;5>_G&BCb+ zBm?m4fn^$aD$_e2Yyqf`PQ0|G_BcfJrH8(pxOc)u>GMjIKsP^L)m`Mo<-9AOKW6c5#zQ1P6Thg*O}HEnslO=hdU5 zaFKvbfIZs$-tc_;vU_P4sn&seGO6(<4n`qicZ>8=e?n3*bm{VmaS|;J)$!nC3pwPu zyPy2A(6KH~&j7u+__$CeGxRmV`8@SqMrd*!-I?xt8XV18$iL z3{yPxofij^0B+x9^tz6}P#d$OX;eS;zawgKzOI-xeV6LM|5f2@*U;r(qMl5tA5Co{ zKq=Ua%>yJzC(wF&D+y%oC1q@%zh^mD9-!+NA-ts#YAnQ5`qNiKMVX(iuz95DzYjI# zE2`Dn6LLM~Dg4oEXSYUez!Wd-0`_&>#`19K>|bMWzz3kgJO&oM-D7NfHI=o1j?(}J zxsja`VXw7ZEs3S5+zYs$z0CZoPFvnwr`-;&?EcKdoV|lzvFHO{p;y$RIiz^uf9(VZ zA-PIsK43xp{Vkr3CF}emqeEiWKUmOQg6N3@bfl>6Z|nHiNvbS&e@=qy6euNg`SYF2 z@mEaUmnI^Dq}FiaTtTiRLkj5fGdZ0MOivnyf<6QYIEJXw&=^+p9B%o zrr`TGz>?ZXy)0c=4cDr+96no7cf*Waps45e zRegT=>azo^!7#n_=GPb^@_G~7^|1r{vC|;39eyb^o7*V-65Y{_e27uGvGpS)MYAMLx#6|G>aBVS>9V!(NBv(tJ8;1*vHTE!lWaufR! zoL2p&+2gy=R6@<*#CL90b{1HNm({xr_V1DeU7N__-6SRAKw*^=%VGYKs>oM6w<|g~Q2qnNx>IBUY;bymQRZ#q;PCZwV_nq)P7R;k9c< zeh1j+{R2ek-QWcHmtHYnS{?rrJrA5T%PuMLX5A98^e5(i@=M&(*k5CS11?)P77`q6 zH2$lUyQ=A&55aiW#RB5d0hBc{;T@mu=~lY!gm=ZndC!{4Ty8+W6W-kCXHq{7(VHmm zt;3Y83m(;D{$$FhG zumG+Q@J0Q~X(96iCMSYFl5sP6Mv{CMbRY@lj|tn`Gf3269ztBd?#s}cnLUBOS_Nv68IQ`%L zZ|?;i1I0kZE8@Q~P`|ahBLH$3lwHsy)87m>p=-#-!=)&xrLBz%xFph?_h5i3K>5qa3}?X7FV zWb`Qw+9t%z-2CAN_tD#9h~tC94HvRQ3jtAeBXkAw-g-ogrlFxkuHff$N7ii@*fBZ@ zt{Y+iYj8z0*R;0gwl*w2H{=D`;F5RkpROv-mG)APWuTZJZjaRc+OST<%}&TQmx~h$;Y`xfo|Oh^mSzBbGae96Gr?4r zk}E4th^(hEq&zq>_^yCt^9hA;7}ewX?9lf^ybJ7O_lJwk26}sWZ@CKHSRaGI84?7? z`xx+UH3Cg}fjy$Rt7_GW3kMah?A~6)vhX%QZ@|U4BDi^OM40G1)NXicNr?aSNd09o zjXx$EBWa%56RDQ1#SfzF+inbq7Y2)F5hwT$wSyF0`$(gfxAv~C{C_<$b7I!sq85I4 z@4eVuF3$T}?X(k}6Jc(U)(lOkK&zmm{QNNY6r7c*g++p+#EI_!30z9cny?Yqs3f0e5hKdN1J?3iSer;u&-oVK*KaZhh zvRRy)v>QlFCnpRWK@(B=fdJpDP9WhR9Oxg5vqx%1FkvR>Cb#E&STrSG$U+_5E<0iMa|?Y}$3^GN+ui_$Il; z)6Rk=SVc?aT@-tqABkg%h;OEu?fp<2U|8cDWD&rvnBC^b@EBYwRHAPn0LK6XiK}6R z%<_H%KeHEx6~(Pi?HuXt?k+nZ@CrOADSEqaxTT>X$eBZu?G?BVlc;$i6H&-@Jb!GC zYiX{xb?w;l*#q*~Hb9v7`1^XXUvHrLt#ahFz6~%n)*TpDFJGpfK`P;J$#AC4uCd!i-mVqr{vhlBra=Fy6emo}e zzR5CGiHIy)Mfvw$3eGp4+^)AZVz%6*6J~9FFd7;IC)9d+0UAGx5Ih0wsVDepRxEsH zt%bsFfG?qu^s0?EABchUF%*dN6?U8Za}&mp(r)EK$_W55(_hQTr1k)og%4!@EGM#L zx19exZQv>rt~WXN`0dz2zmZg%Saah@5P;~09iz`Ba% zSh)nnIWTOoMqba2=WH7fJhr)Ah*@Fx1QW5-3be%@)$X?J-3odTM7+g5#hclfz-D9kgD0R?yoLSy>%2*7BiUCd8&mhx2|k%Er`>+9++jL-B| zztTveiL6dd*SwY#q2s=2^k*utT@k=`RA=|@e{fjjs&E{DRTB(*f^7AhgT|#;QA3yQ z-nVut=|tX+d2ZVR>n|TOQ-b6E!7`@!P+7{lD9mc*Y#A#+7oHx3NGp$hOBCJQ`4ox z6v-XXC*^~w)7ScRa<2wVt~tJxCnv~w4YY=8?IR?&Xt;1$Uz_F6tlOH;pJ9o_d9Cji zKS-w@>I^A&v3Cxq?8wPqoUx8>@LH2cARCxFv=Jh-2?sKS@7djns0?77^L&8WN@-fv zTpg4zNxuHpDc2&qM+$T!$;O8*-Iw1Se7M1zYtP-W%HtZA#=ksNhfQB<2nS{QKacG0??ki zg)gFJkQdikkY-;aJK2pS8`zyJaH|qP^A9Q41( zXEBk>C$>`HGT&;v&cPeofEoyGMU4FvFHbZVI&LqS}Jk zxMq4aX@t52T#F(^V>xM>-maFFzWz^JVp1-6HP0mMuVGKS-9&|W$+JVoWtqQe9Y`m9mx+<2tncXP&c+Dr)?N!~Pb=oy7Dg;^= z@@+Q~)@om$@_S*r6tnY1Ms{kS+AFG9y%UpCZkTi|H6Ym{Fig2aR4555GhN*V*x4CPFnrCimAEm=MPhj}bnzrG;5;-*g}<00OF@GHAOu>&!@-sV?8sm6E(_Oc!J{m*wI9ojBV)^dtRH_1dzt{@N|U>zsz)mY7w6v`#smh0L}z@ za2iWBvx$4{fDh0GDF$E2^I2`8J;?0Ua>sGLAWLWU9i_zp=aKp@$hz?|dyyIv8$^?G z#?NSTu`>YvyVZS;IITAq;pXji0<_;i#%aeJH;N#Y712BcC>!#nUC@YcD1OeTT9tRGSe7s(WLKB&t3llZybUJ zIQk|TeNo9jhSlclX!c-qya*4Vecnj48d>1*D~L@tpQCTg9il(8Vx5^1Kn}| z%yVx#hJxRa*|jfQ7MQvL?$f)3%ft2l&-SH;4KgzwGo$xqcR(IX7ga8>=*h&|A>AQr zW!PvT1iA&iF&sTGz1n?#(rK3f92>?PMcWN_K#HmLu`D0sNsxxpE?~JYIInmMNf7;L zI-uuQ76GxN4o`u3(HftD#C1qn2Eo`?$x$kks~2J2E0owPhF0WmV&PEGRm=e zcZ|cOCTlgeaZLj*fMRJ^O^m89__ryYU9^wOD>)K9+f&|W^N{Pjz#GkOX?mv74AQON zA3Nv=3vN}9Uj>(hvKM+7(mES<)P*L@Aoy`C)HVwtxyhafRE6R1U#7{{;eCz&D;ZXBo#7YZo5I+of2lgOY1jyXu1L#+%;AOTYDP<@dX&}uOlhe4BR z99CBfp8(Y6cb#2Jy{BXk+**K=g-21zs-2l@t~vmoyyj{{s9BmhiG77&0dDd~-Ot23 z%n5=2e%birID6{Zh{j7}7SPqAhS_a)n;g54hPi?~RI~tJfX(Pij*N*>BylPL(K?1~ z9PLJq%gb@}VnJ0sU1a{#9#N(*$6qs*`SSwO+wO=q2ObljSQ{h>clgRK-7K}2fjp$9 zr4&(?u5oId7+nkZ(v$A4?zjQMKlKfRCArcU&**VB}`34rkpM zz_j0w-KN>MW~RY#J@OLBGHo0<3T_WZ&#n7b{V-@5N^j=`2xa!EEK|#N$f_fN3wPBm zz$pXW$5^o%gr~Q+w{dt3U6FLSy8Z)n@BC@jubKNY0` zL%9CxBP0@l9MczU-2kC_eWpET_D{={Z+*1x$)q)qu-ysuM-->C$C?uh(y$DV-b&p8 zeq_ER0aQ16tX-PYfm$EJjl^r3i9`nJJMTxRW4|8dXF|IW43J6VO{2Beh{otcaoYuja3cI zQ57~Gu^aQ;GL_Ic3Fg`l_YudYtRS0AYv9;)wYt7u^KSf-A*8Dj6x3?dLhBDitt#Jk zjt}P>u|WOKCmpQa&4%o@Z2%~8@Kzg-%$TRCwKeB=vc3pL$4?eY=1%uT6!PFmVz1;P z?g(-S47lb zI#&|`z8PK~k7*|lt@_CZAcq0uxp_o!=dPNE6U(Z|YbVY(RKD8cNa%+QFZFod&vaWJpQ- zP~QWgAxU;zfF%SNk5B8X^3VZ|HJsPU}wnAlR+b_jzhEX^N#>QLrP?Nt9d(BX%;k&^I zgjMn9){Axndf6lBTsYhY=D7qwY&Ig48TwiP`o7s<0IFsWA^`CpA=!!wJ-3iF1X~%B z*EQmaOP>;{t%F@M9^>h(lgN_Z8OD$9gJOOCv#hWae(+zj3;W`>rx29Cw<0taJ{LlD^4EbC~9mx`kT^*7)?}58(enBI3 z-A*?Q@;`nApw#vD+%4(3+G$#nJ{EvpPPQ=MRArN;7`XF0FyK-S7TNCzikd~%-StCS znu1sehS2gWUJkflq(=Z{4Ia)3#LNk?&f0%hRoE3`8YdEQ91CNmkemqFjxf|X2}Tx; z5mp`>T`VDRLclVtdvt=hdcoB1pl!LXz;*I+cgt6g(*bKRct zHGKppfW}~?uMZk5VtF9HjY%CC+&yFE4WXMfBpkWqm6YB;KF>eb1AR9)f&QQi+iBKU zfiBb{OW#e#R}Vi&Xsu4crB1=Jj|@Z~xx5Dt0$X#@li#`G$%h5)b9+a|xej}C&%Qzd zn>^6;w7B;5&|M1wQa#3#jP z%c(L@plfBjR4T^s0h0Ujc9ggLSTEWZ&)Qg@`llfq{_y;(9p?Gi+fW3Y72BcTfHm!q zs>JVr8IR?Wb#0GfrAY{hi3jS7b8&V3yV1aV*f5Eev3xIYq0b@7l2b`-tKSX=F9U4K5hJR#+xK~k&;W#)3 zIlp+PCOv4)lA7tb{iLbi>%u;N*7{MN)Zd6?4$NY^V2lg`E`)i)W+&3~1z|9Faws@B z7(v~AF-bsz*DcMD7(5xM_agBWAu%eBrQZyk5JYf#piAM-!q|bzTme{>7*hlspx?

qSCkBtD3{FgmuzT<^ml)NySCMfD4)9604p?Sp*;J z-p4!qltk1+Nq&i@>Oqerx}TW>L*fHjdXIU2px6)q(iQVSX7HlS4(jI|*=-auoM&Za zMRzX? zvxZ2qc$Z)b08P(qpO;;rXyBi>T)%9$WB2IyV|0lgzZ;wyr@I~Y-VGVrg2lLZBUELM zr_?*){-e0Ln%$O@gUJIB-m8AmaR5*sWI<0kdb!~0<{G}4a~mYJu}a;xOw31Zaj95> z^KoJe3U6Av-&P)_K{?K4Y@j(Z-0=m=41n;yhP}(~{MWCv3)Re}r#a$DDaFW0O~=VILlpJ z=$j_V2U}DDx8wm-LF|WFtJ(V;bF&u|?f(8-KKeec8N;=*5KB_Rix~mMQ3759gWNZ; zS$HNR(bg3w>q~Gg0JPRr0)u(^ZYo1!=a%THzd5c{h<16aK`8k7D{LWg-q2#}3D$~$ zGSk)|2n5fRxebdAWWzxt^!)J^j~5a5I&jKnkH`1u92c-?gs4NeO8bmn8hfhgnykff zY-Yj_(U~6zZSY>4H->_#`w-tyf+7P)XJ;j#Io#e>UIGA+Lof#9aF%atMwaHHM8@O= z`0qqj1$c^aQ!b!#y`U6&^7#@AOZcfAWQHW7cwpUf*d?(nTOk0KZV+?|fzq>&7{%hy z10G4#%tU9;`E@{n0)~h7+gT`xe5Kk#vq{2;@3%aKu z-Qsokj4@;_1qRfL-ft;+;SN28+58+h=a!2^__5GzKLJ@WkvSX#XO<7i%ywZz% zVe3rmTtl})_|BcZ=E_6AGTo+JZ~zjj6+R5+4$1d>E5NfFP$NB0omu;_x03Z-B3w7& zvAnr`Vtf0xTxWmC8bEEO_L3TiovPoEdeSz!~2H(jXsPULhZvOUd8;nuBSP?EIjN8F) zRe-$3^T2w#ETY!>!g&?sS`j~BzyH9CxBCdELwK={>*zlC41Z$8YK5ij*lU>Hj{h1% z;jy3ocq<(v6QCzMbY=J6iBs>mkNXHz_t;)m`Lc2Nn?BVXL>R93n?*Q%(@BM!?pm>S zaM?)<+5zM$W0bJ+1Z(B}R_`Nvi%+CV>y)5Ya&2)wtB2e!_%(}+oZlFQSM~J>`fhPRI z#(*;LtSvkcDCRZBb1?nuE(ZHJ^56=YJk9`KRh4Xa(2N%LCl;Ix_3;o~@qc3Pc0=N% zI76c3@_CorKVA$zI;R1I*Ey5zaER!~h70rGh0HCS4!~iNulryX)&SY>L5&=SN8G!2 zM^~3DWrA?n7gy`rG^7BA!R6*)Z$x3uAqOuTVP<<+&NIZf8rt$$+Mkg((5-I{#+Adb zPUKinRC>h0@yoFJE7D*sX?`>wSMwGq1iXy`3lX^)Mu9kF>-EE7q(T=Yja-1f{4qy? z!iF-VH%xkPJ(1e|vR`vgNmtVeUuIF{#*ty5ml=&{KlL(+7AlY>G2kn@dPwI zKwl^X*{<$!>il;YPfD+7e4GPi;9uWSW*Q(I+_Ub+R(=pnWSCO6mbizZ7ZN9x(ylt(u!IZ;Dv9gpmbe9jlFZ}zwG<)OE zE@&hJ*%Ob79Jd?}_fyH};A4i~gptS9e9a2rUEH7vzy z6ZwCc6>r*f=9?H;m-CHQtco)bfo6jse|R+bM>ul%wj8cT-D%Pd7+_3)O}uC2Z5b5& zSsFrmiLdr)sjTk!$sDo*R--1})e`*)$9~k}KwwdF!GgO9gX@|xXj9=g@}orS$!-9Y z$2?B$C(w(caVf8jRgeJpLD)*2CS|oDc?wqiyvXLLF~%Dkmahoh_3rOD09MQj5&()! zmiBPr1V_}jAAa{hkj~~k1lircsw<&`(MxHK7jIV3h%iqaIA@Bwy3N#NRjAAh5r8<^ zw>?9sCHNe0oDguF9r19WkTG}oRoqSn>oyz%wAce$&G1j}XZm;Ya4=9p4q?{-S(JnU z#|pgC?T635hW0Oi{kwUanxKF%cwQy6Op*%WX^A`ZS3m#itIcOZF`sckB|Ur(l5I#) z&I-7wc`25oaRV+W-93Y0WrYbl4WRPDjy`)R8xql40aEeH!t$i!LJntmDKIkM)<==T z#2ff~-dA7!@`k+DoBwYMBUy(Z47AIdq5CH?%q>u zRw=0bM7?n&0c!6EEL^U|*x3O}UiSuFmb?2ke z9(}P);uU2g+XU?fxbyFH%0X-(4B%zdsl^~j*PG=mB zz;_E;`|q9t-~fh?XluSO)2ETN9txkV>@82uMLFer5+!r|p6mq>J-WPG` z0?g~hb!gl=(lTb|L>~C)8B^Km#^7byI|4ne90uX)vZ9bkfUP35L^2}U;(ZF>RUWy| zj4Os&g()0RqHM(hGa^PH|0JgQ>Vig>6&*T$UiS*AL}{g(O7tBTgxTNlSnOV9u-HY+ zX)#7+zu;n>HbF`r@22RSbV!s4dF_<4)5Em5{D~*{18x{!YI5M=^bgi>IB}f311rUg zeW4I}PxrhoA^Y37fx4*WmssFb8;m-EmL})hnBXTTaOp$L=g0U~OC|{%K5Hq(y#EK7 zYn%_luKUApU;W2dY3vx8@q+5)4YcftW%;{~`y@%Oy1M%Rw}LfmCE9gnKnQXWgQCjx z)Q3qCH_f1e66<2PdDi6^f|Wd&|Hhcgo5h4#>R>p>@gX>}@;WWNKr#fHajSVZ=|WOq zVZ`{9(N*PB&|cWq+8@JpEPUsd`#wczgrU`eu<5l4jLXWKlA#fTueELEgPyb!)zL$i=?;!>s zwg{;v*SBxg_v3+J)6G$dz2k`5slm6$`#xd#Uw)wLSgL}Ao1ihT_6ZySKAyKqbf#M$ z{j@b6+9oL~pE51jmX~6rpO8tTVB0eu_Ka$+YMIMqO~E48eQ zcK`_jkX78V<=?_hI8`N$9E`Q?DOYjb|8MmterJ9Xibo5Z*VKzdeC=_7IAL)R@K)C0 zxyAlgj|V1No;!zYJ##(c%%6MG{;9F%p=>_BLgX)-P{A@~53vR(?yb1ambzY7`LVIz9l{1E^H)X}S9P&&Xe8DSp5(l+fGY~uNX0ie?B=D|aMd38wHRcu>e z!VR*~082C4(o9UCRirrmTxI+C1DF?~?jM2(ZS?BSjb^8KkFRQs%9MusL+akJZ)3x+ z6|#72RC;ux*_*>abDi1LN(dsXJI;umx*9jiu@H?mgH@=Fdvtm#xSLK*+IzXVPJdKg z*Z0gyxw?D@{|W@PTING*qi289H!i>E^Zhx&*^y>d9|#yPh=evmFBqWoI=m{}Q8>NP zFqu`+Ewj~G7xyL2oXe$Oy}`%0#D8G)4xrjZ>-}y@S=~T5_jhXy^6j}#|MuN*;N48U zJm+}Cy#&1dr>d=P1`m5CJTR3ZfKGpD4cA-|^V~5ujrrlS9(lRBQD%M4{qk=LXl3we z)Ns-UWgRF7cbOzf?6eI&JMenkmA}h`LRiUE}Pc7r_*k#^<_s;HD|m zjO~A1Bo8Qvh5Jrk?XB&+Yv3(X3sgbKmETDSFZB0DM4{tViCB|Q89Lz&a^QSQ0i-RC`|M?q3H0!Zw{o zuB##rIsLx8m_PMRSgyo>NAuk-Sojg^qAZ3ECj6>ccS?7*T_t#%uN*vs@~5Yyii$r# zi);`v%P}`Svqiu z%DiIj{3hHU+@*u}Wn;fhdMpWd?Wi$=S9Bz$RW*(FfrXmbpA48b;|>$DS6NrLZUvG# zCyW(PM{1RHig0t@8LRFOLF2@YpRVImC0nx*)P& zqiKCT3k~0d|1N$mfuZ9XW(1+}$ZDC*O4ntL$IfqICFCw}o6MMFD7?*fFUnhihnou( zctH%OfAl1r&C3zKK`q~VmOHlHSfPXzb8^&4xFh7W@Z_@VAe|ktxX0B9&wSP)Fj_e<}RqAepn-yT;m`W@H0tVA%mxepuD=*|uzA`Y9U!1P? zh3ncwpA%uJ0dGqYNK`~9_)3bkU+*5E>mVGtZ7*l?hpm$f4$M`lQg%>W2e19C&Wx)f zTk!DNa!UVa`-zEb?XUh|$LHXTCxFRm11`1|aGaz+?ll)kRp2$6YxmPIwSicN{}vK_ufZuFS1Y^-@m`~xwihZpnij|4wMbU* zKQeGk76`zM(-X6?+d3cyaT5<#@JQze`tMGl)BeGT#8u>kx1d3cxN8pgJv;ohK*5$= zU{*tDPYj`5@`1FakZ*3g1pb8lXghNzf_l-N8*rc8iA$yc5L#W?cA~Zj>ESi#jF|97 z^lbqQuhzi*ysblDaer?3=Q+u%gbfk+NxMc5r9F0QW+#Wde_Av9QsLUIw*&@=jBzTF zO+^5rYt*eF-f@o?)f^n(?Txf&p{0TT+jqjR>0FJimS_msR#WUh-DO0{A#f4wV<(;x zj-mL@>82vC4u~M_*MrNgose5A<%E&9)V&wjix+=)(72JfYQJqmd3+1@Vw7JgQ|{n4 z-*7N_I{zx9!?@*h)<`jX5w2X`)}BN6t8?QpzIWj@yxLm?7g2O(de3GSK_N_L2~@+y zFcv?XVlc$|CCcp@$ka8EsU5IrJJtR_AG}EIk}9Uk3a&(r*>%vOxj&$8(y!E90 zO@*xKQ}<_^rhQ8~N5?k!9PN7+aSD51+B&IX)rSe{dH{8CebUrJ>X0U9^UAqP?88Q> zYifUq%}a-oO!)UnRq+Ip89!C?CJAQ)sV0DPbNcpEz!BwCk#Ec=%Eg^$_SJ$lOgrT5sS zjZ>+wXdWZb#L=uF_zRLHO#i-3OOT=Ut$c+`^hC6GXVh@hWILO@*X(T@a9dzY$DDrt zHC84I8g(0JRId9>ad&iWD-CYd@5UBS}FG?93BOv1NTAi(jenK}PEA6|o!&$&B7Z}k4 zBT763aIxl99%$FHi|}gym4J;2Qv9dk?tOtV(Bc=s&>q7#a6R&Yz!&ysjF=cd1u+WS zgTIeEU&Xxqrfj+$utjHjz8E}9wHTY;{lVD?2WBvw6!?C|-o2J03~(%nU76FhCFIZt zP$HW>woJU4k)wymTTX%r3>YGwb=@acO&(w0(D({?nX@)K4*Z3K{c|?PI#+@-$Qrfb zF1>&cg-pA3G`fKq(}VH4Qv%R@(64~D=Cy}yeCAAX5cNU_U1q}E7xY%+{8UAV!6nJs! zzNQ;#s4orbjQ&K#5d&!%xe+o_JpD1uqloQxx5-8@5fr)31sMax9;A5 zR&^F=2ak)N1b|5p(`L~^?PvD#nx2az=4FgRZ2ch` z$sHyusl|NXPz$l$+>;W>p0u>LBu|C7<l zTF_<`Rk1E#A0K$OG{7J2!Bah2UECk^4;Lb}Vb!ZsTIca&ug>vL2VNrY$7# zy7yPJtbsl|QEw<4;K-En=7T zGw~J2J+UVM+|VS;h5C<>;5fkFk> z&)K1x3`mgMl4(+HcWIuaA6CTYBlNAkZxy_KAVsobtglFpS*1{6HedCo z!D7RJPSk277`LAVNn$1``ZoDE`@9Ensz@qDl75(+@l_wiRo9K;odypXU!YxN%KJ zWx-o6MfY~n6NV`-tD{AzdYdkx6}*ljU!|f8zDwS9G4&c+1oih);^Y(R1I&W zww`@WIQFsuB1 zV&8V6hN2QL6E&*mPcdBy<$^BF`!X*I6CEowE{#LLVsSvf-lslqI8=2e*L;Wex}n+6 ztjY?6+C_>H7qE_<(@A5GZA)D}(PZPen@Q3$_%9GDXjq&3FFn z7T0sAYV3R(H^j{4GrZ3G&#(9%TYPsOFKaF0-3lsA@jUT^#@JQVb%HCA>m$r}X8Xqw zGW^KF!Cdq*%H`(?gPlw>7Z2zzjExj8$t^xC;+*qmJo4dvF*4^?(2g8MDKgzRR?xHz z9J860r#+zwpagE~fj9~o*Ha(gd!R~FJKO=hxw z>yZ6vJwJ?YHgcPGhdO|)p)fp}43(Na_=5D{jA(Xz(EHK8hB-Lmit|Jdxby7yxS>nu zGADjz?D4})VUhNp0)l~h{oeuAERr@e(G*(`IACvr_GU z*~xp^PqkhiH?X33a7LlCxFQf{n(bdM8V@r+e1KBXilV4!Ciw`H&PIU+nGP^`86nys&_Ic4~mP(0lGfWaqu)EQ@CE z^U4(Wq&51_w`%IuHEsff<=e>mWoZGHlYIIw@_SG6tNTwW(D35H^-5a0W z23x4N<$YQ(#Jt#jN_7W%jb$t4!oRF1SqW(rLzfC}`=ZzDi|EiUKmaa_6E}%v#XPf{ z|KfR~eKI>)exr(NhCP$NEqd*42E%UB!x=g@;40BVL$wKS(@)WOem#pDxCFVvJbYVo zMVV3T?R>`~5h$qmo^=2FcB(2?4&VqnmDKM%J@XC%fF(oHJNC;A(Sp1cAS5!O?+%Iu zGCY}Izw2_{29FQlfWHLIY*^i#6QW1d6@UU0C)c8S`PD0Eb`a)ezX=)Hh!K(fC{OfN z5jbOV!9(x`v_tG(#2NW--8QqQYRw*2?+9@NOXaYFwj+i8y-ued=>Labw#EZCaQ4O9 zt*#`E8zJw^SLHL?a?2S7~lsIbqa&f0H9>#F58zGG_? z?Ehj6JPg?edWW_(`T8}Pe_qwDC`PEYW@z$AGV76wlH3NE)9_&L#Fu+zm07&GwxQt$8m!*Oa%xMj<{Aodi~^}Ul>X;pweY`mR+ zn17gql{fKb2&oYoy%h>x|4zdxDXhj7BVdZr#v@Z-BPY#pf*76(6Art~S^B&Lb{xsju}#|jPyB=d z-CrpR5%-Jb1PbO|uI!>_ce4bKiMfS&3dIx`L1N7NUI><&vG#-xTHIi9l7=9BbW ziDHSy&ZYzG>YY5SoF``pTZLjyg*kAPR)FigB#AgASGm=r+_{}N;rYUL@55i-f3d{D z6L_2Q`L%R}9+klgZ`aF)6t(k`b96C%-Kk78vrag?f#<9{HVj>@9D7z^PhuR$<2$6o z1&_fQ|KE=^BiY{OLl8CHs<4<3=SDb0sAk8ReJkVLF-S`fKTn=B6YWg)$QG1i#~I4| z0B({|9hIxLADj2U2Z9uXD`3;du{E^qfp`^qpaJm+eJSIjohWDj#1|$^t>aRO-<3wr zlMncccO85X$_u|w6b+cv4S`Eb-J95Rd8nnqwJU;nu*tK-Eqn`pr20A<27wWg zF~|*c5f~>4{)`DV^6kg?XP3SWF?|z|3eOqo4O>0@v7sb9%u*Z@4cj*nY0b6)3htFO zTKK${SNtMk_3!W{g@PIUGhIiiVPSUcuCgV;;zF~F!b;`mTOY%e}>J4!Ik^153s z)c$vx;?L=(va1hT4(tm$n zwb?a2a)6c%5X~ed;lT=w!yrRPfPv%0 zF%#Yd`0^E#!-_Qz(eVACS8VybcVp3DKbyVk(Rp}Ep`zS zm-ITvkbbyvHj3jKWMDdP^l+}xqFfTmo7Sk_;5&K$&OAs+1D>D?gq<(VP=rY!4LeeU zZA#wN0$NvwqpR+|D-tbyr2UvIY+Z46;2~y53r{w?>E}bjV{lj&FM;)xm#{g|?^!Vg#fYrbrcFmDzQ@@s9{Je_( zo-(FT65&?wdfAIE*=%P-w}K8B67u`&%XVtt3P@lADLp@~Ack&ei;^^jRmHfS+uwp= zJJsv~F4b+EMz5Kf{Y!gUmCVzi1%Il{LU?Ep^XfIy4+67)rWjL7~ zc?3^Zu9n>lKK(TL$+WWcJ_Dh9Y^ zJMVM4tagmxsOqz%f)GejXQjGgU ztq|w^51_WSh2-f#5_OmoeGrT_RiLA8JkmtX#|8;~Qo?kG)UxJp!5UW#bf|TtW_bJ+ z>GcvM9P^>`AdeqUSB2Al;|6h%M8fq*z}!YnVqm<;1qZ+&Jyny+HC5o!*e~1}tKx>q(hUovleEKJ~EwBnZ_FOOHEY?d@6O97ad{xPW zz9Wz@16Gt9JC=P#(HPsTBsNkm0@0;U_q@@r0sUrzb7c-BeV0G4YVBbH4=Bz)*Hg($ za{50HWY9v3?jbexvIm}oLXkO;_`P@}pfRro(tM!z?&IB*LZ1WplUzO#Epl$P*eK<% zK#T@Jj*1B@Iw-l>b9%m#YX01L0Uy(vF&`J(I)V`*Z`q=#Z}{M0J#{y# z=k8Gvi}ToRu0jm@(@-}Vb3+OwMv?}=~0s|NKH3tR9TN#P&W1J!hZ z*tG!sX%XeVY4P?fO59`__f+{B&)%nHL_zq9M|x!8bV1|#Bf#R zDKch~@(;O&M4t>rcqyMiSI|J|8_-uBj5inq@zL>z2KGNJ@0 zqokO?^4q~!*-|x#2InRcy(Noboi^Mk@UcTV5v*wl1+|xOhESyR-305g6Qp?QGnWio z;}h%(vc&{T5i8;!6dN}&yN@~Eq96yfblUxX;r~((ey>IrY%r!!irBNmdIFW{`>!0_ z1`ilYv6L;|#DSm#%)o#Qq%)Sd*{eJRBciA0>>39NMQzBd^pG9m{jh85{t#Y0mAQck zmrFu3_@B^aeJEA{__U;+8bUwsg5{BoWMk;h?dSF4&!?;@STHUrT=2Y} zR1Hv0l2Ax*5;r%kFvm&lKy}`qYtE630filL`*yZqY1qEk98J~Ch~zDn_}|cy?fKP+ zqX4$ww{swXp^0~x*Wnev>1I4S@$My5%NZ))d`Q=^EUV}4V?Kn?rYEFRI@31zuo}3E zu;v>qiSt!+bx(X{?i|k`%Hh4NL${=~<@n)owJ-r2KM-iOuIg3{d`Y=#D z+))~m_%P(ghhJ{ ziz5Qr?;?-FD>so;<3B0A`YSGHqzXwFuSUq^@f)sahcRB1k{7F+fq^j1-!E~h`l~r< zLxiMML(WW8;_sg#zVDnWgt=Eu^BigrY6dRm26og!+MOL9iBVrb%6{A3_vbp zFgNCZXQy>6BRtk-jvkeVi}D~Ix}-qg zWx}(qsc(LlE^ko@4Dgc1Ew6*WLo;XmZtSC>QWb2)PW3;~$N%QMp9jg3@b|+0E{+HP zSp)fd`X%|+ttpr#h;0>2n;WcmQAp7t-S%7}GXImXBPOiuNTqRVH3}k9^3Lt=d>A@# z$cr-8x088sx?85GFp9u}NA}4f&jiq=4Ug`Z0RuW~{CpLW`pO4$?8TOz!! zhy8p-H@M}~aCP&);>NlIsWjk~vd+Gifa`Ts*_#?O=6z5PvoIB4P?ZI-QmA(8W;}-E zFr%dK5DGB&8nA`Y~5KIHDI++G0DrQMx1g0L(aC6qUU zK2c8%EQqc{ATun)4m-Fzj8;;g8VNVY>!rfs>dZ~Ka4@O1D>Qu;tE%V@#kvnDT_(M2 z>;xPW0SzDMgIk7kOk2U{ZE?Z3cug+G{QH01^fJ3!b@CsB0 zd>e#a`X!<;?LK;RANwMrjbdd$YjYdus$N?#san9TcgZ#4&wRKTCN+wYGrCVV?!on^ zg7<%FLc@e`e*;kN+$bQ`E zUDSvN0=77a>4Bew~sH;p9zJ(!N2zd zbU9I-j%s#)rZY^#M?{Q+f1uAY9gZWRd;$wWwnv>2;=348vs6f#e&SEp2eSa+R3Y-c z075PRC*L7}OJz#XM%0EgK@hAU5ZJO*HzPf)UY=Uv_gVNr^7xjQF&X+vSMKlnpoCvZ z_{6(%4?EIdY5|C_(VP=_L<~j_Qa6M5rN2aie$idTV%wnR629Z8s^DOZi|d^S%O|5Y z5Q&V8T+a2iGb41@AX4|Y+)IZ_V6&~FNi!F<#|zUbUJ5qGiP-odi~9}bw`c#mox?1D zAquEk#l%?^)xzYK;mpqa3geG$s{QgSfStA5no`!*x@Y_;fXTJQF854uJir6_42jB3 zMQ0$tp$p_S&8D8T&)vN=NpJo}KJ&M^CqR&4HaPo;7Cm_g+!D?g0)AmzdfK0mU8ddk z-PoOQz58+Z+;?C3NVz%oe{{j(#KexI+?kpDm$SPc_K?9g~tk<-)PpKRO$2D4!9 zyHw#~-oW1v&2vrJL40l#x*hi0v?pT?4cp>nQuA|(#{!u6-U1rvW0Y+vxPM(q_n_GG z{E`H9KjcCCc|jiykot%zaq8YQwrqb-_iGIbPuSq!<1?4_W3RQxZV|+Mh*O;=Gd9m{ zDoX4Y=xK>EZf1}xtcLnkTt#76_lk)OZnbJC2cay&Hj^SCb-W=2yDgWER`-a$&g)Q1 zH3tz-WLIXOO2v)g3Sv+`$^IP1Wl)1ln;>=f45Q506H; z8H9&~3GcZlh z{AKCYiI|e1%>Oj(sF_onOAisPnT2RgaI}j^A0)7-CA#c?OD!fc75DXb#%=W_d*$WPwgA!RWchX4u3AWHcM19La@d`2()WMF{C3@CyUcJ03ZBG z?}R-gp_E(ychiYJMYr~G?M2$AsY6xXj$Lk@?Q>J7*1iI^)c)qmR*&+ueMAy^E*h9z z!7d1m63@MbrkeKw7~fUBrLGWucItRz2yS|F@bmR6SD@Gf1e2(fv{C6^McAVU2K|4< zcpdo+zng>`BY`4`MVCx&F(S>@B>#NrX3brYH~^&RYJ35gnIWX;b+=SZaRm+YSlj|= zA_A6NP9BtLnVCb3io*0yC`ts)8mO1Xr9{%V0EkhIOfrf{i#|{<0HHCqu0wm3q?A$C zXOV+o7S7@b6G9;?Pw5D6%gHyN*U8mU-GJ(`bzLUWF{$+ny{Xw*9f?C9x>)n}c#Zk7 zZgaOsY{~?AufE;>*5a%6iReDkB%e*Otv9+l5gz{CgIShkQa(p)TblW5YFya30pqHn zGf_{0it&Uf#9T6ssA%j{o|{d!xuwN<#gM~uIIM7p8U5I!MSm%uf=NnMe|tgbh3>r& z-QK}5>qF$BKWNPx8JTKboVlOsWOuPcA_2FtyD7RCuDSpG0ltP>mf5q20BILt(~$&r z$sh+CG&lrO4-7gV+}<}&N5~2 z%cv46E^3x}-ntVNANHTa_m+|0gI`~lVyuS8IUCz<%SbBdH_a0~x%8xRQnbI>ZRQ>q z=b)3hQpk_+i$&UAXgz13mRmLe{ZK=AZibD(_(FFGT&O4N$<(r(Uv3gUbTuP=)+No$ za*~01`N8;?_I2g55g=^GYgPUojC%9u`#9&v?u%gr!3fVc@cS8Ixu@wKE?0b_kl~}B zZo-ZZVDbGnkfhQJ%vX)$q65;<6QcXvwMV+7_?Pl);jT8FWUVq!Izzpm)@Xtc;F8iu zM}dK{>A_>4fO@}UV@;ZQ5C(NME>YgjfBp+0O+mrq<*jk&iAdwpm!*y79p}1oDJ;=f%PmK&c{w+)eyyWX>Y2+EEw~mv z+iyUh@?IKNe&?5lC0$4M4Z9Zi_HT~}AT6T(i;T~Rs9kAT2SnVfn@_pBu3GlMe%Z0o z-pSd|I=|)mdK4N)9rawt752132@Ex{Z^GT9pf^~2J3|kUn*T)@y!O_u_UUScTgm#P z)|X5B)foj=z}sByOzmqe?}>K|hWA%s-u=mh z6!NY2Ny>?84HJF=gMdf03gJAiH>ro{u!y=_;c>SMkRNzNIC3M-H5G|1$(}aKakR(q z86+s&7o4jaXNNTnc_K&aDn>RIgpZ#Dz+fcE8yY> zShGCJr`6-^#sE4Du^7|Tx-7ZBqV-epg9I3k$Kv!vGqWzD@ zMbuv@&D1{v)k?inK1OM)I#g!M+e`kB~yc_)(vSIi@>>)*|lL!N#R_mq2kp z>$#q+AUZ8^Wt|QqfumgQbYM?Xd*JvCckP7kG}I?n;$Mo6n=)@hhF_i1WSMB3t6;_Iddl#CJ4pUmO%0Maq zxbqCvV#K>-6rWgqt=;+EC5-~hppHE35%DwgpM+R$%vDlB@|B;Ik5i~_<62g=#CEW# zIq3+`i>$v6P=)P`^=5k782P|jFnJ9G`w-F9n~9XN|TY|9k*2ah8Bi}_FdChZ%M{g*}v5&!Um)4{H zv%5f4pGw@O>%a~)5OLM`DX>2O(HHCW(;iOjQc&$>M0<%iV+e=XdC z)*rw62)saQV!3;MY@hYpTRDWPj+Ho1Nc;3LAsVcXR>n8G>rD<}_euH8(c~UD>}7=) zcjos+wk8}DaIEZRM8YOKP-Y7uZ!J@v)l_z~P~h(e_?;q-3CyE_+|`^CjyfO3$Dj`o zq-Pt6um!mLh~U*l!n?V-|Lx-xT<)l53!00Q9y1bgJV;3=`RDZ+l3QgKf!0r~CBM82 zi_PF%K_g2L0*ob1`CGi#6LRaHSz2IBW$pCx;apg@KPfN=%H-n> z=z!kqiGbyLeJj2bAbA>uup;5Ok(3S*fsb9{iV!$0ZSev!b!Z&L?@sD$!4ag zleR4CRX;-q5y4qcm|VQ1gzyIUH7H>3DcSYU8u7(E>RHKfHWWpmWR&#aP4zFA5QsZ3 zZ$dycFp%dzXUqfBqb+QtT6H1qpVJ z@q(Df5?FPy znsk{r0dxbi#!C|FLC37=HWTe`Yj1GNI}kp!@vIlhqKM%GKD>0mOgxzDoph3e9mx`C zrKZzHFl%^cs>eP7O9{N)0<{Ur9nUb|5lEXY#|&>)>eM=XaKFq5EBh!(r|!5{WslwT ziGIq~6`)p8nT9iciVjAK%Zwp#vGMvU#O9PRbffYnzQ*VGCe&GAT0-mUkCKs_0(Q4` zhng=G-of9DdPv|ABFetRi`IK?J_>?W$7g-z@_05Vx{G)|;SU3Vgw@eaEcT0IL&cH0 z87z6b;RRIlKjom`@GcEElElH<)$&~XIu^`=7P?|}74uC=_4mDJwOoo{f3&+sVhg3l zS;y^I;+C~Yg{}8BW*w3qAr)hMp zeIS;&=`28E1h4-6x7Iol#1iCQ<{UM70hDA{zdbal`0ih+%8~*>J47|mzC9pKu zPsEhHp$PvXJTZ}`4Z1Qct6%B7HJI!bG+p%ypH0VK`CikrSAPGO)$VaHkLK!J7zPb{ z!ht@8IG^+jueK%2cGKo_l+8bl0p3S3+E~M3J2OghkhP=(k^51*m~fpmN;7Sjt3*>3 zcD9mXlVjy4?MOGXi-5G)kaSG5WuAO9;{G>MOQC?U7lV(GB8yjV*c&$fCwZ@F zv84necW9FjE!iY7Wq~KK*u=ze zoZzDJTl83XN@?2lhVL zokTS8iAk}_OnonOM}B3#6Axp$47Ar)Ass4V z*#jFQZI$is*Gu-jJ=mEN>N>Ki@B6CNrycV64mO!u1{j0V~tq%wQ>`xTH=mr zvf>C)zne(IP@ICf>C45RR|jFwD?Vx_1w0m1V-xEw@u}7eO!6-9BTJ~jRd(CQFQjj` z^qqFhApno!<0XEOqKL+dHHs3Z`F|#9vO{kHP7I%U`(*_!l84wXe8Q&Ml8}Nz5|UulGNCVZr3`#> z^<%k@CBKk;YwiSgHAJ5eRs&^SIOPfnB!YeG_Edv%0`{Gxnc>?GsQ9c*Hr+vG92Z42 zl<(zF#vk~I0x1x@lZ?5c1Y-pmm$rdN2H0<3HeD8x-UbPYD!R>%Bm8Pad5mGN)!PdW zA_*iDOPNfvZNy*54Q)bXTyiUMGjM%yq&Ix+xP{~w&V?RE1v=WEUNa#4&3+(iP}8fg z=+ZKU0(ptcuILWI1AabcMq&ih@1Dw)Jd#M*QI1e(cWTQ;!%xG9LCQNpUSNpSh1-=r01<$h zgWo+-7>@zk8H$6BBI*Mn2K(@h*USP3&XVwvI&Jg0oeSo`0qTK-3iNjtu#F`uPSDnU z)e8|yl{ja0hlt$64&(;=nK|3|tx0HwR6_4YJ`VCylg$DslTQ$#9Dyc&|IA|@cXzb&L{;d1i)t&bJ&-QbrM zMgJcT;(ijk9aUkN@ZzWDw#BFZ226F9XUQLApTWcVh!}zBM!p`!5xW7 zd_!q6Teu+f6gL7x#tE$_cm5I=K zA1DBdzk5OY7e@mjYWX@8n!hTZB~10h2ktX*SV!?Yl@9uVHDWUukfrN*jmeB+U{SMI zaP~3gAQnH`@#D6<{e*XS-km;0nF?=y-BkIfdMuJ>X%{*Q%4BeLYw@50-bL)qfOE|d z(Kts))bG+dl=l_e0w5C$tc6I6ekbIN`$^+*h>|syf^a@(poZfwie!u~-vs-397-$e zcUx_SA1}$mp4f~n&Y*zR&L#|9TZ)G2{^Evs7`#4)Pv`se93eS^_y<7HK1&1D9Gv{A z3mpIQqMs0kci6aWap?xaqxChafJ(vv3GXJBDYG zPZbm;80VDiO73yFZNLvZAOhS}sr1GA(5Veo7@*wwe5xh-hm8>kCyAsseFK(dywFvtmxlqc46*S? zz8;j$EbCnA6 zn-{+;TorgX|AY4=ZkGXhhy>_Pgw^pf(Ka_T&Uy-gYEm}ecXuE+*l2d}xvRUE=&!d4 zzWdMMx@)o)zy_Xv_Pn)B>RWr`uVNm9JTcDtl_1dQXJC$0387Jwx(P$Lanom;SZ0)y zPZ9t9i-`}3Y~XBsCnG<0Z)eHm&Z~zc<>Xo2s`CleGXiBMQ$0~(27cuQ8KMhC%@oZJ z>?=_dOJ`uA1o!VDx&NmnFBlhE?2LW;qUGGIu>Gybb*=O7w4#oJS)+dbY&Y0W=bAY; zbsIvlXVd7gMLz!ZR7*Hv7Ct62dtl(WX}XCq7*{Ort={ zwyJ|Ov=BRqi9XIN>#*K|!eBuO5;!bBnD%gCe2-Hp9OB@6UKbXxYNwaFH=r;WX-luJ zJpEC5vF_8X)BVWE=cMDO4wEBgEbY}1AzlLmu-QMRE4#CQj zlGYixnY4_R`e#iPD1`Kl%aE9Iw&PRw4Ob((PH0RX1 zHm}9dnP-%{wfALXYCJ%b2_$R2{8&=0Ak;Sez2{?>K{FfsW~uhUenQWpYTM@5AE&-D zO%`VkddhOPwKXPt5X)RvWmcf8sZZOR+dKv@U;Z%j>j+-v`f6*HgL^1f3b`(SS1#Cg zx7AaD!=AX%fm}Cawq;7}pZ*>>@}cTRzCj+dl>}xwzH^>Lr2p0}i?6i>Q6@my(;NKrYV zMZvm7$5@S@oP%REkF|Bgm|+ZkG?`CnPGFy zP?-DOI`VVQ=*gtb&j$Ry_1`!qfK+Jr?l5V8jGuu!*e)238+4Q>_btF{q;@)|8Nw;vM*{$}G68%RI9=ufB~Ct|WaMisn_TN~&&rk7gyTs8J&ekPU#2=VC$BT-|`~_p)#)7QoVM z{*c_FI|MMbwnF^^a_uQxrs!wx=0ne0GVL%>U*_nubT1ZXU!1vI%`LMwn-wLc+u?vu zErN^&zhy@2$(*HVd0bMov&hIhtFIN%>LTX2WyuP9zgvRkM$jpE1bWtpK=exc;@isDi@INEO}-uQbz}2k`XIAJBA%g1duXhJo83{xXl)lS^JQ3 zr3+T%yLP*quA=TR1T~5`Ra}V2K@lyNGuzy)iQbOTC0#kLwlS`Lzo6iU!onjq?eFA> zSqCtYU}4(4(oBpp+f-lN41+VXps_a$x|J}UXSw(|+476prV0yJ)FU{SD> zI&$tO>X=v^#otdsDUTpP+40YY8dynjdB1v7d_i+x$&pOf0nKNz(3KYyQf$2dFY50X zC2gh1m;E`tPl@5k4LMHM`zD8+bBSJ-#I$!`n9%47or+kAaV=F(OYz=LeYQj?_Uio7&X^T^*j^ z@b+%ZuxhG*_sQ~JO zgNXIQsb?#T+gZA!TZn$Q62A9U>+C)IQ!A8pvKJ&8nOQh0%?m{3xKP}x7L#V__MYxi zv!0QK6@l2M7*o@-*Ug_xGW9ZP(fb3teWqw*l)Ey^o*ZE9@31{_2d1h8bthb;8`^D_ z`7(31^Krw<_8h)*ovPsh%gc8JC?eXQD&sp-hfrX=yg&?YHx69#z-Y zmNhioLL2|lwEHNdpoypGBzRvSHFGXpm}}8yL10jQBwzxQU4@mET=;vdYWar!=ZEC? zqZ96>XITGQ@$IP8fmYz+sy=bGXZ{0a36pz|43P3 zwr;vfuJ>`dfMC)VXJaIpSvD5SksenS4nAR7CFBDhzju~V%S6lMQC2=aJ~CnqZLPwH zLsnnzWstkO9BstXERPF_<%>&LtVxz$>abz!)Op|GVUuvPVJB4tQydk6%>dPZYEbV4 zr8_AMju!yrvPm}Q99S)XpVs1Q2=Xh#4wzH=N3}N`@;BBdyC{6iXIb^<{W zBel*R;|B&q0;1~V%shb+Zj9?Ks|D1eIJZA00NVflhB!=F2@b8>Y&eJcDVrD08HWks zm1jj5DKUKM+f|AEa|IXJIsv_kGxG>~44iVx7VL+JctFM!6Oe+0G(ITM@U&)8B;`Or z>?G$IsxeH5VuOlFI9n~SiJo(;Df41fGvLRH!=Tv5kPELoBpLT)K9?>NOhCF`2b{hM zBR`Jy=r6CqO>8u#h}#e8{vy)YB05rApyPQg=?X*;YG&{hQkMF#K10E9$wvWS_+;Ka=rBtOMR5f`Gas|$F) z&7nTRv}#xHAKaKvnea?ZJSk6g?1f3QY;Ixiwns3sL~!$zL**&HsO`iWh=MK(|3V^IGKvp)ZYvxK!PMTrn^P)rmg^H z>+cZN$%x&;^Yj(NN8Z?!imR>mYWvF-f_XOO6`}A+nUQcS&uds6b>S`WVQT0dULSlh);%r+p(=m zl@NvfnHGQ32Wm2&ZC@`6a;`^XuP&vu_%uEFh^o60xq8vlUMrGTotosNZgIgNujxIV z5OQKy)UR(Zu8$4WhIHn&+$>QhI6U0P7TAx0@<;8gV<)|u1~3$vm+VY3)D>G_>^BEK ztg`Oan(i^BMZpt5Mi%A<6l=#Nmg{}Ws(^G3II`&aeAa*Y^bN-V(Owp&tO@obPES}{ z`yj5)wDt;ZCa76TO1I{tdXCmY-N#N8@9olp&=uoRaA0M{tNh5VKbC3FGE&3c6Qb@- zE?gebO>qW>$9()fa9jIp% z8+^0a-G&Ddxzi|%{!zFTM`=Ov4A%1g`f>s9++$Z=e|fC<&@Y=jU~%yVrm3sOUHQTj zK(VwqVOzxLy4K>#3`DML4`u+o&n|`P-U$d|4gwP5)jl8>^@7OkG~z(I$4x_|X)+Nw zaX)Tq1+X-s$%Y2q1A(HPh@GCwM2kdv=lf)ss-o_lJ5+?ypm{s^VYiH0krriv6`7Xex<1(>IY+4D2egs`Cr|PSUeQ4 zkDWm1W95iV6{iEa%Hlkm8laSm=qwRoiV&hV%xqNf@Kq2wgUEP+Ce)*?t?gZKum{ir z@P;{z!~xyqC4{$VUUe>e_wH1QfbNxoZuB8L0Q*(%>;8b_ts`dlODllS%WX69LpZaW z^ou;XO)UG$g%kfQ>Re>VU6-U*_8~DwJ}kd~d89u#>Y2jWk2?+IA6RO*(;&v)U1XIL zYYTP>+_iGo?5q_E8_BCfl9JIeF)s>28bX|=E6hJ{XTVh-k+n39K4JNhs9hw1CW^>_ zLV!)poLtIq^>PXFhKo%x67^caE{g!m!MX9AmPKgS*%}Y zVWN{9#qE5iYpK?@Y?t=pmrp=hssrR{U$s<^10X)Vsq?6M|6s7GH;9d>#5&oh{EmKT zmhqykFu?cPI1O-WzeKb|h+MBgt9#rA7f28&jiSBSd{d&IrATazH?;4aEmsdkLAO~Y z)!I9g56BF zcUrfU0@<|sFK5I^{|PY`2)fP)E;x+)pHuJKyWX>R=h_j>Dj-?lZ2iEjmY-|Jy7fZRzg7}RP z)8J})3-ADhd+i1II&(zm{qZPvTKf)Fk4e$Nf+%r_N4s$nz6Chux|&TAbI6lc83>;zeQ`+Ax<#qm-9z8CuJOJ(A0BBlRa>j;z*V? zgEk{UlOKl=LlFvW5ewxw=@#29FyrVW=92{rWl7mxB2&2vF?1+bTJ2?7@7q~ z?KsM#-%^ak?c28({UlRbM$e0isxMFK&mt$9vXG#Erg?M@ae4o#x-IgNwd45{>9;1t z3-nH_^2;3~R`i3_XuC5iU6SIWf4es5`}n)iIk&yU-s!-tgvDsJbC+doZ*Y&C7tPDf z-~QL<-_D!SSZ`?-pq{FNsUVdoc=@Rj`GF z%RXTEc7v`FdUXN$^%e@~eSlukxXoxUkedN{u}j2f8=`!$Kq+vXEr;|rhl`HHM)m=# z$?Y6zuLuNACVz1LT|b}3 zy`i)k(;*OGF_|YZFIk%VJ?Yj2Esvapsb_$f&xD(+eQCC@mgRTpm~zG&qWO@g7Z;Mz zWY@E~f9w-9wzCRPkzB6}Tr8v3R_}9ZhGfPfG9wzM9Z;iv8q4w#o4#hzXy(TRp&~hKAz#1ENWip< z2~vUu1bi&_k4-{;<6jK90~dB}m2yuEaB)+OO#Te&=Jw7o%4=PGFERy&oC!TKT6{&D zXA^$5b$?NpqTJQg?kl5z!9;@gnxO_TmU3pslPw`?n3xL+HZ8P=TM)$`3vq1 zW+2@^^iIe7C10(OPMZy&J;nomnT-C7Z2QsCcy2)^;&lUk^oQ^v#^ZIZ}9+B~ss>0K@=OwZ5v} zz1+Mr>A@;W>Z{hBzyO~Y6wK!Jpd$3WJ&aA9eTarR9g_YC6{s$M5X7z;P{EN3k)uk+ z5KES21H16vsbt3@D=?jPrArn8FsP1;i_0@rKCR{?_3RcSC{knrEC*qKmimCRGaTj= zv!hcTW1P96`hmVP+oJaOIN9uu37Zx7G%wRb+B`O&p8n}bP51T4R^NLsboYNa)oySi zjpo!nwKjvSiYqdiZFatG5BP8HNK(D&um09Eml9ciSB&==gL9d_4cD z!=$5gA~}0Rd7S0&H61fs@t9hrm@Z2RmY0$Z&Lj3L8@?{1t8kG7zZn>>8HTq|V4Z$v zHW;P5Q8+&WjdW8?0U8z+G#f5(H|ggLSgaor0?LT3Yqt#Y4-Vs%$UcPt$tqVE4z zY~X}*Wf$ICclrAc0*;owT;t``(8thS~&b!IcsN3OfYhCPl@fR<9cqUVicgk+^he}XLaz{B5CKsn z4lTBpOW1rVa;=cn+AsZ@o0zEyF)ND)TEM3ygqdvAPK!NKjw*d{ryT7CRpn0oNfh%F z-QqXf8|zd&G^l#QQ1sFS70MnV-8*H}l8c||Bxc%M3T@=`+O$jx=9=l&odGu*nJW1_ zst7Mwx;h)U6^^nfqMIA}nDeZw@yIPP7~`*a3y{Gdg2)6yhP;(&Xl>Hfb*#H+<0&a0 zqInHiKp&jWwrC}sQB5}I2|zL*I${IZ&9oj` zKP!dg^#D-L00%9Ii07a!?t<%-0Ebk=5J;Iw1Q_AsE4e5Df<(t?#h!W(lN;g^0`}P( zAyYYsc-E)a>{A128Rb;KBJp$sLDs9;uR;A!tPn^mQ!>kS#b@g-na|V+mcPIBLSga8 zGX||gl5`p9R2*5%)MX7rI7Ra~VmM=j`Wjz@PFhTEg0Rd-tB z59+1`{CK4=QgS)+o!sd=uFVJ>zD3*B*=eatTcXzzgwjiU$xpi?H$X&e`rAo!M9fKA z`$0nFfxhEIPCrkw;K^~C>&CjT#EN6lf+Ht&4Arp{_riY+EYrA*T35$Y1Si!0w;HtwR#pWpebJX zK-z!+=w67+@^IF~@qqNR{WsQs-sp=@NOsQ#2!3*a>ry~kR+dUtJ1QjP4~b8{M87u& zVg+A`4Pc@ulRyNuM7$DZ({RzYrc%~k@L*5kY zd4S@{Pjk)c{Qw&8h1j?d??Jh|VCMn+6a!qtbtCbmpT1-St51Hv*O}dACD5`vrfPT|(r)vMH9pjoF%Qs*RV| zQO!d3#Y@1j?_2Dlmb`7ff=xNcZ;SNrO+AU_Fo#w5Ifu8igu6~vERICpC>PEvH=nc5 z>u1xlzL!7J$9LkyebwG>VL_<8V*B=e{fA*q>vCm_yACSmVG$V?p`Xtqm2v=;>ZpYC zla)>$Gbp|QWe9unr#^SPdJnAw+;*RL-Jk3#05b=NFXenBF*=+id2P1Q9H>sq0d$jo zulTIuG|6dgRGS4{ylY5rkzN7H{SftY9}uj2xVect&X*u2cf`IPV%ueJKHsKa4u)Ol z!jV$+OzOQyJ)wGkq7b+>%8)erR-76h3bm{i#;XpflFGCpj9DoM4$t3w!A$jSIAeju zb7SITUSBVpkIMq7aIN}O;qPxftxr10Og+4(oCUT z8(~#ZcA)%qnmM&Sxc4c50>~pHiSY9EwH2L>^|dw^{7h&OA#NY?y3*!yMG4PjVOPdF zvQy@>xDkCK(rI90Om=>R<;sH*>8ROC?Oj4z54SB#8(PZNOLJQ+)<5d$lEUD4FZ2Q& z7E^iwZ1(uJ*gk=J?-XrI8V9z5KP8$7LnkRTM>As7TV- z(Wa`kklRwqP&l={R~t+Jb`VLf)DA$VcbVg!aOj$vBzG+gQ}<0yI*UDAbD3mOFNArX zIAOEf{lkzC>(ghj>qMIh^Bv^_rBD`;MCKkvVmjT0&SVrs)laUt`c}1P=-3d_E*GPfKoq$4&3Bmk+;ExpB~J$wIX#lhHbF@?axmwa z_OwjT%ujTpV7h1@aBcW#FFw<*lh|JT@h8Z=@T%+HnC%WqIp{1*sLSrv5sC%_j6TV1 zmuvUZP4L;B5yQ0D>M_ACI~{Zuwr`&~NqnJ%+4jf2@TF?~K47o#T$wB?@((|MXm_7V zih~M%5S3lDHcswiDEj1Y9c%-vA!RWVb8$izKd(8BD22P1R?OA(Ec-Kcu^k$y6Kn=0ZAQ0=_>x+1woXhuL77_oo+(822@mf+k2aDWT^ z2$$AdP$5>UuF_AJBC*jq!R{Ad5BZdv!*9!giLPFs{APg9^(VJ#h){qn; z(rZL#NGU-;)v8aI+wl&RNmJa=3Chg_4_{ov2)@uUcWqk5YS7nnIz)d=p|ffi)HWAAy@7*IN9M9Pd&4?c>L-K3LN^Td5XwZjL0e6|my*fF;r1e@9Py02tTW z8N{lS`bZ}VuH^+@cr~Z)Yw4k=~sHXi21DW5%DQXtGge~e0O~yIP!^A}JiKz>( zWSXy*a%-@p6fSzQEH1=&QIm5yYZbI?c`bYP5gllk?X?T&#nFd*!aZL+?EcF;=T9V@ zB1U1o@2WYu+toMzfkicc5-kY7eKqnX!=^O6XolasTvF_yw%t_4r1bjjx zGkZ|3nY!l3zXMjyeR0io?$UXM{1AAS5Po_UVO{oQ_NzC@Tx>^b`1<5ccLZUBnITA9 zH#eO|9D)iH(M!91S#zn|)n@6A`DlmML54B$sIcuIR+IRxr1y(@G`3HrV9wm;&c$Vgf!wCjy_}% z3eZbn8WdB0&=%mkPcEZ}G%17ks{&dYd4UwgjTKUgIJXNqx{7ZMWKrn#tP&ai#%QAP zo@%kR>E2argr9x7&;dW+^v;e1V5_t^S@e+zqspE1#dlpm#SY^!;3zbW5a@oIU`J;Q z+93*9ryzzA4%6=>YN8mJ)?DUK08a>IhCwjfY>O~?a$@q&d{fj?#Z->_$ztBhoiv2V z>+mVOt-MaeZ;z+~`Yh5fOTpdn*bZ4gS+cjhraK(tVVX*{3BWRP8U{f_8N}}8f}g=x zeLxx_^m4Z5qUOtDvIhR)vpP2ctPu6`1>rJ~sQ@_v`B)OU1Wi+beR|JlTsO)Y_i_T* z7bTu;QGSSVRihW|!(YHTeobuZ7r2HF`PagzBgB|nbU$~AhntYVIli%NFs9ZA^wUMh z5kYtjo&eoFlSQ@oB;1+jpvO+SJ(%55-N8Io_pmdf;FmYCV5{D#39&Q=fHfdq!JDU& zln09YU(AcYy~l=GsZ4mV?!YHveha;Odp(47TG+LgzjT_f4~s?)DRRRj zGFAN?JqtKMvY^ERb}C6Z3e>01WAD*;dzc1(tA!Bi?!x_Cnmbyz-S&0&YH*4RX~TK= zPF|mF*L=ENO_Y9f4rJOG;gYf;rA79Nvgkfg#nfIK@AytzD^hk?9D10_;A#qjBZCk% z6O(LNgK$W6-G@|Gv{K^C4-IIr4Hs0nc=0aV&CysvxXS4~(VCfvKfo_IL+KDe{9q*h zqfNHkdKM&YZaA$!W;0YrW~p_z%9i4Su(neOw*$4;8$_vTWo9=FMGxc;Lhhr2R(1!H zh+@mJL&;s(D)WqViRtQh$tI}f!gvqIGkKjs3-?=Y3g%h$OI7Ia0ye)};GaAg|F@70 zFC4pQipd(CU^$Hk-za~tpKYiK0UTza>gVC1@9!cieCx!-*l{_U zoFk=(a&t+{yuI5JQmx^S)cDaYUGFwa1ip6xzujSwRex;Fh}0~XK!d?~GB&}8ZaAIu%4;j2x+p9fKFutpMW9* z(^c)s!sE#zrncus@e^ICJmqg2xws1P8aRL~V8XP!Xp6B6CvCTy;YuaugDk7-nulP? zhU4Vp#mbX6N?VGYg({cC4tluxI1QwI$U5D~+sK9D-P3RB_ZK^7>A<20gy!Yx3-g|fDlLst}K^B7D zJc2vk*311RyJpZ50>EPBPRr^-TsSw^3+e#~1-9v!EoMhRyQ9o=^uTq}4L#lHP?#1b z&yIuw4~QssECC@4)xFwjIdjUS4c0OKnh6%>fUoGITLVXR{$qpagNTeAfiv)&drPXfI?0;By*rpL1F{P-or|H4N8n!-exZ zs>QsuA9Pi~rGumFCBq=@%854Uo&j+jzuaPw1@CI)HPtzZb*6s%fr;UkmE+nT>;?*W zLHGvg%icN1!4?`k)h-2hs>*n9xHmTGP9ULZx!& zlj<+XA#7Su)Y=eqYtRHsHmleUWep1o2pgETiu^B38F-N7MKS7+ZhvqcZ{xtl%%hsB z=by>%p!cu1=Dt9w7OhSI2mBJhJR)y~`@O82&#=@>URcw;upGrgvnmMH6#s%ZWWv35 zG#Z+jo#pp&Peal8gt?W1L#MhfiU8D_6m9&EkkBs(u~CY?|F74x`4pW)f*^-3_ip-2 zhsY9D-*YeEw&7GcF<#F_w+m?-j- z>l@xk9S>LG!{iF^Pk&_R+|5hzSx-@9Rp(HF7Xh0hDr?$sQ%mG1`+8!D&llfx7zACs z#shde_@s^L@bsNOC}JW4T*Ojea`0n$JjmYP)zP~5sx1Htv&1WlDoil_f}eP| zi6IZ^UvZ1Yvtao2qnop(Q()SUY)z2P$Excib>mcvZ0~O)I0@nAC zOURVI1KN#)cx{SX7f%`vc2A_QX)y~Zi9o&fSOcJ|9wBZ{Io9HJ8iGyx9b$R;G7^~$ zwh{Pee#{m1BCyejpe9@0ef$15=gOVghZ#{LJ0Gr4&9aZMF4QpL-n<{P!G-R#o#H81 zobm>c^8D^Z|DP97E^*(kKQdi({+DAG4Cq5b6DBrS2%!$veqRf4X@?N9p21V4zhQ|- z;r^1*1uB9xM1Sa#4Hn;e9*S{ce&8(N3m4wYh3Fb0Ou|8-)8Lgewcr92Y+eEf=Z~OJ zywt2%iiV@t=X@Bg(UlQ)C4~4G)Q|ffhe(K?8y;W5R5PBhrUZWk#g-|1889G?3!qeR zHQkHAwXmF1@Fq&gi!dY;JMO=hq{8p1DMQ3(cUKSU@E|Ww?fcH+R9iuK#~K<7j?&6` z_v%)h;|Yd>@US6cK09~Y(*v!$FtXZGqqKAYq9I)(_s1b3{fDlgP{X=OX_7qB#_e(c z8_kDWUN6@FeaUObu(osbz>#=HDubjSR6T_Vp^oUjyryOGhaE2`-#Bt#x3in>M1x*o z26$_Cox|4?&VQywecwi;ujbp}yy!Fa( zxe1IpXwe#1WpEzo?$7PN0)?qG@I+Y38hO*xTvf;pdCe~@NQAM%1(Tb&^DU#q5rRl< zg3cWb+=^dlEZ$jmiDKG)H|D$@(~~;!J4c%zR)f^yJ;>>+98Ac)5VxkCLS*N*2Y2<_ zk@Tg;S0s9-xXcV2k1pW(3I!B@l$P@Xc0(4P8y`Fbx5AJGP{mz$9=;C(Ed|{oOpUzV zP7Odpk8MhBSL{U$f7@$GY%B|mi=yUlBcGb)tx%OXy5NW|u+<%4L#bsmBkNHEPq$Vy zpPjrzu906l55kbT`EiJLplhxk%Hd{1owCGeAr7Rb=#-)P9MEcRj|qQc?F?q7v+T)< z;iZbRroNEF!TSR31t=D9QwaTb^gImA$=yd(<>c#5ckX-^qpykLu59zZ6&wZ!OU*&A z{;w=_rCwvXZ2S-|acmc!DFSRklicYLCrNm|K>>6yHX9%H_z{CnIfybA+6suO9)r8S zpfz`IATjWtA*^zDTG?xm|87iA0;$dHw!00M4G<3?EsM4vl+AMwLpR(vZ9~Dm*X!T) z6RaYT@M)&6`KILZbj|4i9W@BaFHf*Ec+`fqD(7r1#&7o-RBt9n0`Y%hHt;=_CgBI& z8J34yLW)G!M_aTGrZ`u$WhKGDtkkkFv%~woE(?N0VTljImfU2u2SDyG;CDX_3S5d9 zV1{}$)}AO(ON@}g7WcaJ<=V}$>N}CbAuJ5BY!`Ac`3}=Fyny^h;HKY`hg1l52Fy47 zN#x#zU**OL8p})P@TXLs>tF~om(fUFc#FSzimCq|BwCYIFbD$OIbLd_2cBbGV0DfM z(MqND+VN1^6*M;09h72l5W|XdJ?Xmrq%X_qRcR-~N3g^j6DPTFEZ(|9@D5ChZMR3} zB`>5u(ta2Yyp_rYG019Qh4IlFOl|IYh34$Ft^Dq?q%QiH@k4s85CCAW{;4$PmA;2S zguL)Q6S?;mFP;|fjIVB8L1wi$2y$ze4oAr~XV>}X3AJ9`s|;%8+Z}Jj>8QgKq_)F0 zAXuonkl8qp@nV4so8f_q^5Jv_gw$0We2cBbMS4VRU2#~ z!YeRv$D;)rO0!kRvwhHs|k+Yg@P;^Kuh zAH)qoC=b&I+LO^y@R;v@D8fg;N(A|`Ck{S4nS{h%c5k${7~x6VZH2%BDxpzGhl*)% z)AQ>oC5li@jpcbDCLjy!k+g1fk>4o z6IDbf#{rBHA-fsz9c^}1CP0yjT=F`py#*XCrf_zFc>!M^CS;Z(=$^l%AW_2!f08vyM(oa^m@K$mYtvcXM>T1#&Gc2;M)`0wbU-#U#%H=w*|lKj*Y6- zLJaB!sE`p9)63?$pOLutXq$U^c;Ewc(5wcl)`M0pCPRU_d~!XY<;uc>>;j4Yzn!7Xb?Ba*6AF9*fV$+QyR4c}`}HZO7zcC5!YCj96j|W3q(c`bei> z$@ii0WZi;_#6(@B83cP3E;faGXoYGveXBKGI`)RT&LFwS>E}eN?Z)Rt-|)5GUxy8_ z)DMQV#p|IkgyzYhnS~PVjXqlQ1szg}+EIIsqe6?uXYcRxIVy6{)v_h>x{*A^7q{2& zso_W|QkInEJOq;ETFy3MFD5Y+NZntQyWY1fuuUpKWf!L33PM-Be}}YWvast7v@4VA zZI8eD{=}y6d$(Ak=HRMnqS;T_r`xZ!%fX*09HLcSS)MVS_{63cwbc_iM8OQ1)WQb@ zDn5N#$*f4Mh8_y2^j@yq89*1qQx3K1->P(0mGKG_943aDiYqmmU

{*~Ykt2Y;x1 z=HMH*YZfh0=RstG|Es>w{hTUAfdC8 zBb$!GYc;s3O;P&eckR8t`re@x1$y{+jdYxpqZRHsa+ke4SL{on%1Ts+Nglwp2?s!k zpi9o1n)Ne1Wlh{i)P>R)!fn9>YS_2RVsgC*T_GV zl!=O$RU9zJni^OxdA|RXij(xia<+WBJy(X@Do)E0!M7f>(HA5%+GIXJ5-t9tI30%B ziOPYPK(!F$2)x#hQ3jEy?pO6v=^G&WZtg3zNVTv_Or>ZutA%FgH4HHmwh`{An6yy_ zD-Telv+F2iY(8fRCw@Bu!In~HrS+GHQ%^V(f3ix`T40P{i4M&Jp`$inKzW;xCNeGGR8b z`U7uYUYftS2uVS!RR8-0efVtZ@L*t(ch!FuLgo?HOxRMKKKL@gcmWShX)kc(OCl>K zACO1&=@l#{krJwf^8ar;>I49w4du@Sx+p-oa)lMgMpgCpU<_DF3z{8>0w;HWC{IWwg1l8D&pOwt6a2AELTl>l7xSI~g2^W@>=XlwyaoIO+6# zR4p%JO_0xK#cQp}bo3;?34#y+Kg(9k5PaK{YzBm+GL{hD{X= z2Kr>2>H@|Rtm#`yKR8`|K(f;Z?|ha`96O87xs1ce=t!l|?HwY6gb{_xps1kkE^^^g z`d%*{QXis}cVP506XFQ&j~n?R%S$$VXc}~0oZE<+5uo|lD6|#=M+yF4D^k5}Iz{SlvNPnF}YqkdM?-|M(sXXLqgS{uv#AO@f@(>)`u#%C!X(X541~L*mb>Zoh z;1)*B{zek0l!&_3_<6)R#o@I;Bo#1b=|Kvt%VxHCN9BmzX+GN1ScnEB)`+JVq(P-C z+z-7NJMiJi9So!N0;DSFj*OSQ)X@9ydlI1}02<~iTcF#K)CTf#I^OCr-eClep%TT?0OuAn=Z z(&zkD?q4%>2PTMg;3)*{0F;DF+|Ef7%$d*_rKJ#3c@{(`h>ud!l|QVq6AM7q>yFjxc3)x7|CSluIh(eM+LO#^sGWe=0d zLqHFuiQ}6O!}aemRCzZhu1@ z`AQ^#C>p%vpgm0o3+&HxLk?r$0M#PWUSMDLD@<99uqJz9YB-DXVn77Z0~6blX_xE@FBS)*1f@4rqZ&kk@j{r<5)K zF$=M=P@%!g`5hm25FMW*%kVs&4`bR#UgYz&+lXOFw8p=h4k{AA6XC>crqaI>fl@mX zEF6lp%EZjel2K~ksvI{-@+U7*hsUBbVd$Z=AB;T9#rMAm+P|Fus5!;F2VZ6zFVG^V zNDEdtD`jb~kA&t*5PYXjr42BEAq4iD27;{(*ItjAXI;CCAgCz(U( zh40J%7||H8-vMxjE)@*0C@apm72=C3lvHm%VJW%~USK5+rh1kYBD09|F6a)R$Rja1 z9Pz*B=dHcz$eCcl9BP=|T^#jUig_@QyN%;NZXm`B441SzXx7=|bN=HlBwP>VBIT%h zAmB;oLhq2Dz;N8bO)bbo6$*5{z3Lisdfo+Ov6TD&YG29F%`reeZ{%ilmqG}RGD^wp zt=fgsK0o07E(ca9s=;F#5ZdCQ@IpSD$wPYTkc$hQ$K|FGtlhWc*59%1G}irikVOVcw(nh+UW!%Op4?UWLh;c2R# zpE%bS(f<%bAh4uS+=?Nby&JACh^G{Zxy+{X^~-h(9nf~39k#O>Wg&gZ|K+LF7c^sA zE}6GFCItNq&pSaR;wS+$BP~SMiZxJ@nB17%N?urCcH@?GVz=4tf%hYn1r#2uEZIh} zz;V!?v}@KsYXC8+g zBy`~C5+dj3u>Sk|&YxpAf8^bB%<4N|c{Di%IGXK#*44K+pT%cG%U^k5vyUkun7d(X zF;@Xx=N&&u`T*KN2!<1zpCmawUFfV%)m*I|*G}L^*eeVE@YhyFXtXZSK|83TLPN1z zgbp*DLM0PfwDD6|s7fsZSxws^bKbfW5nLHVr2$5pnlm`O)Qxk_QVw-~p)c%V+hWz? z+%3UGGWp(pOBa>RjpNA?-_nz1DO1#aw#}>?C*z<{tcMC5MTwz(w(C;xoo0SiFcVPm zgZ1uxBMxu5-FY7`_CLb!MqAzW+u>W0xITCl`}pGO9_E_#WK^0u#L!913byZW&D^jR3I6s8IiB;`0MqVSfet0k(j@pKpETkXzl}K zOH>7KkT&%4X2BlEh9h~edkCcBotUp~C`#@7lC{Kuck?tucHfHP`;xw$%Dl z|C>;eZaz(!l-&Z^^eAE-prya3S--LKF!*Gm;G(n#m5a^O6?5= zA(!5t%QS1hcvmQs_ME0cr3HJwvF@(Nf9_8=eV|?NZKd#<)&uosuA1fb-V!@salW9d zk%u)~hI}PY)QHXa9wm7W=D2pRJReRtlZKg{cmZXNShw)PzQjeZfKau19o!NZmkjKR zq9*zp0+BPOOhLs=%DUjUp2q&j@ZrYT`>FD=w{w6#f~fG`)|`=S;yi~I|_&fPifQ<#y-uI ze4egPV`Fx9GwZ*`MtsEAPF^i^9gP=fWi~zQn=rc{9!h9Gb8>@G#us#16qlWcNg>!2 z+vJZwi`L)F-2Xh*yiIjmv9f>DHi9N9{NGKBjXc*i|HZQJ5x3a<@J}V2q@gC8Ed0FmU2~Aq06qUicO9LNiMV3#cZ}ydzu!`!xyW_-gJ9_2 zolSz9-SQaxNPJo4SD%k#NE-q&6$~Va|H6g0`NCvj9~0r*_*Yp~cB$!rXc}t9(GeTr zhAWKsT`W|{UUZfGZ~7@euqi%K2hRNcSahz_VdhMa_xO3!s7yhbfPW1u5In)xBq{^3 zkT>vVBIQ(0&XFNRI3aOm&gTIK{!NXGTjOux%H_p}pT?ZlF7(`297G3^`Z#Xnq6-+p z1XB`MXgzf)FVi@@efEBA8YpO1GOHiQ@VpNCKE`toqH6Cebg)7ZdUz?Xu`4*N=u=|P z_nug|Xkq2c9rL%=Hp=d_v>R_h$%ov>>C+fnDwybF`_NO0GZ+4u87gJTANl9aq@ckT zp5ja;1*(EW?qlE@lZ>wWeOx;h%zc^b{b^bBO3k;8#X?c2m7!@jS|_60Vn%pD;?I@c zF_r>nw#f12eArTqYV%TFoYq^+o}PgpF`kj*8cgo6D)hd87_#-5ReKh8%2{-h7wQVLD>D94;s{XJTC1BK|Wq z{TeQvEmK4g-$of>*zWpRWWJj|`Jbjpi1ENSqEar}H%cdzovNdeWyQjIszU^a3f2o$ zx6w&otaTE|a3f{IjxX^_+{N>H%1)zi4AT**K~mqT!oI)`hbY_A5iMzO;H_vMiz9~; z&|&BAkHa0xG&yw9DZY}G9<%X-@xa{WVeUGV-Ic?;c}9Ygp25143{5!!u!Dd$^_Bwl z_BtWRJHa-2C2rtxkNshZyc4k|@MfT7|i|Jc>Q z&UWR7aWrYIH^ErQw|k)Cr{#rVZpK`X{otv^vp2i85lX>t#X?&L{Nn0EQ%-2`hQ2nQ zq_;{^+*fd8rr3YC3bc)%qDCjQ%dU>TZ9ny|XhvoRh)~%nV}}SL6@e(dHM=z+M?p*> zzO3-8FUB{BVik&S%Iv{{(c@3S)L2nvpy^X{v~tD5Vcf3~Y0kX8S)?2cr9O&8nZ0d$ z6t$iB0v0XW@8@ZZ6JOe-EKkaUVLaz^V6XqPc|tN^T&S-=L>cX?!MoJ0NU=DwxBvr< zM19j$m}YyS=!2oGWpuRDQu3sok99zKa|+XmNpl;1XO>v_8mo+`y`@QCZtt}i$X z3?_Fi*>gu3Qip#RLm1Yg9Ids-htn9I%*+*UBY&XqG zON(1EW`lSt&kqU_W>(+$cPG!-nbOD?>O@`EBEh%p>pyn?~!V zUch-OySi-z;=_|_3fl|*z%>fiSLVO#dx1wa=s(hxei{SJRXN6i19cwtzc`?>u1GBt ziiOltf`-cnWD>On1TJ4dS&mdqY8Dvu9(KMUrTW|VLv;v9=ySip7-8_q&HK0FmJfbD zp0j^6VB`%vOnq}3>+1d-Pl}SKTCZLU?hj-xph^0J7E?SY)^M zguIZQ>~-;C_-FWbgev{cXF?Z3yu03i-C#Z>6JWK0BZ)R0z_r3#X<}Q?kkfGQBl0M> za0+m76FAOfJ+Vo`}^v|`(z;}(!8t>_;cvMaaQr(UMS%`H$ z7gxEB7(P?alIRs~-}U7-uk96S9~Agy^%eKrULDR>E!oQGz+oZgh59@`Dt}ytU`UaA zP>u)FV83kKE_nMrL`{A_L4xs<=cXtAJLNGK1(5)smFCHWUvQ8F^FOfj*`f!ds_NNQ z#`ouu(?5bc{eBJm`4AcwoeRDRNcjz?X|@yT+aU;asJq*X0C&Cy?@?ZT2cuEkRhXU6 zIiaQ2R(9J9*Jw)lTd1~*OGM{O`8E9+dI(UJ$B4+D{`E+_in%$4$ z?KH$;gR{XtYft<(_!#gu=Cl)Q*SqDt&vI9%D*@K&*He6hGM*XW(HD^N5b>l6mUyvg{fQw5bGIdTYpfn>lBt8e&gra=G;jN*un`~_mb3h3H%C{EP z@exj8%*hNVLM0Bf`pQNNok6wktf<-ZsxYcXIm`Ij5eVU>)~?%ZNtF?WwG^)o{;o0Y zye9}5y5bAIt^ZaA4#8O6_3fbA37S$I2*=*Ru#?7G7u-4V47;zaUiV8>D`+~1@A8SaVpKx! zFYZR`95B8^1>}|xbOs!+NU%?@6&IKrcubS8@}u;dxO2pdXj1#`-a;Exg)})><6>j< zZVa?1I(R7~NVbsl`MniHyYRZWGr@|OP?QkpA3v^t5q~7rfIX43wMY34#&Lf=vH8tp zqbS}NS3LW=id89C8F#3-k|{pD#fHUXz>Mck=g<_#kHJ`Gc~cJx%KE40zHTa=-E`v23&O4{Czb~P@>GsNM9oUI2YF-A>pMvbMqQI`wl7VcSyDsg=aVqAxt{*aPlvS3%BZZ zK(M5;PN@bfhk$hq+T6J2{cIS+&I)Ut?GYl=xkz@E<)XF%==%+mNwD_tzKA2~!ZoOo z3g5SXGT)-7f@gs&ifDK}KII9X_cPZ7-&w+@MkWf~S?E9(SAk ze*Z}N_)eG{53Qz!s$;2-u$X_s@AuGHvzZ_>K@4h89*4!nn*O$+dAjB&rI#~RgoxnbwQcvcpJhu|_w#v%9>);V*uHD;j2H ziMMkk034>2A<0Qk|k zVLb4jRb{z6reBb0i(&^Q?Nx4ireEvMy)hx%-;mMHX_4R0hPh6A)0$URcG3&a#~s+Y zk0sY!WsHSMb~O#2`tIoO%#rwXkq#nGum`&GD7lMe1AE3bBo0;t+~%)Ud-JOBRb{8u zB(>6%{Kb$@%OT#MW)tVrFMhsCO;no@IS{^5?=QnO_jb?jsQwK{gN_g4@HlMlTtFi# zJh&Oe&x2TEhJQisod`x(yn?k!cg0=Wa=$Pah-;DoXpwFHY`$H&EJ<{5baJ_`-+Xd8 z>>nS#pfz)BF*$4H#Cr*aeg{Lx$)6I(;7Qh;n@P2zx+en&E&D~#`Qprg8wNv*Go~TvXYa8RT{>xHc0NlBy+|IQ2~~BLp7a!*WbY(n_`S50>#xQNh%ETdirUA0&w!2dUn7Gv;CO02^USSiqqqGU zGrxS?neT@JxI>uL&JDZG)V>oQHiBh~5YV-(*oIf)i0$`nkHdoPLj|(h0R`8SnBkRV z#heo>(!2CZ*?vo=jU2qh0pi_u{+!pd^;E#57`!sJre3y&YFk3d&W(QNR~$!AB|}>e z@h(ar%dQ}`k7Y&6fl0G-Vki{TJQMS+(25))WHjIF)frb-_R093qej+;lP=5d88TrH zkX`J2yPWfIHg?qfBpjfISJrUm_V>!K^banqJ~$gD8rfcTM*Y2_+mlPf5Gt@9k@JT6 zT)TWa4omehhlSttt#xlWpu~cVzS>S*Ic&XQGXGTVg*Nb05oaICLxsR{>EZ*67bz9G zbnWcoH>saDkk?I9+)~yjWQ|Nl8t6LqlofRsoL8L~@hE&PS8ejhos)s|(spB(l{`{) zP}$L5`P%6KpF!T_7vP}9mtOuT3sQY82%m+PAvIXOwLI2b*9}Md`Bm*7K%%vLT|bWglM9#N|J( zmvdTrJx;FnzLaL(EfvyPf3WJHZAnVO&-}{-6Hr!4FTkgtiSvfsJ~Va)jq9J*yX4d2 z6S#L=$*4acDV%(_Vc*7zKG(|tO{=mGiN}Lw2frq@fc(dvqlga=)w?)$->UMmf+w%5 z82Zws$LsI*DKkY}7-(u`qz7yktWs6s)x%T19#5a2QfcxcS(U=S&{;=Fy~*o>8b^!P z+;^SezkV-Vj*CUz;W?_4gZK=*n{*ziA16P1@iA=HGkmAjGuqLjL<4jB8OR!4XddH8 zd1cX=?V`OJ&Zs7B+x_djb`faCYCpFov!r=fK1Y)0O9#EHrW%ejL2xo4+F)#Dqpp-c z&gNf2?K0tRV4CHZeGq-$=~tOb+Dh!u*!DZ0HT?JVeD(cJV*|4Gxk|BtJ$0E=o1+Z{#apn^(>l1hqn2uONV zx>QnH5QZLlfT3&}2|-#~x};Ny5h=-`hi({phym`}=(+!Y?>x^u<2f_zwb%OU{oe0e zYscGZP8C(B823DVSll)H4_r2ZJS|^$XQ)>WRB7I z+$Of3N_0U@E8#p8o~w%qRuaOV4CY4lRZt{qtw>NZR-38h4)!Bw#CoSf%Jx24cLpQt z=fW3m(glWMtIEEj33!xn3vGceWi&UXL=M%7EB-yjk9s-Uwz+8p!jNLVBk5*=*Z2$Ye3gM~w)I_IXVMh4^n(hL7^bjJfJ$Q&`~BA z72S?iCk^9xK}aQOV3~y0Qmw8|;sUxD?I{_@+Y~Ci7MgU3A)cx#H=?iKd(En;dz+%@ z1@3|8UPh;zqaH4dln64B_vx3W5#E!(L{rDiYpi}zDe@LyLI6k?S&)|wo*-tyrY(Y* zWf*q8CFO;kbL+CcqSjB}HkaZvvwkmm$X112Szd}y^m zK@mQhlbwkHoyrnk;WgSIkc#`|L^(Gh>IknPKcZ8){KWI1u0w`?nYX^=?wb1v0gy5A z>)9MF7HrhW+#%YW>H`z>_sI&ke^L5gs&X~E?w6SR2d}ExiQh;<857oVPLL;jB$6N0 zbuw@-qR>k5QyaBvMVXuZ9eUi++$N+)O7oi=B3M0o?Ib~wL}VFBm%0LoJhexr{E?k4 z=i%*Qa|EfX*$19Wi4h-sk|KB?1M^&}nESEsuM-vO;Y=>H4i84$99VHh=B+9X}7cvF;kjrS}xG11O+P2mg362 zUIY)L2m$rYr^eQx=Ac+m1+MlJicjhzDAU!o;~O+>GLM_WD{YIM739G8=ZoxBNBGOJ z?)IXPD!Ku$VI$5*=L8o<7dO*yghVG&OZ)T>6{W-Zj%Pd7rQu0VW2?*4JK8(}03STx zNLs#M=_!z8i?+TBj8<9Yj{~-{Rg__imOLU&GCRxnsjS>b=y*GhQ}v${23x?wT=9l$ z>U(wSNBCN|V;DvlFy1~pB*7PC1uFN(H`m;Zr;qpA5jA%V9VZEQ^FHbW*7%Rl9vIL# z&`Ajsy9hWn!d3#U2^?n+Xg73=mo(W<2B?UJpI_YwQ0nx<*Mfc8Hp{Q}CW3ROCY~I; zHN6~UKHbeteELSURZnAmR?mYd#&^6gL_31P(fjS7h!u5ly(1{4s-u_7w4F^L!x$VB z@#w*cq|;1=mka|$Yc8jB^W->O;|`_C;j2lV@=R%2!F>x0KT+gyJCqKxzx|HT9j9Wf zv)tjo{r%{TDHP*2g4tbLAeRbmLG2%(Q25D&jzrPU7mfxJT7`M0xGuTuqTA+W@t#T; zNK8hfg#u-3jAE0hE@`A4;J38VKGJo}0js7+%&=EcxzF}n`^)_fnAlqA!cE!vb)uq? zA#K+?LqNHacYJGDX)1TfcEf)JBh%F|Xc-#OIXhiYSAEyc6VJ*1qCdW~!GcZ7;qais zY<5j_edTZ)P$D%eDf=6fBHX8F00_h7Y1c@%vefbMfXl`{*2CdPPR5NGeW|*=-vbp0 zFExni1Vs!kz0qsZPR-9Z;&`Q{X=rJtc7`q_M<}g5AfQ~XlZQG?c;4YZ(vT>qF?agg+PyXXJJMW zZd{18&(SQ!$(f9phspM7!qHYXqHN!)5XM4Mj=f8JFXj^+aMQ$nG}^mR7^o9-`F){ye`1l_an1pzrx2vy8vo1TaxbNwqW?S#a~#^$ve)p3jU3 z)MU7Y;=PuWTC-IS@k41iz!X=oeK(Ev$D&n#WVc0hQJWlo2f9-2GpbSv|5o1A(@f9r zqt(VzkiY4Q4?cCd{RUqAv90K0R;Q_1>LiD>5hPsO$a5y6KXZlB`_#d-2s(@$8dA{< zD(hvv_q+-AA~^%#yh+b!#RWW=Py72dkM%ruaQ0oPew{tbm&4`{WmI0dRN_~fabAn9 z3pcqYAHqr2bV~5sBH6FGCEslL0F_`Eb1eKiQl3Tw&i>x~;f7u2;a71 z4-}$iBfF&S_-43Jd}mAS+A+wirR_}HpL1vFRHZQ|B6s60q!m8q!~#NfMM9KZZ}*C9 z^40EmtDrXOj*#;udZCqL6FS0D&ePcy?lO3OBcr30uHz%Bv5lf~u0Uep72boQq#^e^ z2Xcbyj*dv+nB{~S{bsAlnuo`T_{BQwhuj6@OhGZiZAb>LoVB0ArSw zGV*KT@L0Y72a2MFc z%%>fbbcx&>;jRs=h&pt{dFG|}w-+aoWH7kX{$Q~Wge*fw9?#V53r_dETUECT-#GqW zw3j)8K{v)-X$pDMC|5WB`zki22K&07SMUZdu<2sKj@n~HZABu`)v2VmYuvf>`Y zXoa*E5-)SIFo{38Z>v&dqaa6^Nr$(9%zV^sdFP58COJ%eU5577sQ0f3#y#| zCG6nE)P`&(2Q*Pr1Deys0cvwGtF;@Q(X7-k9tc8aEa-uBkS`?5r5`Xm#uq``g7C)o zbH)LmT4$#ZP$JDccsnt3!N+iIAJ4-qgN=S*=q`wQF@{kM!dxP{j4r6i#!iuHkeQ75 zPCemg+1^Y7Z3v}}8hj}H{>DbRAr%yuhniU@DwFV4V5#g6&~cyZ_Gc!4EaB>xQucZ= z2G;>S(a+IX-!%k^Nhgl;?<;mYlqmFF_JP*ftlg9l_+(L&Wa)qo(kXkX%4IP6bVucz z9Lo5S+Gzcxedh5|m)+Y$@e9oHG74HP`h!AOyo#vuy1j{ZR^@OFh6y2`J_e!T}c!B#!83GtnzcoBrHlcX&b8bRQ&CRn^i5a#yhM$@nszvI^!zA3M2r z3)N&!esi>yFt=8*e^UPbY&M`2YzTh)!0iWKQDKL5kI}@k&HL>}L@>6Ubzu z8OEfLS7@N<-H$3e>cQ#hvuK@6ND&_pD!!aR7?raRmE(jxIwA0q1cG8P3>oQKmQ?&)v zLf)&fPN~Vsw~yE6`q|(5gbs*=`{O;2Vp6=XNE^bNekFKqL_{Y(?>P!D%R!1l{$#Ja zWon5Y>*1&^B>b4r3GNAsO8lZx!7iu+Q!b~KeKC~X2ubhAp`0MVNeiFXLCK)$9lSlj z-Ry#z2>x=5(RiUiA{~6{sQZKrU0mtbg-N;(j!61eWFsZz+BO_M@EhDj9x-^*()m@^ zFyd zL)}$uK!Q~%7^g;~%td*zXnMkaMO2jT-H%E9I&hIvbCT|Wz0|Mwz2G=tkAyFSn9->GtCm z?t_RbH!iK_dI%;OLP!_@aXXrks;S<(V|=fHlv8#1arzUm{a26@B-~SFost__MkoG| zFRz%y`U4i=RRCiNIq*Bp5JUo>NyjZ+9zdO^rV$`7>q@u=N~{Y~Ja0!pOxOaoxD1C~ zE#UBq%1_q!WBZ4lmDPhZK}O|;^<)!HnxWecHJ_gBAf5tmMLYAY#Y16qCT>K($1A{P zTF_vl)yV5#CUl73PnPSjMBM^GK+tCW$)Xk)REV1Im_53=14o=#j8<78a{=VBJ^YYz z^~0kX?RZJ?e5p+4W3*;qC?W13Q+xmo$6*E5iXd_bBv*`|w)YnGrN9Kxm%8Fa!WdIi zAlSajD{(EOLN2?%HVwNahEZr7PI##*zE3U#;5cYYvyWn~!tCM{MSz?&;w=s+M%>i?FB z5ISC}&Y4?d~KF zkJCcA<#TjmwmRTv0E?=3GieLptExDd@;-!Oi0yRlCtH^$Rr(ML8?s(kvI~~5Qu%DW zZ=1##c^G;g%jr#H*M@H_j<#Z4TXLgBQ)^j;SGai!$He3Pk)Fpz;REW+1FMUncrR1; zrxAka;(eW>9A2%Jr9hliFBNa4y*FT5WC8GOPM&`FZ^=k3AiwB0!Y|D?FDI7s)e(N~ zx|ySsb*ihS--lZB*_)%R0Zn$Tpwjc-n*IGi$lRf18glxZ^tI@>(zJ;QiTJsB-jIQe z7Ii}ksbP`C!JE=6qfQSCYn}y=ny5y3)?M}4>(89(Bxer@H76tHkOqbdl13prqF<0J z$>fm)PfM$Lx6uz6lV1iOR6RyCOdsicXrTz9Ih`TWo;%ImeS=qxylhZ}!?Cy!p(_%) zC~I{>7f7h;9Xl#F4voAwBhM5|9;I$1(`q+!b0X2=M&8E??6ulINYz&3pPiZT0^en* zNxJpi8qb=!bS=rp-rDo{dtPRZfl@ZVq0|2B3Y*E5z3;!)23-T}=OAHf7u**)-n&OF z=aju6Z(I**yMUMr0&`KxI^|9w%nt9c3`7mA21_3-^=8_@2&46l;6DS?1Lr~X|8#|1 z_OV219#ZkV@8NsFjhrM@TAD%&DAU;Df-xs;MAsblyl^j7=*&ygAYiwbPR;G#^8S6r zWR^iuMz!<>RRJnO`)(9e1vy^Vq;BTqxeppkiXFymm#3-$&(@%jI8V*}nTnB6$;kvV zY}{eX=8YR|a!vl2ZKrpB?B)0tUc-|op6m1Zeg?ITnU_zZtVI(7kHeIQ&g`%NRE8uyJ41$B3h*E!Xi>t0b{O*2bQ`Clkm{*U|b(*T>LEVv}6Mt`i9^e zKS;Wg;7rt!u(d2L=kp1dj$6ll#vHh z;<&?Cf>DELhHkVsRBwRl5<3-sjltCcLo;ee3pZ~-h^kR#FQko^Fm|P-K1zeMadFhL zz(I1p;fcqnWf@)K%D%Xf=Tv0GJ+vSQ{3zAlCc9>k1As(H6_q200FP6tyT2aD3x9qp=DPmQQ0h&jiB z_Pw#hS32eJTXkF8`5>z>L7eO*r+qK7@!WmIy)i_dkC(2n^pU9GsD$lmSouA@LpjA; zS5iE)j^OC2^c*cRM~psgs!xJQqgHW|raVABOA~tfHyH6Y0o4N`KJ`g;p8paorjJwJ zICiOI#q&VaZg^uonieOCxRVfwE~gIyZ;4g@-76W>$E1=DC+`!XN~4K3Zk;2k916@= z>NYjHt=j>L++fU?Tou~&|HN$w6*nssf-pzT5DGGE z>O#;phDjakzE}S*_F8< zR-MNY#gj;Z(dUyk^cs2%U0k9zRb;>!pHw*H^t~h@tpLPph_wf2MrUFhc3wNpw?KIX zkEp4Zz7Gz9VR5EHPE(b(3inzNH7f*A3b=o~7}ATF(5*+_^4>2AZ8EzwLNRiOFE)YD zA$fQpXS$;xR)AQ&dDkOFrt&~m076TYrTn~1Q-C-N3avGJ&h>eW2J&77l4X+MRv3FZ zJdbmuDy#r0HxDWs{bNTU{1!;f@`K6~L|tzD&N%80zv~s@SOh{@X8X*0P@3@B&6{QY z;1jw#Dq9ud4hlYggEyg+tCs;j@@jI>)mYTdpj7;Lp`W^We+%A>wtMc>L&}DgUi^mr zrMQ>~w!QG(w(Uq)gE6$tm_7!(%0z{(Z#1iz77;?Kvui1{CrqVv)V20R6x40Q?TWIm z-5bG3(}75PjIHehvxk;B%7{r1@k#e~7A#P5J0MgSX>IdMqd(KPTX+NV?x%P|8g z4Rs|X?7HIfd2Odqk~FGt)1$;!6vv$&&dc8wD#s18Gt2O7j-zQ?l?v~URLz7U0=Xq0 zg|*V_oe*}_#i#vkTL}zppE_r)caL0)Ni$1|T#-ID<08%v3keXlMgHqJ(K!2vHv1mC z^<8z6|J|1ZP9*^a)e0N&D`aS5g#OJdws-Tz54@I9pv28&{T$F0HOEE_qN}UGemp0W z^H}M{6FQk2sQaTO<-YB--E|4k?PbO4eI z$d%}{g{Aikc)gfobn4-^WJBX<9C|m`ntaBe0lNU1)k{MP#qQ7g7r-uDW8FLKFbR{h z>)#5!ZcRyJGE9W#X>4kj0Mr=~!#{>2jhq?9TsMt{jr_RP`Q(2t<_)^vk#d{P)~Ob+ zT%J;{3v=c<-VfP#4l}(&a+kQjY=bP_7J4QUrh&>&k#x_Cali6v5sjB5UEJqcZ1(llx~Q4KK6 z3lPVoHjny28LCVh#nG!M7EQnwf%4+oeROf7JUeWdix%5H6SbOgahBhU7 zmv(uCX{ayA-UC(Vzg=T8R+e}3Zi$#5JZ=T4JD?u4NKUkVzU*7IdtO;>-dG>63%D6P zwvfrrvnpp;DeHL^9MmtAl>yf*C%At@0ZySqs@_b5qDg`G!Ph)?w6Uu}IEmVv;kGY7 zfVrZvN5;YHIF`7e*3c7otobDNu7%$WmKfn?6}^t23Q~FaX7Qv3Q3C#*=Cofdg{9;K zVeL`Wn&)8tvJ@#U>AKnY1J#9gr2GR<(Pg)v2;p3wb zfc+?_FTXoPoNQIM{Zn`nOVR^v+A}tZRS$+R<`6l#Y3g$d-yH6^HaT^F%rm8;tgiW0 z4;Q_8hDofL%W6jss0I1HTT*~;IULo-W!DB-W?gNSN&;NiM!86V!ZyEXW!iFE9O?o< z>EoXlOzj;Nl16X^3jrV+C~xzB_DuJ@&hw6(?SHz&N`*g_SpqIU5O|?Vc%XoS>o$E? z@}#o_2v7i~%VFi&^7SRy^DB)F^@}Vz(+XIbQUDPQQ7Ufsy~l&2f}$K_^9r3+V?^C3 zeZRQYux%$eL<~1x!LT0Q>V5DF>cR0Pv9?xip3vE#@RIAPywUm(Oj})S61KkkZ&LYk zzc#~|)+*~qUr-@W9O~9vHT&q>Kjsx7kQYfYOMYA`U0Yk8R$u=$KJ8J;6}wTNG}n%q zUo3zY87 zAi+S@Fj2lpsmVi}=g|H}G@^!SSdSfNI@uV9M<;nZxv#7;#(hJ_uZ8nqrAvA<@~jj* z)cYy)P`0Dlux2MPFMm#`|DvPWkEB8KQ|Fwixsm{yhmuLwQ3`=cwc%lGL(*mM3S^`| z{4sU`l!#-F^;i{72E?lmDZJ0MM0BzpmUs3VhUTy(*vo4?dcUL~Hd^bMId5AE*ny^9 z@0S!FD!>2t)O0~3qTFM;v5zi@6P=Y+EH$!Vgu0;K@x^KXY)DK8mHuSt5$28Fv}t)R zJ^m2FC|p?gJ9XgPjXTTpcl+y(yWQ}Z#E?fB%>$o^-mt%Ki=k6Mz}$x~d<>AcAG`*# z<8R#nRei_-b%XckeRJ-%+CS2IUuXw0K)1Wbs`|v!c%BrzSMke>O|w2HNff)UrPOn~ z8)QHJ3`rZTUUsPd$s9JYMak)I%mdqJ6xBPNzvd+V>jmHgty;q-v`oNBh26awS!)U? z18J$2SM*c__*nJNnnO(C4x1nQ*1)XbI?Bsm$Tta|h|` z?RTca*95~mn`@WxG7x#aMDO2ry$lVy6sZepW`Zn0y($yAecdY;q)(t1X=CcrTy)iT zO5WOM;?;g%TJ*na5hyMl2cUNjR+}V%Dvqmdj5h-UT^2fuPLOQZo z$657nS6ao741atkK@6J53d=xGVd%?EekPc{rh=_+sGognN)?FY--I=f#oXU6KkbjS zXH=Lk3)oZ;A?a|d&x>k$^Y+J>rs-MxBgJnDsyvJ&vyV9*J`1)9zjz}1c;N+9|4HAR z&H)ly(oj;Lm43K$If%;Ost3p}2ut$}^db|7zcYw7E+u&s&fFsyH?M``)Gx-Nve`Fy zCOd8W7sw51X*9c_CCde8!+i$U9c@wZoi#99adR}pOcJsDY58YAGmCD0xJ}u$7m7Cb zvQGL6UY>+F8s>0h;TvsUpP7iHf!yq$mTM-~Yp{?z`L~c3qV$XvFJzcPjpQqcYDjPO zn?^i1Qk*AG9G!62yLP$@LRo(iY&qjMVS1s-N&^!f%FPa!D9^t)z?+=5)XnnEn*@pB z?HW1wG_&;!`?UX4A5OXzW}kXGSY(D3XaEKq1-`LS!s^z_T#5iqB)oH3R#@9FL*tQt z@fS%b(K7OBb%(ZxLMaaLa7r^95#xfH6FQO#h~M^hIqVyxw}ch7-$I?tFba&;)V<0_ zP{;JcqHr57^II=mSZVaH3FqkLGi$5$1T&l`$&n)(JeVCFC}3en9*SpIg?kvzlH2@~ z_a3xe{a1zqU4X~KrsAr5!=OXO0bk{{@s7B>#poz>zPVT2gTj5K^~*B1-mWI&=PaJ2dOPGkY2rT8cNm(`vIG+<5m^4t9xLE3`v$hciLR zbt~9O?`AM*_Nh(x59sT{J})T=!B)a$G+EtMeu1%m&0q3YdF_-}1Wf9K=)3A1xuZ;P z*8S?P`Ag%7oI9;fan55O)s<|{+Dlai({cQPFmoTl5>jS0-$54-!k$TrHDGvq6Rb}g zU>llBHIq3QDVSmU_2D(k}`sNoxnSz7a- zsTg3n$rEP#HJ_#6Ca`V;1t|nt!XZaC_>1@b@*U1@jOl!7cDQZXPKz#?`=v{G`N@^-7! zvWJEXtB0L|Ts}=O%W^c$zek&fdiC)@U;C^bg_B0z`~RPK7Q3{?tZ_Sh>>k|l(GJU4 z>&VRerE6>Xq`^D;P#-y8)^O~3Uu%_=Gse+e*}pV?9DG`EhGW8VS|SGzKJ8U%GJlN? z;wWU~IKf5Z&itAA+EXLGbZ z^cId*`}Rd5Vc|4=auC#A+KSbeRN9OUBWVD;LJW=s&QwT&-63@r9^+bS;q`|PlflHF z7L(o-vdzx`nkEU);mmT1n>nmFHNNYg1i*?g^)H{BNCQDaQUN$#%C8Kxn^uof*T8W% zC(>Rq5kkfUzGquB%7?WyBkBt$Z zzu&b5Yxp8_))}TM!geXTTfXnPbN&`jcz8_~XX29{V=A42f&0$>J3OF;SmrhrPGILy znj{<+ zZ>PMbS7<2A1t#8R<0$fuCE?|6m6>hA!+$T}Qf|FL#?+L#NxMd6S?7qqSi@eH z2?ApE-Ja^`U4|}W4EsPz{NA|ON%?pUJQ&G(`4*X82C?*afUUqoh`-r?G$mbZnMr(# z495+t3REJR3{y+wMYnjwR6Qs#xyTq5axm0m2O}_vM4K`qJ}l(&eVresfd~L5ktHFL z5^vwIXqiS|)g+cF9;Wf*iE*KLSmgK5%m)q0dD|1I;Jg&@x~zLaX1^z-`Hh5C4+q@!Em226Nw3k~B{Q+kIgIT_VKm<60hCQjPCo)zd zGc(Lp6b26dJ!3>hA{zKeZ}Amb1M~wvw`=6Sy<{W}<7Uokcdv^G3m?e-h(X4zC|U^c zlb~gT8mir-cX>+iPjmAkl=Eznqc4e#O`+W^(Pg{ zc=y&(I4BCkV1n|XUmwVb(rbrs!D};3tjpO|=%#46=;*YNdOdjJsA${FZPI}ODZ_ox zQwv_~GOy{Zz@WujWSQ7L2VLdX*yGpUV~%s8wTNex$HmS$QNpDby=x(FLhEZ?3f`0`8MNEm ze|Y&2-VEfYAX}YhFW(^St$TVAU`z|Jcvs~$?%!typF6{Ld3I@Q+cX4j`@ij6UQ)fo zX=AQ0`k_k~ClHg?HZ0cG=YAc zW=q2Xv;pU%XWnWubnpqB-hiNAIHYF29S_gc_o~a^BrdOM(`X2DaY@WtI?m1WT7Wj8 zz+k(6=Xw$KwxWWS7y z)tkg;3GkQt(4T{ddwLn+OT<06oT%J@|0r6|#BiJ-P3+ez|JE&6==Pp+SQiUV{B& zl_L$Pe}5wuTh!5mQee*k3|1og{#3PvFNMK8pD=|9T~Cue`K;JCYahDRPXEi)c6F-! z@9bQ^5ZQb1S299VGXY+iOI_hbZqC*M`LaRNKQ(RoHlfP{3Xq1W*PpokICeltxCF6j z%nbh>s0XJ3y8dCX3jI5zdQ!1DEGmWFmZv`-6I}T9f-x!dkFO|vBuaW|jT8=jl}hhB zgm8{5x^V^-93og2s?3x;9mI-s8WRf{OcVj`8FC5-M@aT(_0rXj1OJ>4Ay4A^d2#Vj zTe;We($Xq8q#sD__H}y?$m78#?m5G}yDHAn(!+DlN_;@k$<1HD|MjASsiN$;RC>E& zlBC-aty3m5Ece^`>YfV3uuQhUa3(*EIA%7s?$WMw*2^lgm$I&wpXzBA*j=*QUR32_ zn0H*{9SuzLuHX!&DO;k0?)euB^WP0zkkl@pCkMF)ke<0^42(|1>7Ne|inoIDxS@M+ zEI-^|{3H3Y&-^J5eDq2i7cIXeRb6Hy6oCMx-a58&PpnHPTF2yE2y^8~b$cE+Ca)K` z_oV=KU`J**?=ZC0MwTcWloYuwku?09q}G2vCY$GH-#c|uWv~|q=F9v)i~lpp+o&{% zew69sN`($`>DBjRW7`C19k#;$y9bespNkx~&I1*@Z0nMoBrm_ovrALk)<<)d*`A?D z5;s+~16;F`gAtsRl)bA#TS+0_S-B@aMS9!*FDCg`H&EpoTaUR*+Me~sXyZSUt^_O^56YYQ0qO(L=XeLAj1e<#9v=Si zCp;VTwiP??x6>F%mB^xYT`c>{%Di#bW*>-X)MHcSfAexk2JWRtjJ-K;+xev$1~byDV-g zAWq?jxoracu0zrza4h8?{P8&=`eu&<^Q8-fgC{iCHz~921Lupm*< zMKg8-0}d@FsHT7D;CDg8)Uw1{dJRWdWYsjud7I;qp#=FnB75HomeWBWe}ksnV7~Yn zrp*2n#{@L~>l)5mV;G9PFuWpKvc}oO1ou_EbPLDVFlv|@^O${`5$I2|%d)}ga4DBr zkm8+9^Cki@Gg|}amGzA_z&`sU?4hsX2-N)%>7 zTQBqF6he;PRX$tzlx>%K5KJU1|06KKP^RQ@8Gv<^4a!-_#kxj^!z*w?6u5*UQBB9u z22yLK(}>ql?PmdLDOj^2)Ia`jfs-c{Wtotua;!)SeQ>HV6I)ylbNHr$YWMP(b0txPX?dZHoi zs0pa{0w3TQJwLLB7PQQXi%VSALHn>6aKlH08R(Qgn6GvEG=rfSe^I@$McgG0fo`+> zh!s2ZQ~93iASz!o#vupDb8EwI zbT0bp4^PIh)eCDY26JSyMP;tHe?!~8VQZg4P;QG&@@MT|7Ys6{ zq=6s`IPJ_y{jQ02X;7PkaUj1=kyH*zgh=E68zKJv2jXD*wc8U5qNX3tE&Q4kRVTiu zd=z&x#PhEzT8F`GqGHY&k9=r?eb&(v!`$!E2>KFn2fWMt{RxHrRr#l z@HvdRW)70Z|2Xwd$o~YNK0Wy_8HpQp>)3ena8(kP>CZgus5TE15?^P=$R7lzyB^cO z|6SP`7sLuSk<5thhShRLnV9JK6qR)fI*heYD7a(}s!;9%&-DD5foGZIS%0O6(r z%-jJ)rV$neg%DH5ApqcUQzZk{%1xcm^^km@Dv~aWonpFina7u)tJ_3{d>~$gtr+Cy zAzhj~SY9~Y>5`H<3+?xWP3SIGe27++hZY<4j56HWkSkH+#{;-LIY|PDILH_e+)H4{ zDfWU6l0dV_C~aMd1+hNQszomC`71%XWB9*E31;c`%L=+~4u{;gmHFyOfXsU9R^9~BoIRE1Wfa6q1ftm+Ni`XOYYk$=XhQW<4z551!Nq|2G!5CwSi0$_y-0^gY?URQND&0 z%|6exORT~@Mw2=9NR98P}#tw=Ohx=c@ou;|@GDwyZHg@6(4PK3#u zHDeRrm?PQwo1El|0?E@0EK3Hmwcy^g`(nP1pGsAg(ow2$!@wHxzrxUxxW}j>`xn zi?}pXD6*|0lE)Q-8XRgEQDBk=Y*N(wxh}*M{)Ze$*lrj(G=>`$@(}toE-}7!6mq5K z%wTm89r=WDD5w3cuA{#*x{dCL+wL11>2_#GaK<&Rdx z#`Q^mVwdLsEE%OdWcXy(SCw5M(_?C$Fg6nXI8R0gbCCWo%J4~qfy=P?dql^~*j15N zy&8iOUh&Th2d#%i;-44E+lH&o0Kg@%dBonVigSiR{{%@e-lV{oHscQ0|#y=f5OM^WF zLimGq-Kei|L-$$uT#SK%<;>uSjr3^anXB4-*M85(mPRN2jgLwfv$(3ubOV5lsQpiiH5r1xa*0fB3rVy+cGLmv&5+%LvxUf^ zTC!6OBdNwlJlDn-ij&C&HP8n+znrgfIZv?+)aH%U-ynGjbw+L*B5rE-pmbZ>t&U|D*=BTx~t0-7;19QWaIT<_NMCJ>Zoj z>udrIv4wK9u50Q@MpVZAFyEzs66dA2&w@GIBxm@`xJSP~meby)9s9ofFr4xq7t(4> z6w6cm0zeglFL7@6iD4$RHSE=|frgDo0E4&}wd5Y*%X@UOAJU-(#=m)q??-HA$m4@^ zBP*&`C4G&H#Ua^2pxygV%<;_`a~u$rJlYjrwOAIL+xl@PDPQkN!HJva?9~pgBNrF+ z&RmP+!8Q)tS4F?dQGbj*sd_fAn*W=gT1CUPV&39X>4h;sD2=<^s;m}I{EgMZ{r<&` zDouCsNh;v%2)0nREK|+p)w;9Z)kHDSFG*$;_?Rgx1U%hXCyLeV+);5zF}iiQ3XQ@r zCCX>Jt9{TFGeLW*G$69Xq}88KGKYpd`}mzcSt7+7$lz#e>j9n0&W6(hYa7 z+D$#s&>bE0|`QQnP@eJf0B-3`FDc6ZM*M(X8adyoJsaA=xU^} zGr7wr-_T7@CS6!mlBZscr$02#F?*ivXMTryM*5fA;ud10jl4CHi1C#nnbYNS#1B?v zl5HX7wl7avDXeo^q%^=UWBRM=55IPi5PMb~{qWZntyPTE6Wboq7AD)^>g{c_MlMb< z)(pZ^eicbuL-81|kNcE6IuhU8Z;==SB##_5%M&r7j}qYb~jZvVKX zSiDoGFiZ3Fv&&D@6_Kh(x#G#_Xxn}f2Ez=b>zdO3j^_T&s@0VZF_cLq%M_6vc_4eK z^mPovXz0tK;YeEP$jBj8V}SX&d&v^oCj#&^)wm}fd^Z6J6WY1i%il_ujd*I ze|8pO;1C4~eJfMr7p{aXgm|95qNS{K4Ra;YAa!2L4s(!jcu-SN%mv8=9nAGRQ#Bv+ zHO0q!{26S39?*FAaErh5u5b;MaF%BhJd#)qgz^-PJh10v1Yd_&*o{p!+#Beo!Vn>B zdcrfV=Z%ez!>O^OL0^`Xid|$M#bkv3l%6Tl5Qj0k@j_92Lh?T`;qn}l$dp;g73t18 z1m?Rv6dxAbsm;`04n+uCYabRx_+WGLMU@yOi?pcK3dHtsu`Vv5Jk=Dw_hBZSf8mn1 zlN|N3e^)z3n^8A|UE8Mr7#V1K{wOMhQS)m-0@l8;ZD5sJwQnQ!;!gjEC@Xv&*b4XN z!Y2Z%!Fn0F{Glti``eeMs7P^V7xwL+Qym8fNzs;0O4zX%SMUjF?Ij{KWXW zZW^OyGnB)s!aZD4kojBpsjE)#r>95jL-!80QaV%#_av6#yt%!f@Bd5gYcMsA5ncpu z(!HHA|1|IY9uMI1`jG2WeIQ`{ITwI8F54H2mMT`t9UV4r6HW3lF3K2~$ux^^$^nuK z|2K4_X)~{C1BqDrpsmU-JHdo?d%6Dw?dI4lJa*7v;&m9_nwzJ@649eszlZ+P;>R9- z;Nzp8y<-1>S|#ThX!$j$e__a!b%y<<4zokHN36gmH2*V>A@QQk?qCnMhj%|2If>-LF-Bx@$-T7cABlxs zIjw~i|JmF;;-h0mT9>2Nof>vjdmJr(0o|3?5B~O;WIdK|3U=H>-@;rcT@gW zP^81oI9ol$de=&1@RX%V%-1Ix<{hobx%Z?7mRkSCBNo~C(B(&WZWqyJ|gV9SS|Xc6U3z7L5B#zx)kdvPPwX&7hWH4A6A(m z?LR&!7CD-!EOmyth8fk?y!dS@QSMk>w?1K_pkMCF{3jD_?5ZfP6aRtLjz{?YLq7J+?{^M58WU@mdgc&|2Ha?^Xm?Y!PAIcIDS#$89DI6jy5LwK=pDM~? zEXerE75do?SKxG!9v2_zx-aB)sH&ZLPgtldJ^kG1Fwe|{5xIVISsMB@l8|`evYYn~ z+1gXdB}9(v9p(k32MymuH)|G_IpUO8bkjaakUz~8g|32S_kYV!RuFh`-Eg}tdOZ1T zO^06zghv|I)s4dQB3iDCOOoEQ9X&Z<1B1ZaFq<8DVAKl$5CIj1#Bm$2gBkUC!(p4& z1WPyBKXjRW`4#A{FZ@39`JC~sF#=Xv*wR5gu(x-evR>xGpZbqTl-Xk3C3X&8!G&!N z=-05ubAJFB?tg?O54)c5_?6H$fHbOV-_Kt^d8j z;dUT3*1TL>epdUos3-*5BybnMOlhn~3c zagE+LqBX7T+X@DRv7P<;9q|z=@n5%_CtdBY!N}&>|Kv&bms10ZoqHEe;}csx`k(VU zh`!If)0PvWEyVnF>9w*-ey5X%ZsBup^WTdc4Zgr5=x+84Iv+<~%*;GX)ET3*woPgL z6Vr*X_qfRSa&3VL$TZIE9ia*rOW};W$1W;Kb>m4)^a}#~+T->>%s5+l! z=LF$ojp)4Le9n_Ys?5xDaY0<|eTag@^i7NRi8^&EU3sHx+mXf**@VkSyVE5aG11A- zkrG+9DDi|ua+@dWAG2`!VlusQGdbdkPYlhUpmv+%6R%(3n87b*Q^+k=op%9uv-4vK zAgN3rk=-qU*WRYk^95k`*H7DBV8#ysxlhs%7^l09@G+G7!t%SU)9#4y4!ONWJs!pa zLiJJxQQ`7=&nR!_S?2_SIt>7a`m#o*@u1zWKC&q)#7(HK`=}I zJF<)V96>5UBLDG~nsK2>b(w&C$*g<~THuj)Fi%H!-;%_q8a)YvaPyG6PwZH}3>=Ng z&h>}Z&WF{Dj1;AypsF(o`vmof0H#pTN#m7yNNmhA8pU7R!ctiT^{%kFfN zEEkA$svo~Fh&yDK=1hxdiCV~_8oAtl`Hf~IeUB;l?kO*c0-C(z^3v3z=D{i_Eou8@ z*UtvpUrX4d@CR<-rgm6|Xfz{P+ltAKE3xp!vJ&(%v$T)Poecjo6^A_>*+1JvmrSEr zHD}DeN{BEeb&1UsIk9Um~r-~zO?du-U;f=;m)l= zRsdJ6B(`NN5I8;&d8}$W$pYr%nOWsEN!MxpS+fl9P`d3y=kdskM@wdh1tY&|f|$pd zq4jYi{!h2X*kFycicXDHR-IoB8F>R`g{oNOrrVsz?vFAnlqX86`WTg~>*numE5KZnf7M(ba~g^~!+OGCzpAj~;nr<# zI=0MbPpzEwdn{UoetlVuMlS{A7++5C==8F7xU)i;mThWkA^lpNa{$k0vBJkcYT7^M z#|l2fdRdirl)R?DP*SFzy(Q$MT$GsJSd#Phtkjt2!HoowN|OdtAuU;#?~xZJ_t@UW zjm_k?2!LLN_ost*5X6p-`-20TBZNDZ54J5$ZRnwJ>0AA`?0f-yvbWP|e!+TsMiD+} zB5?)4bFEdImq{H+7g)^>e5e1_8hma$9k22mj?)wR>aebM;_(Y4GT)-OKFKs%ef7&O z67cwGDi{#q;jI45w&>MSbwfkEQxFg66bG-%P0uOXb`Epki&2NviwPiE^z?otlP~49 zbi)?0+y`<#kRXaKZ4smZyfn`#63C7~f4ZEVihCd<_@-)cyQpfTkKbx|ELjD$%dwv* zxB-r9c)#mHcmJe4=rZ?bLG@H6N3yk6LxEJW*>e-Iua#{F`|-HGOaF(xw~nf6Yu|>K zdX&dLib#XUqEtjcIur#F=?+0brAta;14l)rEjksD2I&r!Q0eZF+OR2!O>FADC&tm| zdEPPJ@%{0A;~Vd9jWci`*n6$H=Dg#&ult&7f4+O{vpb!=7Bka9q+{R|9~tkKq>!+F zdab27*r~_jvq8_?P{IZ82k&+-<7hPfqxguI^Vf$QZo84$X(icqfU%!ZwGfI$1IF`_TjU9vkPGr z&NFEj>I`{l)dS-NC}kRxI^SRLo=c7OYVD+-%%=EwB+v0Hyq)yfe(!^;2mPWqa&M)d z+4xlTz-OEuLYxQFg!DDKeOra4qNJ?2($1+y1nR`*4@_L}U9RzDGM-*H6EYOL;8*=r z2V5$-r$Kl$t=p_OP&doEEYry<5fHuvPUbS#YjpkWdOvA2LkA6%m51;=yWvWD$PP; z1KOsV8%I=Vb~qB17KI zmoElY#mZlm*Pm1!j+y7Ix_iuF_RTV>A;WmSheiU1+_^jf9rO6+id5o|d9f4vYczgz$o?1^GaXld0d(!z@#C z{i~^xsxJ~>3zcMkP`Y%?D9Ov{UHd`lxQ|(r_!>xq6ZuCc&88bW=}kMk>WD;jf1rJo z4|socuq%%BVv}UCpM2PPak96K+a!g!pH9cBEJFRc_~AS8ug5GtHSZ`!Jr zEH9l}ThZxlElM?|v6xMP-0)&<+?d8xzqW5kl81z7tu$g*mq+aIZ z-P@f=pB~>C{Zbx6e4yWod`3~b?|JB3A6n(ex(Gg*g3bc#^+oL~V?>*Bb&U)mq34g- zUOx-xrcpgA=}}JJnKAt_x>v3=)dbldwV?i*u zE|j{^kKfd?n184B_e5?x`{*Ln_~dL>HmzlMi(DN1O#c>wT)J{nc@+0zM?~qp#@vHz zBh$2`wN>^AfeSAZUX!|Uo<7uaXR5pnq>PQ+%g5flIieWApqiYBZ`ntBJGC=LG7Csf z{N9D*TU>4}Tv;0^w^MNNzD=aV<{XBX?Dafs+TKfk$D9=)*b3vyzQp8x+R}kFWUI!5S;XRdT{EiuslK_!ko69)l7Fl2)Gn=W`fNd8h&&toR&P;XlmWp8>G8!8bxP zsyLgs!VjKOCoA#U{n;9K9&18ZEkmkuS7&BMz@-$6`dG``d|)k|&u_hCtxBH=w z!H+>BQ#~T11$9DhAU`|hrY;mtZoS^)aqEULWxMjKx{~K|5C>ZxqffEN$jk89tm0KnSYILUOptssqhN;k#-gvc5r2|n5$Gtc8Tx>yc_H$~ zd~JC0LQUOHREoe%2lE+OlyoU=UlYD=Gr)}NU!qCw&Q~?g$w@qRczV&e5-_N>;ljIz zL(6&|#EH+7YwOF4TIVlsSN{vQzFsboG`|~!p!+O^*g5r7e+~Sp(+-b&? zu;iGU^}G)A!dgyb>vF;OhUwx}YYWz4^)eQ>N{C({a9<{z|H$$*|Ni zv^og}BlS$)Bq#scFs)YrrVyDhB1G@8IQQlRWGhLTp?;Tu5%EL&mYO@HRJ%U_c4t^` z%X4t*P{9q$N@ZmP)Gd>qoAg+BQsLJBF0U-?qe%+25X~U$%5v6UdAE`sxdG3a37}KO zeJr|MKdoq4Ti>^_&<4=dn)FaXDEpQtnp(IbVS3Wwrpgs^HpgAU%9M0P-?TvHe|;+e zkw;DZS@SPKirb6K8{G|wl8?7dO^@%kNLnK?;wE6K*!0j8c~OcU-<-tXIp#a}bS)QYN{%{QSwm%^c$T_cCeOTVv?~<;t~2?>m3k zR0R$0TeovoxdPO$@ziM4bfsh?zK$j~gQjXeLN>Ye`5S*Rk7oMzW4QxM2Y@~g>f|r5 zY13nyUs2^@Jv@y&ccCO^yPi~YZ%cAO>xAG)p%sjUl*xgB!0@6ve{uHLb{9#?k5zld zKC2(wAyk`rU^!l>)Po9 zv$^uyJ?`uv0xlQ_1aE9;m8eqOMcpu+f$*}oU*6}cJuE@jpz|T6v)rUGDSVZwblaVl z!=s6KZo=O@=f{}pk|*cZj!|rhh%uH;XzF~Z_QQsrMaQAr#HrC`lO@VHsO|lRn9HMmoqU?6SW2~Xf+!1 zjJnn}GQqhkM_LIhKnTjN-s!ohTH>cSdsUjW4w!uw}Chuxy-XPzV(ODUIu@)(t!#7Q z(Wxp0n53Nbo6oe>dRCT}gD$LbKEF=g>sbP2&GoZc zjbnxgQ(f7na&9b}#vf`dMKQ4l{--r<%OYe0&t8xUIAe1|+@e!aRw$+j@Y4*QkB^Uk zdFTaw-~miP=qu?YZe)Yh=Z<}l(1GesDU`g`9RM?N!qU*Cln3{7v1Io!>O%e-DG9r=_G4;BKJ;%Xh9DZeb5i7zlm){8RM#$*KCr5mYwt9SNZy zwCK6bzRS*N(B8~kMs}uPIt1_zlt}#dvMW~waR<6MC6;08u?U5# zQdk5_!~=Id8EBaB;|uB*3)qH)0;C(36&0is?itp|0Hm-pB6>(CPfoM5z8yC7DvlZ2yLF_XymtxHz!0_>k-RN&8*Ww3J7-6QCW>&cgR zBO~c>$S(XQZHu1!&$Om$PZb0XK|E#1wavcIa#**gqcuLZZ%X|E@O^$S5AB?{E)G?q zZ&__9Cv#b>;>jTd<>VLxGRbCW-OdU6#)q?7K=L(F@4bzPv^Jgz;o~d>R|9c5=%Pp` zeqwB;Cr#bEmFGO)-65}(pH4iuiD679NUtZ zlQrgNQ;->*ciC})zO&{WQ+Lw^XCULWwF{v2(3Z2}h4*5vZVscAZro`z#a?kEr)Tmy z|KJqfLAuyEwMt)Q+{g1|%qpk0dX7|GYVWHUaEt=q!*|@8<)~Xi^WQ(Xe0IP+nnAlz z9W|a}YEB!C3v%62dfD?rO~lUnnM~a2X0~x#V25SppQJ37NoJe%Bxt!@Q&yMsu9apT z@8M7WVCtf0XytiksdsnfDeb$Zv9k10v@-NzjZ5yA6nszjyjJb&h=HU}R?wpgkR2fN zOUo0%T0L{>UC_kDrJ6RsmOiaf9HSie`1%V9dus657DMu@+$n+*>`7?A$r@S7lTT&x zinqCmu->&97(IIX(Ifro=o8XH#$7!UC;o^y(X;reBUt5y#*81(LwMEcdQI9zgXNJT z!jtmblA!Qaf?&M6;&9^Gf><_lNBtahzfvI@nRkst2ByPaobYCyU}?VVAQp7hs!2e5 zA2xkiaQn7*%dkTQu_}8G6uW-0Fc|@n6aI1ysoA{O!ht4SMe}7$mO$r<^J@pz!bOUY zFQZZX@p`0yTlSUO&v5*$7zoH=dGi;d9hPzati9~bNmwc zDU^GAki)1V)4sUz$?T#P;$l|8K0YtMkONA3mzA0%MxZ0B`RSHIiK7khV)ybEY#9XN zxs>tJDfOrIy_@{~*EF(hQgw?~H4~qRH>*+8Hy+9QwBr3nh@O8=ppH1cXb+K`RN+Rh zNaJEW?%cCHx~nMn&g1NC1_#%;bL?Vs6^F+CIV)M&IinYV1f7i`I#>;woi;U7uDrSP zOF7?7Zs188+jS>9D4Se_vPe&-1Rqxct2;HctH)u1cUXL4vTP6LN|}b_G}mZH*D6q- zcejfgXvFv7CMWVQ_Bekj%Os?GFqoTnBwB6E+1n5sZ_c@L(p)8e*e}DV)R4WFw)D;? zos8e-eJJjFPyXl%JA-9WF(S=ZMC|Vqq^c=ZAL1Z>pqZ~9ta4y)v~Os>iW^^hK|kr` zmaH&97Itl+JF3Ia+=3jIbnyJ0)Hx;XeM_+jHQNbg4+Pc) zDTKwYr0`w%`_S%lrRpMUT^eg$AF6zpL;pT}3&ZBUSN87t0}p#cr}~sPn*v-fBdG5> z>(QfsA%XKS-u#|AsM1P;aVp9D%z>9P8iOK;I$B?4H zp)dL_#7=-fnVET6v9w}cuiPK2|5XB-f2ej6o`*g`@`3SjJBTDz?{>A24e38>RtriT z6hBO-&{LAl+x4dJl0zI@ZR=n}P%67{?ob?=Q%WfJ#hg%XnT~COtMbpu8}b0DP7Qfz zN9d{h1Hl|McT&}$W2808R_~)@4($gZ_#_+6*NZQp&I(8)S`G-zTgV!kT_R_T;=k?W zE<>YvG@gmYhV-PF^=51aaB;ZF`#W%?#mXsLVFXKg^_@Ns0>Vbs@s;P<)02Yj-mlII zB;8LE>(k44zXf*r zsc2=XqZFB5@(a}*yY+B2SmQ-%Jd159oebRcYqFHED9tI&=$sseppSRQyo`EmYnL*w zte3w^3DQaQD11^p8yh3x)T`k?51kJpgzV?5A&-R5=cw$ZkVl}!v^{J3X(j92IcxlT z_h5ni_E#O7gtgD3u+1LQ*&DjbO8zHKteEi&OsM-?FO=OCDm1Vv(cw%!sq-vSCnua+ zJ3>G&v~|*;iC}8#!4&P<2Xua@*uf=8$)vif*n|wn=PG7~0#w!2PCP+5$C;cy-h7*6 zA<8L10qukP!gvK>)1bJy{+e)TW8{Mrtg1-y-Tc<+?${GGr;(6BJYdK`_qNjQhF1b_ z{V4X0=04lbZ+5HCcxA>uOYCgayzQ4})?xie)?M2?Te|PwlIU@3N&x!OTlJ2Cg{B+? z0Sf#>GVTgFubl`GVcqe(Oipi~&^Go3c@INxLUd6u?dpbFi6+$2$}-0zp=3KOlh_C> zF*RE`h}6Gn0d|C~?$(ETA2(HPiP%7trH5OK5~{0E2?Bv%Mt1*$8|tm^E{3n@S%Spk z72*CKw{6EeV+){D<}gYkC;Ac#GBe|qLo^qRwd{S~sNfB)S$guD{BEoByIhSK@j27F zJJAj?1sVeREppEigQ9kEJp#jz`k zeMJtKHh>m{c_kBK6k9CYvC+2T6tlIqrbM!}#Y6z+*LO3;gGPouwIe=k@;a{g5j;b~ zckOxd#~RcKw$O@}2NVpPS53-bFfsUkQvJIj+&!t%>88L&y61Vw43F&nPFg>58t&e4 zeKsoK<<~2e{pKYu>9q#T0!w`W%oA-~uKBX}B-jXaw&aVnrdpnoJhm$Xa!Jb&Ve}ng z%1(<*UUg&I7+1V*rSGL|%0VWE@qB_D0BVt1lT+g>pU^A<9Q3|#ov>L#!vEYm^t~VP z(d*fE#7UD{b$V?bSRZ6tX!sqLN#!4?vpV)JYJFKWv{&v8V)X?W)L;3itv;y)Zmq34 zwFMZEj@h}*Gyn3VH2K@!LhJ!jSjBVOqnM#lVinQUB&iOw5qr3KoP5ss@em$2`tTXQ z;Wc;XuM;$<%{rr6x;mAhcUa*Om%?xPl7=lx>>Q%?e>*G=ejjx^%&L&poMdNiq8RiE zGc$_jo>opfS-UOR(09zVW>$RGQoh9LLsFA8QzQQz1%7`8_7aKlrv|^j)??XlNm2pr z@>3Th&20vQUoKK=_)THv7ipP)bHCfKA28$2G<~!A3yDCD7y4al4PKGyA09im zuzlWXtb03U#FwQZeo*R`y1%K&e@yKSk?&r1)2-tsZt39xP=2-UHwu-lPHaim_sua> z`SntpuVa_K3qwUotLlTws-fKdZNBVvE&4KydV^m7@phT-B#hP(K;qllY8zrW6BL~% z{W8QydyQq}c>8(Ia{l{=O67L*3T@7^s4u{DyX%6IjNw8Gspjp7r!tzJ5GGhz9o>Se zSiM`tAm-UKbM4<31v~kDN7xxopzwhX1d+#oT<5PJ3-|AT!TKY#tyz|8|my zy0M*Dshmc}9q)6ToVV3gA~se&s}>K;TYGD!>AIy9&R+GV;<(tR<5I-nIFTm&!sUcv zmH%lHG1Vn`zf=FVgoK1f)100+Jq33A-=S^k|9+INz*L@1avC6ykdu&j+|*>zy}q_$ zGoGAd)EF&EYDsmDQ9E_MKh1WsGe%%4S4^+cr)6V(dZUw9>fcWV|4$W;&StVYp)b<( zLRNTeo{O%nxjEW?Ze*-hV46;8VERk8d0)zY+^867R6-=7wpOOAVzbTq`^j9tJc6bF z@V+%!(`K%Q2Sh%V$=XF4ocguRiK)d#6Z)H12+|LijJ^H)CpZ6(>InGSp516xY^QrC zVH8=GgW_R#KeHH_nVnzH2)7@hzHZ%cIop=%KP(mE_?P=|@$kiZvHfGcj?*>{G(H~X zx*E9_ug;sa*W;~V_2xV3oK;-b#&xpn=kD0p+9o6?OB=T)H54uOCbFgEUZkd`#`(;( z>-mmZMXZF~lRr%a5Gm*nYl%5YvR=%cr)E|@OX+)Nh#6eb@86X{U8_C7kH-z4NvA2EBQ#>x35R=J@RG?Hxvf^yl5!oxZ^1!J^`m zlA6t3Ry2EXi#<5u#r*LUMMp=+68z?tqF>JquRqX3-Vhvjqtve7@3QnEO4zpJc7Wkj zcb=HwF?}b3VuZrcXQRX!3*ICNMx0WHew~c{1g%-_g+5Yij?Z$abjbO!g)Vbhdy{`V zFZy4q6tJm&$?Mmzla?w)Qf{5IFVlmut`W4xxBCi{;cWQ#U`y(vD zV#eR^W)~c>n##j7Om=1&mx^q|zHW3BG#z2v&33aimM8m;>V+dFuibaaUy!?0d35K% z)?8yQnb-2S{;YWz82FdW)`qy9{y_#**W{9@21aws_S$@QeNV+180i{wB;7+^{m`wx zv32Kb%O|309AAws_U4$2$Wj1#QHbZdEMI9Qw1{>_{W$izZ@Ur6+;g|;^h~R!c?;DF zSkK|fuADk62{+4?$sDE%S;3hyDsH3ZEp0)(mbywRDpTCWx2yaEc`XOFpeL04a~S-K z4%>EF|K0uV9L}ptGSOKi^}x5o?)%;C6&4jMh3HG=A(7iaB9SWF^V-SG;t zy)-Yc_JA#xOEQJM416)pOa0^1=-GiGuXpOg z!>B}nLRCx@x>4#{b}yy(*Nhi(%7FOsz@kih2{VB5Q_pFsJb0xBl!p4DdZq zmbx<2y+w+NeL3cRWlP<8R*H#xe?5uZ9b4aHotluJ`D=F#A^@=T*2PH&E@~1SjlPcQ5 zSQ#tntgeL%e10@s6~I)nUu5;G(s)2XfJ9r$b#kk_#NS|9{Zl?{2O*|S+wt@iL?{}) zo_rfm%fX7_yr_wL_%OSJgY*Kn*NPs?gz=xKpx@jT`Qrw#i7;@>-i{(iyFHA;f(sKJ zih521W$q10>KTG|e)Nn^UoYscLK2WJdaT9$U#}Ym8S&UiO^B-A#B0wp9vQX#Y<2Xv zt03Tz4?@_H`rm%g?}U_pnKVz2l3tQ>qKakPbvra*^&GS7x`p8P@rzFr#Zwr5b9|cg z*^4~bTM=HYw>8QTT2P1V~we z(2vh;{@biN=Cb$r+dBVK>Ic_W7TK+7Z3t1m!u*kaC17T`3!TP`G!froHiMkEZaRD4 zQ~^Y)=9Q1iQLkSgB{KYWHUb-2>C?Xo?52IPjN1<9dtX~#Uo2sqF4=JQPTS31c=pjA z>gR9+$?{R+d{(oTSfO!SO4(BJe30y8y1Q5CaPtlEZR+{fh7;{+gPf@W{{G^ghfgb{ z$}X66q{md4Pn|h^n)qc0CK`4Y)^z#C2!=J@fe7;BN96gdQc}Bnwqn~yU`CQe)@OVz zA^A5`8F!@L?zU;WZa>AmvM?NCV>i_u=kD5ekX@fa~xy? zk(Uq~z_7{DgoP%GLl{?_{>^nFi|=B4Zq} zVvbqQ!9g~aq$`^rwwn(B_YW)EgOe?l`Oph|OMh?y8n~Fxrx#3Z>P6+AluQ-)>Yx`H zy-)uVdoA{OpG~Xc^^Z1MA>(*qIdEnVZsXSDBfQveP`Oi>id-Lre&%z~9r5_EPv8^> zKC4YzD%m+je{rfuAglAosW<;EFWquh^Z@_xOT~kOP()lyUhtykJUE!=@EcY(7zHCc z^yWxQlOndXC^1p>Rsi zSID1gx+6p18fN6b;gCC-WJGE0=_BFdni2FDn}xn9*pI??AZYRD6a*PLHjo?&{DBS)XG*ysv8s zzd6t$2wT|Y1c2$5!+xqKN4lNnYEVVEErr{(GxHu)4F|1?7mKFpEs*m0=i&MYO?!Av zC?Dt5t5*-Y^tf!S*(i(`^sSjGDJj9Mnf2u75)u;k#Z?pw4t_l5>tzLa(3SA>1n33V zp?$7fJk%ih4@PV(N03{EI}qZjIPY9b4le`R-taw-BEsU{G!z054C*8Ajl~2UoO`s7o<{7^o(??z zx0&X$MnlkoP&>d=vMgO|-oFNQF-0YVqY2=4@-#5@q7l>fw|_aW&qYY2Y8UB3dUUT7 z9C|9I3q^Dm;hU`W`)x(OVr949hDA@$H_7_aniq1I6%kv@3f*>7RxINq7@;okWyg(4 zHGqdANIKD(#RjJ%2TyPZ*D70>?6PV-#m44I#&GWlgike9k>4Cs^g%y-Df8b;pJbg6 zqQue-lg?*_&^pZChWfY$Oc96u><|?I-Q(d_Nl_T+Bi7o@Hv3$-^fNVKs}K3Glj zX~=S3h8l)|smqL+VfBde(JrX7UxRjhDzwu-}LeN`>}mZS+RD^$#fZr{G$0HBt4 zH1fd!vQ+INhjP{8SwCKgDX-zE7x~R(MCGAO;8MefJDP<$PUX3o9plupL*) ze4tj8K*XL+T*HY$uv zIy2)j`Ylh*VXltI26GuI47&U}Yo)~o5Xu3H7uB0$Psw83HoGgo%;6G>*uNeBXY>A& z61>uYStG}c9_p}->Tz((h8U@Ut=5-boxYyWWjoP6^Xpw=qG=re8~oP`WDdZXHn=0G zl(yt=iTo4RSu{LJBP*f)^ivKY#|5wLyAL~!5E+CV%2t=>cGn-kuKm7F|>L z>yKt}Nx*S7uR?yiTMS!QMFrgN$9l#8)gkEr?jZf$wlbklpq6PMUkEf^nqkwM_Iw*- zF5}iy8kq(MB38Qb1G{yWE&|UMS8s~)=Alp_l(gmgIv{Sr1GRyEz>dgj+YkHQoBhNz zSh7A|qPxDj{0(XO`}tk23l|zp%Bb}Kz{msyRz#%?N?*IG7*JmI=u5d?p!?;$+ssIa zc?ATq!5W@EFBl1XYpM<-giznTwC69WtE+RFc5(p`Mh+a2*HlkIB}XM4`5KAnxnfckv(U{M#tzG(sc&s?X0g4#z_2gePZA3Y*8YeIOY ziHp{go!q^^2Cj1F`A*1VM?wfqg*Sb-VjWO}QlPg{>Ns&|1BAG@JRG10Wp9?VHZZNa zU;E!#!fz_;Ux`H(3extu>y>Q5+!RmEJzCp=ecg!?4~u%P#Z50dzH{pf2h zL)b@u=qXhKY4NA8;OrGa;4ISs&MOhDr+b9}q>-y$w^4rS=NF@JjB;f!#_XjV$}<7E zLl(upEAIwSG$Fe21xV~r2w*LStoqiK+!V*}%3UXP&13;D3X!Z!>NM%ExUPReV_u3~?-$auj zSN&}g+#7*FgJg!tX#~Vr%?Xz-ne-O&oyqOLp9?5f(H=3JPvLtDogMbjob&eIaKi*&N3PC7)ul;`QtF!1i6g7If}J3qM>9Gfa~}rrY=yJcf$z?kz8Rf%8O- z1zN2B?64JFjV2rMewf@TWG7%RMB$=%PT+=@I@^j5BlaI=9m?#}x=nB3%WXT-mr#{- z56YTBKUHl>Cvk|{S~y~hWwX4*L!+l-+{Q2{1s9!e!42APx|AYNL z@VoY6oMY1Ug7YdVTGZ?%t9J|67P?ket0Pv2m=HgT>MvHIF1Xn>1x9cX*XM*x5!*dj zy(V^-wM_ zV^2?)pEqxh!bH!buAnF5YCoAfp9F*bEwqNUf^*fpP^3kvXWZe7D7ZWPITt{=?)!&3 zQ2`se48A&3%~@Bbt{;|FS2VpF*=nI~_%~Z!+HnJOz5C^djM6U+SGFC%VP=P zYzJZjv{|hMxYNO!Ny)<1w2pe)cE-vtHU4WG{MbkKT zabE`d7fiA;)u|~dK3_gOuDri}_iHGEvrJbw!MTnUc--!7r-fTEP`kRB<8e7R-ra{T zlCEwo^db()3K5%yOXBC;p|4um9IrSCjh!piA!l!1EF`vSt`JfCEpiNMx{}>_##4iSaJ2{wC>O%* zU{1-JDa3#iBPm*W=PG;|T||lN;Si5*DRR^RYKZu{w-m$3M&E>(c|b6k=I#X!;~q>A zTC6MwXMpE|z@1rkTUM5nh~vi9h^t53!wj(UEeWXXeToa?xAAaZBV7gtd}AZ^!9IRS zDU*~aKxOM9j@x8;6)(aF&gCt2Chs`@%QaJ{LE642h!u~Mk2*Ma@><}ZB1`Y~zXsl& zOsffEetHZQGHKb()!+6O`PAC9OGKa*u#cDUwPE|?WPpvZa(=!JL@-TN0J}&e@?_C$ zr*X|bk9ft{3J?nnKr7gjDg55ib)wD&w~WZzyn~$=TI3F;YpBMcM|D1;=|}1!7z3`` zsl zg*DS~8!6G*w%>I02I`3k^|$!rQ7XLkL0R=W1#o)az#CBJ`)#}P%MkijM|cKabK$>mMH(BB0*&kv<6J(B;nz10spf z3MN`*91o!kGps{43CuVa=?@G>I2Gf$TUS_Ztc2_UBg8kO>5M!5?bb|9yRyB3MLIE( zq*GGdT9?xY5j-5iv~UezU(wS^VDG&SAKqkg0tYkLHNO{#oh=`~pYxr$apRQ}S zVI?qZsOlXVV<=T$wy9=vxG_w+)6rze9+4+E=jRI$?NYjhkoOz%tnf-kcH^z5`K?Ev z26Dn`C>fyweS-blkaVCE7ffXizW86xa}ydV?lTaLqBTm)`-_(`-rf|`l>y4vh-d;)F9UO1M|LWvxg zk|I+*1_XI>L|7TD3e6)f$WrJ+NJGC~Eo z11)Ncf@>go4MJzA=0$k%HJSowG+fNtg>fB$pf7qD#w|Ky4-H@PL2zcTGuQK*2_4`p zqL=dL#7*1H;jf#9yBksCUX0F5U*cQqh^x?4jDc;QS1E!6ow zWvh*ijY}wC;8qsAVeQI6V?qtByeh>UsF+aXyX6L%^H3^S`@NxO5(ljiSId0*baKnw zBr1*Z-niSaihDh`LF!n`gw{YiEUm6gr4PO0OzwQ%G~6DDcvksg-?N`!Q3;gD%T^3wR@`U6 zd&I#J;nu)>8lZ1e7OI8YiaB*c=X?OH-V^bN=gqp+Ms4AHLvFzQ9b$v=fAo=jak3m5 zGC_e>$lHPEG$uMBlbf`Ul0&I%1)-;jSV(RsDm1fAf&!pD_o;;mEA54#RpJgBrOL(_ z=w@qI*py0Su9at6$!hod!m*oJBwzqwl>!Z_*bKJbm6enwOXW)glqFQ4 zvhaa8a2dGE*U;!guvx9Z))ZjX$<2xfsOSM%7m}h0r2UBSjRpzE^2iGhHh+aeJj(_b zj2e&wmi`{@*`qGka`2n%1D%+0ZB&9xsS-I~ic<~k%4hV7;oFKq?sA`*on7@(%OeaC z$gwyV80G*nv{zz}D^S1$FLPf;nF+E*C0v*uQKKAs6^L~ngcR?K8s1R61ZRw(9Cv^B znJ18{FGDkpK!5?!{0r7LQVv1oTp{3FEulqyVgx!QWk5Sop4Q0Zjr@shH*rd2W<6*V znt6KRiSM(?kfvs$7}uCplGF~=3C>+ZwF*9j-?0gD1A@j-Ju(Bt(76P`p|+0`0!}XY zt+Dcc%%B~v>FSgLaB2WSp4|CHDM(1H9Md2Q@NAM1m~|CxT19 zLoUgKT+$3e%uNJ2!Q2A_+fsE(atD0`2+?mgebOzEN4N&oV(H;#V0bxB4$sZ#4MS$# z5g=;_ZuOW;gl`=wZ346%Sn{pMo(JYYBbiFT*2D-0_WkMSg|xvR+!0Dnzg=~3ZXf?> zB#I(YU`jR$ZD_fDF4oXS+(EhIJ!GR&=g(PhKef>cK$yMi6`Q37gr_Vt9HFNl{^X=| z@bM9$wfUyBdou%qHrug7+t3oWBRG9?qC1Zh)kaHm5gVa_Z4iF%k;Y;d$22Dw{LoG9 zaSP>{MK?v*ziD7BZA@=K^To-Iy9ae-oD_~U?~WQA9I>zz4EOr~7PR@}`vs^_^mc}t zw!E!mop^738Bab3ExrNh;G^oh*${_-xU*Y0&#rgq0%V&PhzB8|`wVdW;9=ghJSQux zh&usF@N`>gkWyA{b8`srLfSEXjr3SINn5TF+hRLC(X_;#s-bneg{B1oq8lPMV~r>DYY8ohijy~W!b{j8$TvrW z1-sAK_1ZIucw-nb9Hv`t0y+QG+H61xiW@`K1wf6UY!bhS5M?=&@$YdMNRPVZ_;{3} zvmR^JnZr0iRr02D8zxr>#gIRh4otW+%@&Lxv}u=U!h7R098Yax+2FXw*!Nxicr^--B~!isljd5u-x|TGFQZ!sa~^e9IK2W2`^uy4D;5O)Tfwtg3 zQ!tT^R4lr^kmYF=-&}KVY+T()O$AetD`|ObAN6#zPNZp7+KS0Z+$~B&Q8d)^b!R7( zR;avo=R>i0Um1k=gM(;w{_QG(_y`x_GsQ~-p?$1&(Ds0i2I5cIOeJFkVB*M|sNber2pGwp@CU}c z1EpaO6w*6G_^j@Pf}L$bv_d34nOPe2l>jDTwz)$e1@<+ih>_nG2rlUk3S>SG{Y~&5 zE{t=~U1ePV!g#RHdMkD%9l%~7kGZz443Hk1PO%4N5M2byvv@$tOLg8v&7>>)G{^Ky zMHzRP+Wh{FH8U`+&B}LIIT%IyH>@9K+iBM2Ty$$6?j$EYuMK!kucTiy$MsX(ys0jFCjYh8@e10v zp!R(WySNQkc01PI51kXz@ozJJCODzx9KN<<)%i@pDY*SjE z9&5!`eWaEeAmg;EBlgaVrD>5MM0=GKq)JaojM1Be>wI#l3ha z)ASBOPV}h_6gcYgyixV)mUYl!U1WZyl2!GTg;^X7pcb~~U;tWE6#@5a`e4Vek z^IV9$re+8+Z)Lhf1mK{Zn(;PlEC=i+ckE5bKpDBL*R;#VN*WY?p~-6?@Tml5kpdWc z{%AZXO5crwAh&jb4D*q$MTphXXDc?Qps7hqdEHtbG9RoTfW9<~FYl2)#@ik*SaY^h#AigF?e;Y=PVzy;Pp@4@H1 zT&2U%SPZoX`#u47?5P>#74vzCfOikbDuH~VLka~%IfEw5;iK_7N`gpB0V*VGwGG1R zUY_nh_X{ue{{Ok-@KG?CBe`0Zs z1x(`U8Hp8GX?P(Fkm%E2embcj)NtsERgOaVBFv@c#EkW_>)Nz`=OSLwWY` zS!ZV_qL_hPS$`T1+*y+z)ItprIp>BpykA>teU^x@eh zGE9NFX}`dRs=T~>=)D1Vj$0p}jsh5`b6K51J#zzyK$k8#0pOe&i;bv2Yo!K)O0Zdh z$6d)w+-XH3r6k@O$bVU@k^Ib7DpPlW7?H`yRhi0hIQNr^g?0A(Pn}7_E_LaHPYhH4Z^r;N!S3s@;(HL6J9`zaO(OF#?rmHHfj+=R`I*0SGCN z@?xT#!w^FZ_Q4rT(`vxR>gjl4LFN_EI;0_03}lFbkiOMB+N~vD-|rqw&guQU;wu5~ zHmnZhKr}xBV7uwJW4t>c24FsSkYWD|JiN34oi92Byh@Y-loTgGX_f~{|0Um1m{FP5 z3HVtZE+l|-^rKMB%Rmlm97n3C7c%@TX=?zwsR1*1B5DX!qX)Yvu~L|Bi)eKBZs_iL z6(FLxRxkrqFx2ppMRAjKg=okNLN1bDE6U-5Kv1IwoXx-v}6H2<_NMM+F|@3oH?$ppX<9oa=73Fjo4-0({j;8QonbT2gq4E`Erc zi;L?JKkVd5L%uQ7ZB+*(1e-3$W})%T;Rx8`h?fo-7)IYJdFg_ZH>d|6tV1k~ zs-Kyif;933y!$+9F@oDz<<;PpZztdW`iJyS^j$Y>B$HQEw5lJ6qQeO>Rokz;Oe)5$ zRDgoNZFBxzI|4d1_j8?L+(!?-F<-kKhM7s>q3fUW?_-!mA?rcQ;{dI z>xXfk1V0C}yUf@`kAC|^WIcjuo5z)IxW)hoH_ffjLsmu2s)I60yw?kCYt-h$pq@eH z$WA8I)qrD{^tVUCL0&3bn~xRo1{FCMKdR(1O*+nfx#WhnHeQCEO8Xs(UcLG&rDUDN zYtb*dMdAC^+(p~EmX>@aGdy?5W03L}|8 z!g%jmgjs>hl;(x+#zu$Sm0hKqFEDI-HUKQdzEms&00_Skyjp--l~8>dTQ8vGv@=%H z*EqEZA)?N2lL_GNMCkWzN6d$|-}rVW*R7h6LMQr4L6Zqdq0$g;?mO6Q5k4+1Sm#>EM8mZ z!L&x9enc%W+XofN3B$rW05%&#e^&#KPfKHW*e;j^sEsUSLLzJZ% z)b&e=C8R`geGtNWyR786Nd50l6>7GD8-4ZoT<;A5Ks-o@{NBBB49fQ!-jz0&wYGL> zP2V^CJ`)$^eq;ycND_&35B4;2)`m!Jxd+9yx_RnaNXc@@A5GC+&+Yr$^cAx zB;1)a_H#BQeCF~=70=s58e>%qVpSHb=S#wJ+ z?3ZeQO>=)V4Q=XLXwRD%ShoT-o;#6Vbx`J|Giu;Nw?aR31MFG)EHKyTc*^yUMSNDl z%=YDMh+jguW^h8YkED_b&isx`!WSAIw?l>IsyR{laD(RCXOBphyY2h-60=C^ggI4G zR=yp|^LVR;sj2BILAB&F@5Vw-N!X3xjXu!JP$O;{fmZ|y+ViaRn_F5g!`dM8XaMho z(Bhq*p3Xa!JNP;-j=8}JaRb&9?Hoo%M*D&%dy52+-~uqMG}m{L_0v87j9wi!!N3V` zhx!6v`i^Uv1Gu4f;Dw?xz!l2N+{wwS6hH-q>LA2yz!ri{$fBd;a%CEzj_Lel7Y~#l z2VEBQT@LH4bhhb&k2b&r77m*N?AC(KLL8vF7smtJ`2$b5-bsji1xNi~-=`rsV?4D) z81~D5xwPm6+^24T>EG^C9f62-hq|wQ6c*!*r+&Eo$!TgN=UVKs)7exXfxm}>a6yX> zmBO$I`{M17a%!h{{ZO|@<|QU2 zU9&Dh9T2pCb2Qw0d3CN%Z)TvJ8jmQ!@pY(%XF$nv_H$L$AYNp{UZ$$#zyWYLPt;Q6 zZqp)%Mn=t8r;9achs2={iON6*34D$A0%{_|u}kVla6IA*1sy1oSsR3qIs*##uOeh3 zz|5pUOUi4`9K;ItT?HT?LlT0e24CkxQ1;q);ZcVsAixG~t^}oh9WUDXI+y{%q&}6RouIGZyK=TUUM^pl@f5LwTpmK&9xlH zVm6tS)a%S0yGmiY5Kr_+)32YN0QRh&&>!mS#0|X-0~pWZd|bp4J{ZN z2&?pngcfPxHlY2GdS4GjJC+~^taRP74RxyI6%-DZmzV!=1=OtoT#wp5DzMuDbQ!*Y zqK8g6o&;mL)4B{=nE}|JdyV;r-~RE_@&$uI0s}%7`gsy;O-9PR+NEMBR+yj-GwZj2 z#N(O!GiW(X;uzz0)65%kXhW2TlV!?4i#_j#+F#!MvURVlSkJc{%$xIIW6h&U+z&fJ} z3kA{647F?%b+iv;2KWfZhG1!GVW)c)TP>henCQx3_wZc%v9+>ZYqOI4wl;bVP{*9B zg$<{cN&zm%(kWdb_fP}#UA-J$vNmbXSqr;*22@K(Ee8TzHkzT2t_ytiCi9W95}Qu( zW}HAkWsrRj5*om9#s8-rZ9xi&L6hb<`JE>}6@fjXj`+FSIm;FEOJ$Jz{48xjeOL*6 zaBR?N=;O1UZ$1@4d#C~eW{_q0 zxaPfM>lVAGz+pIR*@1cwoeqkABb;I4X8dhf{i9Joa>&!S6l^ND!Wf~I56iovj%NzB zxLCUgoQ-~~J=Ev5i`NtsBRXJb)>FC7ucHJx$i^>k_$mz z9S@u^UmvF=Sb75(rk54ZcQ7Y9ch`EuXwSD3Ssc=U{f8ADNYZreIb#Tqc`g4mFo3m- zCJ=dF`upDr6+u!e2&SRaA<=*d^h0rwM}A925kJ%6!Awv?EdiOwSt|jpF91m>*|gdN zeF2_HtsnZ#G8-y-)H#CnQ2;wguMHt}e?vB|QICJF^L=RQ!Jj_tE!A??Rp#R&KhNlM_bnE#0=uGDW@As{|V2&>X(rJW}rjg1THZ0}D@ z$!7(DNEk5)?K1>55+Yw1V3X_;P?@vOPcZ(tpZ@k&KUX-?WP3m8oeY2r0h|;i$Ac}7 zH8DXPw7pVyMm_yFygH0j(>u3r3v41B$DFmi@lvWpKqx0F#G-PqafF4AfHwX4twLb_;?kQ5H4U=lqEl6qJS9XkSLyvAUJ zs5K6tqDkohci;B@Cr^+z5={+2!5h%bJElJlPj}!j%NzD*hD~KiX)3Ry6OoY>G5{*f z&4btWA8$F{wYL;KvI2w@Cjw8p?80sP%9v%;!fFOuY>*-OAQ=rrK&$Kp*!DVr8b1h( zAgx7ca)|d2`=k^2VItVU=aW17q5pR>@OTM&V1>>9YVTTuqCC&&CJ{}n2}8i(3L%UV zns@_60wN$f6x|p>OsN_O(ttq&UbrP7*BUxXx*}P$Ca{7dAuS3xvZ)se>^1>W*Q|Gp zEeZwV67C?bSP**7etU7!{_ad?^bfki%e(LQKDYCn^Xxb}9Zm;2EWtpXL986;YydoF zGpG!44D3jF_9yqEp~n_|Q~W2DQKQWOk*1@srA{?OPDk+*`Q5w`U|WQp#9DN&-o{OS zfP|?#4GX>S`VuPNp=55f%ozBT9lUuE_Jo7Do80@CTWy$%z~LMYx&p`+r6e+vUB(`v z!@7y(r!MyrcYbC5m|d%IQdh#vC*}B$UZvId-IH6 zlKoydi$;+3Y%cqb#?A|`@znL*NnI7Qt)2ixXmS_mh_V1e?OkRa34bzhRK@GEhCw~)Q%}ZV_Rhw6@kmSAtT2=e8e=+Bv8wL44MsAtN44i`psDQMDq9GNvsA$t1W$`i z+m)7$CcEH?FtwJ^9SFUc2L#%!6>pUUjE z0)0QcR@S@}<%mMV%2nQnAFpGNghi9Pu)@wnb2g%&6uP|}bt9RGldd}vkq-_FlgEVz z2Y((>(EL%?sXK_{_Y#%H^6e3+9r8Yd0@Xmox>>7bE_quC&HmBf1`b=d$oReQ2g zzk6%^@iMy%)SL&dKMqG8S$;pq`j__-mkB#MGGMwELp|&Qd2$kxtE8%G`nx#FHdOJe zUDxz2PD&kQ?v5n@#Y+{0u~ol&E}`0xh^$REdA*cB_6Gcb;-vww@fQ&V9k{_Bix+nc zztYM^H-#4RibEH`h;GNbNjjGTHV}#6(W9@T<%FRSvba8-;reeWGH|exVSh14~>!puqEff8M|rL zSBBk=TK=!K-UF)V20^M;UcHSV(=J=RAcsmG2yks-DSK+R!#pXh$j~W@8^A}b@=b*@ zob_MwhO>o>kX>&8_EMrCy9k84gV!Gm`^-u-o45)Mfe+9%ToT$(A|f0$o@5Y=Nvr^^ zW*KzEAKDK(AbL-%hkQcM0EB@s_P~l(!m*TqWN{K{`kyN*_O(omKRgKs%3lkG=i@wG zKZK!BvDYKc=MJA3TE>@zGe+-mJB$o<3 zT=aB~6F#W+rHYu!v(DO4!)ia7)22KSLEoToXlbD5KeK0tcWSO$!p9l%tQySYA&2n}uyXcH5S_v~MpCKeLq3 zmw0x7^n6^^ST(9HHw~2+oL^;Cv263j10=jrb^u&wmw$|VDf}6GImwt#&<4K71+~L6 z4B1+wVKN7Sz(sZ4f4|47lbtwaR;S4*H&{Bt(rt?~$5Ys3#1mp@+%lXF&cq*}nst`z z&L7Skf5iT5Ks2LRSkldqCAYO|7p0UThyfHIHWffQ1ybu&{}^Jq3(j`P*zs>i`6)%h z@}pBsB;Y`nfMm3M`XQK+dr70Bj;N;BQrN56VTy97Lizx-|9u(_z%cS;!gY6m7L|wB zda>BW9T`MEb`GV!Evc&69NmKB+8XTq3o==p$njxX)1#oAN@ z&2WtXEL{2>rz3zN?cMnRJf$`9k`w*N$1{fVi=E`o zKHU3!0CRj`7nQ;{?wl4Ue6B10nNtXrj5i$il-j$vH5h8c?%Hut+0<@KmiyQni8THP zmz1s(>;a{yOjsmq#ZL1ge?`$)0#lt*TZe~BX8AKOPj9+-aBe%W=Ix0eV=~=bgVm}Q zo-=LOrXF3@nSi1Dm!Gh;wQWSP6A2QL#j21Qh(a0j!p;mFxiyMLAGM1zne5rGj39f% z6Kh~L+jK-=-_8ff2^zqK2+s2V{UER_kN3v+jeNJ}g6VztnBTXB8xT2$o$H-F%rbEy zo#k(AMB=d!o&zIhytlmd+i$a_4H3fIJ(4olgx-j9-$&%w41ef@si}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_l}D4?4n1#VGV48uF``;_yXviCmW7-JKxy(hk7_{Ih#h5wMj9&0_)oALg>&U_$b0(}q` zi6M=2r){QbEMNt*Fm~_F&IX}EG20Y?Zqi;!x3^HeZK3^WVHlTR$}Itt;L^{Jj;bW* z|9QCP0|1r}L8aeK!V@Ur$IY}V3Qk{gKAF1WD|+6li>l=nhf2@KTK3j(=E(~V2uIcW z%CRgkqUDjOlqd>^tB54ZlBzXplNx()Y9@d{YS6nI^<`*1y*_;W^lu{-VZbp(>lpBf znN07h%e?PA7pLLkO(&0L>EEj>#oliOfkG8&JL0D8kB7)r9<=#xIBOh{ognZF7*+SQ z_Lt$t7)-9h3m)m8{dGU}H#v>kSp!0{j?saVhif6GBBrYOTQ&3CecgtAIcb(UFn_s31>?fYU+0 z0oyS{^4R;=tE5{^5erbt_O_{YW#SCzPG(1&7`b#x0yy`+D@^>zD`nL5nF!JixDPO$ ztHX8tU{uJfpgidY%d&ME+M6hm2Y)t}JPNgV2aD-0p+}}ooA$eQVBo#2w_gZ}!g%f# zmaHoLbE<}c2M&6#kq5W%?%v;#tGy@al9Z%SKL!%$RYT2Iluq+emot5C-hlKSDI|6* zeTLb>(XNUiIctaYo`+G6)vZI+o&hfJIq4ZM6kj*dAL3M%D7?RBHX&UwgO*YP3cP~} z&U2wYg5(Zcz5z=4$jz62eR>#&B*dVue`-lHi-gLbhYd5F}?%`y<9 z-vqVfd2umU{_x016Dmxlt86f#F+tDpm)^kMnjmu>^0DN?tu;6c2^ph_>Ng}EwPJd9 z5)L2MWQA|2ymR6+?P2G=82b;<-{@<9d|+&m(@8D;J$o)9Kn1l208xp1c}xE+aJ24D zzV|Lzo8$Ce4Az%d;w3*c;XpnMtoXazJjhf*7ccJQC^YtnQXksq4bs~zh0|ZDPQ8GS z&$|3Tv3tj8fztSL&J>`iHOBp)oM@g+WKRgpq!;WJM*MwD^;7ov@Eizq@<5}-*s&N% zN7UfM{cg_upeQA3V`I}gOA2~AQCKN}Hl)beI57t2|=4}?$C*1mc~mXF}~KbS(fg0i>1 zJhBV1#NWkoEdf;TQTsV17o7#}VG2dL2g{cK31ATz172?mKE$3+`6I{|%-mPZNtiCMy6^6ur?*Qto!Acy5BAFArS{D)Ia^Du`Y-Yyd)5Ep zJbxp?3Z4ECcyCuJ~q=E#vdb z+za!$WsJ4p1nt?#D*4OTAUJUdvJY>25+UP&Erri1-F3Hu z6-L2%KBC1bc(84VNumvD>Ojlng62yeoD5PNs7ZI+J@f>@u!gmDCInrCbmAVg-F`u_ z2iCe16lGAzyMWrqk2+pp0|*f7(4}w&gA{!8qtyZ-+yt8*%^jse`dwgESA4AkDBwq( zq1Ts}v`87pbvh(Bg}ti3KQL}^^byGslkc!04pGdxnlQ@%Fm2RhT{#vn_5!TE^?bhk zS{QXKRKhvMl+$ttr1f*@{Y6NHt}eA*1f2t-OMrZd1p!31Qbg4k?xjn8h;1Fyq6WK% zy|Ua82XLzs93FLI(Ejci`Ia%~qL9{UcwBBs`+5%?LHWV0NZ!xmSM)_17nAF*?CP3PYIkj&?yrb9 z+p~(&&duZXfmJ!^2Y{p){^yvZ$o7qWAja}SgJ&HTN-4qV1XiLizY-tK`HrjW*7k=$ zYQPjrfhtTe4G~M(7cB6^6f{@zL=!cQ(fR7S zhdjM*=sV2bET+0~uI-^(PVaht|4+Lsh3gBSb+t=AQ*w#ulaEZQPZ|kJ3LA8uC)410 zHzwv-nGBLLz95Z@@j-Ue34~9GJ3gs=+zCP#bcK0whsOpK^#TjiBp=uJ_*oRToZ9+I z$s*?d{R=)mJ|rc1VKB4#svc>=>E1n7ZB_AbIik(V&xIlbfO3(9Ynf#lX{usIZQdxR zcP8sWe3G_Y$f?MYv!brc5dmkfKP+_=)(0|ekxn>5xR1X>gbjH^ziZo|^>~qeY7YMM z+W$w!oiW?@1ACgbqwKX1vbD!{hHrYje*|?O1soNN5G~g*=iNhhKdmCMM=H;8Itv zUfl*APf{Es?a-k@qw$4sAdmJuQ->$c95;H}TVo-XzyjO7Tze;XWq^F5#u%6r!oy!% z+38a-2ddDEh=L+%TU(n6LXaM~%;eUa0?i!TrWCmRg?O>d$}Wt#@7L0cJEzAfZuA%* zCE3b@8TFo1rkTKfUUF}F;goTCmMjH+RuJ-`;9YN9cgo7bb3K7+8oh_+ap)FMh z8BVZ0Z$NH161&p{sHv2r&DE|;WNeMs=_W?MaPSy<#%}^k9Lv{2%GTJ9LP!@@wJAdW zZK+G=zSK$k#2vPB=n}<`CDMkhmYevuOL;l5p5{e?)b;2rKn6Y#`y(f$Bc& zT0n(e0WWD^kqoF4awevzc@)i7h=hK(9a2hp&^-tbyzvnjX}vLVU@cNAJSN7X5)(J# zT;rmvI^t7+HO9x=Xe)uF;|0cxw0Qx~8~3R>Y@LJRQYjvHe;1YX@>;WYtvAe!B4nf3 zflK#+-Q1?Cs>;E^;X3*)8_q%xgpYIKiiKvlyL@>%izu$0pUkaY#?wu6&x^iJg_0Dp zjGdQc$JTjBNHaz)ATyItD3Y!cZMjb_<^ z>&bk{nU-{r#C%PGIk1rM&4?wvQS&gnZQ8>TP*x7?dn(%!#-37l+EP0o64IW#gS%6zGcu+X`#pvCG~XG5nj7oHre?T+a8tJ%iS8|lZJp^ z*@GizJ<>rF6^w8)nI}}`fT;I)*|9b#H5W+D@C2x32}vdM*uN5s&60w9;0A5!hx>mi zJFe#3)qxyx4JN)Pt;8)Z?}InYK(dqjSTu^)dEM@V>Dt}(OYel8*g-0}`)@|W;^)xlO+`Jk@O< zxp|)NSfWPq9|f>w4<#)oR3Spm@a)_M0*O4tah;7;8$30h7a&=I_ZVjPBsoPgKwNlNQ{AFtt3`c*yuA`{`}BRo-ux zibiDD1IUFe9I_ORvFKI(X-P3LLbrDYFT|HVue?qM5-RDdcI?=3Lh93YY5^eAb~oyT zV%PHXJY*lA7mB4w(Qf?Y>Yn z$bRCI8xj}3m_n_K!sn}+oUO*yN-$-0w+4`VK0-3W>ZNAI;FVGQ&5k=AlOt6M~?iV7%XMpI>BPUnD7O z6qE>0#;)@4wLHMb7sHgv@`jel4OEztD7>tk(aV=F8)3El*mub+7i@C-2=#Rbs4^%a zz`F9zE_AP*LZsg>(w6s=e~QrC8Lx z=Yn0ifn)P3z_{++$w%^-7YkOG-_jBpE{*_&fdji*DjPx=@ZGz2F+ZKbC8=)h z*h%uRHzerZa{Sdwf0-2k97U*HzfvNEWs4+cK8gK93G^VX(gfU9bNYi4+lfoONIm+4 z)4D0EHz@vN`W1(J3gP9SBELRb#i+r4q^1ao2Q)r$aB=0sSiL(Mic`%A)0t?f4t|+D z#;<7DWwSbTcGp;n-a8EeAQPlU{gS^S6B7}XKz$gNS9cp7BD?l;83g_p0np|Hp}%Ic z3~IOmns!<$T!zrcQ+X}Ey}g#jK@#JH_}AsVgLtY30t1pT{(+@-OE((lc%mk-xyGT| zDgj4+%kSr4+NPswd9vnIxdF&uArF3w7u4zYXmT?@s6H*{JkN=rAq>2_ z=@eGhBh^E9&<$mI@OiW9cWGm4o&Bj6ndx0mgb_czH%rIPI+Z>&_D!v5?mB7586Q8% zpvi>^$ZK|u-hxLSlzfW8un+aCwAr_y8$h#D?+d{w36Tds90BbwCc=_~MgkCVZU@*hX`ewK2PbEqbXJew zfkZQJPM*F8v0>#!hsM>^QH=^6OaBa=eGBmWRu*y|F2*h`66n5Xo!MU&_I@wOn7bAF z_lAm+6c#i9N+2BH%aC@ zX(Pq1O_)b-i2Ipa{dB?<>JLaeHp+CRHf^kP1QFP^|GtqQ67HYImS`c3P6u5h(UF26&8`j&|C3Tu3V3BSh z^)LV?*eg~JBgbR8boBLWZgGmCnaid3JJdT{YsRAoPS-ptMwYMgfdd?jpW9l}W#N6+ zKREBa2&7unyIxhKqWQ*lxJN62y5ojtUo<>u1;IEwoV835exxFbohI&;gm33PwU2r& zU<(8$yxxLG3bXy=#{_`JWl%*De`_v4Gay;6&rYXZKEH^lkPt~>Y(t+A*A}_@o~cpt zJxfw-X3Ut;12sRH@vnE3^3bW|TF*H0GfT+@AY0HaD!I(0CEU^9)L&M>y*Ds2S8KNd zCsKF;Pymn;Np1KQiE78JLd#3ZwiC>*ArN2UDJ?DSX*ZhKL=T_DxdV(E4)gF++UxX^ z*IA>#iExtOt@T(BhsV{nldn8j=c18}vaK<>11~qL2EW6}ab3pFB+81cK6)p}-n#?r zoBKdgWFFw3O-Pr#`nf_$Z%RW*NJuJj~$i5+IqJ zcn<$4|4l-|_sgUT4xQ)aI?wBH0CFa>AX@!?UEF*Z4T&N4+5sfPDBD2}Uw?mp(ZMC+ z+|*J9PN`#3)e&I^PtS*Axd1^PbExKce8+wyu&UkeohwZQigD8SJHaW9Xg;()D5Si&77*sz`-0j%ZL97;v!2+PGZQ7|HCc1{73E3vg8F!j z!Y%Tl<|d)T?EtHWxeZkIoZ%l`2JAu5O`&hm08oF%X$KI5>u5ag+5ruqa2{_bJAyE1 z2|8=IP;iIN0iYpD)*m+4*Gruk`rP-e%Q2h#KaC|s;El7x$MJ?ANeS`5OLjZd)tktD z1FS0_>N^w@tQ@=SZ1o|-TBL9HIGJC7O4|gg4bb#R*C;`jo7R0Q3gi7RP>E%f+0S<4l;^IN+Ni1ybKR14r1ebW2MLImN!-o>rGJi5Cp%+ZCwC~ z4ntoX-6hnn3Cg&K^(I=Fotq9CBPdP4F%iK31tQ#sGa&w*fXw0D*jPV=$rOlyP>H0q zUI$wGB%q-{-jrE93&_c&)(_RSF;0()kqM@PXitS{Kpq^P&`gTx8j&aoKpsi5iuYMfuoXP}IGfyNjSi3#+$dfM*C=ObOnCn+gOO)b!V%l#w(geb8t zghK(vh#tEGca5^$-#{r~F>FDxc67C&6}AdZ7>XGFNQUN;$A;Rq7qrDy)Mcma}eJ{T8;`sQ~(!HsN(d*-!793a@i+C?Zyo`fuHobE`_l`FY$&v*sH zY`37-$Z{H)bvm=>TB;B7LzBeU11hOKNIQ6pcEi*0rCYvt&l?zbYRy5I4fwCOP-15W zuZOQ0m;m17k0S(9TDClB4+MRqf(*Vn)wkD&m+P61zsN+ip^DSBNonHS?x;@GVisUI z+4#r2%%IK@<6q7zNu-Xw-a6k8P@azuZ+)H1Cof~@^x^Ex6vz!ok@xk?2P>>$D>I$J zQ0_&z#fuy8BL@op;jP=Z1;Ah!>N%!_43Ii%T%z;f!d1XU>N6mdT79o5RJs6ZZE9nb z01zd$(Sd^1a;QozAa8dTj*h;aYLpdD@h0f^ zjyPoA>Lq^?M$-BbvzZDKaj!I0EnLRGwV2}6^GkL{^4An8YS|d-<~6?kuVzyCA5W=v z8dmg3kvnE-$!#@=cxo+oV>)CJ4>XE;d{aMDjpOfCDm)(h1Da2=Mw>+oFpK34 z1F+W;Pi}3*h0FpOlX|CHl_7`O2n%KTsE8~Ws8{|VuJh~c1N$Ta+MzS6$+C*UW#Q4Dfs0RQUGJti>p!n$+-QNcID4$qCiFPWO8H~& zFE%QO5_s4Ocpdf6R7<0Ih>pRj{qux(yn_~R<6gGg*@Aqv_C|*eH_mNB+eO>oV%o!P&Z5kRy+9{+pfvle?a@-|$hcO&qCRo3wi8d)#Q|5~= z-J56ea!{i_Y>iADB7$VDXQsp>VTEYM2wOvf+}pY5Jml^@-}e_5VC4!Ckc~bV;o6st zXBgu@|9MsU+PL?H(xEC@bsG>z6yg_AXEj}eZpkEyighSmxHrvnjv$!h^>sibkv1NVT4Qi^}v&x?{J%(3l+ z!$$c5-1g`&b-pqll3vjW>&rfl1-1;bBh=C8&zEsJrF8yNEBGi?D@r`pWn3N_@<^omzrX5(Hn>U zG!}ne|M;~!rzSsUe1M~nEU7>>p}-^1&H&@^a`UOyAq3QX=w7IN=6*dNaxP*>$nfX{ z=>f;*t2EZSTd!7|h6zY`9Dw2l`?2K5lYJJN0H<7CO7n;Lm4Z{@b+* z>VFp#vM7f~jT7^SsX^6qsVT<)eCTo#5Y4_{?U9r&Km$h(M8`{7nHO8cdcOkN3`j~f zHBrAklncyntiVM)YuF}D%(As8+xiea{`3S69cJe@oNJmW|2=(4UwI;GO+DF*|GaVp z*MpaatdU-Z5jtNqB8PXO+pXJ0Q&%_m?4N(Ib+Rpt#*UgZ*BWJ9FL(rWCh|Jghyh&0 zPZ>(&gg4HU>v*_k&6?+jey6Xf)I{O;>iTcgh-~s}XwRW6>|vG{i`8ZRX5osznz#M+ z!5=3-EWPRZ+Ygf#IK891W%8)eJIj_&UR(6e#RZcmfZqApYw`rsJF8SCJvhC=_Y>*Dp!YVgj9?3T`$*a04GNWk%DC-V5BvKOvA1%=VmA; zr`0hSiADW0V=0c0RrD|fB;@=t#`9TNQqL~|_?io-B8CI$`g|lp`u4DW8-Q66Lw`5C zi#la4nwQ~S#_O_FT6 zzB|_cj0NNW%)uB^8t9Twec9W=KQzPp`9iZdD}<)oT5@u#T547~mkJ$B(4HY2dqAJD z$SgPZRL4H$_s3$jZyt)iuYPv#KK+A1nsyevyvhqWIe6v@O^to9Wx-Unx@`Bp@gpJf zg1_~J$@3^iE*XDu%EcqTW@~3Fe?8xSZgiu{qa=lzyt1-ANV-ifhB4LI^;BjY-7^O zUqwSLBo7%mk_kuvD3A)fnFCeAgfBbKcls!5`H$0drcYiJ#*1z-eo9Y(p1XJiUQo?{oW5Nf3%+|@#NIDFfdJoFp1t@!SGfUihDIz_tfb=v)2k!Er z3Ke0&00Lb1`u5~6V|4f&lp36>{6Pbt5PyY%3YibTu{War<%6QVV8SRj8-X?e$=X$e z3)ubfqhKze$cvD26@8sw2^vf9V##CsKwnu;CA;17Ju1b$sF#6z#;h0s_q&b?&{T8= zk7bc@(`Y*Cx#;rCqg%=xs|h1pr0pw@-#t z3;FwX`bH6y**RT$JxW<10zL<6T-`o?QaYN!*z=Xc^N{o&O-(j%7K$x@>7PJD z<=cxTj_#p54H^k81WAC6AieT~HTL%oQwLHnP`n5frB(R+d_5pN&Y}SRbYK z*~ZK2A}H+mc6<+Vb{Xmt?Sfsyz*kFnt;lG9eh(!oEZ*vR~8(>b} zs9;eIFzi&B?i&E<(ZKW+G@S$>n9E1=(DchJJ}-P`F;I}jHK0)vEvUEO@?#!A@q~si z%KWEfi9yY=R-Llg=l%MWnuVwVdzAZ~~X0vYrQ;bC^>cz&XGL zmsji;Z-%l%06~y@c7ldO;MRcp(NEF@n+S7sK)sl7T|fhSVau-U=^(TzN{AIV!`~$W z7DXkv_HbUnWMP0Jh~5rNy=mTlYG!?Nq~*a~&isK42mm@<~|Gg#C9M>XN8I8FlW} zOM<&2^c$>LR+t0-?3_Kn0T##)$x9pCIuzguyY&dhQ*AH>T7Q6>XRih_0hY80n&nn+ z$BGW)W|^qeo>$P+;|E;NFi^Z0+)zCJ&c_I)Px(INxJvYi1IWC;%EW zZ1DTD1*rV}(p*h>i6N)UqZm#qM*5L>0^75YcrN=!U)=fvz*G$Hi|6lrD)I8|Oh zvI}&aECyki4=cjb)(}(yB30~aktjtEG7~_s`?H9O(gdc7<+<4Z@x4MqLO`M1e)^4& z+$b5pQZL)DW55aUnemxEAZTdW8796>M&+4MY>mN?sgguf%FK7V7@#8Eh;gFG00URs z`rtOWmRr_AAfc`j(5oe&BG~*Q&0=&aGS@J+vOy!vn{3Uf9+2_N7-}k;_pOdd1Lz?N zr7lrtNG;nHNtUmQ2*ww_FDv`BT2uqJJplG(W(yU%390&0uMT);!U)eTz7LoJ>dMZA zmJjgsDNk+q6>(tnYV(0m@z3kVAfzBQ0o=~^)^{cu2~OgB6P=)PqwNaFiHX<3R0arAkuW} zh8&B5=M1~%2mZo4aIhVwiphVY5^CQo zWz-lLGzsvmmk@lcF&J1>$)FAbwA*Fji3zJKRQc@-R0&oWzdN0hUlV@+eYhy0j(`g+ zl>_Pe1Ps;fWiJ2B1Ae-J{ceh8Zr*(aBm;X}>qQq>?j7JJdYc1>8@j_m@#E=qoHlo^ zy5S%cD4x?}9U$NPGqFJGD#=z7g{Do8<*HviFy3@DE7{cn{;{tw0LNwSH<5 zJquO!7bnggxDZ632G(;IJPk$wI$eTB1M;?eHS5YS!?dkZ#2J$N?ddH3uw(9VBOsD# zVI1^bejl^;d+~EqCtMRC`{V995(sy=JsX<_Q@CZ z%-6(lqJ@G_m^lb&A#L;g(z3-|xDLjJzjaT^H~TnJOYlRm=wlqqfVP5|;Bmvg$yZ=h zh~eR;Lq;S}rk=2G;Lq z;RDNS0$qfAEv{&5-#?xK#tn>9_-VyTEo_~JlCf|GqxWgcT*i$BuAdl;x1aiEGA>F* zqCEcSTgGNBiLZk*J!{Xy0Q|CEFL_mQH5`zO3h;5S$&@@cw||arZmh+kr$Yd3|H@9c z02{QOwwPRa(*0q0L_{(yx@rVyD4}ALT@wrHe`GAPQbd{mY=byz@qc~U6h?GW%iPN_ z#ZrT_84^iXnGXwa7<DP{gm5E;*EV8TbYDSsBuk0@-a1ppbmG?$irsugRePdeIW(Szy8I>z_iUG^hyr|%y z!c`|yMkBa4_^a-f2~eWGEXBWlUjk{93}pP_A+XBI55UKk9RJy<7LnoUUDP+mz#MykgmA(D~LWg<=z;GnC3z(}rx!^_FuLWSPRVeX7-rm3KQtT-TQi$5Tn0&_YoVWbo6!` z+=Sv2HX%0G+G~k#PQdtM-&h{qEC4pqTYp9anL1#N_P(gga&rOYbVJWh?KwGYX^t+4 z+xHe0pK`ofKX>woxY4GzXSY_{I=jivqQ;-StX6uL%9PV*vi-b(smEMFS7)vbH8Zd*djf zbz!G7S|DDudb~g0V|9dV=c9MM5iGDkiKM`a{xU^hHRsKnj^!TtaMB|l2q!=dRx zd?66A1Ze<6@xEAut;OIw<%&ZPtjMJcuH3>FAcUu!Y(Jb`Bv8x`K?3v# zP_665CQTwzo#Qc9E8-J~sSQ>a&6KbkC%!8D(%@?kki#i};6|9!C*o?UYgbV?OAF&n zA3VG~@Cw3HGK|LBbP_;0nAt+?UtGIoJt0f~et8TcjF$O`@b^c$im?nMSCH4zYLL!$*jhnl<=GAL+KUfKEpCbj^ajEhd6h`s~2Fua&0 z_%SYzf)TuprS)fc;|y~}!MR+JIIi?(bcG?!B|4;*ECF^QQ?P1$3DmE59UfI8JTJhm z(lYfp>4_bS12{B{j&=%T8dE0Fr&Efuon>rM>-urLqWN3iBwa#N!MlZo6|Nb%J4ba-LhK@pVD7P{U~h~9ue?h>iT(&n zhuCVql&tyGE3(|OLJD)dvHo=HcB-PNxP>v5Q5XzOE zX`#H(5K>-?>F^|OY)>&fOcHxoi1R?Big)rDdp7Q=s+q%RMH`GA6n`Yt=phovp7BF_ zynL|&9(Ky3kwgTNG$uH7fht}Cfx6SMN)I)I>xc5C8k<}wiMrZT zL)<&$pqQ-DUGV1#R|)|UMG^%d6HBKQ4sz}>ji+##nYd&AY?f8WNZ){|F~Qj)24FZ7 zsUGP*Y*E|?3s31p2G(N%c~8blsHQI~4h z)RunJ^|iit5lEi@Qum%l^|BHr)S^NS9R4)qY#dtX**Dpo2G z^K2N(!jam^Q^DwXLU~PyjNNepsig_g4@u&DY%V6iDWS>{F6a}lO4RYl8zg3)F_j+VH&o^isK(E9qxXwtwSXwoNytU;Oi0%;w3m z$r#2elSmTux$hVGJ|+yt_jSVfzIVQxg72o_yD7k#_}vtIHwE8K!FN;e-4y&k6(Cr= zP6s;SPb>hw^Se9x{S5jZnKHhgLElZm|69%=&x-WEWy0;kHVv~vGA%ecRLnT-boRYp z?4>zd{4HKnG^IDEl# zrmoe}=$mQX{M{GgHHXvYe(iLB^365oiBMY0*Y2>9`@396oAj93<+cAMdhz`otcJf| z-$&!`p}-H{N8|r^H1^(!S;TnDBn}Xk52aU9umq4g3hK+6kYJ2G_?THz0_0n#)bjRQ zNIdb8bSt%91XkB~5ji6bbLD;8!uHRVUvDBZh5?am9I3mg+%KE;rYkop9Tl z2M-=RVq<7%Nb*Q_DAN=ujlEOKBXF#D=4JXqJ&^QUeS25o|lvapnQ@` zrHuj}`<+w)A|%&Q2p;YCV69CoRbwn3*i7^Q(qKgOOSh|jEwoukTn{pdO)1%9R-~jy z8qujAFRPzOwRrO2K*9<_b`jJA+E3R;22ogCg!OH3J7-!fy~DRI@pjj)J_KYF9c`zsEArj`IG^6+w|wmP~IC?18S0?Z5_`ZZjj@_2+(qxXrk9!a{X zwuhj(tzd^gDB#r5*IaJSQg~d(_-VwK9{%2)h@~Wcb2dT_V%ajySF}t}$>Th2eUNx6 zgfAJ&6Ln`pl`Q6=J?XI#h>3qB!CBJS^ zFZ$YgJuYyA0$ShQDIg?jQzz@7abeJIQq7+>k_nJ?-b_{SiJ^cAQknF)L+XH^vFn%{ z4#ML@ATljQVR5Hxk|h)}Nym+DmkiOsu*<%)KsifLoj*4M?Mm{9;sAb&|1|W!kn6{m z+>YCA+O9OLSpzgHsRpiDw{EArJr<-U6#6i8?+iPQ_&~1lB|J3olL%-3Y@Xb@_HID9 z6v!UUm;a(n%AmR<*F=r@NXHTystUcmy+S5dlPAy9ZA)j2A>+9p`Yx0cH!C*+fTvu5 z`5l&w*9Ju>xa6Y*y9gK|^$tB0Vre%u8%XXaxHYNCne5Iy-Osdy>GfmQ*RWA7p@B=t zbg|Q4Ki@@nZIf=orh<%76&voj9ZRSQJJlc3P2FPdqeH3aVNl2kX}i0CB81r&%QEG2 z0jhs=ymDiEH?5W)lx;gZt0vzyV}t{9@(bybqTH?C@eR;6ernGE=|Yc`V#Nl}X^q%2 zz61hKh)2&aMWCN+H_6Q^7X~# zTTKAzJY0q=FC}{o1>nv%-|*@g?JE(?8Y94`7?eL1Hf6_i}UPQ5|g1XA4v4Ot3SB@J+^^UPu`-YyHWl-I)tI_ z3{Cv#E#@q^ulHtCbM`z#=Z#h9Mj2Ys7g|3mKy(Qmd$geC2FhQpV+mlQU`d>e|FrKm ziT!U3-Wl8vOmaRz>FMS60AOVu1?W1sf2RODP%I6GMTGiz6)G)C)H`%=95W0LiUtCZ zxMR#!P>j1|17XMU!@7$2VYm z2+0(b$TCaHrvx!eKSPrg9kw|h<5eF%RqbOA|AbA8?DCSX+|uDdqL zomy%@npOKyA8F~WhhSooA?z-Ixp5Dj(*`aWjjpgP0lwfwHtCc8{ZgKb<3{rNm9<)p zK*tCt)#1oTqf?Kw#XK8~mES|*_SG=X-5Av`eQ496{s7pxQcWN*W`_bHnTf8OIfk8A z1jygPd}ecnj1^lXU&x}7v(+pbT_!h{m{xkorBciZ! z)aMZx1i7a%NT0Fk01PGLwrYR}*!%yvo^k>3Vs9r9(XJMAIS&v*Wy7=Y zBz6Y1y9k%~(nb8BBn+(DLKpH@cT}+e({G$+#|Ec{%K^jz7$CcTM~(-o{NDW}91OqR z{>iflQb{*aC?DjyG}aZfl`#Z=Qtd$sKD)`WOJA+}zt_t&5~H@<4S)W`ldaChq9qYQ z>#KLAWu^4K`nf67?HvK`iN2#ipuG2So&2mmSMzee8In2hRN331qHl!Vr*uaS{pvQL z^Hx|zpjAoCMXNiQ%NE!3$Hm_|*~pRTbQc;pO6Z(}H8XKL!&^S><3=PW&Ff{c0GM+}PY44ut>2{v6;XQ+( zxF(s1s)7=?ql2`GLUqLc<#Qc%c)L4ct}XyhFOO5eq@E~kpdkl6DvcN+h6Wbpekl)F zc1>W+4)>|?d$2Q<v&9V?AnKy3nL&8<_ zT~)t6U~5fHZ*#DLx%b6kFrm>=35TnZyp5{IW2P*t(%4b$$mY2ZVVrVLBgXr^&b0aa-fDB+(M>u+yxotk#e^P(m8<`j0irPi;){Py zeUHe5<9=ZD5L3qg>c{X5$;ZU+St4&gX)c)4WV{=jBQt<8vIz!$N@C{ne^&eZSRH!#h12O?md<2tqiaTKuhB;9)DP$I5BCYh7LX79fYNkr=|gu?`i#9| z76 z|J*!pU2RC2pJ+`!7cQ`m>_S5|B5~4zd0C3ZnYf!a-Sg(mqllhNG83of{JsC)p0=Ts z06DXWu-He4enFiigr;GYPI{GIqA4X_sfio>%AmvoV1(J*D+eCTwn$AsE*{fZ2g)il zRzOHEIB*KQUjdDfD=%$Xm<`IOR^u4X0igWK0itmfpLsxj3((fN5fU>!lWJ>`q=@L_ zB?viodVMuc{aa{1L>i^JS>$CQ-fn6*Ge0i6Xwuy=7z1<3#1L}PvV=I*VO@J7`U;cG z4;LnD#dXKZi^G2l?c;Sg2rdJfv?`#7!sQCb=gZIM;(~Mz20dCb`GPrF& zen%w>8Nk?RB?dty`Qm3pzG3gaRTjrTSkT@T(?*BJ%hYu0HVL=Jq^l;)+YOXy?`-f2 zDB^EnrR8|K1z}Q{oivb?E7Q_lpNgxGvUmBf`?auCm$< zOS2xj=8aC^hAbSRs2GOO4{_f|GZyEVk)=-GgM<~~Op^4b@EyI~;Ny}ef5F*Bh6ir;u}sMGU3j94IAT|q0kXXW?R6f!4koxWVeu0L zJD0zu<6UW@Pf2h9@b+7OwD?n8P=_Xv6rr9i9<3~K=c4X8CcEK^6DQ9X1j1YY3bFPm zVyB*=eh#~o#=ho8AU!lY{2N$R0%g=l2O#G7*THEQ*LR>>R0JVPLP#+(}4Jtr33hpO1D#8n)<8`2)@KQjYG%z-jJ>gOVsvf5l z3-Z~smcpc0=svInPMc^_7M29y?z`~%R5r_cv2vq)ryWO7bpRWyMdT~DmIj`nE=aDbwRs{V>dh(#oYM|3qWcE zIC26j#L@SQ`t1&W9wiZ&IOx^nMqrf9=B~J-fix?zJiHaq(8Ew4t={0H``0RFBeGND<8q61(^O^Jcc%YH6GpzREp=Z<$dZnnSO?=ifH1A=j4uz0B z$ju@;18K2P)0M$vbzNk6s1rbt6pNX=v5Aay2Pt5@LO)g{n4>nj;Bo1DNTEeA{N!F_ z##UFQ*zn`n@~2EDQehd0n~C>vqDY<^i{Ojy-i_b0dKV%(Bb2=kECzKmzvW>hSuP#8(G3a>XPun#i9t zBk|;o<=6Z%7I!P{4^e>v{95Y+Yw~K3+mDQAid4^`HaZ2=Dh3uQ{-QX!EkvQGc4icF ze|#nJ1btVVu=;(m${zkv+<`0~@o%Y_&}=!@kUWI$PK@dw)SnY;ib;Wu68D$=be)=( zA{iz@f!pl54dF=Ia+2Z=o!pcGqP^8AzEtY?Vvvjv(-PViz{d+K^z!NL$wR={=XffH zsvylREd|&~rsye0B^B~cC^aPp8Yy*j`X3c8qLz}ILVUAZFdRY2mN-XN1isi;m2sSY zL0h1S4kN6lTo9bOsMdrqEe~cf3jIk|tU#+)a%QLsmJ2h-O${umo0ba)Pn`h{?o;|m z?#M>6SQ%yOA28TmUMv0akIb!@^1BZ7n8dpQcTuNbh~@F#Z=i+3@)o0Eg8koQ4vzoo z2JrozNrUG3eKh`mIvV%1O6R?(l)gPki5&;>epzzc-oI(@|lEMgSK#-4$92*Zw zE=X8aNfgvi8h!le*`~}${Rwp(KZuU3r-O!+r>L_gT=3rc3c)*%q!h11(>bCRLtrjT z%M!O62A8zw8UOf(VjRda9S@%k9P?nkZj9iR1{ zU0ig+B_=e=|104o0AX-<|NSzhQI*{C$2JpJbab<``+RLmYIOAwhEv08JL-{3>VM>8 zlQ9+?WT`?kluN7bOwEByfO-tK5+b(7k@^XDDoAPS>t__c?k*mWzR{gBExmbctz}BI z@|WV0MR2C628|+b9$J6*QU0{JizNbQc)m>8J>8SKrl0~w-PoYQWJmoZn`e)8U0MG; z^y`uOTG{vq;@RKioyF56+e$l4_{b;$zm=1Nt zrmRKxZ?=v??R_>?rQDuKb1kD@k8d3HNQC+=g;$T-p-rFtz^{{@PpAsX`KROW;3o}y*8_%&&GQQ42C z+GDKT!wJz{`M zrJTrSrSCIbq8;{&?qQofXAU)w_NCYxjlsv4kB)RoH+TIsYY_(rRZknKNj;>nGO6l~wCDX^ zRtX-)o_Ufh7_NouQ*z-zX3raUm-~sE&1lw*L;Ps zVX-iKxHO)cW0H9y)X4t${U4C#SwPMyK@_l#C|hVW>z99RPWNN_44J?exg?WE0+;KI zvgFVGv}7SAG;xu&B*jP!d}4M(yJY2x47Pu|`_YoR5pqv#N&_ASz4tr_e9!}rk{P-n zAGkkLJBUCIfCdOqVlBS@2i8@f+`nh#)EwZh0uZUu1fh7s!o8=vno$QQleK*@I0 zp7Hdssvf7`g~qcBeyN@Di{=aWPXCzvsUZf!bhGx zmxEiE9rf{CE3#hiE@i@xMqGx)1l;9QhfO<@sY4@S(oA#`HAcn zvZ=?nt93Beja!8xU_PwCYP=cMnhU4=ixYlj_P^iZVEcdlJD03==kF21slJeuf=pqN zG>we-EkYbBl7J@3ndidAI%A#cjEpl&mo6nF1XGq2wOUi??DPz`#}|Z1T5ggUE>gR^ ziVCswJebXw|M~mQt&Ey<mluy_W4u2!paXgHWTA6~mL}86UrK@<-1U(g9=!(NK|C zdCT@o=qk1C0i0}&rvF?IKY8w5#jqx1U=zWBNX6l;L{UL@B18FRV-8VbYJD zdIS||#D^?S71UpS6JPr;QhP=4^c)RpJ8M^MmGbyWyG>y~utNn%YtdmR25CeRnxU4x znudnfj>fEaQpY~UmK_e5)ws(|1CMtSeyh|Pk%9FBU`CKKjB7+iyT8b?+JiL)QyaFS zl_m^vG-2w9wI zWxb!z>+o6R$+9Knc3oaIF$P^gZ`dZdW(u25GerRY`TV9}5iG2AC`PFh=-}<;wm=v(nevYu;9AN0NUwkV(UUvYC_Agt&U&z(gdU^3|M?>N z>9a4c0|k@Was0rF@yf9vFc^&R5Ju`7Lzm9|wv;>WZczKzU%$d%E5ZTW7IIrJw!F0T z@CKHwD=rYkNY#WO*VBHS8R=&PS?}+LI6FgnDPToU`=Qf$^2;jL%bz@g8HpUq6QeV9_z;bs2+q768^0n>{o_crV;{3U7GQ{3W_<2oqP32)raO!EKeL||vy8f(ZrLs3WW05Vg z90e&^{jo>bY(s8S;!FmKHdB<3m+WSpCFOey87U@6Va{0DfVyHX+Idroip~MwJ1n_j z#*Ozsc%}ei^dqUCeTEN%CsezvqN0L!q15Qp4mF#6I2w!L>G(lh(f7{3>rs+9WUr^-D z)sU{`psv!Z)Gi0Ohn~xk)i`6!`W+RTQyZ+PfMu~q}#-<-U=McW2@z*&bUgyr8^BOWbo}QVb zbA>g!$QfD9u>L?+5t;05Tem)wdS;X$%6gBTn;A7U6}|w7AW``K*l4xHsFiaZ>;w#* zi;A;znlh^k;yI|os9`=mprh*-PbBMeBUR}-{4Ua;6k_Kojee0q!aGV&T1k-gySf8R z9>0OF--u#Bt@Y^0z1?m?)DD|eYt44Ces)JF%mC>m(M-?~dxW0L2Byu00-Bx|yWKYy zim@*GHFns#BrxPqBQXx_wk3d49$o+^E1r45dhO3UpO`5qCtSyewXu!1!H@!J<>SG6 zz0V79J@f@G=^hRp;btQwA&MHV+NP`@d;Q`E7(BzwCrpD!En80yc7?w|f8xonlTx@C zGVbeA-4QgM`k!V8paP*(0;c@$U%PZZ)_K~Gd~4GGwrQx#L|Z&5C4kz->#PgLvv>!i z=IH0wH)oXN@}2V{ShuKW@lHm~X8@5zQw<@-|1@y&oukchFid(lDiTz__{%6FyMQ+2 z;UCOcKYLOD&q>pyZ~JrxjAv3mmM5hn{>wyF{@@upR8^kE1v%Ry{uYNRS*YjSf+FR! zf6o>UGL4^jWHumVNGTP`dHnb>;SbFvI9b0s+#BYRQu;!|!hHp42A))%%SY|&(tq9L z%&84rz`n9U#L$+ix!G4QctYyl~z&Nj{tv71bSSh*30$<2$sgHde%(uiOd&Mj``GkO}m^avs92EAQdS( z;?24!0k!qt8JH2Aes-@n&r-d-DmKFA3A^pPCX(7Baq>Ko` zKStGgjIaLt^i0bW=~G(#t9$>IE_$edQ9W2aCG~Ja^;ajo^qDDwZ^T%JQn{6lvFKsc zAuF!s*4qF29i#KUdKs%pL>G3`Sq)P=;#jSkvi9_x_0bj~{j5h4z`tn25k`~{cS`YfN+z{2@wTJ}6+dgT`_@Rxtd%oRF+w z?u&ie+WA}OD_rT933dT~j|nmW1|=W0+(bUsLHCpr3TDWxSfTOmK!%eYp((^%hrW=? zSb3|%^l@a`_=vc|13YaH)S~6ll%%HBoprHz8tAIc$bn;#>#?-~VyQAn&6z@vjeL1k zoNxK>9>oRq0=FXMlRiMm3me$p<#+r+$-aQte1CC!E8|k zL16}YdPljYw)opGhyMnE@9tc}0Z}ao?y2bQ-I09oi-U{mxg;ee3EEF(Gnyw5s+#^U z_TD?Js&oAU+}0R7cEO50_JRmVNyLH*Y7|gWF<4NLCLk7Cn!y6tiAqti(?qIt6N)85 zXo6G&D$+$mlQwIedoyt#oq6V&=b4$`%$R>}E;(nPy}$jH_g(K=>-FhqHNO8wv9ai0 zEvw9os$k)NHoHmugQ068{J+Q@PA^41Kk%q|fsrLgVTzuv_w}C38v6iVTcLSC5^~C+ zu(PvzH04I(myA0e zU4(rKa~ZHad=gPP&EK(8JS=%jF=b?AaF)5!Zg0lD7pF+QqZ)|BZM{X$znN{OnfU1J z)NQ~{W<$Z$nun8kC|bH$fhE2ai0WH3jDMeqnIeN>YhFbq4**VBG{b|UyJIN~>HYn)bH&2%wfL5Gxc!pM0~@0QSBEYHGl-?` zQgExE-4c^_gg=8BQyt1T_Hih=e$o6WtpVd8yI8V#agv^jFiC5`?hErM$*#QMtwI(${WFp89FdB@mTNrxB0*_%>+>&4d6&>Y$q@-nMn1mL)pDHCFGhup zExRk1Lt>V+5Xg)ow-Tsh3MH8siS$4J z?2kDP6lIj^p@!p-JdwOgT_P<%8DlZrql5SH;{Kw6cQ%q2ioWLihA=Y;9Duu{#N+5Z zAZtRUcoZbf?ZtV<1t0nxB6)%tix2W~E?IrV4N znM(x_3cPTaf{sNC-wo~}rKg~Aa-a~wB%6)ZW~0HzdI)S;W&orX#;$JuNL95PbHR2h zK@Sd>PF=bulI_HfZN#9s^pRoPsl-dIqUg>5D1Z;mhbQ8~N0ImrCER$3c%Dsb zGMnC@eQNtJK5JiZxmWlT3SqJ`6p2aXf@%%H?nxw#LH+jZud)wcl_1=yEdRUH8*Vfe zS+}fMuR`;xcUI<)m)RLywlJ{koLcA`c1R&M4TZx205DuZQ(8)E6m;hi31-z(@xb7sVge?fRwv91$AH)@+-{VK8dcY}lXq^D?9Fzfx3 z&G7+$M(ntg|8$jUh}qO0sR1)_{v#nCN+um6M!w#CEwSRkc)j0CUI@fn!9yldvyRhw zABX|b+UXXl4c`=*RaZriYc#F)*6x^OhcLxy@gBH&an=Q2!xb|_j1!b5&< zCxc^-r^g?G13!)bOCn3%j?oo57->Om)^Mmi!AO+HtQ-@9K)8b;veDDO{=XDw6i9-Yi*C+)PF;jn6}xB3|m;ySE?` zvPdT0DR>>jzy&?d8J((J>HkMb@i(W&AAwFZ(Jt=UqO=s1Nx`caLFOrPm1(4_+Dlb(69R7_mY=8X3&{~13?$Lw9ix8? zbiqlL!OD`9%U!i$J=qJ?{JHc{=`0R{s*ILT6m&A@;lYC_LFmujkUU_-W#0Ac&r^Gi z?obMBB+%-XAl_N3WRdOH0AW8ar#J(9!4SI78)3UmJ9zcVESd+s7NSGj>zpoBChL^`Ico_u7ab5gunCRm};;En`#keZd>jup&H zzzTSBP@LEc%J*16T}e}Mzw+HP=I+&+;f|Fyk1Y~jWCVW zlK#slQK*<>kw82p@^UmQMS9gQ6aVm?%@gE=Rp;kSAh*2L3Oay`-R_eQ z4-1AdzkezIp{=I)a2at~8K%Z053xwvdJnsveeZ>UXZ)9lXM%IgseaC<$3JvROG;3J ztwOvJ_(TMF^@5JLu%gz|CwB?3lIB|N;#*i38;*;gTSH|^^TB!Anf6&1$3N8bDQG_T zmj!^NceH5m#ZJ!_s}gXV7zw7i&Fe#mFI2kaJbwIG#YSp1xLnlYP0=vbeyD$|Iem0 z3z4gj=g+GuJb5TIrX32ORSQx6BN3o12b2B^PJ+>0-4XPWf&%EmAta>HPFmDl80q@M#VzrmYD=0!FihH4i0oQ|w1K$E0H@ulSK(ZFYQ%R}*NX=+x7%48 zVbcTi=;|Sy(L4kvcx)OVBf}O598!PA(Ys2RCHM9D8#M; zGpH0?rNUQIz}Owra+^+;V-Xe~0n$3(;PK)Jty7Y25javT98-#bDeSSWPCfdAb&jH{ z{^VsK1^{lzzux%Y+1>6FtI{thD(c-A?O)#S@zY|NTMw?^yyWZ>+1sf3-e1d8ZeJU+ zdcHyRpzjiId8NM(J-Q<0{u;kQS^M@JTQNu`bfaJBQRTkAm+nrP{GjBw>)#Aow0^*E zZEdp;cVA|{zUE0E#h{#b1z)^XE%Qz*8m8wMM`MA?6FRDA9SB!Wpwe;W%1p zV-w!1dk{FQ(Y3mEl@>{ccI##jis@)?NvU<}XaQMwRnk83bhx>=tMk+~y2}*LBM{Q0 zL<8O_HQ~l+o6#J;+Oj#w$NsI>wXl8HcFLc00pXWzhIkZ57mgEOD9lH&lnsMOo^4$h zV9Se8ojPq=LCv}6)E}WM$HtdW;$I@IyMhW+ou6UbSAA9g{?jHxyhUgn?jh*U!ahbf zC!Xlo*fPHL1!$HI)mydso9VC-L8v*CK_xL{P#Vcjo@e@W8vCcPjS=fqpeXyC^A_LX zO;tQ<(-RBFkm^Q80Hj-@T_{(;a??WS2@|K>@Ekzy@y1H=H&?fODd=OO^`*8n5<-r- zh2ry2uw53rQc?URq18()kr9L}`OXRA53N4dL+a4bnEsKCUzp4Ptryz9SZG4~P6DMn zqg*$d;lQ9AYG;%b{p9w^!JVEH4`V~3Bve2K9nqA}tj_w1?}czV-J1~FJ+x5~KlHkB zQ#%7fhU<-_V+%W$vqActLY-s;b;fjLqJI_pYG+o9zk27`-HE~onUl-LQ|r$hl|4Qw zHu1Ms?2Lw5(`YC~VGm((+PIXZim$NM@SJX^=boOPE=}=c-k>L(5&AB%C9|a03#hll zYi7ifCl*__9=PrtpR)1 zfw=YWo3HD@k^_=ab}}ACI1koQ^5C`I%~TTK*PYr2M+HkHK@ri_;YPyzNs}fGIHE~{ zsuh;?5;A15?C413(4Z%wqQtj8j@JZ#g2f;5+?L`FWm~n!4@gIf)7wUzb|=)}@^4^j z=8NTr;ggpS@739(W7DXvI^ze_J(?P%iO7RGZ#R0~z!!#Xmxfn5>2nd9!$;~hcm^y) zSV1$GjDMfnr~O=QbZaBw6h0s5rE{{yie@4DrsH+FWk0hM>(^g@&8AasJOjYZv+J3t zH{=8tGbB>1%J||yB@;QBJ=!U=rGM47mLo0{;FSe4%Nq~-u;Rb_u@r48ZSv)BeMvJGog5MTQ zhln5hDo$RE|xkvn2JZL)l}T{6)Y^&b+eDSd{w49q7sOC%$whO)qzX% zr4&K>>6GZlzt?3`dQ#9{qg&S5u>~%<0e5PO9QTE7X?_PECF%@0o7)iu z_mrxfY(J?yP?(VeoV^K*n*nUz%#4s~Sdgh#%66aOQIYRt*Sn=={h<^~OAzWysLL(| z>BfyEO;YPGs7TdLOf=h8DxT0H6h(0x^b;e9A4nY6kPT0sI`x>#&3Ro%$mDn1*QjS( ziK{A;YDYZ*`zG$N6^Bzdy((;k$W0J3P_~NjPnKF|NevGm&RA0Sf&CPjo9kYF9=m4t z8w1qZNaXays-bJ-QvATT8^!yAbDp-a{|gp<+1ifmpe34#ptVSNVbo`^lXD7i(xGTG zu9Y*nUys^H+V^SvG;r0z**ePQR~MkN#lD%`bz+O9s0uCPJ3Tj%Y#YdulZjr)$Y779 z(y$2%^b)ptWrHxN22Zb#FyBm-5x}D>u#REej!oeMu@POqLeXNguS(S&*m^mPK!>in z01JnyzpIGjqf7H;gd%Mqa(pe^xUL(BM{-QB?8i3ZL`O(KH(&9e{tq9;#jtTpmD+HH zF~X)Az{eY#rKJXJr2bvBUSbthmS>XJ26J5F@K;C_zj{&P5IzLvjm>* z;NBB)X6y3v=29EYwDCf#E45S=*)8#)R^nmImFt`^m}+x6Oi3Es;nQz) zE*HNYW0|zo^1JW8qr{qADK;9Mm@j^~F}*NmMsSAX%q3p*;?*njp^$fVWpeH1kjkV`+urG|k*Q5P>|+oNpp2!_F6B>wsM@w&!*=f}JP z{OpbZn4sp%7yg*rV*h;--u>$6FNNBlSIoFKz6g<>MCU}u4NSI7+yyT{>k3*Gf|WRu zVdoohY9ZV->+0P2E!0b7Wx6tnps8WullXt0f$Tkse@JtIYW|P)9sJ>c|H+!sIbli$ zQUFG)68+E!D46qqb{yC4C}){uj7l$q#U*%xQdCZg=ZkMZqi}-YX+#NB41QdqbwZ(J z+{tBCHvBf08G;f5MF1P!_k;L1H%2@J!W=DOK_8@0C78m;srV-QqT0MYU|83{rfDaa zCDLsdpojb88PU@a4V(;a7r({_BRV~wX97(m={9w+yO@rhCv@{`#gf{HPPI){s5QA@ zOI8N5?>2e*^d~Fd{rmL%x9vX(mVFk`aT1ZwY`E9$Du}egq3vbfMREgt^9B1$UDJ_U z5i$7a2}}@+^|@sj@3;wuoxzrW{WffY<@0@t9TR&=0_YF7tnplH>byo5?-o% zs88+J8Hx8-G~6W(38b^_w;jZn$bfov2=8=v6nH_2oR_|?n zIn(I~%@LxVJf>zM0i;sE7mRv#@J;OW#fa65ylSHM6o@<-65^I)=`CNef@fKNVNLY* zho`DvtsBxbz293sg}Bm!{~UUQeYBw|clAwEg{9N+vnZ{Nmf7O~r58mCIiI8Np0)>wG<(7AFYaN_o6pAIGB zn2H6Kix6{7bSr?zatpp&>pRw0X8DE+Ll{^FZ}dN>kG5?Rz@iv!+R?2y>8!N-P7My}>T zw(C{QsM17u&*CnPtD^^>DO`hnfi*@tSkTCZE^$+;Y;ty#iZPnIKg&7WWg^oXjCoM7 zFQgVFZ6d_^PoB+AFsR#Ey#3uiW8hu&+n^)YJ^ag5wL|opKxE{CoPPm(Z*R_>@N5_S z!8uztKmX5Eh%w}e*+s}afZ4W@At8JCL1_SVc+*hSvNqS4jG>(#p6?`j^kG6_aJ zUV^FwETwiPvT%>v{tPy z1vDmLc-Kn{*R#jR8>+r3X^BVOQwcH1a#!OqhJT9?IuDYm zZ}wd=?DQb;Zl6)_b^7!`nvU}Xq%&}2b$GrJYVsuEAKa* zyH=|{e0bs6O|0ab(+L?(pBBAsS9t3{8I>ourj6fJXh#H?YHZr>)9V$sJ(9KoGac)W z@s!@D)M}7U@}+uP`6`L|3=XYon-+^CAH_ID(G-af^?zNBk3sY>i(9DvW?Nkw>>`g0 zerS{cJRpc1WjUKh)6*YpD$+kti~xYse0=8Pasj4CAmJT-&IiS zX_fJia6da$zeX=D`=Rt|o!ja8@~S7*aY#`tH`$~wW~jyJl)Dx=8w|qPTY!+a?6cp= zeP&)k9~{}vGddh>FKaYt6Rm=Q*90$XGLwDa<-O~v|1a(RvN=mGbu{Z`ueyE&9D)wFXPa=WYJI5b0UEQdn@LqH{dH#++MX zRgSHq4jV!;#O-X@AbB-J*fBc8E8_u7NlcSqjTXJR#{vYP!YUvxl-dN3(sHNc5~}UD zM}XLMfGIMpwL_OymcgxvmBPQT=K>rfMs;^-rSYR5y7i*x)iUL>8|rPlY1VpZlY~oq z92(PdPac67sUKAX*Q}AAMfrgCuiQ?s0IK2%H@7-EX44O!0TEAWygA7lqvGp#uUda> z#?<%G)O%b>?fv4tv?Br9ro6WLq~yE>pL~*+HOcshvm0;gU<0KSpjO$+3-hMnk;3(D zO)|jLxR?2)cyJit3~FFw1FbDgv+KKY{Za678)2Gu1Gd_Mip+(z`nvsc)NF})L&=&9#)a}B9jVvimuyeN@=on z^{-uh%1j%Zm#&)!n8WbkTKnzPLP((Hx^?TORmPKui!?Sc8xXI_@0rX&2Mrlgqw6IV zbZBfIgOnaX8)H~W{{xDBC7>isU&!y^PQnUJmS05eD18?9*oECCcVDy>B5CikCl@_# zg)a+6X_7v|r&I5Nu`y0jQE@_jMNZIY1}zy%xT#=N9?xX0xIuRv z@jVU$uUqGq1v4hVf5cQoJhTa{-zfn~2rhCFX#0&Ygog)v8%zl}-WDV||V7rXzOXOA=-R_l37aQhNQ-bo5zR;-gY$<0p9=l4)xmeRrSj<(k{l zF;zv+BdZ?_K)kn7xrjbMST!3>M)UN=pkKA74m&hU=jV#lnyj^}v<<2eluQ^|oN4{| zQ;)q4Ao6vCF-eHN&f3I4+POQx2|L5Ykv`C-ZLF-l1>@Ua)twwOl*$)ISEN=0em{mp zsBq(4xkeF&xY`5R=2$xN(6WBOk;L$R&lvk_r9|6So_qS9-trlBd9s2xuQtoX+}xZM z3$uERqilVJZktaDehM7)`{n`XrDx!ZuFjS8{alQuKy)u^uZ(Y>%EDF0n|>YrVVL^B z#`J0e$_}R_%M{N5qqOlOJFr?ZH#)7-wKIqDi91$WXm;A;$Hy>g6TL#BjXgg4oeJZq zP9}PY8%xR4qk%gmEG{m&Fn2v1Ek9Td$NJS$a>zDT>PNJLXPCk3=jcbJ1;i}5s~%sd z8vW5KFX_JZ$`;j*VO5n(`A~dVsaytc8*S5mScf{wafmUR&`u&V?{{xvyryYYf@7r|t1r>ze`zl}j z^JDMgItf?vy<;t^JPe*S3eHiN5WooyTYxZT)L~fI_N~CQl{fnsdsKWpjVG83 zho`;4MmBL|&_m%3pku!gL9Un6@+|k=>dO(#FazkqO8jBp1ja0<@-^GGP&xGn*P<&?E3Rx zhW%Cbt%Lcq$Qw5QSg8;9i^ooj0Qk{*hdC1z<@e4h{9uiQZTziRA<#G6yzoN#5aGd{ zgXhhK+(X!QwNlX6=Dfd?t?li~xdTmpe|GJCfpk=BdqkME{rkNBO$BF_!)E`zK`s?u zxc}ZZ95jwfZWOs>`F^Y|*T2_n_QJU!TfWUM>u|`5`g_u;W5ocz)9k|VD1>dY<-SqM zI8Y5;{|;99-?#&W1UEn|CfL&XwCGg09eiPBRf#R#YDqYnlLix zKl5IHvumO1e}3kWhh8vi%u z9}ZPrl`?1xR+#pSzS|!7_lC^dl~W4K!lx?0Up3yK^3#(H!yVYLB%5`s0M&I7j=&zf^>*4S+a=n6Uf%Z zQVh*10ub_tmx^M!C(c2)n{g3j`k00J85~-bHeLEW)$buJIwz?WqAH~827;@a+2yqJ zbB&XMg#0JAVs&QsEw7$*nmz3nkF~MeuMO0M@t8Ids%=GaQn*0WH^Q*HngsM287P+l zyENEn5|5g+Rtiv3uX&!Hy8)?cDYqA+2g90gzdiLfiUo7n5_f1Rmth(g`G$S;m_K9D zo~-!cEXem-D++1AQQm|E>-4#(TNxNY+LoOy1u8ci&ctVO+8!IW55O7dzc+>f8`x2` zpA46V-CYLs=ad^8wSc?yYsLkJNF)=Kds10|_|b%RRm|$jJyBjeljFb`*v$|WkTv+K z>PD4M4e1c25|?pTK*!c9W1f6Xp%z)})lx!1oPZ2VsVL5rNq|< zSR^6e_!d92*V=j;T&3}7;9g_YB6GrM+|7Ps8A?=cqYC%wJf!!A>-ZTOHI4Ur$Buk> z=vaMQ@EQh5vKr=vl-wXvjzCT|kY@I5 zBX_#!Og{c=Q@XojXv!ymw&?fg&9@qcf%`-X8yh2$_0E838-i+Hg@rCn`8DGlUc7jb zh*l<>#)akD@rDTDH-QU#+jB0`2FBp5Z$`(qLrXK93XBXTpcsDhT{h*D1VW_^2(tcr zQ-O_1G&fWgAs~wF_~jdLK6($IGaiI}FPkE=rLk!h1%&yXl8O-@?CYEm{TGepsGLDU zvJH^Nd2@1)aC_UM`j}j1O98e`BhSIlbM3lygMiiPu&r91SFOFVM@~DOoClG#fC)Uw z%MRT5rHG~M4ix5AEiut!Vl@IK3x+J-^x;uO^<}2t)K)f0*wSEsN;^8lo9A21APg>F!04l zps=MBJkU+Qya1AT3B`$~eW>s%mlqHsjDsCt^}e*QuMuO=9+R2w)py>g=8}QdTIcR` z93Yjhk_FgM?ESVFlAqgs9zmrxYZTZA51u?J^ey^$P@7 zszZ>NEtjnUO^Y2vF&SyJy%gOiN|*~HJ!hv-qGZH*P^T%pc7c2%n4WdHmG{jOo64ut zDV${iBjW(8G6=Vmz>kunw-WsvQC~U+c#;6Lq$TFX`2l$eHuq50N`}wP#iP@!#!GD^ zCjz=U`^^G0iriqT5sEh8hwbaxw)6dvEo0HO0gt{760>wP5|zwOFLi*&@cL*Nm4gs^ zGkG$Ac4JaZvxca@Pj@fj{sPOhYkBubPx*(4U27FfNth%2L2Bw6?G{TNQ)A@F$OubE z^--2xl0fXYihg4ue=--u87xm%$F2GRmS!+tg>G$J#>O(bJ7N+oM#hz~@y0~-j8G;( zd_6XmhDB^DnOCW~y-cdY;3~Z73+3H#-YV*5dkk{J@BV3_`+dRDv47b(ZPg!1QV9yg zNdTrUo~uuTXY8*^);seSC7+)K;G3;lHk!ldJkpAI4!xAl1bMBLewvF}D7b}b(KQo2 z2N0KpN7qMOx$Vs^QmCv9VUrQO>*#A98_QTBBN|Dlvg3VFhb+0bTY|6-AG6#=#ln== zcN(JTJ5PWbM*FN|Eq_W6aq4%{5kH;rkBFAuZl57b|AD3|b?pT!3LgK%1!$?&mwj7U zw*kb-ZR9@UPa$si%KocAPYc?)>@u-%;y zsYEy-Zl%y9N7$7dI~|?W@H^inJ-5JIrEwFRi>wU)a!L-?9m}%U^K;82gVInf2dUl@ zo2gSyOKruuL*blSie|L8|2}Y_sgck*^`(cSMevnyDe#s@d3O`KZ0%{ZZq`l!=4yqW zsXe8*ajVCHC_|%%uTt7e)!Ti$t9+2BAl14wW1!HU4A2@>ph@yZ`9U%=I9-mR^UC(y zA7qeB$|{Dz9~o2=i$-gdF@WS##eP^>>b_=No=%lHGVBTAb!KJZz0zLwe zBQT>3Jh;HWba?Oo{&Vv&2858BS)(=H63z?>$s$WkOcHEQf|tc2DVVLVb<)_76=m&5 z8cYAZ68|l0G5AC*Yf0{BG{EtX?+4VK`vg~U_~kpMK75E{Um{+FGFkaYFY)VGjR0By zPoNRhIqi$;wjW0*A@dzKr+)Cm&pSfwoPu?88b_xT7iUcArqu1m_DkV=e$?>)X59AQ z`j@+1NifuRpDw^k76U>#65w=U+RyW!G%bglHsB6%Wp^V_g%*HNnVc7|=n9N)%r}0GfpQa4BPqs%IgS zO2Kye@So!oTsQQ4a5^q7?mJ`mg>RQpUd}^%*{SWbI;$OcyPezyIP8p|(;!Jt+Yg)2Vnd!N(aMiu%LKyFY)F5Yc*XPWQmU zQr=Msx#NVulGBI7HvAO1p=*lxrjExQ{>bCWII>e@&xlI#S~@YfljYCzv_r%vqo6Tz zpy2TgYwxMl(!6Pnr=>sKLGg72+rY8X78D7?J8u==)`O4SW?#67u^zMn{K$ApNnW~D z!-$WZEZllX`I?Sd+BHG^<0r=bUv@jY|2UXX_7`5a%8lY^G-p-wXnc4v#9^lR22w|F zlNZ{NEDX{*aeWy=d!sR7tpH4LVzS{JU5i)+yOt;qe5PmI#&A9si^wPgPF z&d*O8<*t(b+k57k>gGXTiD!?cdGb18({z`%d9!Pq`#<%bd2){U0zNAjNgIzj&rQzi zli-sR5NV#%P4ww8Q@2S(v--8-UlDwgf9>H+bG=Qm{Y2jo>^I_B&CSf7WQ&`&2njc` zPt=P)D?INlZ9@G2jcM^eY?l7N@OETFMx7Xns_8M-Bpm`)Pu4ti=#cAB@rkh7y=%f^ zM65?pbI@}L2nks$B_r0*?%{k48}c~q%l z-j^58)QUA&HE*xP$2&c+E}#Frp`l^gEAb~*-@v^>DX=W zRTt*nN?sxU?oH#)&#!6+jsCcwhDs+OjdDBh+ujzkUzKVyH=`z?Wz|RFEoN6iMZ&CjZ zJ__X{4JE&e5Js!)o2IO+JZGbL6Vgz{fr$8lZS9QS+_UNR=D%(n4?en{1`bwC6+1gS zum!B%_z&u&j+B|n!t2`FG|RE#2baVj6aeCSMu_`=G``j&($8-yd^2du|LCL7pB46Z zCE<>wne@CoS(q9mp6?ME6f_gkMv2k}0826$Pjj~P68%)d`t)Dxofno@R?5AFsOQD& zni@Ai;YrAnM@q!xGBQxnvq&0@Y??0Mpt?8hSYU zHC>e$T@JZFTXa`~Z_p>g19Ktpx9TYI2cbCJG*&y)f0Fpmt5fh;2+%z1#kVX}cnXn! zzz5=^2*%6w!9npg1k1xxXYK#EVB_lS%1+y!BqV5zSh#;y-w_MAUff_yo(RZxoIEL% z=~-EWAeY`vHWpzati#9qr3U)|!i?iAmNyZRW@ArpZ|~d)3&Y;MdwXUU&!0a(8A0+k zuxaXCE$qiJ(uRT}`E}n9%1ao!F*#ime14yfDQ6nL0`0O@4!;R1{>gQm}WUX$#8`zyK0qkh8S6 zvvMjfE*_2gBiouLQf0R%Zl3sl6ebC3$50MQ2Hrb@R^=rRPL6~1unSjxP1VSmBtI55v-N-CqH4=wYQlNpyBcUJMeclC{L z!}7m}FFvK7ap)wQ0!qk|#ueg~bz(}VH$C{asTHjPOK?`Z>&;Q^dc6+%71kJ3pF^bg z{89e}+L;oMImkO%EU*iWn=gKv;ii8a)EMP}PI64nmReZUo_G_nX-Abo2CU}@PM|8W z`0{EOZ1CJjuq}WiWCfrEbf|tM7=q*M^rGXV))rj5VR)x_(9-MLYMs>C*^(4$wT_wM zC{N>h*92XE6x(Ph6p|c&?Hz3(3G311SE37m2fFopPt0J=RjXF9Gtnp@K-h+c+jo5X z#^BqipZQea6-&H+@e1u<)r#fR8gcWstB$b%yGe$ODA|s4zubeqpU7}-n5ljYnowJz zCYb{GCRM2&R-h&(N2zHc&J8s1D6mONu6!?F{_f4(ugD@CFcMT((>PO{(2`?U#&UN)$aKT;v7qJ|q6ZO{zyo;~ge*Uf zHQTZ0(6b#L6nLM>4&9G}hQ#64W$s@V55d5aw0YFa6o0$P^GoMr;o!Da`48$`45<-z zurv2>cMONEcme+JqTh=5s_d(}Stk{1EkTou*Vq_Fw%RpU$20#X{cOWZStFpKq&&C` zi<&8K1oN5=E5*6!)Ts@BOxjKEEnfN4r z-a1a0p=?#6nf(svM%Mm^58%*y+uI52Q(=qvjuUplBieOP&M0-qnB)~p=4YH^XGrM~ zZrF7ED27>2wFBJJ4W$#twdBON>(<*}trictrxRW{J2%bK{>2MHoXUTn#0z-mC!Zw9 z{^is~-mvn52@76ydU3H&`t7-Hqt!>@%>dXq>^Vtm&K@c0e%VaKn{dljXsUgC(HTad z9m$}}pG&$rmTP=*P{Ze72FT#UR0GWK1nx0=et>CtaVCjj;MhcnJb8?2tbVRpBEbMA- zVscw{rg#}yIwFFmECYd>^7z*2N#W=x!7>Be5d!LT9F^uQdryf@MEcw z?LZiU;PkN9*`*0^>@^_fu8{wZ9u|)6?|k~*tBc40j%pGvo(sn&cjD(z-9B=PMsEL9XhQf`H^>is^~HeXYfxKaaq9}y;nn`LL~^{yFy)7DTDF#GYqw?h^~04E@!BzNLT`cG!OBOK-f&J>sx>>z@9CK6Ugq zHa5MNM7&)7wYg>@s!W4mmRrkJke8oN1)DpirkD|qsXn$al*zqkZA=i2Kgn&8kUCPA z!}fY%eaJ8;hUU|LOgzm`tRM>K3ovyuPmCr^8MPPPi(D?tSeCa^5FGR60Wlj~I(`se z@P!_8Koh$5!6qOPsN*l);$@7l6u-@RQ zgpC#2hq1U7gE&c2JDv3?09M3CiI$C}j%qa)Q`IMFXEqfz#to$`WhKtO&^W1mS!oQS z7aZnHBZ^yJDXy73NNs*sHu=UOF zbvW7*XF4@MCX>mp=(WN0s*zI$1-7;zO_m%LAUYqREO!Q)4or)e0;Ck4A~kxKPER1H zNRBZrVkw)vQxF`NGJ435mWN8_ zR;716rGlQ+9?t5|6J;kfgy-toIXO?=4OQ{(mX6a(-^Ui z-ud8oVa7(RYqY=%t1$KQ^6I=*{QD-zr?c|&<#5KSSnSyYQ!D+QcRq0uW&0+}@mh1L zNGBqX{bNW(_AcO;wzjrK-YX(H0aP%aEgoNIaAb>hCP_%SNb(r6bHn!0HqXSB)A6wlpD-Uut$)%|u^Y;5c& zFJ6dE;`dbe!$T>*^Nu*TaXyGU2WM=}JVnKRYB1`SkwJd!3Nf2;s5k(1K8Rx+MeR*2 z#N%EYHtOr^cRwb+*PBZLi*p4XK0LQ$0&;m^EGWh=zz9npAvcHOqm0I33fd>STN4U` z>FMbw)4vj5u>y@fzA-j7-ei?D_{TJqSx_z>Kwp55uJ=Xf=RGl1qN1be^hNZd>3i79 z!udnf$;s((FY&kydyM^%Of5E41G`*y;nc+m=#G&7^yv_^HC*@6=lxJ_p{sidRNk)0 z#sK8Vr)nm^kt`U^5$LQ<<2|<#N~h{JiXS2QXtMtoFSHB|i%*mxe_aYZhN2ZRDwdrZ zkE)1^3j$&`-h&Mr_Zi=Sfaz?2Np^o|XsD*Owe_H$KV#=g|8rK9m+gubk8j3FZSP@t zIdehXzn>6s0Z|C1DcX&|Am=EuC~g`ywzka^o}HttqS8(3PO^RyB5&dx z=h`pI&81E1AD==HZ6JR}jV`wtsWpW|!>5TOic6yukR8r^-_r8SLJ#vU<`x!dM&htu zuw9PbFe__aeGGc&NQcxC$Q3-hn-$H__nCYOuf2fd?dopjD*LTl$NZ=u9?&c_GD`=P z;^!R?*~2F{q0Q(_teXbZ`qN-AVvk?EuI-jpv8(xGYaj8|>v8AkFmVOR`Y3z2*2&8^ z)D+6KG}fl=lIj9fzeLys8dxO7a=h0tfP5eC=9oHU>G$bl+`a;<53xS$${69^9^&b@ zdL}+fA_sy=*?qm2#~-{pk2U6*X!3cVKAnO zjh$Tzj@vKNmdm`MmTIb=zYCJ6-b2MNb=J8ro&AUJE61v@p}t}mx`S*P2oR_KxQyVRBiy~URPAy&Mvq=y-Sxa3T-RJ-(BL4 zQ(($lRgdB+?mw@XE!ED`eh7AtafK-K)da-IL_U?S0&l~&kFJt^x>KfPr_2a(Dm3do z4tMd737&s-fBsd$Cpr%eW;Y!1OA(fzoH%Tr^&6|voBBiak0_Z3+wtG)z{GI)BSQn_bKK_$J%x4 zJLW-KYrDx?5AWK;)(u5vhvo<6Y@C*pmu9V&7NS0Cvth^n7F9PeVjiI7o#`QQ0wcIt zcTO0+7xd1o2Jy))j3_&5dPqFAh36Jsr7OjY|EK+BIqupmmF0++kIs%ZpzD=)g!nne z==Yo<*aPNssw$(V70w28)AF~c!LWKD6YHgFGr@~O)hzqBCE~aI;+y;3oB{KUhSk{U z<{0G88+r-xfYC;`G=o0zkj_eaJMBH;x#a03-jOtv2W=9Xg49NwYm3yd)JDtY#%*b> z&(a)+fP4B!g@1hGU-vrS7ysPPHzLD_J~#_jmH!t`9b0znc-hhRaMFE4(Wjh$)4kK_ zx&2Su-^t7o$7#=-zU6;;GjWUP3&LG(X(<0&&Ch@NcZ~kWjmFhbOal)xZ+GuDk2jxT zOfTk1W#Ucc#Efnug+PD**7$fG@CPTZ^7cF(Vy!T4w^Zi)^Q}u=5=NhMf9`K7^BypCfM!MXsPo!E64mCq#*UR^;e0g|uj#t4TE1sd=) zRT-}t+>ipM&z39!#77!9MSfC*z>(fRqupC2+De_S0@YCRoN~~kWDZtBAz}%w@Fb8uaOWnU3FfA!~tngMP$=v(O^FK zqSMv|eM!-$6sw~pzT;xHHLSWHN?dh7sNJBds7>w-@N$VGi$c%#_E^fz;{LuiQ=%7P zPMLR4Mh5@u4w1uLOoSn%y;CRx>A_v)(%%UY)5vFT>Vk2U+IT(@9f}LKK-2eqG>VE; zX>I5e2m1YVO=lvJ0dBg)=!{CNCl*V&ML68;+6+yosLI7t{#G|QsS?OZY)Q@P1{jrhyo6+hFH!LSQI8bM44<09WA9O5+p4R%^x0X#l87?W+Laz==Q%x&uM@k*+i67SNk6LaMlPZ z13PV}R6;`gx@=tmgybGeNNp8;#P4DgiLMmF@}cN+L$+MDASre8nEJbA9z9 z9}0wv>!}wh1&Jo8&Xd(BtPwx|T4)9+xis-H{Px=cY&C-Eo5GLJzGN_v3fhGbNe^#f zMiL^f!}fH=c65Sw9$W+^^DuNI*W2j|o)BvWJ23I&sYKhkLr;wb1Ox#dxz^Z#mf);$ zH4cMkA9Z7i-n^B*qt!MAyfX;hC8OTaoaT#tF#CP;wrpILYSV#-h>c^Knr~?kO`w~V zU7as$K=M!g>te3;^C>srhEWS?G;tvAsOFQo;#E@OYpja?rzc38-lpz;rjv- zkAmBw93}7auA1Ud=<1go)lbK+3l7yKZd^rs@URB)!)09fg>{UAkGNy`JcEn&o~+i?1)7X zXn1kz#?27*SsAsl)&WfB<@SByv`ary52vCR+iTbAY^_bH2HO^84|Pd|HhmwWPi_+OQKK1m()M{20S z1<=YAgNq<(U1%mg_#(a(7Ih*4z^Dymh9}RexFBgfksE?-(ep{rEx?|TnW_vp6lGWI z9ny^7Ugm$Jxu(4ccQCLLzBrFFCyG|3?L{mJXOhW+9pTAXX5$FA@d1^)`v&ifie9Uu zG~vem?3H#A7$L-u51zH|c{E5=uwx8a@qyYniGB4Z7rhc;MCw7*iAk)wUo_KGOokej&Gn%vr^&M%x1Dj z%3Ciy2sOYJp<##S@7LVZuUcCC=u@=~ofaJ4equ4$79c?NT0avCZtSTqZGOSyOn5rC zdi}*Y)lYGJdDfmNZ_gMd6rr9=)3V?jj3N+CEi@BRSXc7}jEul8nRpOq(v`>s5gj*a z{~jEN`O5(+@0)$LynT*C#GVK9#$~#NRZ|X#fMQ|;HD{~xMPr}kfYT%edZ_8a-tG~B zqn;dJdFbi6C`+f^vC%Fr(A-hKeKwb7r;)ENn7$1aB@~inZd-sLV_+rr(TB}_m(CrR z=^b`$MuFkR+8OdCriLvW8IuK<$rU#(q4;x^oM-`LIa~vhvU)Bex@G=l;}SMviNeLm z1-rfOv(w4_D-lNxuygA#=)C=}7T+s36LID+)q^(P^KaAUjz)ba-YLP-^;L>v9Q+J^ zoolRvP-pcCnn`HkyO5 zqvsuO*hn0B=8F!)Rvs9K!@kd^jBeCNtGD&5N(*CAe6fO&*3K$9mi{4A?I)N02aZ=c zr}vpYCT8u}N{pb44V&-tcO4XyyuL7I^g?jK?!7wDMR=f)CMReF9w-{~5T7&wE^V^G z%50{P^#^v00hQOTH9u@NzHoXs?0V*@yew_6$SbTyYDcqvK)a8R6C&H~S zSt67k3A1&)$&?ys1{rhF7s<%*m%bwyaJKMJo%2KqmFF!D z3x=GpnIW&mF_TB#|dZ_bW#^* zRnhE@mDeLuMuC+ORXO7HN^4-lZ||lAFSroV@(R!Os1R+=)s=5Yymx~+168*R_lW2C zuU(yQh4dY%JP7fsU$uhCX6&Z}Dw}%>qrr0y_WpN>ek*Kak9wQ{+a-})2|S!1{J!K_ zHnu(Xb+lG1BT*G~dZ!ofN=iy-I{n|N(VQD`a_G>Z>=8R1KR-y8Z%1waD@e+oyo3MK zKNIC^TgX>)P%Frq(`oC?(mAms8xp?nf>|=-r}Z60=`kA=M>l#jL|=r*A{!N=)ARXU zMf9Oz22=~ zFX+?@Ek2kz>wd9ZAhhfEU!9_WRTSKA)p7Dfuk)|A=Y`B4@#J?)P=JsN9;wfZi3V*q z2|T;O;DYN^MWYps5%?;IKhNBFB7S)u!mKPSoLQ^5@UU4I9q*LRSr0!W3Yv{psnyKP zJf0U74H!0&d@JO8tEwuI@-sADz9M#=s3J5*4#%XM3LN|fR3fxfD*kKNPTXF2*3T_| zuF(cKGVE)teU5=`HojrA<^67T$WIo7gY_;{B=FGq3un4=4a_Wb{NdoJRHi~s(zaC_ zyCm5D)&ADOj?M+_Gy`X)fi1Z0QIPc7quX!U?zta6pL6Mt!Yo@oxGr2lwsEO_-BK)v z0hOqn9_Qv#S>+psX!JjuD2`pF!pl)}3JtH@tu-1*^82`T+JH2}|?2{uOPp;Y)6h)pYu+VF&uv%<#de4N4jt1sK>jW~3( z&6?zhQ9d|O7)BkpSS5~W4ssYxkrpS9d4(IWj#_m6UFHY@r*dGeIrbNN7$$n#7Zl?> zW%5JUvBWs6mPGjU4FW0gVY80-?xrFd7mU4Z^^6>V9w>RmOAf^AZ6<547c#&HAf$BB zr@U4hZ=)1lh#x;|b#cMOSc(*p9?C}?FaWNg#cN^+_eTAPs*q*i(DDx#;J-hYPzNin zo(Z%+SZ@e#4V^N!HVQ^|*yx!Wbfl&*nhq6b>zT0|Sj3(UX+B>Qi1QSEThE0wGtFjy z^KCBCNZusr`7b9$hXovFemF5jX#GXKb*yoSBAEQ(xh=2KvKAt-LD3I6(R)*o;q?&f z19q5!lCBEyrZO_bfo}xG5Ui$+U+ftw8l3heyk%pxcjpt|11>T`aI17)6A1xoWTUxcGM&Bu`?zuf+x!TIMW)RyDw8c2jW ztbTX5Ak>9tLh8e+m1SGt&ZBhxqIQ?=y_fmZ+h>wB{2a-v)2VtGYGBI&Rr%gV3wX_;9$w;y&*THhL_VV4R~Q_QDTHQNL|&GFwb5Ks5` zeF52jN9yT@nORcc~=P@MzJBP7$9l3PD?Fjvn zu>L}n-?0q{W{2*EnYcw5=j^cEIRkisGX3}yy%`c!T8~CXoOtkh{Ed_fQ0Zpdy#DjJ zg;^lto7P6B4!ghM5bO6&^r9Ci>z_)q$bpr_d9d7#ZFdH? zzEkh8Hgdpb#UKq?Oh;>4MiQaTF-f+i?;@qp|A}bXJEcvrh)e+1{*^=6O1j<|Bn`E8b;G&va0#5N4)3R4b8LA6E*S9TPj_+orlb?MYERW z{)__L73s&=t5&2IrwfJi!f-=Ug+loQknA=_>nm#8O zWNjr)dI{K&e*QelNywu^@@?C8Sb&xSMA0!?1&aPQyfvZ%w%CU$H%jy-7RT;TCSLJ) zE0L%_mx3RvRn{=$8RwqXC764MQmzQ?cGq619 zJPLcL{VR>t(OH3^6PZe9RpHWAciN|Q{M1fQ^DF_Q&|h}|n*5e|M*?3h#oAixP(!R3 z#{+wyjc;hnRBu}gEWGJvTEHXV@RAM!$#LxFyzRBa%PYlr0LgzW>wVE2 zFCJS^T4GLIL)b9*VbPIVw;>MtDTz}rIL^t>Xl};#$=P`-eSj8>AOnStSj6rfI_eEO z2D3Q>n_|zvu@A4P=G-{qkDw|^P;j8|<5SJyiNYol3VG`CC1~Seb{yt6+YE88&})Le zx3XyqH|&tw&7v56YjnAks|UZTN@9|z_-ExM~;2HpJ6~<%(mHE69jQ3)VVid4~Y>F zJengRtChfhjgW8=cp@_~tc=Z3A(Pwk@}gzs1@0rHW$wq+pVMFtb`css8|og?!y!fo zAGAnbUoDC`gvldV7(Sr_I-#WNHO)vfl?YW2;|amWS2wKRmIqxfKnn26Mh7^UqUb594Hczt8Xa4Y=_$cJ^D)|N<;GEvH7L=z+WU61*-XZFYL4e zmUtSI%LZ3uCo!ojGa@XCUqf5PY?V@h_*FPa{w$2)aI z!Y&LAM5dLg6rmRr+cCYc@B6`)d3ONDV}6h1pL!f!-(T*iQPS|ieHL7} z3EX;%(M6eh*DJ%u-RwU*v1pF$wxON6t=p5UaManz_kU^c&BJP3+yCJk8_zawGF8Y- zrZx&`+}k{5$WV${(IBLfp+P-+Ks4CftjUznB1sWVduuROhE{}1sc2Cut9kf+KC2Av z{XO14-s5yORjse9e`bzj$co!5DO29Nl~E7z`Zb6b~{9sMjuWou;=L|&?0 zEGhzZc1!&VMQb)$*4ekHISYz|{-K5W?O$3H?!JxB*TeC7G{!1brTha6ApHMx<}A)k z>nL=#1*w$~dqURiA3&AFHG?_M?=u((PFoiPhJE5wU7Egu>3Gbw*XE- z-9cd43vl0b;Bii)McX-M(AQ%ocMNlGzF)p~Met2{w-WUS;puQ(az2Z=b$wv1|x`Fp-|1iNJ<;xNO(Z8KfW(ek9V4 zUq8J24fMM^Cjk4=6U`eFKi7(91n)ZeYoPBq8C}Ud^cB5;<0!Dc_3i@5LZd>X$8QDE zY5SX#yG4MGI_la$DQX-V@Kv%6BIylmL^il7$QIi^LwOaA~s$ja`(D9;2a zGdIsiFGU))K(~7BJ9vz5_`+#XHeE;Gq zvC?QlI>e4?p*iDT14P8IV*30HoVx3^Ms!W13A%{jIZvVn;*u0wT4~Y>I}x3&#lCg` z(kHCh-LDrQ>xSzml)WOVywdk{i`QkO*E&A!x0UcVVl(j%ECse$Ki-eHqX)^A#>PE72B3r^FKJuzg%$xlvHxjk@q z0)%Ap=(kc4Y@o|_D^sIJB=?B22Hb8{cHGOsvcHy_J#hcRK2_&w<7WBG_Arz&SfEq_y$2-V7 zYNn0?pB}f7NR)`y`>Tec60R?3l3hxVH7>&fOhDsV!I@wL_VG#fnFyIOKTCT0k^z>q zr`urriZ1AfFS}$Kl~sH8Eq%5DPC1*o0?o$`(JjdK@w=u9eU2XmPlkR~{!b^Yj(5Kf zxXfulMk1y-`)-W%0BxtBlN%z2IsgwwA>rYk)x)BLNH;fC4W410Q_SH1jD4-d9Wdt+jN9kzP|kj zo8D7WZ||l-Ib6TZHohlI2@ta0+XsI=Z`?cY7JgJ82zHzYBAQlMA^CpbA7$92K%B8Z zbnZ5ZQt3ej*kEXe-_Oc;{UTSaL{Enl&EPBtSXA|dv$8lW7AoKDKF1V3Ne4YD4|jMe zQUbD+-#{REzxou-#7OTa-7pMb?d-|WGAkc1rQ|ZUhjb(2pm@`2;T>K<70!dE&J~?h zbhQxz=FzgaesTcM^yzxh{7?*6^2*wN7Ol#W~aM;TvVGTQl;R}Gh zPeQ;wxKG)ZbLPN2+DVj3dChA(tev5+sUQVXb}!=D>y252XHdc0OGf-A5IN-&ZCxQX zJ(f-u>uum{?a~)r_O@9qw7yo~8Z300pMYT5A4~dDSS&j1NeEhpGme3OW+09OXRj0s ztH9AhiJKTa(B{9>%=4U3HYFV0bh{^uW)7{OzS|D}WB16v1nTudqy$7J_Ubz{g9n?3 zGkzEFamV*?6AaVcoD)yOQ0aZ*K79J?baw`iD+;aoTL5|g0KS5&mkdZw#=ERSlB_&r zgv8-pAE}Jeh=Ph-9?%EpBf(v~465kVzqYoRq)+#Axsq%`d%kxxLmnCK;I9SA*(C)9 zk1;+9Qs9}E(@ws`p(`w986CW2kd;g(-?cI-eFq{Rp(^6YNXRTEg7sj$zXe@R077xt z8oZe>08*5sfKd8iEodEjh9}r8a)lxh;lX#`xsWoWAO*-}?z&9?_=!MAn)B{XPlJ@* zG-P}m9JuQJ^Ib5JGsh0S!_B#+4zUKeogBiS#Gv;ShdrF395mjUQyO-2N>a+?AWP6b z^sIV3(4Yx5Ac`Kyd}sRCJJXx_w`gz$=&5x?1ksBKtHDpUeKolSA;*p5^Z^=Z3YYOz&=HbMMry$#t|#L=Z! zx43rQBm|1qx|kgaH5f;~qB`)dhDgGJZgt%DeACU18zP@soPUt&xD6;tZ|qD5nd$@cHIV=L z69NzqgT~h~5yC6Hn3)MA7p=q>tQ*_nPVZnd`okCLU){&Y3p{in38-fHa$rU^?#sY& zr|av?G4F4V0^S8IrJ)sP?A(|}KxzI|X69MnO-f(`->z+`%_H%_J=&YO)jNt}&YT$% z33b{f+n$0DiTm8TVOG@E=j%f*F3uj9Q6JPz=s$k#EaaWy%uKSH5HfZIwxGJi*B~Oy z*aY;9hipvb(?NUpJ+42Ug$*sC22d+Tiu8U(BQxsrYc^Exx0!LNpN$mg{XGa5H!@cs z*ycfs^1f8N#S=q!sE<+e`FkBdVr-wx{F;=lzJV$-NANhP(%NB{w@f8l=uGzIsoJ3t6| zL{`Qu-@?vCr_Kf{3ljliO1quk;c_IV*Z^nd1$IYFohSY#dv^YZ$_!9(5}b64FM**) zSnkrLOVcGYy_A+-4m>n^#r4f=TtHpwJkbsCZ@MgW24p(nbks@$&S1=T77i2~O75YwR1M3SMW14-}^w{C+*|=NB*O(1*D#j^r9l z>^8ISqLLPHLg6)cKzlg1Upx7oyBw|V|1F*@99%eW*gj~$ViwH|!W|Cgr5)WJ!`eSIj-+SCY zt})69@WC{j*Xclv8A;6!NZ*HPwACvgli`Q=_{+OR%F^N}NgVTrv=61=sFkJk99#np|6{6M`~wi*ViSaW8eZxG=g#YO+IlgMFY_HFSVQRa(9^|=>S7w@b5<*jb9Xr~&S-*UV zJwOq%XBQ&3{?)ekH0)YMTQ(W0!w0VqmT-{+nel-*<+!<$`f8W+-}Yy52hez1PHb7D z%vBHUq*$_(I>^~c6G=k(G*Nz9`Jdfwasq#GpRoyt&)MSTl`7v`-_{t8Rk_Bs|1R7B z;M{Y?8TrM<(37LYaYO{-Q6f~bmrMTv(CfsPo*B8(*GO%eyCaUbOg?~?$Mh!M1G84N zU|_LYhG%BhOJ+Yvw$6v`EcD-2bHu&H`xy@ktx^<7HQHgTK#cl2Ol&MEhElo@Lda4R zt%|4SdB78j(|5G^^&W>gSHUTmD~6)Eo~$1kuHnN&TID2dc8iF*NeVA>`SmuWz$3|u zS$4Cv;7Q0F`2&045eEV2 zmq`71N`W}#O7nV-0n<2WRnqDEmCs#zemY~+OxF>=95QIikwRFbOLsYs`SvEhcdg!H!Mp{!O!NJ zY2d|J=rs0+Ec;YZYE72eqf~vyX=Fg>(>KjVc6cz{5+_^_8JLwbK+7nP=>GM%>K_2Y zaK1j!g(4&w8j?7`A(#AmSibvhgG5EdGua`VYgDa3+yb6EXnf;7wb)r=+p7;}gn@{k z;hfTM+lxgd6V^*TC#1|0mtaD*j{o`_g!B=c7^0tJb}2|zTt57Cp`0Aj1SjSI{$?uR z^~~#3ITqCtD0qiFDJZ;glY|c-T-X020QF}QVBglAde%=YQhg_>$!X39@`VrFJfS2p z``zsF277=1{F^PxlLLU?PW$d1-ie2dRSCT5#m96|I!JJ0RR$*sgLPYD-=QYsA;Ufq zJW&g;DzoKFIm_(boy!C#O*8YD3l~NXGw?fl_nm1W8QtgaKL`e&W~gL1NQHM_*v8dQ z1RC_%(*rh>T8zeVKExpVwi~IO5uGXqTp#GtVPS>)r*^qh`@#i$V>66%x=|qT`S_9H zI|6G#d>hNNQ;*2FI^@chv#)Qw7^)#pWBm9OtReiw|d zkMC*IW%7X1jbS9<0|GuKbON5UBB2Jkd_SCp?o01qWd7g(3 zt36o-E!Je(c5o*Y76Bs+4vM`f6(?5_Ld=e1l{kVWRh8x`I2&l@AB?^~@;7?y?mC3z zJ(&pM@`)ul1tMz$6Fm%`o3A&vV3Y}7^0OVH(5elXs2UQAWWz1bA*OH%(n1JdK(qj- zp=nSwz|m^q#OE8rC!^4z;Cv~rp~eVuy)l-QZ|6B8Apq>Ct643Na#ntT<$}KD|nRyJxO?&7p3B?vno`vaU4o5IG)U@yMfU!8!zQ)6uX;}bYE{ZZ|s#9 zS51%GVV7XG&7KPtlN)D`kp*BWPlYfX9Q`iY%9k z0RAW)F=Itp4pa;r2fUeE8We^?eA`>I;Aj=bwR>#?oD@l@^0#R5WocDR;7O7tW4F6= zL5jaJwOqh-4q0aD1H}g7pTYUkr~tDOWsesRt=fn&ue=ajAhrORKs%`MB;X7YorQI! zHHji9(B)q*%Kl?!e?`<9%}N|vOaLo#*1o4z)hY0wJ#?52BdVw|W%RQ>7zzSOD9|YL zY=$j4ks?UQu;_^@&Uit6eEjYW7gx`A4yZXMkw{7NCQ&w+B62Pu{Q72~&~zG{T#^su zwKE(bN^xLH2GfG1g2MYah{;QqAr~X>W+Z=gqcBhX11S7q>k+KHfhA9b_Hv*6{CtlX z%9v9wiCXnjQl&_4v@w-YP+nX(;mT{bhC(+HbcyW1ZOMPP5@kkh?68gjOQ9=*^MTjY zE}CajEL(h0+Lj)ZKDO3(q9G}3XjfsXk*>+jiZweNQV$gQ{amwPL?x!*d`D6dUVt}a zcULv|%#;?o-R?=OEnRP}V~QZKG&jEvr47wh5HO(x(a6F{XYj-n=h_r^aOaLjs%pm)5R#}edkYk{a*<{EAU3G692V_&Y$>GX8pdK<6E(az#_cdbO052El?49Qhh4_-jSK$zd+YuBnzQ$ zpoP5!#FZ{n-kf*}sT6P##3%KBUWKCbFtEon(`;Ja`0Up4ms?3u7Du`1^vMjXgDb9W z>c{dYJ-|E1%=y&{MN@LS{#8$3@&etFmY+tv%9j5!{$I+P-~Q$65&AY7-$tWp1isCL zZ!_V4-Awqo^PjK&g$3YK{x6^HRc`NIn(Rqm_dNcUb6-Pcjo^N#Ha>YW`nMnN&FMPm z_SKB}54|glkDmN<$-)!g9qx6o-;x0<4i9%aVWsTl@yopDv;VWV=VXgteE(J&EWR^; z#FR^wIkzUo-CtyB@!*E#j+JS5Rx~!GK7RI6=W9b~8=G`E6vH#$mv>Iny){-&WJNIMXx&P5;&Z z7J-`v;@jTTG!EZ(?WS?~md`YegYYedXc~zBiz&pJQwvA*nB)4rFu5P)=wY4Ze7_Ki zIi4tE9?qF@FcW{~LR~T0B@0FVH-KM$zv(;SpfVr@X-fCe-VcMzhr4J3di;qNStnHK zm)9QB$OYwNSKdf~3iO=KgM}5oD3-05jXq?9%q_n8W%G}mwUnHLUWr+ejgZzM^H5C- z#YRX^WdFZP_218RZ6!=zxn%kBnXaz&;{pRAfkv6~BYYxszjFb9!4siZK<$(N=O;oP zH+V8cx5ov-(eOylMB(5se40Dx5X^OL`={dM&8wkiUwSmPw&J}q%+rQm?aFpxCcQfPeiksntI$tG+FSrXl*jxDft*7`&<`gC32+ za^h5ptU8*C(so_<7wv=*GYdKkCp3-%QS)i$H@{=`>9CF;aj>REmm1T!(Rz8&KTF7N z3jegn`IaCxz4rf&3DO@GT=(&B-yrl*2_HE0nGmcR4wQK)8X$6h0y?{Wpo_Q%VC91~ z$2k^5EqxdfuR2z+lcaCR0>z3u5WgdirnEF!WhQK;)z#JeRz8ECQy;`4cwdYpmil_} z4e5$fdG97@o%|yCB~%oHVkBH3raqBK`P0U=orMuG_JIicWy@jc*C8nOJ3(KQGN%x=8%0shVR3mELN4tk zE`Tl`y`mL`v}NED9Q;^E3<@@rxlZkcoGMryqSG^!+MsL#Qa>9_ZUr%YN-AOm?lu)F57|u`;8A-dGlKlMICoc$Yy-H30S|oL!BtVjX<5T3G@-7#+(aYE zV~<{q=Z|_p>Dqno z&tY!w`v~#YtAPd_2TzNqksD1;r^-NNVo&=z_3)GQ?>m zsxK7QoB}S3YEd=JOZFmr>Lu$WkRAeH$OnK!jEh@^rcr9x$(Syk3460lp zAL)Wd>^Oi(55(5q!3uGIG^(&^lKyQ5aWAV@uvFB0)zxuVSC#&BRDkQx`!iXZSY)*S ze1SPx3Pf4I$|&%?5&_y!0a~Jn&oiPcd(|^lT(3UK5QIM=&%OtNVLEVvxp1KvEpu!* zgcpBxE2ee!n{s$K)2V@0 zrAY54$ug69^b>5p3rk8H(9t2fe>UOdl?6#8)@DAr*W{gJLt|t{?zK248%DMPNXs zMuhQ1px?GI@1yM?q+A3{9m41GV`8x!LrH7+C$C1P4$v@)8ET zvEBg!orh~y1Sj-wE7*_PjqkXfPgV)RVgL<0{Jr_CDwPFknm#W;JL+MfMQT7lbi4Nf znG*6$zHGd+C+~B@*$}_K*$k53V-~Ub^9cNz<`>pC8d8 zX^ZiM7zR-h78Vgb_!VH9G;DgW#&ZN;lN<$ru3Iw5f$Qt8h0W4&0fv@eRkH-{VGUGfEf$bBY#I5zRjKB}afG?d`U5|7^ zKaA1KjbU2-At3UZZz{3k#@>w@?oj zn{bVg0VW+=w_9knEKljwfNq05dU+&y%=mfOVU6Rn`g(bL%w9K7lyuH+_TmE@J6R=q zboVka-E(5rkPiP*uN^k>dd{v6Ug|cm;W}9E8(QJ2blf@6xwb;OG+)nEw_dZP_{zuy zDYB1k;!lpBNx;^lM|kQ4Cr3xeUyC(xyy|e;9Dqp%U;@l(&Rdw-Y{`H0209No<3E^UP4yG(U?3qjLk0j*S@p*(TJEOA$C z7s2&XDgy4XA59~;3mWg$-W>$>fdwN3 z{ec)f_uO*e%7#e5egnNC`pZ3A{ihs>;LcviN0nAXt=2;Zh-1N3H`mHIupao_J-o^3 z0nYOM_M-E_@;u2hH6WoJbk=7#-b0m=6_%8syEPK4Di zbs_D$7eMRo-V%HE>@Wni-pn+qO^gfnqAseb)7v09JF#5{ zv`E?5zji{s)h6v_0hY|PO@WiT{EksCgkCej}a0JdsxcrA2u=pmdqdKBsGnkk!e^j%7vv*&6*1~igV-A_M1 z-LZbs2iW%N6$*qLF z?tB6_;?u!ocwz5)sSCL#OoQZ#-*zl;awXB8xY!_;DDUN2ZlfD z*L^t7E3I{Gd$i_Un>VHm3h*bwo?-5aVvup1e@zgcC}fwO zk@Xt$Xh*_@&;_oVt=yA>kuuo9pDBrXQ(*l&%hOny9)->y-*lr{5e^hd^dq_s0c>+D zic&xeb?JP?#T%nTO3Kmk>*i3kn2tUdRoV(xgYc%^UB+?ERFFRlS>U{c2}Fe6%&s3h zWy_n*Mltts3bLM4zGJWgM)HKQJXTC(ba^BJvy0N+=5+j_eHb<3o%EjEIRm;e|IWi= z9Skb>p=>6p)gi7F>^O~cDni=TW7t`&IU{nf0i$<4=a-JBu*^zdkbrFIXP305asoEi zv%}vPdijiJ++B;rC+COsNom&b6yRKQ$cg{&5_>2GUjrz$3bOc>Z@~PQ6mI|rktTyA zlus@?ce+T2uZWg{;Sv?WN{P?Ruh+M8#=*!OP9L292@b@BQj2+%4r0X#>pRKiNi#7Y z1(l}xSX8_30^K}@qAb{@AoOZ0!E5T+Mti`rRaD9gQ++_aOK_mQBZcNQ?_sAMjwL%_ zBj-T0E-;kDmdov73U6$EuLNsMH=+?ox$@iI-p=^Pw<$k8Bl{}_`9^nXl+x%{LL#}q zgxfF+IIS`*t+!@dhWl+02LysgNtQ^^X3EV?DyId*`zY_2l?tHJwKyBOC`>?)y z=r%nAB9n*gs_xVC@^vEUUTB_u2@{AJr&(3dG(q3o649c^C=AuCWE!(jthz|2l4g3P zL29n5!xeek*L(imGP>ba9XG-*P-%FFc6td;Sc*cCJ&t?n&IMSA^9O#9BPgeo$O2yw zC3{)2a}s5?ol;-g-y2g3$psxtOFDZ#qsmp0k!@mM``G^Gn?38tT zI3wN$?yg-Hfn^_KnFV;dpT*>(wOxk|7xY(x;C9T&4Q$%S-y<|T@xt=Z{O)F+w^nYZ zP3XnS7f3_2!F(2DB<`@cDL;4dS!VA@>x>jNe=>SoC@2?JhFhld4>8 zftdLFJ$XJvC6BOJoII~V9H?@q6oLKq- zn;eDv=c%UaaaXY$@w(8O{f7n-yzct)CCWj{NmPt)Qen^#r)&q zT4ae;VIx$+DaE63EW%XP1KXVnh>)s7YuhuGsOwO_V{jl}@MdFqN{BTyRB~jD$>GNh zn3?m%J}}c{B9*&r2GK40>yKT-+XOc&wqj>B3w=g}_ zQgDc5g(Wu%RWTj<+LFI8=Z0|UC3y>Zyyv~$NT_0{E6zcb|r2nYj#{l?} z$vuJQ*QI?g47h``2CRw3m(Ig+&JgRO>D!Ft-=>3|jg%7{(+#w@0h6BqNV#8SW8)@F zEUyLT&RMs6e_k3&Z{(ycy$|tiG~a3=P$blV&hGH2H=YOV50etJ*nW^bm}8AswT7>1 zFkY3_Q5wO5u^__1#G??Feab%CWwYpD8npHf=Rm2I7&Cb_XYvF2Om=!O1AGxn zO;L5BQ7K;h;yKIoIQ#l4l_RKdrptp$nm$Xw3I>x0mfi>1{aAVc4L(HmaE9`3sIRq* z7%rr3LB}a9D{fHZ`30^cf%-R`gY2^7r!6G@OaU``zB&c>BKeP&&-A6B5m%-@k?cZL2 z%Hdqq&cebC@`x$I!0s-UWagvA`z^X)9{31CVf-jVXs#fmXPOLL^xZjb&<$-O(kT zHxRu(PmY5r6R^K!AlD_s4TPd1*t<~*rdu&{Jk_B#eK>Ko6U(C4U~0(^jqz)a!#)kB zKEvhtxj9&Goo_T^%ck+%&;V66wb05o!>|z_gAocnqKdEQc_RzyYX8U_OI0q_1hN+D zu|ophKRliMlWSEQVSfVR^zF8o3?t^T%1mb()YyHu7vm)7iBbu9l$ZzG<*%j3h^ITYM$@tBqpnE@M zSA&s9Zw~G}+GpaXG;+doynog0Dy+>wz1tjn&F+snpg8(4#WasW!G&fyulI-3eh2Kb zEw{5P7h&NqG*YT9-^J$(03TE3Nttxrk(Iqb5t=pdp&p$$bZeibTI7$#gt#3la?bh@ zxp9#Qd)t7yTZ>;PGKmFarr(ol7UF3(O`R(g4rZdoK}S>`Q+{m-*~lU*bUJ3Dc+qwE z6k(zJc-PD2ZZJpTVcz^h&R=vfnGC|@X}q?F7~MU4w!>~rgfnF+_+^Q-!-gr*ZofS6 zcs)?Q(OUsq)f0i}Qn>Iu26EVItr^p%y+A(6md35vWX!D&bIskdct-#GF)sfUXTex= zm;12(5h1BJj^bgcEaYjxB+M`O8&zg&vDI1Qez<}SpvUy|%DTBRh1gtsfyQmKISx7Z zQ61;Vu8yc8g3tamY*wvjwJYk%(O0)dy!8YgX1l_f7_R&bI_{ITU(`TW@&(Oc_2MGyThE8(S9N=YG_evx_qYcaFVI(kFGbyzjF>`>@h&4I$g zb2L={Q~+Y#nYCXO>Sp2Ks$^~gp3#z0w(;MTH`%doTj z>x0fjB2&vAC*!t5x4vN>dEv0Y*l8q*8&lpPcnFCe}(5Y{__&rdYYzdX>fT8~_XZsMm<#=x0ZiP#kU&lw=Wi7>;d zi8dL#8_i3z^|}c9JmbW_V%@Kdhos4-NKDeMa?knt(y`g#?%zE~dhWFMUU1>XDVddV zjrHv08yYmri1ldw<+l^D+xM%?a<=u4;CcHYTA&9N@{_m4mit5C@o{o2vX=_E)${&l zU9j7eKL7TaO-Pw&*p*?dti64+%X=HMxtfa_DEgLns)QLNs|cFS9?|=4Kfml*FX>Wd z6tRA(e*`qi#zCht!2VR-joiJXXc(tb>jd})+ta9k9@xF4=}GltKZlqR0+k039z6J@ zIu%aq7%AfjghfCWl#9d&yra>T@xybN!KN?Q3|@Fr@faLas6=;Ap*e6>v*;%O3`j){ zwkPtJR3jC1=k{9Lm!MPRjne3~l+3vL=W#)PXE&p%HuNEmNKjMs)nevm1^!b&%W>ha)$=Mm>WY|Lw4lov{$J`t|-1%gtOh=xO)m ze%gP2*E7Kcm48)5IuL-glYWX&^}{Ih>1n}paF zEyTU=wf;bsJ`{c~hEuRCaa?lW1GtZ6*(S}Kl6$Vj=XdLKcko}&E{0kHqWm|U){r>z1;V`dLP%V8;(l1jcPGe$`H;{J!`Fv zg65xL6*#)kzu0gdnpOOqIWO;9$^Wjtlpqiwgw~3C-)j8N3iNHTILvX9U=}mQ2Dl0jw5fs)2jLvZMmp*m z!&$?ii!kv@=Ss%lKzZ7G%1CNtQ7Xix>_8xk0W*-BI~=}-be>(NWGqY*OL|{_3K1t} z9Rd_fQlQlwv-HQ^1d=09uDPQ#Y14~7m}>JPELTDcQiW-)e*_eFhO>t3XDJ6^pg?Jd z(q=M7Cw!|dMfG6eYKPjU+@}&5XiDZw6?D6nxs>iR6NfLuc?q3ndpgO+s5K9Q*#ov# zA zXwKr4+{hD|=(3WAGypgHqsrzeS#M*LhZE%8*=9{&G9ZqHBKha_LPS71AEpP8imz^S zxY6fVteChY^b^NRs9stqt|Vj&;+UnURq96oqU;;4tCAV#=4Md*9*1*^Oq$mN7jW;( z^~)MPnjcQTn=_DJr-9r_518HYwDp`72JaCS`a%#w^KC7Y&hxaC$z`gpvA z>ILcP>0f5}>d&ieH`Iy(oKoSA8I)Ci8qZ~pDmn%x$!i}boVfBOs$?z=<$*qkI~MiD zF0)q%mypAvy*?$eS$7|Vgtt+o?yf-~q^aUe8VG~YU-2*`ei zR3`&np~)D3bG+D6j|DD+sE^F9EuuMUe`7=_%d@V{^+3>&iFGkSArsRr!_3W<=Q*Mx zk3!UO%}e7zoP8`!g-ehx!jD3tqMJM;TnEEOZj2^-WlKiyllp_&G~J&s=Y zjFh3?w|DjxTfCYulnFg$rqT7222uV<(S{YWz7F@tX}(qNrfF=|5C@D{ck1q>Si3b{ zWWdT#VMJIQiIUNF1cC`v=Q|`i{*E=kch9e>nd>~aedSe^Y_b^};PJ4A>Qpyfsm|ji z*(IZ`Uo{ImTe*B*kY_ePQ_Mq_)X**mn#P)8St!VfD_>x4iDGcZYWmF$=oYffF8@6G zvOLz!?ii0SyN`Cz*hgY<*$jzfn542KJ5Uy24O{o+SmD)!8)|mS@qYlAIK_D`cwvG~4Is(OUg!$D|t1%wrMj&J(rg{DfC!AVVj7rfFS zRXAP(2~~g5pD$Qt5XAs+U|fQ1Knf+^dq$1s>(Cw9f zqQ2xx)8*$-?4ycOVDaXRo4<+m+psL;iGCk-Ae1~o0zKhANF^K%YR(4Xl!`vY&XT6< z=;y8Z95SXunRzz0G-Y=^lg~yh+(w1=V(vBG9}E8+B%f|WlCmn<@GP0 zws@;4UoJPoy47{a^)MMlvUEE`*}WDAbd&_N&V{oJikXzi6g$|@evZ7ZhHE<=IZ}Q; zHrr&NWwS<37q3s3cJG1g%LlOI#351a=O#FfJ>qAJiVGy2(tZlm1JYr%(d7XEVIAVH%@ga>h(md0I|B9wKPV!NEH+AR9H-{#BoE<>g|Z0te!eIt-Y8D{&g zN2=u?p2ax0yT8*2v?3p#D1o@G8$%4yt&UF2x*j|INlh=~t{Ff+%cXg+ms{k=vcN$pS*i$QjtA~B*%UPtq34Qy z<;im;l@esC2mfrktPmwnj8vyKAg}+So>&0>9|MM>Q1ZaY25=7IX5|kvX#J($?t|$t ztkAL7=sm2JdZTzQet8oc&Gn)Sa%t0@@L5mFig6C#y3IBE)9gC_C4W(!?bPN2z}2VG zNypmrcZq9NHI*$1`l%E4O(9~+G}&xJL#(#+y{(%TyC2AK9%RPM{xm)GAAgy;LucCx z{h3?H-JEsRg#6+Svuk1^ zC^U`^Ye`akLuc7)jP?Md74I;YN1xP2XFz& zlxXDkL{u@4C)o082WCfM^J8Ov^opw^=+gY_lg9lYouxp4sM{3Sx;MpM{je{a-7jaZ zHO}b4c`uV5F>*uK;PLm1eIN)a$Bv_xJ801Q_3PybP->K!`{?un8hi`j`h_QoGjX`! zA&Fw;1w*7z-BU)gpeU7%S=k)rz4qxfHj_Q}|8k~n4zfgIl^5gbey?knGlU2zsA3;Q z?Vm-_PrlK4_%39UZtud9b0K@=Y;YyLQY*yv?WY)xov!%{&J3__RYl7HN_!q1b`3Sp zqegBNew|~#o%t^0B;|hga`*&_*hTdLEaYq6S)6Thpna!4`wzr6O;Y`xpU;}J{=(${ z96z;KHO4zvq-fjhar3vbqsO{)AFZt$a-%dI3SOUSL_AlJCRVT}&yTv}=k;p80Z9o< zlNMrmWKe(0PGnLhRH;PR>o7mPfoZx9RkBl!f@a0v9o5!~9g)hgv4Q)cm>zcSeV#Hz5rpZRMb6KQQLDU?Nn?#L1T0V40@or# z)_4g5(&Bl4UOJQbgoF#sP+#N&=S$uvvdFxwmMvZLjV$^C{VuL(o>XP2 zpO4etLu0yCP#q4blTM=gTV}BrFFq(TahGT2uyg+-qIUcateZSIxX(=@a;y_Thc@+G zHc&iPlx8(FuYklmUoP9vE}@%;j9DcHojw-`XO`mOG0!R%UWCjo1S$LA9mBT^u${n})s29H25g zY(PXf5?!g73YFzS?5gIUd3FtTZ|vE(jm#o97{_#c)IJXiefw-(r6!INs<4rGMmb{6 z1SBw8Z=8>eHttT#6xI~NkcTFO2m5bbp;)V}Ls3!;w5So!UN)8aixFm%#M$-5+wvd}JNaFIte?i^XhodDi=czX2fBX-pH8l-gQM< zclWN2wcN%YPvj^e6A9&)IhugbPmOp%_V@ZF5QC#4Bi$<2`d3`4f$ys)qQ7p_W2`!ZImM-zJ>TDo``ed){RDL z|3SrZ6wzZSh3s}*?n)Iz6l3-PhHGnwou%MRGIS=To)Jh02s|fRLjL*ZTu$o&WO)Ls zrm5QH^EgX*AFKrs#Y}4gWYUg1vyls!1JbD)tm6X6-wYH(gHdsSDmC|@Wi>p3kdMT$ zMc85((DRr#g*b$vnZp^rZ|sc`Je9IFx9p09B^DkHvA7$O*K?~RkpnCw|L}&UJJoOa z+|3!#lYF9i$JNiLWbzn~>@{_EHcBQ5I60e>n#EHQm^*Tp53C3+E>Nv)#hzHC(-Cr6 zh$cjoX(VVT$uK8rtPDhYoj)Xd<^$LSk?v#po{k|jw>Z@I(=B}7HV0_nZ0v!6|HK$) zc~9)?2Nik-pdqH)OKp{@<$KCH0?iQosq{I^B;2Jr`~xyr1-!x0unKgMha?X9-5NDG z#UpOP^NxwCn_tWE|JZ)&Hw{=CSo0(}*Ve7}d2%dTt>tp=6`G!1&v&>*uK={ptDk1j zNr}gQMOZeQPy{@J0xT0FEVZL+QYRlrm?BqtFMsz z>6|5;*@O+J6jnKI@1&?~c(b{PnRRUUl4{xSYAypCJ_hT#;{RF^u@@_8I*P{S`-zyx z=XQI1bxxyANf$eX&ZmF$+z+PR-WVc0uf$sNzaz#ZK+=%ge(fl)LP1?DT7M7Sd=ET+ti> zg*wxcl9K$|+MA|hk4TDLbeCU$69s<7oX6@x*2g8A#vfa9y}4vQE2m9!wY&N0gzu`C z)_(eX^Pf3t|74PX_b(l+AHMwvM(f+SaLVX^n+zO=ZF3qI{2zgy`=I~; literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png b/tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png new file mode 100644 index 0000000000000000000000000000000000000000..9b29424db8dc89e7b3a5da1115be8d5b3772c36a GIT binary patch literal 144089 zcmeFZ_dl2Y`v$JM(+~|r6s5AVvxUm2i0nO66e25|x=TYwQuZh!TlUB(g_My!5=F?! z-t&80jrZrifA~JW-#_4fJsx*=Uh;BX&*%9(&*MCfB_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!hhw?6 zZ^L(5s?|(MWh#wGLK!kOph0Os5~)a%GG-Q5YgLBOKxK%c0g05Ad1z%Qg(y_UZXua6 zkMZrtU28qv&-(rGe%toF@AhurmOs|x5!ZcQ=Wv|IuYy;i ziON!xb~HEch!4%pzXHTe+yfY#y20YK5 z@%LOHV`4#G#n!_XkuclnJI`h?TL9j#57ae8xMQ>4u(GC4p?;{GtC&Bs^sv;*6lOyt>Q)~;sohc%B0{1-h4TLbfMR;f52S4d82*n)~y9ASGE_QI;aQizQX`z%$wkD@Civ_p>0|Nm?C{J#CT*-VgQHZ~6&FJvqT5!5M^une?$;_j(?&a8| z10-tZq4nm?o7wbFU}VkX47nK*A>5ud=Ek+%uk6j6954a$w!OM!3BxnD%qeKw(vAd@ zqEbKAj)Kqi+%0qOW0~{dS_>lb66;y+q@}CN3rV-bu6>Wf#e0^Ye+2? zbUlBv90O}`yp+(AmDK@3ofC%T`tW}t%%}$cS2ca`kwU1qx3__Rplo~mpbo%oCr+Fo z0m{=woy|Mk*TMn5^s=}M#bwQw=kJqhoXrnQ1+CCL>6}+@IBkJ&L~QH|5{9h(+U^jU zn3(vgo?dcQ(KlI659{cJ1SqYpWd@taJs*DG+uPfDPGw{v0@N%0f96L5+b0F`?R-?_ zSM)454K10F?d$8iOJ6^v`p{XD2UWMT>y0WBXzSn7_h(|FDym-qe?ZX?SJSBI-Yal6d#HFBV zdyv$Unz7OTrh~%j_Z~l%fx|X8Yq+|D$@Gy}`Dq0pzx2+)A{=xbcq&xXypO~&A%P%~ zIaC%urzg4rg1NL4-U99hJ9Yb@?X6?Cc4Y5=c=-7|9%0(85C_mLfc3+>ezUi6h`p@c-;{uz8ur zLc?#PjCxAI`7F}!EQNVBM))TQig?VsfI)@BwKm0lDo7&?(iC`#f3;jmPKp(q{9cd`Q3ew*nf<{W$DIv z2X~W6A|Ft+&FADbxNz0(ML_}0NGIqwDhQxvXJMx>kuN?E6OtZF9mm!k3YhIoE5Y!X z4S170iFFRVugIK3W(6*hBe-rm#H>=Fgvq?3Z{Y=ZddYClozAG}Xp#1mrm$paa~dQ0 zQvz}j?hrq~XL3R9WWvwz!g7oIA#g{uCf1Y8>CjuIyUEnFN#we8@Jv}g^;z93fngl} z{lXeGH8oPOC6Q3b4K5Ho)l=fwnvibBfR zltpThUPPUQ2{A&R-x{^rSc9zebj7%2ruR`ZGq3XU@??<5B5&n{PdnEQ3|2m1@Mo3c za9cu2w|mtt`%@$JLjIPgTJ*6Kybk#*xei#7sIJqsW3A>E7JfosKW$gq3FG7`}XZHX}O?@N5G24rGAbXc(zHI8;tO$aj&bZm0Bh1 z7v8XSFAT@wL%Qjdf&16q&No^+auLZHBl7Mn5Q{%Q6x`ud>|z9-2Usi*A)n?}bNcmb zr0=<8t50f;d|ak7uT$Riy4@ZFhiW_dP*ImWD*!jxJvv6hQ@MaC< zCc}4%L?%ekr8QxoLBf3=CiF!?FY=X80xPhowK`4K+1Z&1;ZaZbuPp~8p~DL`RGM;_aUX0*GN7TS`rgsW zK6>=1C&~*nnPmR_Qd3hmxGO9whqQ@+fI#O<>0(tBZhD}!tTNi^|EZ z>2b(jsbU9XJ=9>75ScH+3GY_}0L;Mg!HiOs|8@1vq**&1;R+|ub6xHj4}9v$L*o zYRW~GhZeL1&Ib(tE%-%6S0@dojT@h)30{7FI07yhM&2zw``a(BijCMnc7XNuQC(lZ@If z&Zt*l6ny)7XN&0=cy&&B^>K!4xt=MhvP8nK+Hv{&Uo86YYxeiwU6ohm)O3B3^H2wB zYdKlpetKcSj=wt@cu0P{xJl3p@u8%8m%Rrfu4~X%7rgU*c$#OH{XJdl{EhFo)NTaN+)Rb?7vl{wm>Ms~0Pv}*As@+x+wE(ctbrg{UT;#m9 z!wQnV^)UHfK!W7^yN}d!g(u!v}JfF(ZY(9yPGe<*~+nv&qb?`9Xyu(wR86`B3+60pr#dlFnhJ+u(lsn1-K{ z`TY5_X0zhAM=o&RI$7!a(;4SCL5bXm^zF$%G<`k-dLgi7T{Ytl?B2~iL-ETx2%*U? ztN5;Y{&3Sj6K-sPn*hGqLK1rawCmf@Jh;C1Xn+j&T>B@SygA?`^5amP5&YiYVD8Ny z_VD2Yct#aO=u!Te{`aDW9+Cp|ed8Iy@7scr7Xd&#%?@&vl7j9dopa~TeKr`pX3ZMN zG=Jm99s%NiW47#t=I8 zYZ5@LNd9n^FXGOfrD7G|M>%=pKkv!83b_iBQ6?rjOv~5uEHJO+QQYK)Ni2cR_3yv` zz6+CuK!t2d*blwXu;hHLuOwY0PhY@RPEsjA{{Ku|w=<@+?P_*V%SlL&x(HkqYE>CKIYq0tlRLvYi=%FBEwvti}W57!K6}iFKV?> zIDFaPZ9HoLw?5H@ia7sz&k*>(%-dHDMez$C_5ZfH*^WEmJRor@-t%|22l~U%o49nK zn*QLGG2_BSwKIa>Ugw|xI)?mX_rL#)`(J%k|M*uk)`d&xL3utHDbx}^ZHWgnAs@NM z$*Z`|*h6~^mN#chJTDKA8t%DqOF0;M^M|J~76`SK^+&(;i2Q#VGA zv14Gg8;|1HHh$egeAa>;pIchU*<6;PjGNC9ZU;TMFK5;cRZGi`E%6obdyt5ovWknb zs{E}bgE4rpcpT$n@Ye~93+8=%jCFDEELY7($Vv}}OUZihY@Toa??123s5`-N@IU{L zzT5oohOz%Ev+?sW-=@*yf7mHM=jP|!{AiFc8~;ld=I6foxo>{%8`d6Ju<++$_<0!q zPaX!XWWNN zghhX`GDmD;zU#eHndrWRJ)C0q_Zl#G59i#sYt>%&=Ggr`HxJ#qr*UStw!yx@UDjp- z0_$e-%;uja%5gt-!%U7XHCb-mqep@jm;KQls>rV#K5z87or`;X)yB4Fp<2ObGdU0b zGdHYne*Wag`S>{-KWF3H4E)>)KX<~M_)p;E@uSEBt>KDBL#`h; zvd4Z;j#aIBHLl%-R93D>`Pc`5FEtcSe>c_Gx-|muQR~Ja)4UmOUw;1tqRcqi!YcrI zOAYz#siCYpxXmMsO~gQW>5^MQL5g-`RcEhdvNH_O5CQMIp%0!?(MG@FM7bz4~)8_)5Vp z``O?965d^1d7$oh>YQo>RIjA_=*aa{bOf#OMo+vPU?2Gb5qbXl>^p6JeLnQr-obDG z_K>7g*T<-sm}6c0QCy(^BiH)iDHDwZe9?hf(IPmGQ0lO&N-Wx%%g8-PhS3H=ij1CL)Oxa@4(h8f)%i zZ&BM($AJ&$vXRAp`-B)KoHu!YjI8dAxL+^#x+b^>Gi0f||vJly(-nw}D(gPJ?%Q432{bDYqPYhjZTfMK2*D^nH= z-D|2w3nM9gO)9nj^R--ka`w(!nb_CKb*HBoVHjRb)8#*2aD-@hJz${J#xPehpMMs( za^6UVvrZSP`7|}?Co4-WdaPfqpSYw(cmI9?UIVN3t|-6{j@V5;hT3!|#Cey7K}S*z z<>aL(;Tb~;(i#<4H83n9aBxYH;S-Si|+3>%oM=5 z=E_!0(8%CFGv zH9BXn`2t`&CT2R$!5*dCIgWfkj>e<<9LK8JHvtOXgx$ytnx!eXFwFULG`e0qoeu3= z<9tV07A6`9?@*LAE4}3itd7H{_7%y1F`)Jy^TY{YA0sd|2+Yv_r5fBFzfD4?R(HN6 zY#Kl)RUgt`TVcj!_Ns>|I@$b|#J0oUo?6b>$TeTZ&6Rr3KXC%;#~A&bpgdN&w7M36 zp8>$ct_-v#RVG>bL+SI+E&Z}rG1&YAV?z}=(gX(~$jSC1IkY(@CV`hJK6eg!2Cly> z-Sy$m3PT^2kqXBk49W zkRuIxgD2MEdV$C->IaKT@chtzfMmfXdhl8vKu?#Gz|}o*0^EVRVk=yKtxe5tA-VWw zcn(k;=cx_vyvP5;=SD|Gc?JguPiQ*FZ?hTQ8>A%kboblo@H^K1Hm%6~*fAq)JE!Mc zD@g_%EGREii;UiK=+pITn*NE~#nfp?!hKK!m~8vIkAjWR^9!_qQfE_4h-oW^%2_k% z$E7~lAHkTa1`^FuOwkp`Mk+!B_L2TE@XD3EH5CSz9gpBc2$gs>ef4&fO@Vjd3l*}; z9@mL#`EpAq09t*qBrxdswZTf8o(v-Oy7zB$ItUPD}uE};}H8; zgOrC)oG?ko*j7%3{4&S)w&D_-Rs?<@SA2TcRzvC6Uw~0tT7+6U6Z==G>q-T#%ek<# znr#7=fD1~x4txPXuhPA6tA>U#dZplS`kZe6yU5S_+y@G~VXnFWa#>sisg${3c@~== z0ScFSUb<+r;$`#r#>Zd`(fQ{thS=lcj+B&kSCDp%3FTOP;u*++LI9UVJJ{og`M^i$ zJz%?x81|+xJF13gO^`DP#F*CeLc0#MyS}j1A`^W$dZsrK9?Lp= z+{D##@j$QvvCyQHq>RhJ=fDV)x3>tSIUW=s#hMa80dL}S;2adgCd+eJX97UU2Z)Jw&tDSTJ4mY`#AUHs=etVm0p@E#mnWD)J2`}RnDf+ zB=bSfYsEkVw#Qz=UcWeidxN_P?ZvEO22a(8VK2<+d+HnRDfFrC=|Hrs?X_58~hI~+o!O*PRRH@Zd-HDY6UgieLye|*Hjd@|B#=((Ngiayug=$$QHCIFj1 z%f!UQ%haar9luT68~9Ui9G(SUEGD4@eRNP#JZ5g*a$Q$jTNOX(zVaQm^6kOdesF+< zAHa3U88mch)48Bz)9~^ABl*K0+9nTLV0Y-I!)o>x6{(Dk$e}ZP_m%HxkZ*s!?sb4n zKSy>EfK&UK=@&TbKh*3| zH$e4e!`-;O&_2-q^WfnfI6A+p^gD1co=pswWq54(5;UH%Iiwhs@As}X3`S{V_k`^w zuWI=i_ChcKzYthlj?^I6_o2teex_nYSm8o^vZn)hNuGbQp21l&zWKrB_ zctM`HxMcO+fUg63CgEMzb3ylI43EUY^l^;Yr;GW2_%Ox=nQ+<7yMZdJ5@Wo2xsUa- z_u}F-L$6+$bEhR-Y}r4b2vWz^5r}NZI`rMQJcaGW^uAv7vgi{(4o!Fm6U=+q-#{L&*QWJ-Z@Kgw z(^l8ECFBeGz`uD|qX)t`5dybovO6Uw7t7Xq?B4(`7xDg#2@8x7n z>9jY?s3i0!T&`(FfR0Dt3f!KW_SUt{{D2Q&PKv#u{>nqkfw><#pkfIwBsy9u_qsm3 zi#4yY6vj_(kGXO%oIZ3RpUs>T=*D1?E;rp zZ_c_E>HGI}*gu^nn}e}@z7G1|as*RvZ@KuOr)8uOVxQ=yp7v@5K(R*f+1MVTHU%Ql zO_!CRkm(0CuF;C(uh$ujuH2?+j2kmu8^3KY){3(>!+Ndd=f>BKP3G`k2lOH{J#*~l zg|pyuNwH?&!kHwE`f9LG0ta4)k7{=urvnM;#r7|F<_}-9&%)&Y2Eg{RqA5CzqQJ|T zJ^by9{r;5$Gvs z+MUa*s=cN(MZ7}OEKA>53eJ5=lnb^hwY*FKq}sU&>=Q3^qjWyk&$h#FJfIyK5E$4n za^)>}C5y`hY^rNv!stB1M5@6O&T9JhP$1r;T*#|Lq;k(;kD;L;(0R2Vs@Y#Qos|gi zM?=b7xNGx6-4Sz9c=e`B1ueI8oQySM&s;H&H^|ae{@BunE2_FK7F1tJ;IReXo12oq zm2j;F;@=d|OipG?0A$ClhYeQ+=#6irufo$4RHs|PS@898obWTPLdzHfm-~hpYs=&I z^C805T;h%~vjTqUK}U*AdD0oKueZxCDRSxgbn_oL9qR>l`d=x`U|bNwY;6yf0I<9a z?c|!475U3IUeoRliGiCS|02UIbAOyerAtQ!$#z6Hu+8NKCD_EpHas3=>VR+Gvc!dm zqgEgO%8}L+XKead(}q}mtGGf%wVs z6w%gNKc&96+7G)wAP%r+jsPCNMSK{&TQozP-m?ep%t$WfB3vfLi1(2I+21M+(rV8lmAX?J2wV?R)=e z7)+{JIJTU_mo;$nGF7tR2&j))unjwH7Jbe{fs;GIx0mRA32<9iusrZ%IZi-^MWWH7 zQ{lF!0KZ+61AH^znBdzla7c@pNTgInvs;nnnpoPyD>HgZa|VgfL4K*>Ljv#;5s4W@ zp}mBjnF2ys+8EP{&>Ce9T7x^(bh-83JCFdg@Bu6dRgEA>AIy1*#yhtmPFUbUl@P)VaC*JWw86?pq6#Xa+J zH3nS0x-4uSq8)(z?{4YOLK`e%do2wUk&r0XQ!NSx0(dTBUuF=zyWAyL4Y(2MD7d;K z!3I&36_hk_v_M$5YtNp?PuUIFPJS|A6a`}NVL8%hsd0YX_z5|+K-&wX4oBY&^F~5N z3H`VN9NQ`Dh3{HlRqI&+YM)15A}iQKOOCn$P&@cebx@K3Sv?cWhd* zTtvi+m^oQJN-%DjA`oQ7A2ybVzUj;mz&oGcb{pl+N{}rhQUfksb(|L>SCUmyH*u@y ztM#O`&4H{9kK_@qYAJEpnNS4c(KBBkNV8{0fT0X{^X+m+aER*(I^ zBh5NtIu?<50HK)w=qmTTd8RpFlI)h4CwmV3tbDk7T7!G)v1>_m;yj=1$_@v%tKdNk zBJgTe^ypwhamF8!&?=}nT)L`|2Ilq*rJkLNNY9oaS(RQDq(+Gu(&O=mLUKb}5tv~l z!6^h2SyahxhGtLXJovVdj)XFNjVSo>Pp2!yZgJpu8~8vJAIx><d zzXU5$?Cf-b`M6)-eNdoag?InSUFa~V0-X;oB;_>@X|Zi7d%N4X2zNRn7vOU*E>)C> zNPD5ou1KLDVq9WbQM1qgDZfuHCs^8iwE&tkFKnDH@|K!@pNG?Ux}l*I8rY6tTQD86 zhWEb=Q&KQQ2XjZX4PvpCkd}X&Y;CNnN-iqQ4gWbo=c9B6Mw{G6mubp31T5t__vjd+ zGOuoE3(Pq>>&H=hFp<+qOW8O>Y4voZej5#quj0-KnJZ^?a4NstgA`pe8EhN#b{7Bg zpFi~8{Q^}B_OAhz$=U2bxv=o(PyRC_KWF1VbHQNzoQ?mFW@ALcrJpxg=j%kPk=Oi6 zslQ1+aDTL6*O7grzef6uivJq%ayHM?3;SJW-A|nNmQSg!q_HtGho zMI0J%a6aS{yjGa|WZsbnJ%iOFVF`sN2FC^mdYqs9cKy-Qe%B(WxLQ{>Uv%@oxGP@& zq9kzri>dN2;NW`~Qm*Bg}E|$EgEH;OAgi6SD5-%zWDz+&}jWYa%ZEJWZ^5 z@c3zGz8#FkKP@n8A{P9-o4##`pSSk6dHCrkW7vkGI{B$9{ zAB>+a#J7p~|A7m!`NZvsQFEZN>4$V~Zg%#%spumQq1vg_rsYC_^i4&@CgiN?e;~X< zVlbq|q_*96lpT%ek?>3Q)lXk! zMRf|2!-V?Zc~od}3xPBAy~CDDW-L$`_a$opAk4_UEAjx3_N{yQRooPjz&$qr^xY!i2q?EfAaK+XMXCBA(=e~b#>VBdC+iNe50_E3;Fs)K zkmh$F;MT4cb4b%vFhyCf)ddC4{e6$};^h?;`B8xMA+_FfLT+;jzejjpbdQ<`sd-Pp z2zwufv*Ae?>)bf%##-9ie9?q{wK6ikB#q=brM@b9L#;;jugU4B&{rT26{V>oltmV^4GiL>!4qr3sCDkRFHhy+uJ?o@^xv>X)>Iq z)wWb|G^N1>ZD2_0ECIhqiGEVrp&b6vW5-fOrP*>ejGazv0tIhyYlbTekX{gqq$KHe z(!s&MHC2DQ)eA0*!J$w4oi_2E8f)OM-`+0y;D2& zyD|7~8(ZpCco<`VKbE|IKc9+sR49R%iu?KjKCW34vc~3o@tffw(Rl4x_46b1gvN)f zxGUSYzU3l0Mk<=2$zgm&6B`nbQ8z#8eh;JKDN_9`(LpGU$wAZS+O@~WN7^$lw-qTE z-rVV#mzPHfoYgWiB!LI?rt!xpAms=sA&=I5^S5nB9GoV6F z!Z?awvd4E8DRksu=bqYC%f1Ue6l2yh1fgv8`0-d> zM<@v|i7Fq8Fy%aj1O2t``G8X}p;1PHQy1&8dR~wm^ba}_k+ST)xFZVgohW(bE%I07 zhCrf);?So^-PMcOrj${!qijMpK~~WRD5oQ9Oxa{WL9a&vV7j9aMgv$W2Y4(a^bx8! zT!eyKK1%M!qa%aR<_^Bt0tm4eaA)~|S~5`__CfFJ^S?aN%FS-*-W@#~XPP8zXd`2+ zDo2XLPHnGY-zgsV?tbQ|16nf|_1U@jgUe^LE^{W5Dj%@|pdd>xUE%P>`Uudv^Muxsd(gvi>kVyTP3Gu}}{K7TC|RyHK_sswx1{#|*z?|JWGy z?YAc;2SXf=Xb_7!J92Xp2*wQ)pggg=di|MrQWZCqEYZMD&Z+D0NqhS| z)DUN$*>LD(ny*_{ms7O1_md}2NS~dWwP>?O;e&0x2s4fT<73t6^I}8Slg9H~d_e&t?Pk z=WCR(_jxD#D_z^5!Tf zmG}1U=NA7p5Lu6yDIOZPcSD{FEipEY!2S}=K*#x(cM3_nLX^|zo6J+U`%(|~5hP#K z(P6lP@j+$&YUvyh$ z_piuUv3=p(nA6K;v{y`0&po>};yM9-#H$QE(ZAHm)&t00_`W*9lRwPU@ zYMrL)?ZIQ_J^N7flo#plBSjVmU$k;4D5SlxyZ-c0({NRHRlnlIlOy%@Y^BdYPsS?t zv1to)WV8Qdr`M#vRn@-#!@4EH>~I_gf&|&8&!bKI zK1a4Yv`2+6Za(aM{yf*;igDjZ95oc9!;m{574))a5|72E>B?-gz|dY+CdEjPJafn) zCz~A>vCd9Me0;XT?gjRnrYQW^A35NULW_2`_MP>a<&|UKw(tuZkb|)^L+1sZ$So;~j^pB19bBsa&(sz-?)R$E%URE>Nxx>~wwFK=Ef zEGBj@r=NXO?d-*0egP5d_2YgZ`bfdo3$POj;jPoZwgVPqjiaUx4fqIfwy1J_6zGuE z$KEVQpKks&$KH5`hK3R<1`u~CaF}M3?i+q94?5E<;p1Um-p|#*P1U0TiVMM!PlW$a zi%m@U>+RoI0KAXK%jiAh>P`Z7u!9+(rRimvIk;3fqE4n}B%Gv@KGQyCoq z)=<6R>wI)gffT#9rzhYFVt#;Zo&FPGg%yC&x#vP!tsW9|VxKOL4JVqtWeahBg|3$ zG})?|==JJdo9XSmm;e+bj9YUsH_H2!*91{ENSA_y+>;04H$O1sYX9eo1X& zB>z%-s-K0mB;ecT#oSz6oJno=XzIe^jsX-=s=NuZ+vte0mc&}cErttcj0663EqVk5 z_OVoT|MSSGxg6O`k^$*A#!adJhx;rqRcQXp6Y`%nz?mXj!qNE3*6ck#X@H0n5Hn5P z(8PY07AXDV;X_wmuGS7EotdMBy0~k}zl}sspLszoga_cad$UXb506E{ASBHqxol}E zwgNwc(V)Rdo(nWX%bfUb%dxMy5^h|;_!Yg<9&19oks7AmsCc%&Qs3T}A+i!1wb)0n z)9@FMDSD5O>!o8V)hxz*Jpm6ElUh}Br4JpZAp=y5VRl-+&x=vvA!cm{LeeJT^0gpS}sDzBideY{`}E+00bgCcrJpw5Djee*AqE~)(4VsI?Ep+bsyL1~5^BJaM8cYtfRnk+pN&Ygjz<`?lR4bZ2d0~7mtxSiJOKA*13~H=8~bv9 zs4K87dC<)E`6XbHFxuP-rL{fQ&pQ(N*$HfqdV;3$8agfn4Ci9kl@^$=9N^OgmR&!& zn~>7P9Gx7RXfuejPLRa&usq732>eOID;R=@Oe6;$v|aE6SXP}zaJ2LdK>X@wmu0peExiB5lUO9h_3@* zKkG`O(Zv9yg!wQxn)Qil;`>uq)0A9;#5d6{0jAUX>_Pz^cA+29o~% zPnhb7H>Z9sujSY*UAEs6Tithic7w8a^02AtCe`CycVHH4;W&f2yF+`xfcAZ;YuEFO zXxPFv#ycb)3q%}`(j1+agl>z9^z%lWVoRNYBsrl|J-g7iT?Ku$<{^YzdG}W_Y8sg< z;7~;t%MbS5;oe_aX9%fG!tbBZvy1W)M4+_^O^l-4!gYt5c~~bOz<=|>cIhS!`hwY` z;)Uo#Qh%1u!jmovJ=5ztD_z)5_5y~1DwsLO=r*hW%kge^&Bff*#)-7o(IoFHkIZYj zzyLoy47l#S1)iZQJ2HWj%JUdEUiA3Vm@t^YT<4<3()6{TZk+yNd1z32zg?LQr}V}{M9ctYFwoq?&X(djx@Kvr6I;VYXd%)3 zQ^^oQ&WXJw0vUm*C*kn(OE%RG0JKsheM`JYKNP)<35G~F6Tu}Xx3KwQJF8)C7mek; zymZ=jFzE}$L4=RYxv+2}wLue08l^o*Ku=<|C*wcH4F!Rm=DF3Qm56AQhd$qXabKnE z1t4p)iSGOU_Z!a-OSwVRH4iAd&~jxS6F`y)x=9I<_b!E?w35S=FrC1o$+!IV8X^pwOry#Y{uu;2?{XBMABcX&f%W8Qv;Y91mM@q^GdLGtDfcOUp_hcIc@s=wI?2KK{@A~CQL$9P1 z6H%A1h}NBeeHDOd&s}wJUFgZuEeYT&EofQIi!95H)vSC7I7(m4i2nEEx74J4>$dT+VDNv0aod0BqOe)3CcYYvq7 zy9G2hvpEbgyyNP)-=NV8N&BKt?It9SqBc*Gi#WOp4MLxD{`N#wn2S7slb8wefZx4) zN3@qHBoJ_QPC(zXhh1^Nv^L0;t*Q#j^#zkiuYOU@HFN!|6ZInM~ z6@a^rpQG>YE?*3v5&n%49$JD46>h;j?1jrXr`WCU5%FbaKRr9m2Rg)es%&wzC2c-F zBZ>PY^U;TB6=vA;xlBwGiUp*4V4PHKFV?F>ISS$nSl|kC1iWA4emLNx z)#LUOOK68Yfj6H; z@$RKKpn-6b$6Q!CSkQYrhgN^wQ8tSW01(kcgP0s54C@9 zMo@0YdyOmap>K7L8t;DAJq|bFzO!Xv@S1ueXVm*CtX#T1cs5BMtU#~a2A3L8J@79I zB`VTH`tpM%cUS;7&|Tx4oxYa55l zu-hO-@16sQzE;Ay^?}shVeXn^+6BP?`K}-&xYRlK?loqmi^CvtFZc1n#@*$BZh8C&+fd!IoH>q?RvYPEiJ&$m-7-TG3F(54A0lr~Va`$T9}$ zLSJB1yp?V-bUc+yb?7iW)+RLi<=kF0|FG|6i(cMdoW!`g9#?2R<=Eq&iC<|g(%`-7I z%_lRwL#bCA^oE;nD_vxD-xp>r;dJwA?fcDwmgmWivh5+)|Me2x26OxAJ z@O}|rxxirH6dL1t5`z>iCYW%seL$fxWk&AKB{vcgy;iva?s^3OzBbLeh`q_)?JkGQ zduMCa$PlRWYG{V$)j|>xpo0YHXORd!`e*4eo$(KffX_FSOH`96$Zm5S>44GoZ2KZ+ z+_<{73!4`+N%VyrQuLCY-;v&}$?{xrYre&0MlIjeHat1w4pN00n0-Vll05wE0*TWY zKfknudXMBlnc&4+v%A-&zDh=KSgIL17YPDU>kP!^*5Ef>H7_QI6zjCr-~bww1Ws}r zZ8M41>E$2?02%OA&|hhRB@oUTgPRm4X25Fc8yy#4R|^woxwsjzI_V?YK5ED!ASG zq-lelbFv`CPkHE*O`CpL*Z7fWxVBkU!)QjKLOY7PqSm?P{$5NhdIZK+x!ipU+scJ_ zN!tvqi8sj=g{l zUN^`hEr5L@Vop4|#2#fZ^moS6K-!ihaAXUtls?6rgL<-}`iU zNhu z3HK>rO|xQJY0(MDf}k1Y*~DIn9jM3bNU6aH{`J8SXuX_6OWaNHVlzy2uder*AMAasZ^xm^(hOk+u{3lCNXd@ zsiX;yTNLPZRR+4nq9S7Y9Zko`%l-4_{G3ScUm?;tG1!tjiYiP93w#WFcN{nuNuQ&K)iUh zuZ9dK@xR(mMTLUr7-o|pJU$yOu~t}TNKMcad-_hNjPV7sQA{);*`jwD-aaYqaBfd* z!UqN^Ib$2p1;;=fF64hRVevB^LR zc<`R#zVN@t(N@J0$bz3vq8ujGWE!c3mgrH@9~PA1@p&V|QH&C@afm4>zjHC$QuyMt zSK2$}H^iDWYrQ)i%N1DP8uLD78f3D_u?kp2>2BhcfrR!yJT7_a9!ScN&`&x7P0lB^ zOpYv`Q&X&jFIsi4;^HD#BA^9n`=|@@TU#z)y{fy=_P8%iU2_$ygBMuFdyZ9)pP@LD zq8!d`Y({nGS9pL%xH?LZ-Wb5477p5G!8IZ-;u<1)Eo5x;#I*KQvukibes9G!B6irX zbm$Foh#MN;&L?LLiU|S9hFqq)Iz?@uX*wX>PkfUKvZN~fd9j1S>{GLaA$JDUcy)Bv zG(rxXYnQ8|gZ}uG=o;O9j>)mZ59-l;*1n+Edotth8*@SqNqHIk)S$k!Q#kY+`|EWSKLOS0y+~1 zIM1PE6k5YWeYl@G7b3j&m(1C zVPIQ0Cw|f6siSCKwSsiOl92;Rn$&Dzcy;UV6Q)H_W)p_tEk2!z=4ig2p7@T{U~#UJ z^GTe;7aHu4?E(QI&K1Iq1mU0kurh~UWnW>t?OVGOclR!*@#MfrG{kxHBZYR+4KNn@pm z)>{X2ly{`asYaK=?KlD_eZF=#1wk2%CE5p!h)vt}vOkfyx@|CqSXcBg!6j}PNPM^S z`~0_sR+9B5lJ7U`g78L=cKq$B>||7J9ggf=ynN4`c-a|aM-c3QCO(H;&X%djF8Bcl zw1%QuBvn^Ry`aS>+P*8sYIgnim_tabz>B~kNt~z$FJeC25fO7yV@7h~qkEoN#<)GU zrWlqqJw~oWuJM}j?wa%bTqOv1C@DMgX_HFKjpski41-}m6=eeI6Gik-VcB8I@Ga)< z%vTweL^JTchq{T)+KHW(hh)Q^FDu+1Q$keaZYVd_j7MfhpcZ^Wjr)Um-O{xi_4*`U zg!0@^3@SZkVbV;Wn^=6o68F9JOUe8kB-Vl+THxGxQA0QQzM@B^ejJR4z&RwhQEhT3 z=_{_ztXGzZ$vi#bBQ7F^#>wH)$lP|0bQfp>(JW93H#zoLCkC=^XunSA5)-NA4Q)sVZ`HB-GPTm(6IKy!@oqVqz0 z3vMP}_=N6USIS3kw;kBEu>5{tv#pqhKejA3jVeqh6EWfzy$ZOBj?nju1U|wn{MR36 z;^3wwsAb^fX&CTE`wa|)0B)Esl(g~0M#%$5Is9gH)C$tD3TT1t*EAnPX@xdr z<~ETNafBp-qf}b%j^KwniNa-7PNNHR%d+dUh1>=X6{I4eLfVAJBBD4Qf_y7S+v$NO6v@ucj~3bdOxlPV?YRV z0id2(VquI$I(Y8dIKG_)|Ks!P)H5iF>$^S#p>X89loTQuqCN zEEl_F9+EW2_d%8Chp!vUF)Bonx~<)~*snVI<97p-AER~n{jlf<$V#D}i1N;J`;P5p zIv}7^=CmM~5`f|v8dJi@(0y{tJk6rS(!cK0nOh_)n^ZL%2U9?jt^sSP$duC06HVGE z-+BZ9!r=3$XsuWnQgs1#1T(;mr4H!Xi&N~lnysi)Znlx>-M@dDIM~K;twA^!VJP?jh1b&@S&O; z#ANiD&REiVBD7b8AsbCOR1x~*X{SE^s#3;PQuOw%;tCr7)G}s+%-|_ zHe`FMKL<@Ve|6&ttMI9+x&oQXwEjECurm%6^dbhl>ax=nId;;+LHMMkx)1j&)jYIV z$&IRE6nfo!k+(HzDGs z%WBJ-^qfDDd9|Urxy859*2d0?`<8?99DMQVcfY;n?3MmiK6 z0+Oi#<%wW(TUbW1KD5s>r*UMWx}(xCM9wGWO0F6r%$4Ysd54zBtdtZbgE2cI)~Arg zw#G@ms-Hz=MwFBGGM#ZbL;@w(P~L$ozdyX!dv8)z#s-V6-MMw-MTmmHQGCbkDC-fa>52xd-S7ylS)I#hqlGOL&;t|Y~Hik{J zUE!LF92~K&24kos%mzwv#Z|-RJ;+QYqmYed!^#7lm{FZUC_~cuD+s3fg7ckFogpkt zaumr>MA5jP)_f;~gnb)I*`N;|CzfGzBa7^FN*U$p`|s}}iqx-K94hon7-}Fu+}Ko3 zJWudK7oUUHnb(oaPV2kv90li$^bkeN2~Y=ll@a@1Cv4hp={!oKA{s5S?;XTEExNe* z)`%U%ypHSoyYe1zwWefFPA?e-x&?6MBhp1|NGYqk>0gszTnUU~Ve4O5jb))8){oz$ zw#22ajLRAwvT0_!TC)3aogFSl(DXO%0cn%Um{X)vdpcZp21gT8dbE=YyE9OQ=majt zBEfRBgCqN68fH)M+Uv{RV4eroT0rI?*WPPNJ*EdBV+0vnUpD0Ptxt5&%y5Cq?#)8c%Q1zU#GA-cj{&h=|tOQ0U`9_^k?y$2t&&ttE|16e73kIl!G#&v5R=&kO44>>~XnVS?hGaRda$^zB0WfryQOrcx(z zn73nFknE#wjV3ioi>ZHXJ*sW*nc>E{^AsJeqTTnfZRe=H6xf^CLfw`=!U(qk3a5|v zhG3T<7ZS5=IMnK|UoQp*@;pEMux`$Wk=kYG7)yO5nIu~l^NuPb1SEKS_W_Fd7G-YQ zmQ+9>tQAa>mQf+b#snzKj}&$~-1^gmWe-}Cgbk^Z?j9e@#YL47DyCGfcDPf9M5G{+ zHI#@n##ok=lllswkdm>{BizSEcfr~K77ev7Di0z|2pm%3qU;FNWEN3ww{2)DVT-A& zFQp|O#$m}>Wx?9fzNEI#No$<@+XX1^c80x15#zMcb^04CN=q+1zVQfyM6g_~_h zi92x9GtulpO>dNM+WR2A#yAeGM(NgeHoU``r41mx!I0n8UXAI6KJr8|8x5%v zY|F0`!snr3g>*OXuXPBoSmIK^@0rwqC8JC=|I-gFG7n4XeOWQ)H2UZ-^TCYnrgyI4 z2m*63l%)RphvSce?2?Yix)TFc$2DAFQjDBh4*5ESr}=a0Sfc_8kM*D&_##NXU)9$N z4~7Ju{>ow-%j|^=gVV4VsySC~R(TQtiL~I8j>TtvZL=g*;Mu>9SY(bh0$;G<$)Jq8 zA&x!iv{Ten9ami7XM!XQ3r2waX#@h7%EWwNet7U}EZ}qz6t--_9@reia*)b?Cqzwi z>C%GqU*%_|&t>;`i8uhyiq!^ykV8*zv5ipMj%7B>5FDV7w;LB=3u@)?y;F2tC_*qq z<^2w#5xIlnFv8Yf`!N--CqwM^gLp_jK7YYKmsgi)J;18zRxN$os_bm%#I;oR@VUB zhkn{J>K5>&_&fqB%1saef#NYjZ`C8xsJT=3rF<=$EceW_wcTqCqThkvtc5wNpQ;+e-YYY6g!BS;GA|FuCFWdVF1(sdr=r+ZRb z31kjdw`b}P&(gz3a7|bWf<0nM2@$o4q^#)xL1a=5{;8DGTDApcm?0Ur9y)rYsFe%X zLF&Je^?|B;{)?=|V2p11?~b*iT;mS1KR8PDm;Zv<-{6i8Y91#V0x*LdWvY!TG*!O# z44_hN@MIR7AJ@8>z@Gra0mUIsQ43`VTH)Qz z3ufmBcnGNBEuxMi)0>dng4~#wsxbV}D>uE^2TcWg-b;ZxBNwR@&ZEfYoG};*!UzuL zlN31xb-MqJVr}&#&mB7@q1YT~!6*L(4bXo8y;bQ%n`-rlYhAt-vb2Kk>I@_9feBK72Hk9`cj=)Fs zW0~TMn{!|tBGJP{5-OEbHQ9nm#yYztNHFv08gS_vSgT!}Nv$fV-fT_yYZy6cxrJ<> zz$o)&Sc!~wUCqitp2+79kM6E6BY3U}7*Z~*jR3U@sS9BL8*N^WY!fTee8+a4ixQBi z;}x(4kZYnUJQPCh$Z(+mIg6zASvrEK?M>BWC(^Cc(UE>VUR#|oHVMTctIfEHH%7C! z>x&B_D`dP`y%a!h6p6Bgl>n+o?r#KtY-~@%eRwAHaI;D_JA({7?vnFJP(E5vr5{R@ zhD6a@;YsN!-~OPzjQi1SE<-N>jJw7D#L`Pzpv(fNSwaA>@oxPH{O{siE(#<0ec2%o!Tsh=1pOX zFKoFzhDYJANDaeM+Yhr3fiaKX4#>(iuNSe8|H1D>N?`xW9{Ybyp~)UI?Wp-ZHnw=Y zpUOmgUi*~iCZ3+$RW}yQUN1W*H)>LFp2imOgz1utOZJ8e%S;ZuCb~-8*r-(Itj47$ z2hV%mlFT#P780>efWCF{8UC1mt}-B0ABIqFEwo-WrpPo5TK*%T8aGVrX7kJe^-|CY2zl9}2waH*em| zc8=X+iz|YBCYIBiHFPh_yX>Csrb~;@2(oWUk0Wv->L9E9yzYysqCP@sVB}*QW6H!ku{39z`J0|-zyTNB;KHEFGhjspYlq5{SU@UD-V!z&>fJ#PV1X~mqwwx3yF`*{a&Rh{3E9&y2uBwXgxBjmw66cZ6kuAbF=OV*E5!HJHOh(eA z*}DrZf=EbOTUR%qG66ur6}=1)7&(%qVcc;9gO$d4JrUrspq0v3drZQ*0f+AwLCuXVCY#+fdki>ooaL@+^f z2NBem99OFdun&yWX7|Kwv#SO+Td>JiL!5RdJYHYQ{tC};zZSAbWkQ_0k}wn5KO$8T z8`sb5vFlCCKK||1`YI!B@X)FNJMIjOcU_Wd-{!o{mi@5ooO@!j(mHd*ruSHIWN>Mc z8-vY-BS0+1S-iCPx%}q?mY-`DDFyFSPTf2SBYY6VKE5^9p5`^*DuL-v^U_M9j~ zlTY5}@W^o1m%2#MYZouVjIqIvl3 z$Gx8Ceb;qa@Amt)cl);Y`~LWB&$hPpSoeM1*L9xfb)LtuAN#%^->>pRyxz&rLsUq) zsDP7QQRG9;)8=o>S!5L^dV!LG{1xnkM1IU65RSG0RISzeKlA%lh^26RjBK#qV<{m6 z{Uh!jE8klr^gkfeSQGEY_4A;wClvLnQTUhx$t>a!Q|^j{GmpX<((CW7eyBwS z6(T{CsGOMm@2V;{i+QQtJHkhcAF`Aus4IZ*R}6~zyGiUp5YrWM9*^>ps7AH>jwUcoRAO}OIQ zO4kJ16G$S3=wmyodv}2iuMAaiEdsP?nKhjK zCMlT-*NFcPKpnOPKLgfOy^9U=cDXDlkHg%L&7 z?~~`<+R*41`JF$|$EW}Ju$+)t^rFibjpHOYNk%YcxwiQ-R)8+F+meV9Kcz%zXO zuyQxRm)W+9+b)o0!4Z3;RsM6lKdv^Ap1>loFl!@Ti+S+IKS6Mn>Ahcwfa~=#a$Qu>=2)CSL?p6VSn2^ibK*|70oYlV>#M!`sNp@E zU$Tyh6ri;g4i7ACZJp!Odg4`@o6`v$P7L{nDC5f`eWC6^o38D_zM#jl{Wej$ThoL> zV1(YL<@uRTW;lwNe`D9Q8L?wb%5ai#fKYyQ$vdf5pU&`~yos4*-T8+E1z~sXO0KxW zTf7b&Xpj2pbIxGV8({w0;!|;CiXY+xS4TIl`ydqXlJrH0nv1-Os$Db|4Uxf_NDb&v z``VXmR0f9O_5Eb3x z7FQw_SB*+=n}$dpoi{AJWjJ$l4qqqX1LWyg62GfY9++-8?ncDERlSXyG6Qg}!_N)^ z@T6vk@^Tuhg8ir&)l{w!c<^vu(=9Y$qW%%1YhUjlhSJp-19ZI@srJUR#0mf6dT_wV z6GV`ab6NdW7)HgAu`Hr4t?sB($<_9K(CBNXehgR^vs-=@ly|DzkP|q(H)P+s-EQF; z50EU&KHNv?J*ie92(8*mB_mdcDo{B@cn$k)&|5u@DNop*6Y#8I!%Pst@EvNEDKvf0 zO=`5lFLnL$>h9IC+dCX>|IG!cWB*|BVUeuwL?deO3{^O_>Uu3g@DPNm;T;-q}+ z>4S9>#|67ojPQJ@4(>bHZ`AWDZ?PF~_g7_Q<$TYroD0ZuQnjnNJ>_Adz7@7@!wneo6zKsa*k<-e{N&fnj zsx8?o*<+tLMaWqPwo*l2g+J{DBW5C1VMfk1jR#>y%_9zx)dbEE)wqvk%2iPTT5+fE z+YMcZ979Pw+gif2*WKDs-2@Wd&&nq3q0(DT0UpRg2I1<>eX~9mtK%s`6^Q$&>0G1t z$fgIx8G(C_U&lek!k>P@L|#QTUuNk>Az0(#4A{7j4U88y|3%_K3 z_kKIl+75Ce)*sEqB3Xy1KLo{;qRq!MKNg`OqaRYr#b5>(?`f+-Ycx{%Xq=yx-qQ@h z3-!K@Q|AO|c_G*rU_LjMFZL-ffJjEcLha|XW7A#&{w zk9u6WPEohZkV0h_&#e5$7<;%K)yZXu2Z*X zUxP2Tszu%?dt8IPc}K4m$&%d$+@|%oZtqmV20q^Dph!f&j3{y0NZec~S>b!SKN(AD zbmZB|-SsDYON&gduWJn%=nQEM^X&>#`F`>555X{E!-bqxshaHqkD1PL-@fvQxf-4~ zs=XS*Lz^SJ(?)3=bfBKPU`I%IonU`=?KeThumrTl?J&in&!|o6vuPd?;jI(Z-LXJ? z?2S9ui{2nNY%Or|X>(6!k;)ln@N{OeFyYnKfPqO!{BWwXzT>E>7sgrNo9$=y8u2}m zDCI&=vmNbY@;-iM|Gd%=;Trk9jEhw8=ctB-h4DoFP#zkeKMyW_t)PlvEftR z_?NhV@A-oq52u=U`_>K4k~auWj3WmT@d^Xz?nHVh^eXTy|_o>8=Vl5#POY_!qkp-MJL`hL|3Rq$6Z+>V=Vz0~ZbSP16^ zGHnAyHTh`&7WNvmJB*CwqhGuJBDpI|MtK2d@BHGHDMf?=C=MrdhOxnw=y}35)8AEY z>DWAwv7l_vtRaZ=v0Lpxjf+}GfAEWBAMAQfgbwG-np~`IuzrbC-+|{H^*!Oakr$f1 z+W8G9cnJdqKOH5PN9*qAVOJ6p)u6Pk{7}UnlElRb#&GUZtM~WmNjPxPd+^Dp7^zcI z)ny_3!4;MypCoBeCjCKg%EL_2v))CyKB6Z<{te*xBE#$J$Ux@<#4GjK^g41eGxPJn z0h6>+?BRdAkK>aliexK70@thEaqN4rJA~+;x=ayMM9U3logh(0vHy@;vr(u5dR5o0 zkLuoFd9Y#^U4T$BpvCD=Y#rV_SU`rPahyiA*mAXmoE8d0*|;7&p~a-nb!(`h zyvhglm|Pro;jrIQtOY!P2y&5#@f~nl`YAvo%8Kc_T3`0O@U|D@r4>t~JstA;@#|yO z_#;Vu|LJSEf+4jBq_7Ds=LiYU1vi_zmYSn)7+>6jEo4-whj}u@9(P0TOINd})*8f(ve=5QJ z=scIdMcz}QhCDz)j4BoPWxoYXa0HVgiYm&c-uC27hq2EhAzT!=79l}9SY>+?`vU0` zfoRTec;42FH;~@*1@@P);&VU`alOLt_CW?BTlqVCToZ>0Im?jhf)MQsuhiqP@CDTl zlz+?}&fz@IBY8FvEb1*i6l+OO2d9zew+}2v6r6`{osz&-9&Yl8qu&QOW$xv}{)ON` zMCJfP8a|y154HhbAc=g*{`(Y^ctO*Y130tWs^=B z14>O1gw*+>ezQ7{A+5FcYKLGQQkuKsIxC& z9?YafBC;K@`@P3WKO5WwQ{L{y?#Gby5P3GCyt7oduM`D`5I?(?NU*1MlZ4pYr>2c? z&8(h|<`C4?8q(VpeZMNkX&Wu0&UQdi+^G#N{;N}&BvvbN?IJGyy8hM%1;cR&dH1CL z%(>W1T#PtWkaHU7zZ1D9DvF(IcJ@jw=sOahHGJwq#ZH=N?Fr={`I)}eZHwH#Xm`J5 zKa`y)u7X!RXsa?RB{_z{UdLi=?%VqW%T1fyvQ^nPSbR?;YYXL2AMOLoykD!(wcvh!GhCs<(~Ys=wnff4W);l-%HmJ> zisZ;0@^S4E5RMgsj%7OyNEh3pF&uR$Z4f3?;kP?ErxWpKsK`DJXE`5G3J5-c2a? zKncz@L(ve%fr!O5yE$_z7(f!1+DO#w?+nL5kwn$l%PUS)B-q*>{DR$HQDpJ^GwW*u zRSWIf&5?IFIurhYV>#rIF?%+GgRsQt-1;?Bv^g(}l9h`WFPcT&iiw#HM~jke9sK>n zyZ}^bc*fz(2LI@g+cMkZq|po19w#H09@OVC!zsr*{A!mpqyj9AIQ(o zuY=#sqNGRcRYk9zHVh7esY;~(ZpFO{(H5NL#JwX2HNnw@ujTbt(a@kgOrV1cnbl!O zR4saz+|x`orWAZ8JiQ;Ju)2Z%<^jov>t~(~K*nuXne=&HCMO2YivgG~b``r^4xIMt zh}ll>>CCfFhr3`(>Z@qH+^Sp*)DR6)$asG%A(D0izX^iK!e>$a8lMA{ljQoTZ=${K)sA&{BLJS#za$MT7sArO>C{oAW?dI(1mDWWBNECu<0MO^v9n7nTX#z#d zs(=CKWGd}}ykMhq=T?hG&uf^z?5NH5H-P!X;?8YUyllQt#ClYjL+o_e*9{&c)H0MT zoJre4r@_tGSo^U(^&@|2dy<^yw7%o|F5NqL6$uQzs^IlTZa>dl7#NjIhp|)o)|M z9T)z_nf&Mj_YuY_29OI6_OUvs*aJ|yAF^mbUA$BMz>7`3czLg228jUz=7hoI0d`LA zTsxML{RQW1u0}>{5IlGL$C8?5!-fs-vL99mHJ3<>HXHm&!4RyyasW8hMfHD-B39~A zuLJA{GxujYmB>zq#5PV3TUQ9c7oZp`u%BMMpYLRz;i)`xW-Yqx29v>&K=6!0>Q&TY z<2tspFD7P*^j7oK0r*njEfClcA`&KnKH1!oK|Oh4U4>&mp^2{&Y)ueZ>B`9wBsO8f z1d_)SrG&UNBw)e2dIDn3DXUiXa^TUmX_ z*mda3=uXEWCwJ-TO&hDeJkVZE-)KWkmuUe@hPZ`z%t}@;H=OB`e=tzXbWq;J z17ZinMAtrXS)Tpb?(ku$t0_W9&M{G((dSc zc=vYy5o-Ym5TV}-V{XUA^I4`kfIyRAM5h3=$MJ%no6RJO;aY`Ssd zgpd0lRCLS2gSDWHQ_t!h%Q#+vLzq$|l#7Dm6C5;7fI~`^{*me?*z^DoiQU#^|9a|F zrfL}J;t4q=9Xc`h)vLc$MkM#LSNF-i!dVt};Gha}h{Y(z_`TBp7LKHMo|*ozDeR3@ z0i08DoSDHSdnEqHoWTxFBYVZ={45^VaJ-&V6`6=f*eGis%ZCWsFg*YG&E{tdjb_g8 zLme{u=5N0Rz^g=^*zA6twJ~qHmu5P?Wv59~Hi_`0S`g>Y#CG5BbmB;+;~;j$ZHj~l zuZi}UP88@~Z|ig`ZJ5!ckjMc`3w7CvJ(@k@etU$H8wV` zyuR-HF<<+r(QtdD2#$RC#HLM~c61`!ewX*FC{r!4c|~9g#ZUIQmAbr{XLyk%oi%-0o+`*>_Dxi&?6oCe6NcE|C_2bHomu&*aJQmDoVO^!Y5 z;xZ374Pa|_Ao9miNzUq%n~FOHmf-!d;dQ02Z_5!`D(;QsS`gp~Jha#7 zr54pAG&xKm!|6;F57V2AwJ(8HD-{JGY%>5uX_su#R>0E|&I{R(6}pPiJVNpipcc}% zHteZOK*T`~&{Vu2i`=Y_>@TbYF@F|$L#BWTcm;6HU%!F&+w>a(og>_AthxM%mE(kJ zRGeX!BN$+$qm`Yr5Pl=zCGWDk5Mkt^=p=#IKy(QE?cNrfSeS9G6S&*U9tp-#8;}(?zEOJ0_y!>%MEmmddxZm!dcq6*De;!=O(;-56h&_t=#dvX7PBAaT^Qr6 z^92EJ&{TdmR+(Stz~#!<2ksZi$&r0wC!l@RFQ-<2+;7g=_NPo0;i=w~YAo1rM@l5# zBEP+dec|6{2-S>gOna1^v9>v;sBxr7!|7=DE~&R~7-L)fVw;2OkbU8*cI@0puYWjW z`vY;?)qdj#_Qu8V=A;Ov$e`ru#zl$;gS8!k!0b-3Jp0zxUNfJ-iMp7Yk-}N*PZb~j zfyX`ahgJwGKlD^cobtbRq239}NEB(emLzw;%LeS{nle;`mwA|KGf+p`MnD}(bs`GQ zNo_ml+h+F7zSC=3IwtF!XH#7A6_l`PLjP)7gx49N{>&E6oBS?-aUPkBDnHp5*S1$W zg}`@cdG^4VKK6Tja*c473d~w`CLqS6=yo%F*Yv$ad*eLo?#%rcPO{N)VaLC@0ROrz zy?eu$8Yf zd``|-fUSYTK(9c~!c!g36ea*9%3B7GC7zmyDO43ba+&YfeI#>qTm|ZSI{>5-E<$Oj z3`ejOojROpctTkfzD@K%n2ZJa%{iQAF}`~;9CUk8W)Gq^2kEr#coB#e2iPS{$k03mfIPDmPR9SYxizg0;4S!4r%{jH?%0aDG?ututpW}nsSWbq9 zhGbSjs!>h&GY|>#&_&KA&aDD)Na!(ey&xe1fn}KoqRQ`oym)LFCr_DzJ)el$!~myUmbyd8 zNxD@!Eqhdhgontm=^8@pWyfQjCxb>31TC!r)&}W%pMTtcbt$I!Blb-)I!0D6PN^!` z7mG|3S!;`_i8W?4<)A6@U5;;)*nlXrqSn8N-ZS@`)ZIfZ$(OqUXv=^J zBPd=0SpBNDfc^LiYD_O+hg|5%)cdQ>SNhmDk#{Tkm}BI(XZE${*Cn#Q(sERP2+#iI z5YJ?_Z;1aYC(hrwlAeux`{OJWyT7wPUMxIq@mq6i3aW=nJL}OWkquJ6m4XG5?2qo9 z-YQh{0H7VtQpC|zyCM1%2?vIZnz;5u3H#$y zw-96;!tgthg^Qwe9$?{^It>t-Sq+zgd2smzCSLiHu~RPzy(tn|PGWQ5=&i&wJ8+a{CyUrGaajkN?*Ci^Ad?C&5g??)mL-JdhxEx(-B zo!4;Ms*M!U1uf!`%~8+AENcUcGWfE*OvoRq8Cs5*)%3@kT%PT`K6C zity~uo;gEi^xKg&2{h55oXhfi>oueveor=wvG}F*<9^83r}V?%J&!UY8cacJ0h7gD z*QVIA=dUI<4sZVf2P|`9QDu{Z7*#cJ=FWk0!8)f`$!5!vh08||%EUYAf_+#}0fx*i z7%{3YHo8qGRoRDr%ggnNSj5zTg>0@#n1V_cabsy}E;tR2pED~0At$^B$O}W@07j<3 zTw zw0@y#9YSn30s9DTZ-P(+Uoi1o+{O;Gnqy^q8!;0_%}dyGX4i_``!dck0cV6#BXS!i z|CUzl{pr=wPFCT^e$j|~Sv^)8nypuu0D;Q@S)LT^8E>U3gJmp+`J zLD+>HM|G?3uX9>9wdS=h7;|-DnZ3KHU4;*F&ul7rpkbTqMDNHv46-RE zqKCMe?S#)z7Elh5dnyz0zo|+Oyz*vhSAI-PFj;H<+0AbE{aIdNw z_;(7lV|8aYZS^Pl<7_nPc?Ivc#?gbyZA-(C*!wzBnIFnJfsfd~*8sc&Uk56($3HrC z7=j{X$dfgyoR@h)^FrMLG#hVTy@Gq+;xyRtLw(Kb1}X`XW6)2FKK)J@xnP)Kv7pw| z#h#VNV}xq7?Xl45JQ2v^AvThru3+Se!j8WRY{kyUnO2%3v*7 z_JvZXF;#&?0wg&N;epg(iVRAj-@iqZTk%Jhs3_G+s{dqv^CUF6gZF`Uo~sLcc;dVh zXV3+95eE7@A5KU~+Nv>%6I&uGme@>W3~-!?=}k6Rg0&3w+RpR|?Eaj*o#PnCB?oa) zvdy42Q-Ufu;gI1DNfi@^IDRnO#=fOc_~RU12)7H=s^rLNmAp`~CVUetIDpSe8KD~S zcmNNrvIDKMg1noozEW^%5L3kZ0rzI!jb-{rR3NOZ1u4uG#*4ZnC!|IMS1AE@8qCgE zYhv#lxI8qv6|h3>`5nRj)YE|yO0pWbf*<%n04a^@2UPxid~z)+6e{1?L&3a5o;6lf z6x;3z2%Htc0hCqV6d#D?tPQs6SgH~r63@dvEeSwJ<=c6c=R`0>IOtD3Gbj@MxPKuP z6kt6Q5WnwsUOWT5s(t051*7n3P^LQUiPh3Rkh{qU1;U>(D#WkN%j zi^NSzpgyO5I~0-a=+uzA^5DTjGMW%blIXvZ=>RFPY%ZqkIuAnvOXo*}$?!t6>2?Ag zD_f4B21{uN%oVet=AMLlY%l@b7&!i@@wQ={3aQsiSZ9kKLRM8r?hPQ?K8L@hoIS_ z55ISk!h~F?$fMIqr*Ty+n<5;#f|)q(3ox@l>nk`Vseai693M8|``~vW7nZl%j6`~5!ZNA+8n~!P z*mr=bKM%VsO)Gp#7Ev7rlqZ4ZB3g^o2{=sn40)H?d|m{gft;xJ9SEFb$eor|n3hH; zeh9-|RCf`s9onE&iv#L?CH`3ptr7%-2uHvtDUNhS*f2PLys7dO%0@9-n5yx+5%SaP z+7Ef=BE(3c2a3QWrCxaxiK&K8Bs(p8K#83XxoPpu3kg5m!W!JdO}Gogo#m`c!7oE) zCQ^Hgz39La^g0c%9cA5}g>D(AT?FQ4)D!4xyW?d0#)Hhb2C2P@%Ick4`#zO==ABW5cv8~JA+3aNLk2#TQU8s z1H4O-U!HO)ARZzZTa}GlNlzjfiA^(2&<63PBIh|kmCiaj1(i)IqT5)ylFk75g>m|6KIdn_6kT1ihW;qV>}TIz1)^g_8m`W+<14Jk6v(+h->VA--;!U)lvDI3}^e+ zn>Us@CUOB>GX%=NKk@*rkL-;Lb{CNfOuce%={9fZrsttWbVU2J<22Db`p~wM*4ew; z)>w<=TW7Igz4||280zTUZaPA6$UWU%MAeUA&04=e`+Ef&?MT!{uVURrO#AzXPDwh} zcy&p?eY)M4^X3HLWK(zyyEN4@KrbI2ek(|7hMnkzu#D8NxZ&jsFFF2R4dp9Eu=}bz zC}Kjtq1ZnC1xv=Wglb_#= zM!mo(eGL4M0>8&(By$b`syQrMN}7ZnePoodwWpc9d78jod2Bxr1AasR`O90LE^-U| zoSqKWBxxX4e7?Xr48_J{?fX%@yTco+rqF%>IgR3u^y@=-FnPQ%FVKA5x^a}(R(Ch! zy(sx@q&r8LAjKY3nLW`ONsh3>c3k^U26%T^c} zJ+ZlO7FV|7_{a6(zDmp#m&F5B)L3AEdJKFO^cdh%kAbfa_8Crzj%NcD=kzU!gw445 ze9Qz7Sk%tj=zp%2RACeTu&@}#G$j?4AncV3Ql?i%96jj}Q$K8$ZBxmsj&s?nOU4y! zxwo)v(+zpKjV22ww{|tw%M52$&LW@qdVx>86Irl#34G$6jCwLkVy#hjH?2S2?iO_7MdQm0PREB# z>7sdq{bKmtYHaW}7p@}zoYYiNKkL_XEnoKaRfppGJ*drGh4N!tpZ%Ua+o^?JlgZ^X z`ue{WFZ<6c7hk#FXH_S+asB%BA4D0Y-_4+Ic;x}&$)u(@3k{PpU5lu_uHs8qySt_O zIB{Rhd7{|a?1ukRr1G(J+_ET@w{M2C8D49{uqgGgKjeB~S50_!D$WG^b;7ffiTLdM z?sRU%k#p@({9uRaR9k~8;U*Y(5*{KW6e=BJ0bkmk)4KN^We6ksK8SO{0O2(@I|aLi zHPOVfFa@#G`h$6R55_`LRlGwCwXi)&Clyspu$!uug*Wko)?6<2`-BI>UyPJFSMc2v z@6%TY1POlRApX~sK#KInrpV&{o(Z(Idit7QT<~}82Ty#?`({arThyP+LxdSI%M`BB ze)|_%eGrYV*p+5w-6H-y1#RA>LX#O?N6g5DxG`cLj z?qBnBQh!-{zsIc2DL1R75-JmSkGJl5T|Q#&1m>g~+WOt4ejC+YXua`H(0U_-T5r6o zEc4u+?3x8+U3o(XuXxLCJ&D{!USBRc5ZW41)d3KHs5|g6M)=-Y&!Dms#mOP32 z4$?9%Ps}d1O>%?5`;~`9zr*T2@O$o$M*|HCAghr&!fI*QKWwbpPzY{Vz<`D;YipG- z%~d^lud2h7)FiVc8ALetFMNJ@7YsKroyad|ejB!SELgFG#1j`z(oz+>1@SA|)c+K0 z&&b1MCNDbp%wizsH2?wCvV=>@68FASt0~F*)<5hc<0ddNXl8lYfOoipx={_`fmi;9 zJYK51GZENKYEoIya={^fZ^P50mYHeXL+^az%x{dIBN@m|YC_rIsr`W9u+gdXIvVN_ zPhcz(jJ7gg7}B@Wc4b-m%8i@<{dMFy`Sw))`?v&i+V=Js)W7fah3^4k7Dx-}Uq>fG zkb@;SsQ;_OZm&=cot_|^wLSMFkPt>4_}O)XvP3IvJrR$8En8GsZRGvKej^A3s6WIN zWa*>JHpQ8rO)hRA3Unuo{-tgwqmdh-k`KQX9wp-Vq$Uu}3M>RZzB_a(_Zs!3-{Bsc z6!hpLCL<>0q;hiAIrLEn8BXAL0s|-g`Q+$9ge|tWbzyZwNLX72)r81krtTuq(2QO$ z;>MKX6jN3lK8wawk5}`Nk5Ad*4RG|($8cpT4-jzls2hjD{*Chv*a8_K=n6kO32;<=r-;rg5R$I+3l&+W0H%tKxpXisFJh;L7mDJKIv z5l@VF$>q&~^7ps-5Lo)=07{U&-GSbee_I`p3E`eC>=n{ zDyVt@*1u1?o1MYvP8f2^;v!0)DR4Hbg@kjja{+ABq=_G1h0O|4YhAyt7~WCJK2RPH z3~Y*r*D@k2hZohOe@J+DT>%B-o z1rIS3)%Y!-m`b}on@8nT>Q$i{9|sW(0cJ$qQ8v5%IOQO?0WJ_hse9C)iw3tAxp6$P zqjL|CR2TkTs>A>%BE^v=>9Y{)cK~_M*@1f)jiY#BNA(g2z)QDr5h&ER!aURfp4q# zFPsb_EY)jCGe@u(T#;{3U`_UJ)cz3yc0aPoJmK*LHDed_iEC&aHux@Zi#&3R!cZT~ zJwOCx;A%Rv@xD>Fj_pz2?fzuK1i*}dH9-?_CGkUA`X;oAuAbzMH1qz0M?RoFRGlc-uVFF+(q<1qy9b>?slYL zij<&bV+#q)W~YC9P6prl*;LwX|uHP+6;K`8{gD zOL;HhV{NZ(;rAr)_d-bnz~K!7P#~4#ze_KoLzg@%UhDwsSG3FACMEPpaOxN zy^fOn-217{FH8-VgU{ad#uXw6t&dCg9e|7+ma=!T#1|3JuT_yi%2Q}kscEbv4)%g4 zkt!wBcZP5=D&J^Tl1*YOFoYbaEnJgqcl>Z;tpl&pI;O-n^|TD!88ghYE@uACB#`}Hb%@=EfQq3!8?6EH>uv~L|h3%E>3z{D_9F~q(RyWNvv|sgnUg)?*hs%FD z5x?!-xSWv^sT&-Jq>bHta#0jtw!hG&s3IX?Uwg!^j@I*9e|A0ON9jbBA0LQn6K9ft zMgq}#eUA4G&r80IPBw&(o`8k&%(6SyvSck@2ikoA`BPGJJ(R=eG_IjC7+Pj0F5IGN zv|ebgfxsdh_-PIi5>cG~lGiPu|Iq)Xwlk>JU4A_N;2PSRwYxuD6|}?#J1YOe!2 zN8M_}yprIApw^>fR2rdl2v25eZEgMaf@TIWn6Y=8f0-A&2+4xW%Z;0IHg2-o_{B6J zMm2+7_-VaqkvjB)A2kNh-1ly!eq!+69w0NsrP)%;_wyt7Me<=1O*P%8Po4z%pw_bf zELUI(T}fdJ-%InH`xnM`Hs}r<0uSZ(n$mQMzMnuyd9LPgzXJgOnV;oYUu6OenFw3R zYFbfn(9iBEajNH&v=>%{Pqlw0w!nz^JLdO)%RbHi+S4oLcxS6;al{Kz8j`PZVDg z82T(UDuw$OiA4bX%qiWF3WDN@cnuAWFn7*a1Q_9Y+Ug6m6bEc*|J`*yhB{Y>TS~AI z1V(xQMl8_aSUG!RlbjZL%>k}HGg5pIP>ozrpr z|Kqq|#s`-Vbmr-va}Q0rKY`h_Y12R6=Z%<{m>Lhf1pbPv}0>x4u5{t=>-@ z${KK<+&HFT66*KrHysG7pvTJ1&BdVDsu+e+HR%Gn68`;9^kzIC^<8$oq+ob$w`5RI z(5{P0<Y*CdIOFF6K`SDRQwoNU`tahNbLTEPnj|m)O5!R#2UIQ; zs~d){EL9V{0kH9@u<3a}$9EDGp8q=MAGAa=1=@6<3}8!;6i9*{FC z_4E6bDJqJMQ_!n=mMaQ|#67NP{Kj81tQUTiNwZuzPirY$Bi#RW&cMBw=JjGVi@v1D z6TRvAq33ErbfiV}hd1M`ne~xfK422Z2ssO(O6pBNE>}IqSCx;Pbu2|KXrOU-XPZ}( z1wR0lse3PHT`2WcL@zxYL|dQKvwuFiZy0YRZM06_O%_^;pOZ#8p^hO-#UQW(Qmq0I>WZa>@mts6F+l@jyCW^6ikDE%)WH>fTRf9G4;EAd}IG&g8Ws4}q$x2vzs>#G?JTjSo4SlB=iP-o1f1 z4w3`BRm)*fL{Sjz2tK#e|9x;6=FADEa~YyHdGwl{3}nAh%RhOSNJJ{U($H3gHl+p) z^M0dxK48IQ53~H@y8M02x(|`P>yK5w4#$KLF+;X*Is1M-v^+TL$*WsJm>3lbkrH@q`&RjNL(RFK zqwo0TW_l47`M3LOhU)tHcHi(tF`O;RiGBuKqDO!uCKIQLnu-iwR^wMSvGa(raAD@1 zxE2l9W-1?1hzw3k+@)$Z&y^Rf$MlL?q1U3|oP~+|_YY9&#*W1W`ugS`H68?$3W0tJ zkV&n{z&Dc4X_dfu}w7t$3#OD0$c89@E95%~7MOFxmnyX{6D? zgjc{Dz`Ae~`z4On|F@NoEcVR1P`-46-!z%>_Q}*VLcO-{W)$fv0OQqK4}7=Yf%l`; zX`tPSXohEdI8&o^dHhoyJ={Rul99LA4o`G(;6TPkT8+_%o-Ol*#|$=K}+Y^p@#^HlWwrj+vuy~7>Oll`c3xBCB?;KDaR#54UCVH`aZb9p(e0Ob1M58@GsQ$c!0Ws z%U?Or0vC>O-yWCR8iD8yq0uXt={?dBVml=0HI&3v4U#q?1`)YAlRqzQ7dT9?fh!p9 zTP%9&jeS>F3MjB+5yiPa;#(s9RZ~|NZ<@e?Ze$ zSCanp@MU;s0$j5E*1-POS{dP*t8=mK!L2f5EEZG+STh>k1tG3&@^5w=AU|%b+I_XP z3WhkJC_bx2rm@_UZAQe<7>pgG-J<7(+$<38Lp!flpS#iPQ#>OpXYp`%sI)7ZReU{> zbd|h%wfTkZk2f)f5a>>@6J0fF*%Sf~a2lGO|DFnJg=j(<|)8-y;13J{L$zG!38XH=^80HC#Q@7pod z(1lX{F$$iD-JJO-v#Ld|^A;I|lPQ1W`FEHG*hm%47smU`%aI8L01~B-v)GR*2H#U2aS_^^`Ld#?bhCe2qt_0-c~| z-7o$D!sV+yDn_OBo=@WRT8XBgB3<&Q4h6$|e9$|0049Dv@z&Y(##+-F7OL9feb>rm zuc&B0e2J=n6p+GvgYct(fPnc%XTe9@I=Fmr7JD4>V3HjfB&AUw(HrgpH_|gdU;N|s zh*SUgG0dlgr7R*@3VM+TjErwaWc`nEv_sB)0-))GAbXFD-(+TX?w{iQ8( z3ZePy5j=RYuIAc&=1gY_OU?8vv0`ftUnk*|iD*(Yl9wZ2!ha05cPn4<2F^y&{#H;M z{{JHFLQu*+`9BbCK6)Q15SUwQb8l5AV=vkpShcUv&yTXje^@>dwwP+X+=IyT;h^7o zUKHXQ^$u7>t=43*%oyhL5(LeF2OYlj)oWzVc&iY1eYYe)F((DXbFk>hFu@lI=Oc94&u&817kGD&2;mi?%_sF;qzR@hf1k}0 zFPITf(vQ?$rGni#m`RjHgif3xvhzVBi0MhNAt5Y-f?_gbX_7`4J%183ID*2yGW1$O zPe$9N=ENqBxAGZy-i!tqY)fgGsAxrJ(yp<+Q$rskwC53v13R3A(c9QATat)Ff=`$vDuAGbe-nqszLjAVn?u2Q&Y>Pmc|joD9nx7 zO^S@x26zZjw+8BBK&}krD;2Kc)Stz7+OsEsP$Gi2$qIwo5TfniY3~*K@3b}K+j?PB zWL3da7(>z_y^iHL$jXZ}bW{{mIbYr(9@@THjfBnu{4?JKR=j#5nA{_M#n=SCBx41%pb6eRKHD`d2ZGPlhrD9 zZ|m#p%{s)pF9n_}qE3folcHQQz`i%;x&pI!1Tt{}atH;~JyXZ&kAwUoHYe}OuKXJ5 z)z$IdAg8Otrd`mV;*QVv*fG5v6Ru!uobE3$$AV5O;E)F)&oonPU!fm6-n(sCwU_Kc z-~3WuEG$R+dzwQ~Gd1aDi@A&ahx2r=-0}WwPi1t%fh)DUI_wfB3{CF6^sLzghNZM7 zt$S-FPPDV7Y|Q>Oh_T-ixTOuU^IZ~cLcli}1L>qXr2l4=Ux&$%_&aw(sOv6uX9k|7 z(!jCFTq~z|2B}5`tyM(M1A@{M@fQigrt}HMOGyusi=Sj2H5QV=i6vNZf_^b*xtnQK z&pvpg>kuG5qTB*hDKfbtLpTEL{u`k+N(~N_Mbi3E52m9XZiqQe?@`YA-({y-I#K$LVsRkWh<3F&Y5Tj$B75DBOH(%U2(I z>SPhBFr#A_`_f{+z!*hZYo7ucqwvv77I16o#uke&ok{W{oL)I%$B{$tMS+oa;>{48 zt0$_6^`2AyL&eQ&6zj5jE?Dwe;Fi_FiHB@d@oZXmYqiZ zwqfYbI{wnPchlhnT9erXe_n__jvL+HKXrFzCI|Xj9Lq#t+X|w-e1E-D|8(kl6I#R` zH@ybHtqCB`5n642sS2rzy5L1TF5{t8xUlK=zCg|w6cKy0fpVJ%@vZA&{xd{k2BoiFop*inRY7n*Lkb|zX^<5C2H+RwVm-^vNn_bV6edQ)u`-B6dN|lGS&^?kY9(~Y)FDHgQ^!&3?njr5F>}F%r!@2m5}h=7 z>#6}FMW^Xnh-+v5@P!rl0?~(QpMu9W^6AihvfKjuZdzh5?2^6{CEu(%y#9e^NaS{+1YjcCn$RB%Q|a@nZg+AFZoOO zS)8$OBhw2iPjbNi%4O5LgWPpT7?-N0MaJyLPO1YmUqJHcxbR#}<%uU76e;eq=!fdpI@v^)$lgWS;LqtFO2C`h@)(_4iqvccs_E^H47zhdb z@BYD@_`eA;{Wnj-A2Ba21h0u<1Wx~}Cs$)r6Zvnw2ZfgPXYqy`qj_O-tYwH%ATW?8 zTNtnpgqLszYw}inQWY=|Ug434*;|q3?ET%0reUa``y3Ih1G%MRIcM1Mmmde!AU!k; z-8-ymU*D0#H9!LEMIPa8oRQbbx+7-)yi1FjV86W|!d=vskf${*dop?5%)RQ9zkbzB z==Uk?Rlp1Wt#oLXsOj7r=`?-h35PI;qPs z%F(vX5+dwnx7HZLRJaM+Xfj+v^JN45Z2a_g&;to-B=IP527w49bcD?x77247YR-mj zMC1{B7_2sgjpVg`he(`O32qY{Fi|o{pzlJ|pZyr^&vGlo23AS~i{8A~tRuSDn!Mu=_=m9vtns)+Q=^usk|wMx1voW}x? zXThE`oVko1IhOJD6LjlF2!hl!h>nS1X{~W2+aL0Xil!9zc=~#ZJi0J!3uloOcTvUw zDpw9hQkocFf`)h$rum>xf$fnRpg*$#$ev2i+_0ntT$zc~fN!4l1lAz&=EFblDqV(r zF5zF)>gLp(;wjf4vX;^?d*n-=TBKG#aWdFL)7F&;3=!vS&(_-y${L{wO3Beo>}&Ref=}1n3R=J(T4?j zOG!#neWN0M`_N2eyu^vTiNp{Q(L@bLOVBwcG;L&mSxFw4{WmxTzzCC`)BF#xUN1FImwT zxAXwX-q{f_xi=DJecS+Ed;;CBq_ZpKOkVPADdr9Yfsz;&tUuZ;?e^?>`em|xOXXK| zrS!)yHHc(_glcZeXK!x2!mIfrS(IU^cX|WaAWwJ<>yS)j-Q=deYX`9-G(TQD9nd|S z^@Pm+t(Vl9tzhZlPGPz-FKyGanq+K4E{NW2kMPOt1wxD;zcv|Pi;s&dSdo@9%7+9M zum!BBA+{Mfa;D#?UGCrhe7LyKfr&U3^KstbOu|MNX*U8)4d(`BG zi7(_ib7_W;TI`wBAB-+GwDm?o+Ly1*-hY^fcUBM1QZX4s9TUh4-39hz23A&9FUrgF zP?jL_Ckg?RZgAiq<)(EwT=K_ulE3VBs9`8c^7A8U7I~;jiIo5KsQC*xc%#)C+?DE$ zuB1R8i};4-&)8u}m=7k%2|scWrZ<7ucQ`W0>jo9;kZ~OUAH7X4ZVjqg^9l)_af@f7 zr>H2|vqF+To!lP${HWmvP>Y>MYKZhRQ(3vPZ2^0{KP<)UXrm5-c+?N%BdRY8&SO{lL>UuSekcK*AAQ)j zBaQ#p(JixjtQX4On=#Oo*YrbJKaZ*^#7)K)a9-18J6%sWZ0?5;n@O{%~oGS#o-H%v;AdecBt7KlDVp7ImeEtuF8T zTBoO6x@Tn80wfeO{-e*z9Ftbk%$ZpYi-e0l4DYXd^v8=G20|(W;sU=8ipwCvXwjho z2>K?8!vJlGcl@+0j=d_2|G4ij>}-{jlVb{YHr%CP`ZXhijKDz6)Q5CMAbZA%vZ;uF zVX5;=cevPrkS;GM9U|7y*Ox}^^5rfH^j3i7lW_13du|hFIoyNEH%V$x<_@G3gs>2@ zq6Y%EQR1*QI1SXA^?R??3=so;axWoNf&x`}G>RQG=Jsrn5ad22-k+4zT`Cn>oM^n+(=fZHej0yt=sL37>my|-TcuzfIoW6M2-bF-}^q1=r^DFXrX z{Sl8yGB5sxlaejH#ylKExlOg;9&CwoU1>HS# z1*j)k==g3L`G^b@ND$o$6nL7P9C2AmB79(~J8B`LBj1!$rYJ|$W4vN`T=K7Lg~oJOZ#Da#AFB+mnFR{? zO0u9N2B4@YvGU`Vw&0M8ZTPZhY6_GN^xp5SVq>6;Rtys%4?)*vX_$z)plpZu7kY%) zk&mFxA(Pn+MGlTrQ|dW8tV+1Bb0is04jC;eAOq>^<8@6jo9YhyG$C!%{;{p> zGh8qK2Id?Z<69d$`v9E9=H1)U8Q1jy$diWReD<#oUM1wN_z;yB{5tpwcVzN+y`}bK zFUJht#`+|$Y>ANj&{^h*O6WZjyE+rrUN3i~&g_+O&Jq$>1R!=f1BWC)`TPhA)>oP6 zqiY$*thD9~i`bU5JuiQ2ylW}p6Du=70d+t{hok~PTw zQcD`VCKfbsc6hsKuXhS{!U6R5;x}$cD~P}FUtC^4@sw~2IJsMK6A10`sR=&NBCd^X zsRZAuzKXpgG7kE&DhwYEpQh&Kl4R@#ok?R;ms0P!GiUU%#f6XO#G&fHy%gsmo2aE? z=TSbm`8UgkXL29%Q=pjz6MvzJM)|25`~I04w7Ry$K*Ljz5`k?6rK-a75N)=#)wd?Os#4vVU0beIapM;yRm%+-|;x_iRioHf;?H234_24L{l@zajJ!5>e*yNSU zH!t=D)uR5p3(Mj>3eb&FrxkAXr`~*QJ&ko;J^Sbdum2FZgfx*3)rB2{F!z=Sr5v51 ztZd)n0Vb1c1UvNS?Zp=RGZ=lB%!|+-LSO$AJPx}2*dUVLu^F&;C1&tngxLG>=t=^X zhIQmR_NdSZtB~gekp)FtUp~p)NYXzqefAzX<1BgMR15j%$onWP$1vfj1y*362s-ZmuT!QoCBT35R+p1y9=mE72Xqn!+& zaGcC(NM(Qj@k7CeS$r$CYx53UwT;^{(8qq?8SaSMs}8QIj}WffT;gVHJg)G}#S6df z1D%JI*0t#8VVc2dpm*|ThZv?R)P#w@^;<9O=*ela6_G3HSieS$VBG_6%?xah&sT?D zE0eFy|LO$!sNmtJE<5&4Ybxub%!L;=#!URoqAz~A#@!Buk{33pnt=UU3q(GIBuPN% z&V^~Szq8XMT#3;z`%qB6uz<|BHNO=v6S&_Z0HVHLViFP!+U&4_NiD${gp+PhSuf&G zLa)HPJG<&-cN?_=2ETaMjE`Xy1!H*zf-gkG!GCgTbdu_9EVE13OJJ*m>ge4!Cr(D%fRJwMFriGyo~z!Hpa*YXYL zaZmkJPRYvwDa{~iblS|WC^Ctr%e&a5UWV~n{(trWd5*_4zlXXgHQ=HORLIeh61jwj zqu@o3C)C`W>fSIZHNJ;sNa{J`cFqgwDaH%mjdzwRWVxVRN|OyPF8VV3bnJ5{BQ)Rg zGGPz!d=rFq4k&Osf@(~b&*X?H_guo;b<5)dgSYHMmG@~aQ!PZ55<(rRPrUgqiyL3q zH*s?Jh%BQNR8~okc58NjnMz-M&o`@SJ6S)>D_bt48AOJMq+j*BX_e@3`&(=vJ1okI zUx&^!bRK{*WMt9naI+=6c|6Ax&#pp@Cxyi6m?kub@^EGkRoHzZb3q;%Inc5vV?2SY z`t$22)^oorjx|Jk*SR^?kx7D=HYG(fqvuU?E=lFcCvOLI{RIY`9mrgCaLq!@1ocjf zb=&9krlBFi)mYF}oRp$rt*mEd?B0vey8Tr! zBwzmPHw9HU_&OHt;ACOui?9sI;+X`OWs3%<;Aliu?lAc$w4GsR^t>{F9imhjfxg`= zjEBeZ^P{R1u`Rq-u%|Y90-~6@a~6)ogDaaU=rN3Bxb{;*Q7~wH@3}`!T#&G{B(y87 zgrbv|)(d4J^0jb5eoBq4zDBU45?-0UP|9#Ps9BH%k`(zK(`wK{Ee9aXcB-2o{WL(T z7+K0*O2yCb7rF74enUV|mUfW(n*vb!ix7ZbqH=PW<{ao$wu2O0f;*pxh(a0$;dha! zqFJ=g6(GaZu;jf$2NBF8KCz!#uN|Ym4Vcf%!Te({w1=lOs=)$=7|*1oCw$s?U)dQ2 zL#kdk^sw*jk8zy*$OWxTc?%2qIC{G4sd`4dqu3Gyj`HO#6YRrE2

`-F*i!8 zwmU2iNa<3NX5ZFHoqsrXa)xK^*0f@y3p~s9j3dl(emwG~V4V;e#200+H@mA?lFqP2 zX;{R59L8aTX$Jc?7{>a4Iicb?x#GO|8yDbTKl?wMTnWy`ShBT)0oqkUT~JtBNU@_u z(q63o+S=L=U{k>MOqsfCkwvBS{^BKvjMnQ(MNs?X#d>z z!0s6gxTQ}>%pnt`JV@=u;dgfep;9gc^%KYf9E`vEMRKgkQ}J8DpY0AZub|J@t@Srn zz?lB~_YE^&e!7ne*hIL!29f13v3jZ2D%)E#RM4yh?&*2Q6i|L*6gSQ z-{`ACjdLCuTN83mWe(CZ{+W2R0bEBxBOfwfoRj`-9dVmJ_af~VsCu!v3wnE&;5MYE z88ySCBpB>tW%3&oj1=n4q$8symB2#?zNNuOP4^Sv9f55+>V(oTRHe~-g%SAb%|6oO zLIHO|XrdwL7)FibPAgR0I$$54fOdBjg9v07#IQ$4a_elk%O!a5qUR08UUjJsTdA1+!vQw5fjtSyGVC@$y~&AA9c^Rpr&Ti#}?M ziHW@;*4TR#5CJL1f=0zIpa=>|5fK3a=|rOe6+{sW)n2F~BGQck!~!THDAj;~QUwI0 z2>ZI0nq=ku&KP@q=Zx=+vA6tq;(%y-oK#S1@e-gH3+m?2>Z zPoYph0Kw_6V-C<$Y?k?})c4QA9KD`&?V#`uiz-oK2|)Fc5Xrhyrwwl@=t<#3l61A; zX-k22{XIv$dHehZ%ETY$$zd$+WOH*+&pQe)Ar9(74P)wAY)mfNbD${ZO3R$at3hSC zGR+v>YSU1IRkK#Ue8?Tj)$j>qs~yz_(~a#+3@VO!H8#A#seP0mgsIr6NW~7cVN*bI z(ZhgDVv_~LVa(EGa<;|2EjWSdl`|vzTDzjd__J?~SW)uW8z4X$Fi(x zj5jak1{Hl&u*R{*cy_l-?j6n8xKtsB7-brXuT=gZT_jGg+jz05rT3~-j1(lV_?rJr zLa0ey)X!<*(6bf|3eZPitIb@+hG1c{}TgWv&F+9GQl|U8o4V!jYA%GS3j$o z-mD~ifG$l`NFI*vvP8_`b_N;}Eg1hNl!J+`45Lyc(?JDHEH z@P7+feMSnWH55v?yz7D{4+uy*Z5s~P8qswib`2afh$e^>0SVvo`@X#(Zt5aURk&G5 z>rEDUukPE?R>M!HK@eGy|L;{pv24x!==J8yt*_ArDC6My!3G6>qQ@j$md@Xz)b8 zJ!?RQyK+B=Cfkf{BGM^NDid?aN;Q-)za*e{z%j8bJ@*J}n{}f1gVL(kNhjmM7J$tT zr??f^qZ8{GB>*Jy+1%mgBGTl?_{j~VnYrkk6;reWhv|kPj+Oq>T9KU;;fJ}xtI(n! zLmrT`fn#ZJ&n=MT1bvTVb$`6*|H?|4DG%fo*^{&;aw2Uj#Tk zNk|HKCWWeZm@Gj*p#+_aBVcMr-j8NX0PWT6w}v^Y;59?`CAPKs5kkT!jJL~rd!bEr z=dONNlg? zU^}G=V`@9TraDXxlc6W28Sj+VfA_Nnlr4<-DNUD4p+{R@452dIF22?bsf#LRt3Hud z7*vZ=8@$+?4WWr0ts3#RmJ!)A22vLbpE<_M$adma?vsYYG9%1q9WZrUQ2%b4GWXTHjZ`0q5}jc+Y$6MNG) z$FoO^szDD!`)A$rTyn2;+=31q1*b%g={T`8ABt3oNX4d?7JO^Z$*V4`UQ>_%CdoCD zZT|QMW4_TnYDU88JmCCQ!}5+63aIf|U+*+Qat&;Ez)fvX3kiT$O2hKF_WFlL<*?;Q zbcNQt)s<$^lBT_BW_mRE@w&*!6yjCA;Ha3)vma@k2n0;Y_u6`InO;MG98EV2<}R7( zZHO)8U5_~uChAKS%4yt%B&s@7iHZQ^6IJ_CKMEQR5u0--=1f@OeZmTqp+7kvt*Tcd z^p=duNvpwm=;tZk$eixib@vFK575|BO;W#96qs2}$~|$~4JT<= zOl}}DsRx7lh2uj{%US3roL?>AUiCoyH7X}2O9IbZu}LHaQ|*iC*i5~)?Ri*3K345C zIlu%$e`g|J19q|G2nu(KLnv#y2akzg%Wn!spxdUt^;b`OBFhZ%EtThc%m3F1_dup zfzwv$)Kx!H6OH^<)@DZyf=mGZ^Ba%_53{pW?MpcwRU@&WvT+XHF0+_VvjvF3h{WT^ zu9;4l7BRj*>?l8c)z9x%InLqb3XYHh%xZg76$m4h(h%>4WJem{UXp;8h%Oq(V!hyNqB9@@ohK{LDtB+ zx|&v+^Cq;d0U%5d|F==Ci`u0%R7{$8>4zfb^_a;UmGgL+Y9||60}4ujmxGiM4r`-( zN1-c1g@u%6GB+jAeBQao9#=rdG%jX3xG8E1+S=Ow7sUHbgba+}x%jpfqC*zG7tL^v z>znFarH1>e6!%QItb8qRS zfjA>qC@7)odJa9#8#kIk^}m44h08X5dAaVn_oW}t18}o6D=<*w1IFJqTbxF zoad91DZXpgzh^RJ$4^?>LrY4tpwnfn`w|81)bZJu3u8HW2}*v3KVkg9k~X_346ymnryHH;1CV#>I8hf@x{6e(JC6K0)9$GhG6esC(vre$l(ioSDdI<151wT6c`h zln&l?GB6IIBTaR9eK1Ny^c8%q(mA(y_Wg}^099M#YzQX_R&z0{elUTi% zTBkrK-QRKW@`Lgf+aF!Ie4`Pr+m#aDww*oWg*Z^IX~L43F2|lUPQdilVr_(vO93_M z`POppiCrkdS*P6DpxolJ?ja?mo?}S2aACaXA!Ge3)oh{U)`8HqX!UBV&T9ZaDpbEm zM}Q`jK@wIQ*4FB*Z9e(!is~opQtZ*)%i|EjsGJzWe}^6=gdR2caM|Vrs&z?#`vYAq zY?d@$!s)@11w*_b;)vwb7LGBjkUDdCt-AHLqxKznORtQNb2`vkxM(30KeIo2$zJq( zO4*T9PA#W~j~9EUqHs&SQ?wMv{*W-GV}mAzI)P+uIW(9yK6;1;D9Ya?${fB!jdyO- zmP3n2u6LL)>?talV1wt!6ulpunK}K>4^y+6XZ#=yE zs1*)S1C#K=(`fQq{(dWPC+2#(I9S-~q+;W#r&{V-W{YTw-uUzV^)INUYFJdLW3cHa zPWYQ8(UY!Qy?#7~=^;##+|nl}^{+(tC{y2km7rFRSFcA8Gox}UAyJHR`1o8K9{1Ez zs%!%mq(?99BE%9pqiGfe+>Jm6usE!3xgeZ*2?b`4?-IZ&ej!ptH=#f}|EO>wJfjzI zMJa~e=*q`S4>6Wmc8BG1@aEV#Jb!`o(@ev-T!Oi6$WP`A9Fbk=%k(%9bggS8+6n%i z!~GPj)qE~p^KH34_KbO5hb5%ktM`scu%`YWu%O}hZOBV!p4h|HDvk9!)S~X^br2V4 zkDzCh7jU;ks*A8qBtbpnJ=CZ_{_z&osQJf>4M6F?LdVi(!wEd=*K{}QG^kD23!avt zBorA89{kJv#n(gk7x(Ymf4Iq$DQm12xj3)6neDPDC}eQO;GoEJxifbh@z`QgaLCdq z=-{fu%a;8zdFYUvw{v=RksY|Y+sR8mJiOD=VR-h(bYCec-_jAcLtlNhH^9!nO{vd< zc^!2=K3v~0gZuvz;wO1W>8?W5#r}-FE4*l zns8IA>z%ZTLjE3hLZve1NihvLVhJ2OE1N-vVmM#tf@NEe|1y0QxQU$2xdII3c;$}C z!m2$|yW#dhDm2)7=fU=)X&OOJ7hqvTmn|I65^XHZMU6m+0*X3~l(`LDA5>Ajw&;6` z3Q#yQ+BWZ|3M`b;Zu?i;{iuGU5%|1i^UDkm?KBv&`gDWwQUmK3+fUJfL@N8{j%QQQ z$QX&*-}+xx)X(D~qWL2dTdIf8CC^8AkQ|iv* zqamx6UGGT1JBN&S$}1ABY`fr2UPXn{VHc(Zz%0Huma(j?Xxe#I|DMX*ZzuZprOu;8 zVfL;Iw{BUrncTO#0da}#S~J%Pd)ZyeiAdA@-tEk_zU4Xn(`!hS=g8lcL`w7=$>ukCS zlfDX&6P)cE@W)iy0QfB6kNeBeGMe1q=w(7EP!n2>9_OblV%yFr5Eb)8* zcND$sGvj#~dVH>EFb_5i%#UHi0qPs~?L;C~sJ9y<%b8w++*B5?d|wLtfP()y{%!t( zV4hqKefhrjWi+6`A4eD2qb}ngy%+5IMo{i~zF%&X=_n}I&DwhR*CShtOy(EG{8D5R zX{qxfVb{H|f?HPL=5mnLuIgKjzZzf`pU}B9^|zf4H~5%atk=0TY(i<1(x~fSfL;MB zx7{D=_B1iAO?Bf&>UlABOyQ4XhQEI*=2_jd(W7~_wAC+IMK^R-zQ=yS{yWh(_1knedea4x_$*P?%)tD z95MfhC8q~yxu|NMSyn2RZ<^1C$n(MPCHkAj)h(vltJ&lEJ*o#5r|o%Yx?otVw@KTE z_3M*ODOiijX%P7Gk1FjhY|ll3J3Ex_7PV5+msM}c9lkW)S7%mw4b{e|dYynu`iP~- z#gf{0$Qg$i&i?1EI~N29yQOf>$+HcPrMHX6Aihyv!Wf76iP2H&v+r9<8m}q1JCQ$LHQM z@rmk)Js%h-n!kLV6A>S!m70A4)t61cRv&WRPgHk3o>?tZD3k%+@y168O!0xiGU#f9HZD^6PBK~gDs=&6EK^k0rg>La|G zfstHhau9gnA4^(6MfQ#=jGdC#vfa)!+T%onUFU~p3j1lADk{MT^#V+jDy#4R^F0dE zM}^(~>o;uZ*>YT+TGr?_+yjtXGFTG~4DD`raO~W_?f**Hee1=I_^8b=VT$2oS}J>B zaXVo??9JPwT9K#(HN6-*bgEStv)BZD`_FILvU2^JsxHo(bCBa5siYaFcH2xaE=p`~ zwH%t9x06$|J@S509WOd|@%0cRUf8O-&>oE^s>V5;;0HrCxDOPT1^Hp-{mnkL(Pk3NB`9FI#akl%RZgxT$leK@JuGUV6r+PReKF zbwwP!9lPgEe?$^xN-uvAf?Y;2ayCg)V%T~@Yyp5`q>YalgUY$HpAbr^;G@_v*=;e9 zo;j>IGOO~Ur`m(t37q6$_0?zEp~otbL&WY}K%*Nn71W{8;A8dywf&<_wL8mCncOPF zBiu|uK26i#LczR&GR{J@6&q%YlBqpHF={|3i#b^)SAG z{gp7YL*#-VR9?b@gWum@R-{EHU`iwUsAZRGiBE#Rmjqm`vWHU@ndAt-`K7Wk8l3?w z_8>asS}2JkWujaz4{5iO55_(w)Y(x!HMumq*R z+RAeAcA`2rg=L^9Bt8lj4ah&XX@O5~kZ!uN5c`_bCN`swSkl8Aqu6;INclF2-ScRL zE-&Q~%%YwKz_AyHHQ7O8Y~0<_4Q}XzH+X_k_&5YL29D?a_Lzk z$T|kp-Fl8re-e$9eVf{$;OJ-Oz`hCEeE8N=BGZeUE122pI5e(LZ$&G}f+I@(U^z4a zEwW8fT$oWWkMpW<4mz1vak!IiEB5RkOViXBRF}eXG*YI$9rsuogHr-yj>u5u0jE*< z#UdEZ4MnT+zJ>+T$XDoo8h7A?x&~`2lF2a!QwAlyJdN>lD7!M73 zPMpyW#HB#+oqf_|2z^>)ioqP5%dpt#g!Fu@O2i73mRPa{FI($NAC_RoS6HfqrAPht zBQlu7?twV#-cxpienzK;?za-gkQ~xUM)qkHorBF3QJ6%Fk{a^>6Iv}`xYJ{HHeT*~ z$f=LQpd(FFoaW)JD%^JGk(`YBQ7@hC-#WTR)Y*gw5WUr^fH_}fz%tq#AxZ45wA5YW0sP?@hJ4x073@%Lr z>otHHn?8|Fv#8sSHvQ@FGM>>vVF@vsZJ4epQP^vg!@JcfF|0D+v$Wyp2&lzcQqDfu zlBtRoI$N>%ef}Auo%4A$@W9ZqJE?Z11nu!DccmZiA)bQMUA;6&^7f~K1bewl?TXL{ zrlrARq|5tdIDbdUQ9AC<#_zfI^$@Q!G%PqTCKnqBiXHC~=v+pbU6Hq(<=DkXTo5p1 zZHo@Vsct-{6~UGin#_JI_0Q`P4y@l$)#bQ8l%`i}YbPkaJdH6r^3JJYas3g%-4V@W zQwRKHMODsuIFBU$xJ>O$&P8GKIf~lhgV1N)y+0Carph9Bs=nZ~Tf&-uP76 zQ5VkDhjT=e9fK;7LrWAX)#e!~80AGk5U;6wrP%9#-2Yo4hkJaeocT6%&-JcIE;lwd z7LA^;2XDJPonHciQ3^W4L+PPvkFHLy>}Oy;l2=aG6M9h|g=YVZ-b(LZ8iHWX0w4Xd z;pjNg$>H{DheYVINmpdQxTwH!DYeb>Vb~y1$;m6l>j|NC>C)}%g~$adY(iX3fK!JJ zCn@Z)(mx^FpX@9WbIHHk?B9t+YPzm~FMxz(>u8;|c&!?O7#?u+cU@lEqEkRdb@+#j zyj@)qN>6Sorqvep^UUN8eY^FU_aixa_n_HAop}jk#DHOBg?ImMuym{rbP`YvNBr)y zdy{u3d_ND%*U4!FH#yQ zwqu0pzX`j$!CU(lhn2TFZStnyVfzM&`Vh0(hTa^g)0rCc#huzsqkzR>A@u}@XIz!e zay(PB48`Uo^k^@j^H$zgixxBezA3$w-u(4H_rTdw*h;Gq_6=pK=WhUrK14tpd^ZOm zH=LTe?eQLDt96Jz)J#2(tQi&#NJ8q6^UDw)!W2@iX?b7(!m&uX7*(734IK<%7zx6W zT)c*Qwpx=I%9@P|-`_F39*M)DK=iGjwWTpVtV7HhWF&9sjUav-tEGf@#3UOcL|z4I8pwDau<_4Lzl0zLbBFvu=X9MotjR zjLu#%w%upaM+#*fkpnzmh>b!N#@mO%FXXZ}yo06%O8p_!3Mb4UdE}5Af!KqHit?Pw z?5&Q>p=31G7*YTk8G(e&g(GwPk{;-mXa^o5?Qyte)@mAMiBN~Yk#+ZrLYMg%e8_U8 zJVByU?dtv1gO)|?r{Fc$N@;WO zMt`Mv@x|1FuFy9{ZH3Ln?1Z7}OJ)#Q`^|e;R;;9bj~PZtBK#v_v>E(vQfA#7K7e%$ zFp~NO1A88L49+zRn(%vu$Ka4Eg0W%u=^hnpr{3AMcy{DSnqI|cpv83KLo<%rHP^D5 zic}ZIL5aE!14^grN@n3Sn_08w_-{s?Q!$~!+1zkT`Jc;D5DttHw2m^`wDn3<2$XzZ zFt}@BolQZQs|y1M;bmb`raodNkAP;iFn52)H+&P7@Gpvn;hC?Tea+a);#rkVqeZ0jADW|kf0c-JgiyA&HW!^Li(K*d;jH+_u2F*fd(*ep_eSpyori4J z4Cwgm*rg4jOdnV`NtjcYk53yeDcUG)?@x9 zG^H}*n}1Ua_kH;{e?K~v|K`&;G04tYml?PDjSRG`>I*MSCKi2Pv-qYO9o2MNK%cp= zqq2|V+x>CXeqkfsV0HKR1>jGQ>#JvVc{#%5yNX-yMk@S#X-)TPv5ZMjajZJl<)zla z?UFrP2haA{^!oZNu@4YhB2>S2w!R|iT<|Y7(d%~TY>NL~;ZA2&KUpDmyjWp^@N~D= z9r3^EF`6r%Q61UZU_0@P77ULU%n{}Ra!YDe_&xDob)N8Feeair_xDr!?=HMA&+yAL zGHE@MRZ#*#-X-yI`H(ENJ|R>jL~weDCM={eSg$ ztiBf zIbow#cuTv2q9)DB8%EkeZ^Zo^uPz$bx@8nWjTDb2_FN>G360znUS8{;7eV2e(l~?) zkP*R&oXjpCMUgaVM`KtW^rA2;t~>f1*k4^IU{gexCWsg%gDocMHcTe)@(Qt$&Q-UH zXYabIG){)DB~?>-U64R@#r*Z&`9+8O{{d%W1*<9-vNs{mAexVn4-Axx_KHmggdB+` z+r-En>?JuEv(ASSppeq^hKK+Td6I#*Ayv=7o37KHaBm@@G2$_2v%LaMrtFpVzSHpO*f@k5%39&P0Z7gz$xxlLkooH35U#8EMBc z^QQQ9acFE!;F`D1of{!ss%3tEJW+9^brhzrScWk!aTVox=f!U3Dll~Dh4(52;^MnL`t;m#=ud%B~5$` zR3(8A{e!-5L#6bWS6I-A2|na5!1!KP3X0)+BmL|i3`f=k0J<6cx+u|U$C&CsiU^bd zQGe}?xU5Q(MAtj3REcRKeACyVd-v`Hpp!UROoBTkCTL$rXagiZ2Vi=tPTE1a9NxxJ zAQzGV2|xB*wQ)9pizS$V9|c*aw8{j~NFp6*0z)*V$g2c^dY~CysXIZOkRdQu=@!(& zNQ5pk`tMKq!_WxPzpP^k`}T;ZI|9Mva|`5%#GDaZUBqnRre6IryG5 zV}@E)3u)q1bS7G)+y>8>fYbLt9dS3QRblDw0?NlItSRj{z!yok%}V;)Q3i^m^?c}{ zhC_d~bY2ATk0LWI$RAiV0W~8HDtpYmw##oYt9AjE^5iCC47z1Z#oBP!Yx@cZ<@Lem zBSK+f6X`A^p%Q`{{9W6RY_EH?S3Ib!>Nac;R?Lf_hzOC0GiKT98epAmjRWD+3{E;V zjW2SvELK3|baNzj!DlD-n-2K-<+iGTOJ)U`EBSF5g31O_QdHxDeP7$acU z`4qKZ&fkdJu{iihe8&&NTVIfJbX0(bGPgM?$q$3^UKSJd5E;rr(^^k0j^~Z;F9XQOyE-c1i^Plp%_tWOA)#> zmJ7|y%m^5ARg}%&y`Zpc1aK1^=}u_knl)|6L>N3eKHCml5^8_t#gWB;C!E-`k_avl z>88-%dydIQ@}WwzXF!C7!B)mpY>0ThwjbW5$Y>EjWpxeZVwbUuSC1+mA(~IjrdAbY z_?F{-3){j|C}??06vT-=ic0yl*D{sfS$#OP4@33 z{45Nua6xdH6|Mv%=cGxKQY#-p;9)W7V*TxC3mccd{11#gi@~G`y{^4(-9VVPWVGc2 z^7CVO2Twt~WRVHi3BvA;Gsci^rDj2!TC_^#U_yfE~odPd%v8Do+Qa z+AF$68v8b>m1GgT`-g4$Q~()0in72|VX@`sELCGyWR2*m+YdK-KRAgmyrG zJM#mc4O`38{rFN(w%z*k?%lg!qMH{MjT93&QAx(P^gfMPq6=Pb%@eRo*XfS}!Dcmt z33^r%Kuu-(Ymd@T0R}WadnJ6Rvh>S)>X+wEA4TjBz+{BU{!-f>TV~iS9~>q^|WT!bK$6=2|xc!bI7J z)w@E7<%RCdx^l4q^|pxD{T}GJGaAZer}ftO6(JTU*`DlnC%UEvyjB-ro90HgMAz(k zlX(gH8NLsyh@W8I+$(S`D`E&)dc0`h8sK$xTRX>~T1|DiSZW zreI7?3#hXzEFIUs%AH;vI~7L|AmkI8E}A(J3JDNncz!NEdML55q!0e%r|Af;(VVnB z-FW0^X3w|&b}4270Gs_QqpgCMMq3#J)KsDHDkc%&VbU=Wz`Qm|D%$QLfvXl2zkmEZ zm%>7R7y<*4aAXt>SJh`0C|6*?FAqk-IvqU7wFT#Hm>1}TW}NI3t^X?5%v2FjR-Ou{ zHdO-3O*x~mhJSpZAUszPedMO78R3OU2D7Z6drCw%1y7Frv!mX|8carFv(1eU95^t` zrv6n{w-T}69_LxVZ{sfP6W2zZ^OqC;@PCvVX|Up2ujW%3v9Sp1WN4ITBe{y1ix*!% zM+~as{9tnMo9@nmFSw@S<+}!hWyXVW5fZKgikjaGpjC~l8NNEIE0t3Z0S$gNeTO&XVO@`m;etx; zJX1k1YQX=$nAY&M*Xk#ra<=tGOfNO>uEFiNPz^89|_PbOM!DCK_ zg5&5emt zBo!jlKrBdj;63aJL6ig|ZS#t-)g_3*9vWex!doPs11hm5zqPxu)-qpbqjePG5P3+^ zkqDI32DzZEICI}o7ej0c;tQ{3kXwV4^h08T4w8FA9Ih1&_x+LfpKO~`k0gB&wAhTd zj1|s?*8M*%jz2q_d#DIQcSLKM{#FpKry5zcTC&?6yL$bCira}dYj%-=i0EQ&%!~;a zbZJd__9AZJa|?dEtaJqh3k?_AbDCkKKAcJsyaE!XuuR%@ikh*rUmYgnPJS;KcbR2i z3NG;>?asts_UiY4?iSkD_FeUmlpNQ_`i`+)o$9`}h6lC#f9#R#-6I8qBD1*@qEningvqgo(JEb+9cjFE$oQogN}tX*OBW z6i;cc5N8kto?;-x9yZi8mjEru3aq# zqEl%cAY9I_Kx&LS`PsFw2k+CZ6FfCY;D(skx{4~rNW9r3TO|D#aB^L%S*00WGc(8F z;cr?}pp(U_mNO{{yL%;MUoOS&6N|v#q>GJfB!!MHJS{EPsQZ+stO3^J z0Y#Fq$ThiEeH|TxkH??Y!^RhZJ8;Q$z`2fVs(SNb{D<#}wH*n|m-yW2_d$3xZz6y{ zybyd0qKFeVh$X>SrFgg!)eC-P?A=yWU*0<&n~M%WU=4AM2bxz?sBRJzSNHAPx30_y z^`mPeD*45~^&Sy8uN@t*YE#+!A1tYCP{I21&vA>><-MJSqS% zE}sZ((Q5CC_CTU~b#GgvD^Ld#>XkXlIR&J%Bky11BbFnnfcm;%gvV5&9qgWqbL>EJ zp~`WR|Fj;?eNfsNqO{Rn>D_#)vT9n<2(btHh850B5X6@T&xCmmwQL?#QLH7r5HE}9 z>nRZpr68QE1!s86OpScOH!uE9vJ{yFig*(!e^KWHbDyliC`A+y-BUe z*Vmkh#ZsYbk?zXS0nZQ<%wt5$9O zKnOjR#%e7BK$T3g1-E8)XVW&ZPpePj^#HMFzeNXNK+7cR z-y}sP!(}6h-x`-bT-niH_X7$(H&jC9miil6xF@x;Ie_{hEiVrC@)N24k>pPeA5-z< z;i@8^##KMb@exBJs#NoGQ<31F2SsyGHf=RgLs)y2WA7(}a_aNk0ub%RICg{P1;q@< zC)QQ!bjpW|i!27q=I5$t-_Up!H66!nUBh}+HB66mtw(Ae zxhm3*F(2uSm%J1Hok&nqUB|)ed2?G)rxGq{ii}wBa?a&yIt}&*`CtR=sJKaVJfB-w zI!!C-*aL%^sa4nT#`5uoBIn$ZM^nfU@mM#5QemXmU^(d>&DabTlXs9VA%SFKlOL8l z1^pD2#K4@+F{=2=vye`ifza#qJOV0rb4yRG)kT#cSG1%JTn_^COHiz3NZ7`M_H`Zz zd%Jjx4bn!L<0#(b+og=XOseR=huPL(#FW76rdao8sOT4?B%c6XPAHfTrFM@ z6|82vwnZKFkH`s_oD2lgb*C_Ww zv~uf{qs4ej4|DEaodqV58{H0S(4kC9pfD{c2_@J6=zW;PZIXmhCmu#eCj|j$09i~7 zM92@#)6uwaWJwNizhBr+j#7n|8YYA8r6 zT3LA3nFibLld{;ky{JPou%={gZ>M&P(OnzY6%YJ+g~Tr|doH_-oxf_?;n@CvW{#GQ zewID(=CH4STDJ1+{BOIPeY4TrCH?W^{>7)&R?I2L&vWqfeQINzBh$IpNjb5{+rZkQ z#2h%VbvoMZ-n|NpMa8;J-MV#)yme~>0+?c**ug6p+}o1aN3b=}*S|bx&YT^(y63Od z=EvDY%#oE1da<+VouBfXfJx0Dn<+Y6d19D_p2H3^v+ygmVzF+w?KjSU9x;yG*oeNf zx1V42{f@hLf2yvk%6k8P@5-h&BSXWh+KG;vXX+#bFTU`k@q??Yt8Hh81JcE-m3d+x z<*VIw%lq$^tEpxG)@M`&a%7p=vopQY@V(gx;X520;*m1uc%`j-`0!z5RFt}fg~jF< zlEa4wgA-J-N8S=OW#~?^Lv*(lE^g+mdGoYZ`p>(D=kW~h)!5v;exX9hh9IPsYyH%& z)D$Hal}@#QGbc!58%#`1bN2V>vt#ex_ffJbDJd1Wt!Hoc?69YLUnRvL8J7IV3nZtFTbpWarK-aA7J?MMfqj>Zq!!HsX8bojUB@+}*Rmnyx^Q zdA1|60?klMXu2xfn#LA{mXwqzx0X2>Mddx)6;=86?RC5dV{7XuC8rK8EWnUa%8pr2 zo~(vr=d;w*C7{q_^xe8%=s5Pvq8{na}aymcg~Cx4kkW- z_ioRMl`EUuj;uA>v*%`6dAYHpV?xoDcZ(uk1cSTV*d~V3c9t@_UL+R5@xnU$|CFN=Xs;mcwWJq49Kb4QKOSb#54;>*GitqT0lmnb26 z5?_uCK87!g;mcwWJ%KNa;jhQ=B{Fqa z#)@7^mj+#JKE3MqzCn#$C9ZchpFH}j?z2Y!m_JjhbI9g7Ef3%NRLYgh8Yl%s?v=_Y zvzZfis#SsJ+sAl#>133|J};fHu;QQM&SB2*FY)vjg#{~ z`hO~xHw~Zs06gD`$~i*nz6sIdqbWgn-|asyctW31_)gn zmG#;|32ie7q7HB@!~}czo^C2L@P3@9y#NR{bkpeVU&Esu9ag13%ZVKZmaX*cSZKta zhPLg_A1(fVG@m~Bs@wl}clkfMPX2cu`~R^QwB)IlEObINR$$;vLDK<_9oJSmOzD9k zXiF-P65IBl`Nx_OMnC2DFd2vizwT9xm?EhlymXSekJTymb7$25v5)S5D+qmAT*Bj_ zBb4mtQt%kVIyb=lpvtR4tQ#;IfW5tQSqU$qCqTDpMR7rSSeOsQKhB=>MEDhi$gMaJ zMlaKL`p_s+A3l}XzCCzj

)dJu-6v2ZG4&7TUXYRAqEbqf*W^E2_hLY!ZD;suSjq zR6I_C1TV2^1R&5rrV98iM9>ky61(D43;}QFOjo2ZX4mYFVZH*X4*y+NHH45iCKCEg31B_13aEK0}Gf;rSJ{kI}dKmPCV+7^d;Roxr6sXJj#7_uX>fTj&ljTv?ORlGIQ5~XraEO~n zlq_KiFgKhU4jHwLML7V8Q16g#5)_37D6ho2I8{~{ZC$^;&;!qK6wfG+F@&zsIfz<^ zwy_P%bXwQIBTdqTu1E^t_AE@f;)a4%0d+A=A0$dAyyqTg{TZuGfcm7cwu6 z$&kcjU2+Pz$K>MV!+IE$)j?qQ9_CH6>(wxvr%jL&%v85z7oIT1^+{jGUo(v3$(?lpI>AXa z8bu-^;cx|Sepg&w3SkF}iI7Oyeq_qH?*b0 zBW)s`5=aJGl7WY6s4=V+J&!Au8;vzwqA`4yv?NTc~ z6n@$tn`)ak{Kf@2zUbrr_@g(?T+y|#@O18a{6dvD}79GO93g9842Yp6Y87es96-zzq zSXHh^(JiiFrM4Ft6S4tpm`aa}VFg%bg0wy1BVi8J#%6&2bAy+V)j&~4sNH&1W`Dfu zE9cU%Hsu>(e@bKzsTjpH8x1*W)}etsx&*4}hbWPa^`%?QRRm?|D%i&b==EO=Q zpm*-If4xO;mIp*Vwixh}iHfzrvyrUu1o3QR0SFqE1lQ9%9Z`C-Q5rNEiy^$}4jt;a z4Wg6bjWsY8$v_P0!keM9xg21z`<9zzxLNl+{0+Ns$*E7?o+EWSTXTZ6e6LZ`SH7vX zXcX)|mIfnr-as8lO2*13PR3K*bN?QG@1>q&w;u(S5ilv7)$yUIQ!%`Z_T(3C-@dI@ z3#eYi1Jld^*l7~^uU5+)^~RjEH2{f*kV8c!Q6NVK6@93&E;)aA#*W<&=Q3(uvG+#q z{EqNBfZw`>!*~5Q;<(g}BMsq<%4VQ?P0X$;N>m1aMZG)&xY8E?p^mz76{XX0Nux)E#y91XQnm-8#yKHbXSiP` z2bAFqQw)Vv?|a&RVXLM+up^4tE76Rw{?G;mZ0#jS?fsAzcAQ3?<-Aeev3)OTf37k` zt=Ul()tgGeEEz`bpKcml0SA|smNwRp#CNJV9J|2BaV85y0RTGfb<^l?m_7MBoI@%l zC*AmPJw>50bJ@)Jf!LD@Z|E7;UaHfvJw8DWdZfTDCNIqZGW!FWC-DhP30A3#&hpVu zalm=*O+fH?4t4O5+EaKmXZ&%YO7~GBs!S*6&9$7`r$GJP(k=oZSY*)YDzm<^J3hz5 z<}P*nXV*x6WQJBh;zo{&EI!+mkXX4reF!2`HKq^;D0cd5=CLgP+BVj;S+PA;J_rq&#N_lOdVZ0Ja_oXX&YV+?palCM_SviU?s@C-6>j zjGTlE#W?>Vg9bgT(B?rKz8o7=@M3Mf>N`MST+1mo|GEued@OH#0&iT0zMNjmuEQz8D5T~j7H+>Y zezH4$!u`7~(@)&^l`y(bJUqGAXVVH&qWYYCv-*{lf-@Y%fLk3>jGafsdJ4E7<^}x) z4^_NG6(ww375Nd$j`P3)_Sbld<^4W4Ct*WSTPZ^Q<#M;3$FYO|U~lH^K`>O$>=nUq zfjM4m$Cm>D_k{4vfl6HjrE5UQl5a-4vZ{hu*_>)Yuu(xW`)Vrg;o?1{c0)mJULJe~ zp1vS?Ui<6uMgPEqjM?g{1%L(qJkJy>VngfI3ctYCuY|d02z_UQPexMcrY^#;xqK+K zxPFgKaG!REI{5f(Y2)l^RFK}7IEF7{x@5!R(EB*r<3(ZTF~sjrh?ei@QD7e`P@X;o zCyseRPvNoi{nhvlUTQRi(MOUkh-xJ%h9>f0b?x}z&de-qXPTrDkK8>wyek2u8s?2{ zHQql817+DoR$Yqo-|1WdwzoGC?7A{CzE{|Qtl&EIE(s5XV2CB-Ww4b zl!C*wYol&D@vzJN=S4s0W2tr-RMZJ8{f8sJI6UgZYt<)km6+0*4pwxrLQ#uaNFiR0 zEY|~Le5w;^kih4uqHfYHfThAvl6?J&P*bXucvjn#c;axqb5FD;R;~X<4Vj8)p~0fl z;8Gu9bc4tc9XMKFt6ZZ-D+7cET`bi)*bgiOx-=*lOzaJD$Tu6Cl!V7~Q?YP%dSVMX z(&APRZ!{c-R8kC}%*j9{SCpm!Yzk4*gQ26ft+YmXu)q8rzMN;SFC6Eygi zhL?+Wp%-uRSkS+3a>XsB=W@3142x|p?;DRomWJ$1Q^3J;waidz+eriQWt+PQEu!5j ziSK%q0;;PnyqfD$Bu&RL9YUI%r<2;18Eco!|xdm%zF`Ty{7H2}8XKO>^?ceVAk>z+*% z?o34Smi+3z=Ky0G%!9p^x<(bHJ!`0sUr<6z3xey{XMbQp9p?0*QsT{j_1TXnU-3P@ zHvvq};CG?}w}FA}>LYkWX>U)X_2&V#&)3d$ZFZ$;XOn3O=^8g`D1ShYVTsBGyzHsd z8y3%CU@Q1|*+5PY$mlal$+xbLH6;X8-G?s?=9XF|$xRGXvvD|ABPJ|E9o)+gAD(K! zjUqDe?f7$4$GHbFG)*Qt{YVo7ar=qOHe*jQ2i+yg0(-j5C=N8*tt?0mYvK23t+fDFDB*c7g0*bjR>8^tGUWU6O#OSk*VAw2RNi?N$ z7rZ0h1F;@(z?~m&nmPBMA3vRd_Bwme6(t-J1KWZsu(g*WXyHi>pX+f+>|s}AWH@y+ zkcEq~d0aL$Jtkv4dR+?bIK`E?z#A)(k+7?4>>r&wM}zsK00ab^SG9yt=_dVm4Z1{u&}*K>8vr^{ndD z(ZMnP_`1xmpWdjpoAHz`!qtiE9j-^944<<9d@eLXG^keZD#JEV1!=gh<%s(C*Gxou z;DNlpWjSKHWdwFA-3fx)L(D;XK16Z~$^mcOhZCCuw}(B5JGP89#7t2R_9I3Wlcr3O zf760ItT-z1gURATN7$H@fc-F0aVDf1EYjsBGM{z(qZ1|dIR5~I+o_?ww|Nl7(_F)dhaC<_sfm^cnk3CbT{ao8W&6 zzlH*`vM~)4nPgCQ{4}I+1lu|c5Dc}-(*1n)7Gj&zY~f@KBGduybS4T{qv^?o3)92- z(-sP#DNnNfOQ=~{ktUi}iVibAvtbJ3~wD!Mrb{;;+--wB4k zyJFs4MhU!EHw{74Uli)mKN0F(`E_Mrw77jYVkh(28$U4Z?xCtasUd{`hiZ6{Utt#^^8&JJmJ?o4)NJ7udRd~0 z;fj3H;2g$sqnNucXBKZu{SVPY2TxLWGsI{}iaLZU3RfX2?gQ-4$Rb#(Y!{szPw1Dz zOhfW@K7vYrrYYazku14_68Rn$oru&EtN;lOJw6hUHgGYrd?ZKlNdCT< z)o9ig^Q6;V0mB550~z#zh828(Dn-(wA)5yxEG-Le`?HVJP|7|$DZmm!sXu*JLQ5Ib zYg32HO?BW=Kg%niFb#Ju-4WG;9P!wmpzN`=8--QGU3eMWee`BLzag-Wb00Ky!?>Z>*(9qD;*YVM!EY4R*J%^L~X~GQc|SdI?}Q5@XHbt6_vrcDz+q=bVrB)h({mu!Atv}GUsq}myT35?nO@u#vLZpO1u4YBw6$FuiDhf>r|LsRfs zAkP~be94B+-on`$7;uT~(kvzW z^{Y!Ado&4_7nSx$vB5Jho%=X{2teOE8NuJ8Am!Tx^Z`;}QC?9x1MlnAhJ-Y}ud}l| zhDZo!{aKg}o}o1~0A5ubc(2a}-Duv)nL65)&1Co^1S(~r8V^R6h@5{-$cqbe$QXX# zlHpXdV1#hCkQMtFaAR8P*>JZ#A3J*yYj(6_P# z+_p#We?!7qB8|?u#;u*2G-t{Q5d=49JQ2fGF6CcwO@_~z|AwlZl^m|a57nU^dBF>Phrynp>`+_1k6}eNiRq7N!2J8r(kX_BtMW|w&)T&azf&7;>^!W+=16ih$ z9*1@)6J1D7&HWQ>+kDT;rrEo&uaUB@dz07+bw#t#ylx+V*Zgm|nOsA)sgnYXq}ATH zK&WCEb*FmEKM3U%5~u2_H!slVml$RLcK%6)PwdjnJ17Z0{>V{QY{E#WHT|4HEha-m zkCO@y+!$<_iVSc}K-2wp^{qT}0MA4}9>#xd;M5od@nl3}jW?PMH}tABSB-v(fay7- z6$5Ws3gu0+{v_!2${Pvg$DbQD9DC|QY{ARF05VpTLn?JQuS9C+4)QVZZcu8tjgAiO z(|VxaBl?N{3wJlVJCR?Qj(T-Spim9X3sOhN!VQJMmCOkCGI?ZAvp!*m4D3i^M`dE@ zyI=%i-ss<#!&!>x$9cE{;2sbgY`Rzu_H4SY>={|)FwY@GbIAZ4XuFfKOOHY$OG)0c zV%^6F%AT0H>c?MK3H=K{lo}2pr>P>`M}z%Fp@Uwe$he&@8PIo83t5t8%_K!43MiU( z$v|?>P8X*SIZk+N|HWrPcP5D+lYj#nDjs;=Gpxa><^+~4p8^j-I>$`X~{!&Y9+vUOG& z-M4@J<~>!-4&&`q9~K(Vyjv?3`(WAU>6iqg z3pJ-x*n@>Lb`Nmf*1SPtzwKB{gP2uM*d(nE5GY$Jt z*qm_c<(xNjpf5m4fZRugkdNC7wZ;LTCGM7Zf8HD_{X)=-^7i(=Q8wa|Fb}l_y_jyOv)&r9cn`!&yL><=urW!f+&8H_@4#crQ&_t5OUp-%vYw6yfN+n>&P zkBgbQc;cd;-Pd;*8M)%dgKbnN39{1CNz~7iVXikIzpOJa!eC`wOPNnNph3^EoU(Fq zRQ2@qIKm||3Dwk5+~rW@=EH$Od4gcDuvr1Pqw|O);mD^PZV5VR$eXdCHL_gye ze9kY*jQgRbn`3rp{R8gm)7^oX7J!eh|1Ybmt2ga)!5J;7l zk#RUzWQEIMGKCquJyA4nYt`h&LmY7wHo>Il2_T+}DlRJ7%xQq|tjg!FmA|SMf}dpV zPf_yh*tXyMIQDgV|Hr8Qel6%NCjtI2!0*LLf?!az73o`HRF#4H^NyG+66bt@X<3~w}atNU)mo$?UAPds0#wEm zfi$2{sh!c0k2N&HPu_Bel(C748*29<+h%XyeeVFvY|ZXIo7L5aP#T5Opii>0)?JqiFy6ImMrt&%w}7&2PYb{_Z{H)% zd+~E9=)F_%r`vk`OFa5^eESOx%BCEdFj-x$k>V8t)aITWZ2@()>bWIHq;#>Zy2~jW zp#lEDJ08pJ$@Ax@U(WgXaVq@>qWdEH>1l}RsA~qH7y|-Y0yb{ir1$&2?wSp(@=>eS zD_J+!6mTHH5qx3BjFVd3U*b_|U~2wXq*yv>`d{9VBQ)VUTP*c-cemXzHbyPpnd-gr z^pChQQ(X4dkPwsRc%G+xj(n%oQ+1asJ54|m(Ala+Mn)8vsi>^HkdUB+<#_(`u^7%Ue(>asZ&|WDV^s zE}T}KwBe9SaB7UTw?*KyC_6A|a!yXpJrqmk321l(oF--rDvL)E8GLISAszI?57eEM z(tq^c`WAZB?;%7pjItmwYHgnuumBxB7;(=goOVtFHu50*PeKW!HUC}`(r9U&o@-XD zlmUgOfJRwN8E9h4en8LYjq@q_XQ1uU^(_lm$`WVWV=97|vNCD4>WD}ki`i$EZ<~FF z$2j4GBJ))AIh!jVH60lyGsU>e?U)#OZy%ovH?ulF3tx;_^!NIoJ2XTqdbaT#%t5-v zv`Zd~74j1yJq>B$LIa2nd1^**UJU8f=GgYO0PgWVitkntbQD(JaYgIE8@_XhT+RP1 z{CI!OUomaXo-DefbDUQTFKP5C#US-PXvr*w+erzOy1sXue@Ia$FoI3J3v*h9-+EB-F&98u~Du84fS#d z{o}c9`Zx=B{e<#T^s{u;=Q~=W5!!V(T3o{shQ8h9>6AQ4h`M#F?2(U;PlJ-wQZFyB z)oYG_IQl-Xt?c8k-uY$G=e0L_D-IoWn9?=h&Fg#9TGC`p&pX&X_s^)StMgkS&vOAl zPE8BhPgsAId*)j@ug&`OL0u@-qZxro--O#sx5gn^k!wJy{mMZfWj!?aelT{V=P`QN z4N9`S63qz2v4sm3Eck0T9{B43^f=367tz~SW)y%y`|<`Zc5rY=j{^v!`x(3X`x6b) z5CsPlSTw(E!X>1K28D&zpB8WL;eRdOZ?VuHoU#5@(%HJ|`7x7lz~)AO0_j`&vu;jrn*n|)XDY$}=|L#PWl51T$5!~K2Lt=qj$o-BLRT=l~9 z@q~}xpmJ{VXF|ugS3uT1(42&U;!eB=H9Og7HMx;NTOzPsMlhBD_1d1;>VOkx-TL*( z1=jl=lyI8&GbR?GXaooK5R_*>zXaoAO=5#H@*L%GvdcAK=l(k9b2wk|*FqcvYh$?v z_cg+og{5W`hTa(up%oPBmbWW*IyJ}ULJFzaU7^MWvcTn~RWmQd*Jk6S z{4YQC8>MNRhA#lDTkpWn0fixb5Rhx_6Qp7--!5LC|T z>nz~k*d{GZPy1{0^&a{6D+Ma@EyTe4=U=@3_4h+Pq&k5^?w|Wg$F`|Tf^tyj5ipSx zl(0-9`Wwk`Op!rOR#p;9KktZqznReqo6wYghiCFq;o}7h_y2Ly_1F*JW@#v3#Rs=w zXg?tT@^vIj$E7+U3f@0=o6ec#6A-kio92RaF&SMi-TTMKhhzF68ulk7bSw+d)X@=1 zlQT?GkiP5A5BS6e$tfRy`?Va z^8qq$w0f7@EN37bJ^`uYrIxQ>YN7qb6p1=>8aRRNab(oth9NlbTX(>*ljv+jdo2$H z0{v>Q(2vW~x!d8tDuJ%%gPd1F6`8gN*a`ouy(Hxxw;#kLNJ0iAPQ_p%rC&dFu zMW8K*D2LaGClim6$vgVNsL#~kH!AjyEyYzYFK>v}4r z&ju_%uWw>@E2U2YPOSvuHWyKSa0!JDQ+H=4Ct&c>9_WW*?R zLgHD^9PF>hz(w)9CeR$r@nxf?8)1Gnw^*r90~q^_K~@NA?003d%;kRuE`di$_OuxV+xym%v!1t9fNbMGPeLS%Od`pa0^OAz6Bro-&M|1j(GPZ0!SxU8;1Hi)|<7@<~QmItbK1NGm5?=8v zp{kra_`dHkW^~3%MR2BM-$fF6H7ATTF8Hsv{yKR-OE;dD{yCP4EaiFJT|?lGN7oMd zsC;eY@jkTP1B5SD#EXjsH(|gT5{ZPnLPG<@B3gHzb;bg3DTf$r=ogX58xhPBQYh7e zyd{=f>Mk{FrSVcB=+0xQh?WsQpc2%>FHV*%WDyCsob6@Tal+;2=DTOmYnKeb#}$n9@~f150S~^d%2#{i!N95oUqz)PX5u~nIx2@bs2jXw zjnt(uv||A@3Q{M8xBmTY&?jOjcfv@XgbnOEzyaP%B>aSnHF6rsxVh$s=&aV|&Avlx zDU7#iC_V5F(h89oIE#qSfgN&zY}=bGa^2^rMK@0my*!%$;`irL3Qe>LXMoNiSe`Q1 zB{>N(o-1gsG-&lo)N?Zckf#z86KO*EG>k_6=|Q1)J@BO3J6hx-F0dYq*zPiorsPc+ ze2o<-3`GdC#Q|VK8Rk~zy6!e)leSZ}FT87y6G0L5&Xlt%3VzS-OMT5(9#}vg&$@!X zV~%^o+=C{Wbx8JbUhawt^liX(IdompPVXrROOt?KReg4$vkP?e)Lw*_$j#C4*@DqM$HFjajjXgz>ZKgsi8uhCB4 zqUIH}7j%#kYvQDbqQ<_ay)MKpm1QWVlc5E#n$-lR zQ!@`3ugTyMwv<%JmSRN!b;^i(@2!cz2!8Xxn>BsyS<9<|yKxiwf~P~?aIcC(N`c0f`Jz_?SxDb4eJ__vhVF=# zC+uv38W4EjbA2MS4xAb@8qtcHPIq$#?s$k}K+6tn;fkpDhFM*eS5{`V*uo+Jc2*Mz zMlvzx>cHszzErJ~j$@A@_~Rwf#uQ9+ma=1LGYdl0iA#iedGnChUV!n{gpr9mZE3qh|FsuPAq3E{w_Hk~S=es@!u<*yVDjg)K3=_P@j-kQ`g3QcY zM9s(H*kg#UcCuj`j)NaqMgKojeBrK&DX7{*hruHCb}nA8gJ01H6L( zz^@uR=AuQ%5S~zr+@vafvYPsII4CqRixz(=tW=92AKH?0ROm*DwzU{bjF2sC9MF|S z4jxIOo}Hm%RU2SmT5Hj+;37@xq;Z=_n#{Ksc3vS+6~?kv!A03J0Ju3VJeacGLifv@ zscpl4-?5XJ7O)u_JM2B+v_;+baBlhaGGUECvV*c(F_gAYt5?GD(}vSGleOlQKWWij zfoq_8fzmfEQQCC$x8nhzkP_1|?i}SORM)~ob8ev?FdPd%8F7wURJ%|_h!iN`L#)vE zF(+grgP7l0T^&gY4^I~vt~}HDt7Vj<`^L2H+{?xo>qz2%PY63*gtvqGKsI`NE7LrX zr3G8*(Z**jt54MEE^cBnz6329%ZPT1ct^fKgEcnCOV^bXm4@c}x`P2N=*Gm>m`T}3s?PV(+Mb6GWxoqubEcly%<;Ww-{^V3@dp4mdXd6&}GJGZ#>L`q7kIt>CZ zxkR6sos++^*k9l(dDy)1w{7E!$hHD4UItvj|LecAd)7~kZTf$G0e`)>K~387zrJ)< zdTZ(b`U2@0^`?{m`zwcKNIU=cSGLpq_htUGBL7{Re=Fm^b@T5^{C7|NyAq`THj00j z;=hgJ-<9}pqxg3v{@W=2U5WoTivP0`|7{fiF2#Qv#lI`@-$wE8O8mD`{GXNhZ=?8k zDgJ+L6r~r##GGtsX=#}ktUJu}jKn!2>2mM^)M~gnzHEj&!K@{*#bo`? z_|L4PV|=%^4mC!(bjEzjFswEfKS(+o931RAG&Vd~_rgS+gZP*+y<@r?&QWa+*K_ae zFTDG=)>(#RYS-A{{6E*Qe&h1x%f77Q9~%EM=s4>8G70ep?A_!i%lqP~cH!O1)|4BD zW34F}x7$+RCnoxAA>SpVrluBY+bHtojqFoX{2whn{rQ#ozi$nz{jGl*y{O#Ap!IBS zkwl7r_vX#P)-+wVv9`2;s51`djf{*`)z#1Ah0Dv!O@C$@Wt(@L{$TfekM;*U@0lh^ z$+5sDO7h*TzEn)7D?*RoFlbBF&Tv^6C*C(AB4Tl|Kj7`HZ*gCeuVv*=mhX6b`Q>Tr z&qrR!3^zu-#Ya`TdKK>*ADf$d8XubBMxKSAc}H&L%0vkpKCzOvHp}IRQ{H%M&SS@X z@BVFhMsIy4UOu@R7?h+9#duDZQs9t?^Rn{`#vQ_ zeBQMq?($2+w3+KUW+8Jm&l0@%9z8$N^-6Eq^q%P_iM;&BLSkTT6F+ z`bGcC?p5R9(9rWS5^is7ha2a_j+4%=IgO>{88k+U@L6^hX%^TR4cHXy6-|Bh>c9tw z30B-tU-om4Wdc~m86Cf7$)OnPVFs$IhnT=aa#aJLgJw?AM1I6B+@rfxtKnbRWb{It{zmSd&);OIZWA{E z_pha637@|YfAceLh>-mjcR4_u*lZ~`@+9W-7yF*}_dPw4nrGj8(^2P$TFUhtpWTwH zlld#IlV#-Nn-x8sR{rL_&CeG$Gc%L0cX_gl#h|~+@5{T3LC)7K$2$x7Oq*Y+h|Y)J zu<%Cpx70Du4Yrl6+pqpHkvtP?$mTZtWuJhtg1F+=Tg%mw>ofw!^-5(&y z`jq~7;tN|Hx49PUHf@K>=GW(%7A<4VIg>Qf{HxhK#B|)3233lG)=v?)=)4~z-61)D zU;5+MzppGQR)2Xb*T36i@m%nW7u9&{YnH&-)NlA$)2kf;mx4+*88NYc9tT3v` z%F2o@blMU-his`}RktBR@ag!kLb)`Zk8eCS)|IYbXGA@jKg)@Bo&KDUjl?w2Np-8I z^gf@%cxQ68sU7_>P3pnHL873dCmXc=r6J=u$nN4;Wt zu+DI4dN9LnWxh!)RrV>pHC{(d!LjekfcU3lvQtgd&W|<3r|=1F){R42L$wfdQ!bO)sKS9FKgRI zT0C{THQBqvvP7KzgpO9)uy*Fni^r~I9xk5pv#dZ3zCi@McB8)?p8UmjyRR$R}}7Ivj!eQl*b zP>$8Rdv!<%>k*h|f7{H=0Bs|~?)O*6KN;0;oMwis|K_w+-P^RK?@ag76}vw__$;%| z%2dq%?RcA$KFSagC{)pdy?<=f6DuT6ED_(RC4KJeS{!SVq#(@>s}J$BgwVj zibN+C&084xa;SJ?ZDQE^O@C5qs{aceXRa|m|7$sBYDIIcH?9S2y6B8H*`Jt{>Qm-P zK73?-?HyWiReiX?TND`Ioge8x3T#bu+Q>?OO= zub_0}2Gee_$+LE2t;f^4-Se@~M8nXsuB1ba))u9#lwgANW2*R%r52`2^>r(@XWvrU zx$oow_eoDS8GCzs&s5p#cgH*TH%V@|c3OR+nu*c<-T=^rzus`;N&Yq2ESytzf*QTw> z*P=QmN;cL-Emb#@zMp_?&^!_)Uteg|TmB={=+YL2Px0aZA1FnNRI@42O4corh<2O* zx$pEH&1{QbqQwgzCn|v_`q1I71(1_WV%yu>^D+Gc3Y&;cf+4B6H!7@qeLnA6fR%!L z)>&?%GZ5Xb*loply>}4xoMqhLgG;LjQk2+_d(dFVN)o0a-^ILGzmU*~9i3eLZWjS- zFi!d0*Jom?(Lpj0XY&n3i@Us0jFFh?@!V}pUvsB3pU-*z&;BN{ z8HKJkox;23v#1uL!irMQn73z-VC3HU^+7Og?D=E#rOFELz5Ua5CjzYdt19nrAf{s2WZM;NBHFzi z3N_tlNzGo{?`^tw9stNZL$B~xiAhQQgD-Ub^*=q9MKd=nf4F@L zUCdaV9=8U~g&tM$-qr>0x^qAO;Q*|9`kdTg@y6W`66XO2^q3^T>R3R#BDucVYzRDu?Ava$hA^M@jC z8vw6f3)u5yH=BRV`fU7E^SRxF<_$+Kh05Hzb<5b}5XOh7{H05VfCJ&lit_+@v?Ulq zeLg&?UPg7HM&gYZZT)^{{r!<~D7AQbG)&y(ZtL5#ai}a`MnUe{x;ngb`J)|gbxYhc z&|`|yq8_y*X;k~}7cc-UFz7x%674eX4e%V___s-7<<6b%VsW7Dv;BujWF*EME|s{* z=|>3(D)Hyd&CM~=NzaOZ6*^R(aG!dbKl}AkKhToDkB?8X+~#`%UFhWfW#nvP;}R%X zOPlWX6-$-)D-F&M9S1`+44R_F(Lp|kow}tw`?o`=%VpwYvRuM9qLewgxV+Vp)Q!X` zNmii=DJg!$Ou!Txt~b_9*OPKxDC};i6WSfG*In#pjSf_e+mp#USkmdSu{Kq)SMk)M z=%p9De&`mwXtQlSw^^D>*5}ejzQqSvZnhZcavF~MXR(Ls!>>%2)Mw(9b z$NL9P(W6r}&OUY^1`mo;4k*}I;H(7Ex*zXm(;1%M>twluBsVl0wC3wSw_oyHLEnSYp$aw8e|`#31VwpI<)jJhH2m}Fz;mx>zR5pd z$Un}E<;tYZl;LS#7+hTsBbO9->mrfo(o_(#Ff*0EVb?u8;~vwY-MADvv*bFTw5nNJ zT`d>8v_0X1aZ|J(fXr*4f2|IoJ3pv#(?2yvouS#Y=fR5;x_!8p7}PR4I;_gd%98`1 z_eM&3u)Y+stf~n-q;F<+Jyi<@D2=O96%~F$Elt6$)|6>fXEi-=u^{)>&&(ree4af$ zdWR1mK5*j1ZYL+F3l}b&wX!-%d|f@|`sbFR0^8wq$0>t?+yq}?|4(??sl_S7g1nsc z^imA-bdx65&W|n(Cv=L=o$h)8T3WuHom%)rJGPYHa3&rUNx%slLCb3FX!HnHg?6Bq722^XE@aPR_H+%3rIyJFY~Deiqzh z;^-*Mp%8Y!a_OO}sB6%-@$Qn6^2?iLDA*sW3jX;h{qUc~SJ2Ztpi}IcaFxkr{*M$k zLx?I3JHB;cFgP;O7p=Cpr_6J5X2#Ro+dJ{nL41ch1dEZZ^YOZIJ?0;Kh`em#1$W|} z;wCY(u&6zk6cO1!+!Uj6(L$O#0^Bj=_MBp=)S_3ML# z1TMz^3`#w0q#og2LY7?*U%X&gU0WMuTz&TPQ+`(BvO&f!mcw8 z;}u|Sfsv8*!AaTKw1Am%D36^xcMc>5DN0Fgij0aHyng(9RTWvu>hun>UCb1MIUA|H zZ&FgI(B}Yn$yv_at-u_9799K#>|YN90=KNEVXCKWi$Xa6HjK~U+a6xie#|0!AO+M< z#m2@Gbpe=vGz1BVaVy5FyjM$VMP-eQm>$zizqjPl13>&E*PIFXi+m`8BH<4H z>lqk$C}7g)I=}S%`JQ9iA86Ot*AHr($31fuF(sWOs;XGCtE-DL&l)(2Sk$VjD*5+b zL>)ftt_|Ut`lcw!S8dDuWOdaQ*9v4p+P{DQ1qB5e1A~KIMNYt+tf)qE$HmFl(+~J>3UBkn}vjYWXcwJoiV4xl*FT{r<-&H&mU-Myx7(AVBC$AN&FW8|K5e;v z{d&Dfgpj2_#2fu;f0i)8+w|z0PI=)%maNP3e|c=B#g%hn? zfiz}qseT}b1f{UDwk|7jnn`z<(CI98W5P|ycbefqi9bSb4K3)~9J9FS28s@65Qlxy!Nnjj8~0$V5d&52~r2E)Fs9XOr{?{0~fAipNg;?26jfc_&Yy#B$=q zi97At7gNo_4E!)$`aCvPVw5%Z3-R&YFDyKB@X(IHY*U(<)6j6FoSi?E7f9wq1)JF_rkp_RNt9$kr>BQxOY${=hmRk> z!35j3nv;Fyzu?47CA!7&qu~M*r z0mju8E+HWyW=Z$Rgpy=z^emGmUXAEPc@>qt-L5lK#T)A`f7)|)c&yDaKvRqz&Gg#* z!G4U4hbM_YW?1;jc=0V_!P4JuDkbjq(m@t6N9t|cw(%RD5)}NBWun-X3wZoCITJrb zEvNf|mk;3>4$!v?_;y7GgU3)O9 z&z(D0Hfq+M&1LcH!!}&zkoniIUr(Ag9~c-IpipNZK2l=bj~|*{+e0NZp`rnM##uEI zTfWkVP9cMpmDS7NUtQQlR{8pMN=r-2IL!oAA8f_Xf>Jx53f^wj!+I)YVCDOQFZnyPe9{k8M*&T7( zocp@Pw2{-sy7eO-tsj#D8J#N`bC-tm@wTBN<4Ps6(IQY zSB{O1^`qI>dmg5ZO-R_jd-v{D@Xz`V89BLrNbU^j+{9;8l?4EiQc|L^)Pe*PB6?sN z{a6~^%Bf#oUOwHpfiZS4g+lt=IT|*$CfYN%TaO8gic%^+!EUZ^Xb3mhSnS^&J5Xdh zyo*=2xSkf$ye5d2JeQMX^OrC8)6!1Z+1WW7I{f(|<;j=04;mXWT48b+bj7`Tb!`uvDYa38Aw!6>Ki{CJfqdZA@-eB3`f`&3sxIw2bIxm!-! z+S=jd>uFjA%D0?&xKU$ha)#3bpC@N$Wq=+tGc&1C?s#bfd@(&I$LP99xT*x^-MJjI zmRi^1^mJ;l;Jq0Ku?_=uQd{nA$C^)9di(lT=z6SGG7XQ8`gDDCd5i8^l#xyO4+Kag z-iPQKkWj-!Y&pJv|4|r({@>fz_W%HmLi3;d=A>O_T^4A|ig%xv| zSBNy2T$m#39=&WpWph|Y4RoZzRiFfh2(M02&8f4pKY@z5+Zt+$i;IOF#v||1(cr_q z;|8mz+QlkX!*n!6KErnSO2M+o68dV{w{I##4U=q(D=Ymdd-=K)v*f*J85tP~7X6^* zb!=>9(Vm%xmqLLrUnW^yad2>m69z%J^D|Sn*EQx_y8gL1x?MXcDbua{&r6vdNECEm zbtDjy$a?AhEj_|lN_~Fd?vy}aWQUM1bVX57F<}cU9edyfJ#+JvQT_{bK`&p{iM?;e zVEpjmgM35Dt#2Irn3!g&Fw1&DH{=_%X&_(jL|K&n?Z^v^it_XFqHuI_(g!It{T4^{ zjqhXvqk@9MNxPA&;e652(efg#97HdZ{PI70$Qm2l$8@|yym=BFmp?{BMa45IDamw>`d}`|v;M~VnnDH?f6U}ZA3uI9RSPkn z>Z>I7z3u8kw?_bG=O!M4Qe05$9UpJZUQT=Yl8I5sB6)Vzk5RCE_V+iZe&~zan06*o z=2>6B9X4x9t<}a$s`pom+TG%pm1|o0bx+ zlAht=Y9=AG@0{R?B)ykq0^;H<)d6f8`4Yr}Kl4e&0ujI?IXO8jui)-qMuNO-O8SRj z5eTF!l>&F{>sc&?NG2xfy>ku1_lpk4xQ%=ei|TiunZ{B zu|G2_E1djzP;D&Qs%DWRpY3W0kH*&I$1HPvQ-#iR+$x=zjayS6Qn&Q2xVooX^-7nS z5e4v#yA%+i5*>YOk|(v=7zo+KyS=F1gKFpSN&hcl;5@1r9V}uvOdhjq*&Ol!OsCI< z4S*1|iGBnGf0vn_oh<|EIpaHB+MUFFn1h2-la6Tp1D8{UBzHP6`JYotZ%*@uOP^F>w1zI)dL6Xih*dmOsh$x8db?P^%V zp`M;nS_U?@w5!n=VJ9muhn?Jnxk@=`&^tOxDK0MFC4Aj4Wt36UT`W60JIny0IhU2- zpZ5V5b3t|{t3doewYI81G^0@R!-DmqK^Ixyy?Ym8r>CC%$jHcKsw*W4F2m%)0z>jH zX;pZeROcS=4BT%Eh9Dy=>-`U%pEhc~YQG5=K*4S>JwHF>mywYnm871sK9vVkoiI-M z^LFgoRaN)mgi?vS+aoj8SZw`@swz+o2FIo8BYXDl4GaqM1oMY)Bc-Ugn~aRCxvlL9 zur)U9&fB+dhlPc`|6r$l5k}SlUfx{+Y?4(l#ff>3?RV4I_~6l_AK(`>>OHJhk*&$wzjEeCUtkMTv2j1U7U3htWOW|jq2L(+*j2Rdld<}ex zHb#tN%o&Vh&}mO78m}PSzlYjRT#TS##F_L=`HL5q7Q5WBV3?i6JAuiX-oAZKLxVxk z?E6_yGAccN{Y^|vOiC6qhaax)?H*NKUS1w)NqPaSNwnDXjEpiEFLl14d{V#=+fw>5 zNFZi%%{T#7b}=b&M+^+y6mwtQ2l4Zqv-5KG%nc`(L=+1Xd^T< z^f6jh|I*B`<5b@^EGi+yfWn!YnMupZk)t6lE{~;sc_p$y9zJ}y zF?(rbbo32Sb9#FES(sURw{9i$`Oq!&inHJ+0L(o)ho3)x9T4JWIs9c`jvn&S&edHb1QRoFQzcX_U&ar>V&8y=C(`= z6k(GG4U+uEjT^IYb*@~wqL5^>w-*{v54>djw3MkSC#$&gLy*vL2Dv(en>V+j31aq= z<7ct9dtMo|T)1+j3e`Z+L3UBm<^G0DY&wEnx3oMWI>0GY5`>T+9UTP0wn<4&ln2?% zN9yIxn>Uk_z30%B4?-weT3TW|>JLu%C?`h{Jc4kP2&H9obTpASic<|Ur_1%;i^0S7JQ{*&^N!b(7K zgQ`tFq~>v9aByr48&BtCEhZ*5IX!r(OB2v@b@rR$d!@IJDMH+S zVr{Ia`eY$`l3`y}!>=f{W}cY`^fhfsq;sAfxsR({HOXwK&7elQ%-`X(ycH1tX*C!u8 ziep@8^^$Kp%E8fxuDvm$xN`DK&y)4+-9e0k7M+WR9*kqJPN+G9UHY?%FHfx=7Zg-W z{Y&^L{w!zSKuU)UMQ?sK>L8#84K?*WjMW}U6!l4u+^>Fg{zqR2tuM#@P>R38a-aK1 z$j?VR7#t0;^_vSFEX!{HMyL#UnGo8;t+8TTtF7tQ&s?K#9g{M+!eMS^R!e(y?1N;C zukTI_!09TuX5P-1vtYOsZMi4n{|WYk=~ZRAmXsSpahpof^AO8PIk{j*sQn*Z7W{v^ zw1V0b6FUm9X{HJ+Lm%SWgEj+mb3aHo)2Vly`>UvK-n>}~U3xNtLWxkGrlV(=Az@%- z#=Cf;Sx_H&eP*8cbGq_Jp~DFnc1Bh2ladT!k!~!xAYemWOr*Gr`p`T|W^rjahG+Fr zdqsr|>^2ri%b)N{bQUL|zd+}uz-SMUT&I8pJUiC58(OjS3tsK8b~K#Fs@%sNsGwXa z@Q7u>rFeqbVaa@{0eg~C`)sHN>;ZVRTmn@XJ?5~LDeW)bDtGUF&wdudbC_w`|jth~myhK8%Ex)m)Q%%>N*Cw>nP6mTG3 z0(}c~pAZt!kka$=s!@VdzZ|-`X4g0$Lfjyz5_mbkha54;0t4>@T+7JFxULp@dv7O$ zWet~EqvmC^w=2y4r-*VKIB?*eP-wsKosL{8C}=dVGdEs9`4xAWF9lib4gZT8^h4k2 z#lUI)_U#ki4_ODXI79N+#0Nn%MA&v{=fo6m5>hY~6%_|KIEMNuLony}30oaF@4N3l zL5YEvDTjZ;;o(q>J|@M$i5?p;e30%x9(uzP0sdYhGWpgByi`)Ng8gh5mJ{WVb zdmbEELKwpjZgj1$e$+deW0jSaL>a)Ndi3lWb(d66GE|aDVq7^+lEAypD7-CYSOvvXnO3r1%M>3U|HRA7OP+62RXjqE zm9&5wo=7!OXkA_cW-%D74N;hQ4FCgQj*w#6Y*(NTKs8FJ-v@<>=IHU#asvZy>fJi7jFvVxaQZ{0Ky z^z2zFNZWmoCB|>Xoc+iw?zKQ&Xh})kuW!c!%OrVE5X#=HbLRJCsG+_dELosYGpz$7 zBk#XQ!e59C2-w{gugG=<0RH<%NO<`E;lFo5ITX?%g{p z+`eH^hw=K0hxaILRHGJ$aP!zl*RgX0^HR|c-R^dvh%7)3A^`@!>UaXTS`#p1PLT5w z)+NvM%fTxuDk@wn9Dx_|L1S&Kt*v7k7GNNDord`;>rVIZ)AZWrdp8PfViPZ|1;C)- z-yqw!Z=V%nU~j&wsj60(cjgBIqQ|}JR#Q$0ekti8@ggefc&)pe)yBG8V_BKh_ld#X zyKz0d2M(O=b)#N!XsNIF71F&{{Qv_o^6As3($!~@tHWJkbrhi8?O6A)0IG1n+>8C5 z>;-Pw`0ZPe07iRz@z3`5&?T2fYi5%>cj`ONo0%ngr9J2aC#xt_gz%f$UT}!Jz941MpWP&R9=tS-BZ}H(0XOOa5s=fe>EoM8?X@?%LW0g?H4} zjjC8evY3!))vf=28hOz7f3iOg^>~zD_;>8g9tCIiao3fu(HMsUw$? zl8TIoU{ujYzj*Wgox*N5iJR_h`2__DAGE?TfC@mH`2SvlEj3`a0!eGwTm|~tC3*Qh zrV~F>vI<-X4NXl>Gjlb%IzH+HI+6#+R@g{H*-4qblHeFzi_VH( z$-DDY`L$RG;exT8b9)WxFl>DRP=Y=MV)lW!2yW+?NbdAii_myoSyQ#Ch}Zm)qV_%u z_9$T``*3X73n5B;aW?-$qO7dyAE)AR1pj$1z{zMyk47dTY!v<&CXCudjkLy&D#C3_ zyu1?$V8TL$+(raMy3}HVf5VRqJLA9$O+cpZVg)w(J&Zep&V1{9tKJ9ilUTNtqHmwH z?vt4vZP|hN!<(UXWx_H*w`a8 ze}+M_ki6KNdw?Wl(RnW=C55w^9a0bBN`qe17Cy+&gw42}@XH|F9+WTksH>?dg#n=Y z{01EyWkQx=7PY%D+aIMkI541xd%K7Tq!pTM*^DeYGf)gDLYy>@D%U}1HlRs_xEUA` zk(hn=(7}Vvv6mQ#C=7U;{O!DhhD*`@{{B^PaUPvG{}?bTZX(wwH#14hqN~UoyQkLo zR$D5IoxQzm;``Ob_1y#zK{W?Q=RrU5Se<%OALcX7ihA75%*@;~IQR$(fp_i*p0ou1B4xER;gKuPDLjd7Y{KH z`em0R$BylUninSNQT)E`YP@$%yd#kEnznJt*WQ=zps$f(_B(!iz2i5+`2AQ8Cg%Lub?$*$keaN@Kw|vDP z1NMu|@FB+z5$nFKa5D!I6)$YxzTL{st^za;P%>rI<^r9Hrsn(X`}ce(cJ7n`5T@C` zKVeikF%kI|_j>UV2ExMW}hYKB4@?y1F_dD#qtBe z(@+Ky^iWSIt^J6#J;-jtcj1#lBk95WJQ#R?Au=*j4>XYpH7`Mv$khSa#fh8}`kVeh zP2fSbcdlTJnW{=y&O34H6fI~&uOE}7d(l@Lj-y9Ep?)ug9+T41iT>JdM7$5d z%2C2^hC+^jCt}SPA%@AEX>I)cS*pZ+EgjjC6Z6JvKr?RCsQqsk#ZbDE!_twW`cfp!0FY8Eon@9Vq?U-2u% z-Vf*d{rh*mb^qfF|9FUMH!4M+9{oqXJL~K$3RG6cBm{QQ#YAV6LcJ>G?q1B9)Si(K zBNycE5!x^^fYMuEK$pUT5z2ic?<0!Cr%%(vouR#X*F<)8s+x_^emS>1If!nXXQ}(e zqNiVY7t;4-kg>MuW^5thgccS2XvVEt7XgZi15XMWVDvSgKPx#?VHgl`7W68$c?lw< zg0VCOVVv^oIuH$E$4j+yYy?BSC8`&sB9V6+cmvWM=j`mVYt1OAsAM4oY<;=2uiMql zjqhd+wGvt5BV)(_Nzbd&^5WDK{m$-^%R!GJ-_2?v7a9m#!@|PAs}iQ zhl6I}-Qz^4oGCsw_7N6e!zUzn<2Wy`|E+Y+Ne2%TqpNuq+Hv;}k&t=cR?u#IE#Wt| z8aIpUr-djo5;!I%!4u_atU_69D?M`D@yhKy0f54mc%EqHU2y|0sYQ`k^Loe#M`MFyNgi;6w5jQ{=xC|I=1 z+9v`)(k83mxFpPeU}ZPZD+sk8?-ZfoCYVd21S3g-P?foxnwkQBA7rjej=}&}$U2vm zEPN~*_#pmaD5!wQ^)|Cd+g`ur#$oY zkRVyU}fdi@Q4oz+6$ZfGgCD`g$4!gIZU--KU;fywOUGTgb_x% zJ{Fn=eW-aJ8M%{?T{r!eCIXs3#54>HN6os>FF%WiedHzz2N6xq(J6OL&3#Z**d3$6 zK!}rtbbTBXH8mGNkX0t#zk~V{hyj`g&8gi_A>|XW(ax=B$6h+R%2WFk=#p54Znye! zrDmqJ!|SWbZlA)Dy{)=)*zA;ie0)XL0G>*myT>fURJqkS6`j(D-fb#XQ!!#C?Ih&L zQ+Iwmt;Bn%P1OK!%#yUMMsO31};+-I_p`n40 ziK?-JjLcR@_ymZFJ00>DwK39>cVgzxr^lY09)jqauc5mDbHOrW zM+O-1fKV5ZI}QMrL1^Y_rs&~>NH7&os5GxpgXy`s=TYicar6V3hjW)M?SMmAQ(G&I z{z_zC`zm)pi6F|iD_lZ!*yopa)Eld%jzN@!qNADCwJt_t&VqndkEDjGhWc-T8Q*he}mkiSgBDnj44K@n&*Bhx! z(f~n($P)JQ-??+FufN}^qsV@bV#e;2O~5##jFSp9W3kM zr6PoN%Y|&8UWUVoaH|w{4e>FE>V~B%4aJ=ZQ6rB5&gLo>1E;qPOvrk;k%e&PBqVfF zUD14`K+U%nhyV%gfLd6TlrHYE&J6Tw%(z%{@c3~mID87jCPakBT=@ul`mXd$YysT# zZK>y-a8$XG7V{GM$yzZz&2#6rzya;ke!UE#`A5F>+Y!%GgpLP0y(=HCJ$K|7B2>84 zV3(7xASyxI^CTQ6?5jnv1U(peEG#Stvbq1Md+OyyoT0!5uI@Y$6%pY>w-OI`n0FpSYsk?+DAOq0@m$^gUpxt61b^R!dtgdQU!FlOu#|z3WM>YjhHh5na0Mb`0+$(8bwEk_`~u};!%mw=NIMZJjy_es@Z+}|;R4;~VNWdOC$TOTvZ=v; z>oFTZ&~n4b#H8BJH5@w{ig^!CalKbhiJ%CfIariv6DfB=trhYWyq>yMaX%j)&?M>D z(Ig_$#eLYHAZG6@TmVvr2L~&2EW345*We8e<9y6kCo19|-7+<;QBwqfD?rfE`pcIu{2lIS>3QyJ z&RuPay1Fq)vkW!d##xD)+pj2(b)O*R<1;0GPz^^92%moo94%j0K%64#O2aXa$R|(8 zp<;14q@qKm;+ypaI3-X3l*dyP01d;q@h6UpTA-k{K%b;Vkoe1o17Zcox*sOkLW~$B z49bZYKT48di54vZOgjZE5Kp22ikM;@#xArWv_$0F;7uHAA1=%9p95$*A zVcwPG;j@}J{{;gKS!eXpuM0h1w1N~<8PLlzjoye3$&8yyHh%cNZTiM?1|7yt=m z&&O1(wSe1@KeNd6&%Z+E?T2m8;QsUS@Lb}`IeqJ^jBzT4ll$F53qs**lhf2|xsXompR3r^Y;*$+vf6ESIFM8OJdj%(##edgBn!9GdL9>$do((=!eBt?!M zebND|#{|)TjZ^?YZhPHpB{x(Xe*KF2J$I`$IXv-_S_D1{|KAy?YqDv7K_0o+e0{hi zB%;5ywhsN$0J1A6UKp@mU9^sC>j2{J)xt;6ug!6uGduDp+;w2d&v9iwWn@lG@L2WP zdyZ>f$J&H9SrJ4vnQYW>dE*KHav08oRIG-Rl~OSar)#wpbBnebG8-+7sU1#^N%65# zNIXUq;!3jbSje=Gx3_+xIRv9OZR&v;s}|}N3n#|}KOsKG%gO15#bO!m>nq2`j!wFf z#~YuP)|8NxWDD@8g|jh)sBVLUJ)M9x1^WeztzLFPC>rodu>Kv7VVHqd$3X<+>Vc%t{`|IC052qV=}z)M2b(J&~xGeArA&m@F8MGyF zoTPW?&|ChPv96D28~`wF29fSDW)0T9di6ltz)@@)700i1sB09s4RDP~Z31-6=B?5( z0>G(5Zt5Bu!$_;t8Qr{D6Ls|D$*V(^Bbdy5EVk;cn@ZvE8i{t{M19bEd#uf~-yUpC zOgv`VwN*B*{eS-+ch>gliVT1LeER3-QVBNfx5fOj$XVI$MAtJ(6m6eYir1LV1h>YkkJcO!K1@Dmt8}9E{>3VTC4ki+> zuy7a?Kzj8;jOLbmMsx8ZqM|k!vLR6zxueFc<2D98~-Yd zuQrwH4v~6d+?Ty?#Xv^nayEz8sF0Im-l0C*&YhVkM#{%7R;YfP$qH1~3D8ymQ(86g zGqdLM1~U1Gw&N_oGkHZSf?cw!sX{IwhGIXO>sF#0wcoY3AM|rt7-xY8G+?Ho1X@vr zHXUY=ghL}BbiL5Bh?rr>^(QzbimecUq=%!6%Uk%o^5!wBVklr(=!^(o@i|T3R87;- zekKOlsuCTQpif;tpdJ4stBMw%LVA-h5Wr=rnVEf&DuWX(_uJ{zsZ*0UbI2|x7Wvx+ z-I5jbTg{o}7zB!q86o7ykoVU@=nR9*CXXxdLJ!U}5P=lH6orob!a_WPLS|em6InfG z94RsKF~`#iP`Q(zc1xbc5KR@s`x0qq;=mU;N>ddw4rfzOU#!%-eY=hpmg?HirsrZ9 z1Oa%`Lo`<|p1VSv)Ph_-;9lb1h-X4rgRaIkjX^$xR_GCYrVY_Gm~mxHc{syx>_+a+ zJ>Ks+3vOoQ6X~W3|q3+Rjrugt#nAjcmM3e zVY|zxs^Rr%!KIKj;e%Bv6TCmAW>0;s~8|g%RheVM~wa){POt+vCSW_P_nl z(*t;dt2;WF2$k8C!3u-Otyu4axIoysb7SEOZ=taRwns%jb=*PFVj zcJ8F6rY1o|)x3T^G|Bv$TQA%&@`LNNxXqhht?k|A{&4Q-)w?lBumVd+@C-UUmFeYm88jL%wHyz!k4`V zc=`%gJlJ>*A}UC?0U|~UQwWLTrm}e!J}gms&@De@kBDG{`J)vMIuoKI3@qt1!wq)e_(z_+YNf1JUZ@CHsUB<5T^+7+&3HvIQgpvNAA3#=g}l4 zet>sD4StE(lGkbKGMorU{>&2$-SQ90P4>N43?v<#R`OzVUzF<2g(ZzMiRE@>BSf6k zX3(cxMA8wDMS&$%OMBbWG5`+QBl1YlYIaUe3b1a>NA)v$^tOCV{2p?j^)0xF*62}@W6;xG&wYD_SPT^SzsKe>1jGbMHHE5HL9y=gx zH6uzD$gRvGcwdZQ1plgFoYLt;PG!h zs6z_%ItWk1Nx&|9?oEgP%>v|Oq`nw)IL*Ve0}r9n`%w1t^XCM4*Ws)yuinPRJqG{T zq2)I%Xx<*og~ZTyEUrxsFo3CQlKN$11?1%sY30-?^wA4nHNeS&!HCHLPh^O2T>J&s zU7Wks%rf><=1^Gv4nj3qccNsn>Ier1M$x&1f>vi2oG85HW#_8_abY zDJm4Hs=SV}b%sLMYaqMl-ha%#zb~8ZVzAx3haEa#FE)|Fa5g>yo_DwnF5lJh&)Wf= zh}nvV)jYhFzJWuezIcXIu2#Xi-=G*d2|PSD*fn{eK|`&}Wor%0KYX`}_O_|17j%Lh zT7d?{DRPv&M(Rv9#29^OZ^Utl_FVI)&6$7$IK3N(q( zWI@LX;HlNX-fCM4WuLqtVID!0fUp+u+KreqZ|e(z7`JpcUu zc%E}!opZSF@AosV>%A`1Q-9sM&>iWU5$s?5i##g7AixDe?pr3Z;S(XLCjD)9)hjLrFFfCU4NA2O1Pu8yUVvfe45M2WlsXxpd8lK7E^co772JEZV-Fqu8 zoy*38o?3HN2+q>HDGk0PsWXA3auqZ-U2p`5S$q8~1Sbi*yKVST!a;X}Yf-!s9>BX^ zc85$&j{iCbr#6wWPuZkFH7b_6VXUhpdgb$DuENoW@%;qtzWR9m^<+LCRki~`;7_DV zv{KL#Z{R~jga3MO`Mf_a&~BO^6xc-Hi9^RPAbt6-D<(32$X>k^(Hpp+YcX(w)J_l zeqel!G9EDxX{+1*mgQ{g=m@Z=9y^77V*x9q^f?Gswe~#qS^wd|FzQGDZuQy2sGufm z%+XyipJiC4bYluPrKIHpMR?DDR&G2@R0ISE3p1Qv@T{5kPlF)t>9@vRD1&t$v3?P!H9x&0uU4kOR zhO;+|c)B6F8>fEnDtTh@T@g0m{z(|B^oF%tdY9k^G;ciobm=1WvDi>|r0eVIw0~Y( z1_Fo>cwDzUAzDN&nbGA%4B1|j_E{z}RL6>X=qphA=)n0Qo3l>REKl_k1lakdISMOj2^s@z2L1;fN#v&~AHK z2yfy3qQ9R3c~$M6F?cb;ycjBRq)DbQAtCH7=vv3GDt52s28#=?vZ8AFu+9ALg*9<3 z$)rEQdb{*_!kXhWa*_^W!@cT~#W9?CZtW=G=}9{3M3g!&@o1U6WF9%+18S64x1m4ym{18C9>0GQxxNTd<)7#m1?h#VO` z;SEp=oTQWhm4JW0VV?=%VNkM@B9QsZLtl8vtnSEcphFuIbH|+ZV_T;pn$%;&I0K@k zf_YD@=AKI1bf|<+q9${YtGClPGP?1fRT}vNr_q`L(mjQG3XqZ&kX%^Ra%1kt)kDUO zCQ3=(g#Y2L!toU46}}rf+Oe)GrUvKnJK@<5!^ zJoL1+OMyZGFXz!astoj3-m)GrejxB``Tj#k^bcL`{Cz#%CHPHpXG-GPflHQGJ-0X1 z`|N-5qqgfp>Yr@~^Yr#}pF!&0{QSJF>{B>B9Hj@)(9lpdn??Kvn-I-f>;3!7B?_0k zlzyfri`#%rR!^@e-Br-IILbuW2L=Xq=Y=Hf$I-m&`I)Q4IwtSAW3EGqiDQpZ&W^bR ztpsrBCHEtZ1OnJ_JHCZBjOBg5kD7~SyR0VL=t~raH(M9l!JDE0Z}Ci?XBIZmyZ_rN zMuC+@JYw|*K~~qHfqiNhumBS6Yk#C`QIteq6M~kr3FuWMV&;Dm1)z_G!d@*P< zA5nu=$Ykb!P*|G3;62+HUl^e*s3#eFFj z_6>hp@1Mt!g(y&ks{nXb zLGS>V$6F8Q~3>rCmTn79I@&H&uuV769N68$Q zQ3Ann)J)9&)TwLujUVDx*_7(tJG2a~n!mwJK1yvr+y+>04;E1o%snE0e%^UxHsax6EZvlU4 zs>=QZgAtzY9`@|I^hx}Y0na3~6MDG@d|_3a&OogQDcA?;en1YCB?W`XKXQ{R(yX0d zyZ`u3QZ&vqA>?I2qpJO)!grit0ED8fEK1z^#Ly@`q^1*h&sY1z*MHV|?i2Z{j+hyg zd-OC$ID_8HdLmB`pIis%{0*UryPIhrzYVRdT-11sF+q0`P6e# z1XMn)P1LwKkf2};S1_cc3GQ{f0|2t_fO(QE0TM%lJH~2pem2TktB#$aPrkC#;y~F7~X+O@TMkOU3HER{e`BKR}hg4A5 zKT`g1d^iae(?8$8KO9Uz!jpexHw?1xj-T|&)KeWhmS?mEoI|yAKXwqOr3;$TZ%9h> zcSV_~0&ri2`=qe48QpFc%~MUN^GVE)DV6MYlv?z(qVIk=8zdwpiQc9{MtO{G?P}kA z;uIqSZMm$*lAh0>&6~8huGIizNY9ob=-ObBeq;@r`KbMRW@rVTy7Vkom!m)=W@Qo2 zwYc6VJOgh?tXe(z^iR;!oc5osORP&$Kp-j-u%Qsla43UjsQ1GG_@W-t+QX_~MBZdU z4+$;F|8|rQ|=@M)~m< zts&(W+TfO%&US$Ajqr555){jp|NQOm!q+-Loo-DcJ7MjVwYk&yxvSVhs%8%g0X86+ z!SP^sw%$eaReosXswEU`NB}^K_uxPRg`{-Nd9e<#i&#JKi}Z*qK#dG`7Xjc8Qh3Ub zPW~pKE#BrY^=;nzqZ49USFdD&gWrba6vhpzUI4H~&B&;=e6buoVe?D; zxHr(0t8?94w{CjQG)PIZM32qvj2RutD}WM9Pb|Fo;PEX0b!0#|S#8VIlU0m4^8vD* zs1RccZ+mejf6Sc$x*KC7bi{vt`N?@hQR==_RY9X?h+CVwvL8bln!lZ@8Eeee3z^If zcyE9&wy8^IUE};g$pzIEn-;rMt39^gG^=&afk+<;ZdP(#g0p~(Etpb897bUJ{Q*sW z1uzn|{lH!<^WNEDEP|Z^0_t({q(neanXQ9E$W;+GUO@*mPV5r4t7jX4tT#f}i?)do zg?a$2@OSn(E(faJ^!q0R6Dvu_B#!IE?i6p&@Szs6W?}3h$x(8$Rek;akZjW9xe@CR zv?UKb*VoSAPow%{|?Z&n$3|5n>0`4k=cE1+PGVpJR~8h`oF2?Adj= z65y4&hohgEMgWBPqif%RYy^P0q~HYMz$+I4k+{lO`Q%$JKMvF(v;QkcG*MmQXyai& zUVhc5di#03?W2eq+$ket5;eXkxNFx6^ru@wQ3Ec+?&h1F2_3o)K?9ShbKBFT6)hrY zL@U@c6>VZQ0|0*sO0f2MvuxRt(Z(JVPz?RErlE zwWnMK2e@&dqRrNsDv*-G%c-O`uUfx;J>?9iX10>HK+`h)li1rgm>t$Kyynx4IfQWC z3D^%(HU~dM)-&FclEPiV&869wA*g|ri@Dkkv z8}#e`uDH_$^wV!pX}69&vXBLQWh4g0;04ZwaD(8}DJdz)%MqIExFclpcn1+>v$L_V zOgHuKto^AUBIsU__-R#EH-{)xrx@?Bq*q|A0;-TiTzgLThxO8I?d<*mmd6e}IvGC- z7!a06b=7Qse%YMn&(i+ufKi;V@rLRaZ=y-3Z~g(ei{ z3<#9f+h`U*^@q}mn1tma5QNrH86p8Rr}@Ywj}r+Y`DnPO3EdUUDk3yIjT;~1bsL3N z3F^twRlR$6{;)h&bryptojod+1pPIPj61c3j&>e=kE{Bz&E`X6TEbMIM(Sh7lNfA5 zhYrMQ@^uIrg|8acl8srvUelL~)8Ei}e7oI>RcBd8b|c#un7F^Irf4vOAIebyx$V)c z9!+KZA;tnB+7Muf&OJA9?0#8d71~ibil(1Abj{ke?~qn`ge%_X4!Vc*kl1Bk0pa*> zkcT3U5&ckr#N0EKU8_&HI2uq$?^cljqWU(Qfo2*&a5;0~%snxWSb=5lvfO)X)7Gs= zhj-Yowv-k?9I-}l%f*6QWgF+ZK(lEuutSj10glVqMtq?(TS8j83eQ;Mw;|FS-r-jQ zPFjY@O%l^omWBF(*r}LvhxyXpG;N5HzoZ#fdfqU4y#qJVe*C=42TlM8$44w>Jvk;Y zmRnJjHhG5P&!YO*#FRBGkxUYxOYf!o@l1NhUSuJoIA_Ky-pvI?rTpmUXS&y%W7=`& z!OeurrEAg=5Clb~OOr)@X^Wi>FHRAt;n+O7kU9<7GZS@ahr!+I%16JH? z`Qtt8!7=@cJqkx@8YyBW>=rV^*=P4a#kg2(bs?Qkr zPA`2$x5RKq0t7l%DQ}ZP!JV%vy1F`X%)$tB+s8L|QTJGu z76&;X+{-M%r@>vPerLrKh+^SD*E!((KI~JcG`vs!TD{6&c-517jzX7&9K&N`I>Q%w z@H~imxI#wr=C^shMS3(>Zl{E=v2&!>zc@KH5x8WDAgr#tj8sX%48=zia35C zG;a0KG^5G#-$8}?6|_GQWn=bL1lYjft1Gh~f{e&Ow}Vo+D4ixjd)MxzmAaN&VH>aw zL)!-+%D#b7XFqUJcvcG9MU&^}(?U(xWYo8DezssEhZ*mGhglO@vcMh%*xO+*sOEOp zJHUAK3qwNTOaY8QE6eZikz9}Xrss&4Bfp-6(UVx13m253bN@OxxEfAN6LWLrOoO1s zU9Da_fUL{U*6)i)_6O=}^2y)ge<64{Y52G~7~&Glws$@Gk4#O27QF>G93lAp>jU#i zQ2~cz&RKpE{!!*J5@!_(4$LP-vuw z&jLM)4xXg@3RCz^h?9{VtlTXexL^*M7YlbZiokZ2T&14xqodCHT$s{Ps$zDp15D_I zcxHNtxJOXwa}kKFnk)Ck1b88qph=^hQ8vMB*<(QRU;EDhIM_VTg(6$I%(n+j7Od>5 z&X+Hb0RO@*w~AHN;uhQt$hO>qC@3|QRs{A$Yw!ke$<)C%u!=1x2fxbrrdg-z-zl{?ar%N0eS=6%=De?D#A z=-a~^C;I3QZbywf12qV{z&DP-yr*F7*p*Eb{s3M`6o}(#P_w~>}xq*QBQ(>s-cC+v9bCGM=5U9tl#AQCTQ=|l`pKIZBq@n{l^6C)^ zBO-6#2#f=r5aB>jgCM$?AC=Adf7STbpuNfPkg`g@C0uiR;I`R<&CK%WBC&3Y`7V09 z&4W!MY91gCj_#tsm|3BzBPy4N!M@8r+3VMe0hru~`r$2b$GdOHQ)B$VbIRPCV-7 zqPS2Cxjx6J964fzo{^Ym5ZObhc;xSF#&fMCc_Wb5lTa2gWmNo!wtLaiw~$x|rGnLR87^;ru;zS|xHpyv%u zTki}M&IrL@i7bXAxY)+w2qpTBm6og1DX6#w5ft#^;fVGo%Hlc0dPS%}0lM>Z8wzE4 zE^9>FWxJKRN9BqCzzU3uvUG}KW66W=t&vM{wsuH@;H zr%(C6s2#jIZ_?^2I97rcB5<CoG7YZSYC)y+6 zRdgsxo+Dor*)B|=B#4crzP=vk)^%hHppnu?Ru(8V5=oB%OS_?X+r-Sw>$GJQ^c4wq zxl{Jan}k)OW8D!79NBf(raAQCLlM|p!XX3a*|~E$pxg?0R|;SQC5o@7b*U}Q&5ba= zm;JIf%Q$y0b5E9gN|n0}ZVn8}*ip&P#~0aNUvo|F_|Y%I@dTIPrfF{ci_j6F89hDy zYHH`d>2pyLgoDRD&qRIYJ-ZoN@pxwoO*VSVz5Ui%Y7dQZal8A-8y*s*kBl;Vs0z%~stayQ_g}A!bB#dv`B{Zqmwk@$ZNRGOrD;?% zHz-0e!t1dz&Ha1ky=_&Uou(t}Z_V8(%&F*L?f!^8`S_kf`I}ObAM@gL+rJQV6j43C~ADKQ;6;spxk@QY) zu5^j)uQO8%aQg`nULPO{A+$jWzQetA9(~aDp}W?oYhsprSbk}sD=LvMQ27-zgZuXM ztDtLHy`Fz7ocLk4NZD!WPmN5;gkjIPZ>HR zlE+w~orV)qz1@sX@A>&t`m+)Xn4=H?@EZHha^S*R0~AJ%pkSc^T0u;xKtskc%?gtS zR$|3L5IXNi3Jx4NQK94n!0E#|+OMLesP|}kMh=`LJ~!eau6aM)ihX!N)hpxCAF&u& zVJvbj?*D-oZve0pMI1Y9F)CNtg;_mZKY}CRXkm;N>kdAHr9rBH`yg~ zBuB3cz3Wri?Iq+iYj0;GbTD*0hr9QwtSK#ZxCkc2>CprA$eoyf7Er2j|tj-CBA>Ba0hQ z2Y_bIZ}ZRr9z+IRU?0B52@0hz6tK(C_uWL3`xU~+&Gy1vhDo|D$0B7toQJ!@5a4*i_Im(I4vnY!N~F*4t6?GP24+Rf zC&6%{<52}mxh4hHNMyT5O=(2pHi=>+^A1R#kFY*e7bGyOBE4q=5}P)$v#WQzXV_Lp zarV_rea2%Z>vf`BL%HID)&y87a`Bff{Q7$wBhZ1I``~Yafqgo9j6#p}4fSrcfT4Y` zK>KCyl&VmKtM`f7)i4{3;tP6w^hvqAy|15(015ri=@Q8Ks(K1XIz>iMPM|jvJtYap zw(3Hb)RDapaD&G%H~Y)vUL3R)RzxAeF6+iiG+nqBM&wd-o3pKLm5H8&lwCMtkX_m8 zA;+yhHz_48ecWAMR-ZL6UO->zn%0zqMb^RLVjX;%BV6rzOdN|xTLMM__H`6FZo&8F zt5$w!Ohf5{2?Jb#(5RxUOh+q3B-QYfTNMuIoPALpWGCEn=1|wAqz1*gY)CWwHw*$| z!x%UFhty6uJ*_qs7;$Z!UX%H?l09S-8s*z#UVEU3L%XsxxU^y2x=Qe{69@Nap4UwU zrI8MG5Kcwjz1_x9q78pgTD?Y1Ep-`%`xyd@NhBK9i7c%@`Z%i}a&niF>@jgYPm!PM@CtjKq(h$Z&GAoH<7yz7p zo{=DN>0-T9q5)20^=t{7t)OdLme6bS>eN)}bT zRMWx0$lU1EqG)*l421C`3yokPQUbX3_jskH;F1H{yBug;MaR^XJG|!V_jP`HWr!g3x(E+3(-+_SvjS%41w-fq8u19cZ4{1~>^5>%6ZzD# z3SBjB12V+{H0=Em_o1a?U^9?3plO3ZAjOl;4^nxp1LaQ@>#(+1^3@`nDYd|%t}+nvQ{T4ASuD9-iYcO z7eFQ0kFeoCX=h@>%wxJOG)FtEU;NPfMphBktM2TuK#Gos7ncr4(x->VPSz#MM!R>P zLqr>yRn$2l0C@yd1?mmdy_Tgn5dKmfr3M6hBP(klZn0{&d0oL1FJ(}N&n(&CGsR5F ziPC-4#lNAHYmiBDTS(S$kMGh!EVJvFKmE7#KhsGZ9G5S1*3Bz4hz|u~b%K5j#6KqU zE{u5OewNKx22bnP?$ghYboY3u#?{`KKb`Oc0dd63OTqM!hMMHMZ2hs~bzZbxZTB%eQ14jl=(C>)TmdQI1?G_JTbZ#Ytrvt{?(_E^OF82m2T-X{-YC%ht+Z`IER&rcpf^P9CeM|MqYyungiP$H zP;SM$U9xW)(M}z(bIR*E=i3hj}EJtZ|KX&0H5 z1#%-=nu7xYWJ%1&(M`E!tMOpjv&oM+AY2{X4NY7i=_JbOc=tyet@GOBtOb4QQsco* z?gBM}R~YM&4A482>i{c@kkMB?kxqE>XO+NlIL2-J^`>&;q>4knROqx)?yB_C^Hs}g-6&Ar&O z!6+nuttIr8vL8{ww-$sI2xuBY;t$>8&D2zG0_32?-gV%Bd0YYE^Dw~zaN{P$`JXF@ zc>jY;R*g}4d(7{LBbBr)PoGW{!~_d^9Q_9d*~du1Z>su@!2t6Q3z7E^Eujjxd5=Du z6eTm0vawl#kxWbF*_+d~|0y#d`2;vnBWduByG{=uLx)+N5WARrJb%0F zFTCCyy)^&OPW3SqkCf-&2GosTJ7SrDaIivsI!is<@pu^+{7pXdC?9D6`TboXqGa(I z)fI0$b5yw>BT0|}#e|5TO0dSRn5NlD)l^r1O=eX=g-?b$v5elMDujJXF^doAZyivw zmOE=`9rpd8Hz;h@pjA4`6}Oc1qewJeY^=6kIF~l;=pFd5s&V-?{q_Lh|sa zYvjicD?Z0w{@5@QK*B138Bs|gkLgJar~sq5K37+-!J;80p5ojK88-uoCc$kzolBsHa0p*oQ1XbklXYP z+uh$4>vM5Q<7x>EqS4;~k>|)_03cI0)ITFG5bO;$1=@{ctA2*hPVsRFrX{J zFtP_8m!6>>x?_7SunRK5^9VZ7&lj|KE(WPaBaB*zE=z}k6M=cnPRCmSUy9Pj1!-pb zYi4d9HA}xA;7TprRgzl*HMd|r7=IGp>fzkYGiyW2I@r+CGcpP=XMpg$`1*yRu?Y#c zU}^q_oB&ewDc*~|m3uW`km;>QiP&eOhQr*fuhw|%LEPJGyl@p4nM~VNM|^f=(REOtcdn@^$;a}EVtJA@T%0M6X-YRR?1^N| zpdGiyVS!kjNMRdTZ88A0A>xtDC7a6HRhV|~+{c|+FCMk#BrUtu=^42B%<3`I&kmck zmh`0ALxY0!AJ9#&81B!rmey$9jY^Zh64bIrzt*BLdQx1Xj0EKj{emGe4;Wt4k#s!} z^Ca|_WU>PaJP-eObN_=SJEY{`>a_;9K8W+>?xaMFw%mspK^ynU4O#E-+F%1AL0FC} z60tT(C=rmVwB?=ERYn5|Q`)Gy9zzKNMmk(Rev-_HyPsbcB`ay~{LW%PkOX*5ZL7Ww zWy)1S;|J`Tu|j;$tM!zWmIHV@h2l-meoX%W9h;DmdcPJqm}!;&ft{z(LF}%?E(O_Z@2wj%WV=;bJ5DqvK)WY#@_hWH3B2>3>H%Fp9n(lGf+M;RT@WNfn zW>@0f_o*1Iq<;EjcK*p~OOb9`y-MH^k-0s`;tl$7UcF>-{MRp4J-ypGG|uY)#EHI_ z46lQWG7vAA2l08RIbyxDdx$gwNFbn_-sLOS=;e=KE3ZWXkoZJ@ec$DZjjRz{GjMjS zW~D3txBe${z28^8!cCXE;u`|f-dFA8#gR#Q4)&0}@6B5*p#B#!l8A6ZWQz86@;nbYZ5}CsREUypqJ?vspMy9en$Ira4o?DBKIhm zTPu_ah1z0nX)mUTlDdP1l@4P@2q>L=@CqxCE8CJDHv_j6=@Q6u-<>g zJxA#P-gQes!A{L2m+i>bbeuXgTzxmn%N1cW9!Cf%A#!0Fgsef@ z9tS2Oh-}J!^WZ>G0pFFWqw5BA^feZv090uF1t+Sy9t@F#K%a@TfY&1a(G`PUkzgQ{&A>syenL+@?s3N)!qkNID zVE0$Y_Oew_pw(^0Pf$Yt3V`IDK>YmHE& zOn6=Y7vcU-gZcnK6ubASjm6i;voZ4Kw%qDUD%DATrKCL8b72Iw(=~WJ)=*8&&1ryO z;d2ko(OG^6VPLV-Gg=cIpj1BBPXPv_+_?0T0IC zNW8;e^P5wwZ0xB*s;}pk%-<>dZb0`JUz8zzFA2zWmiO!gC172Q%H}}LoclG{FAM`3 z06!q;5;;%wUm1&H9%x~#w|7m+UVLG4HF8H6&ISOa5HiX+q>!}{V)5oNN`a;M9Y!`b zHbReqK3%b0!TT0?q#ZIc?2vah4qw>^yW@%5dkxUW(%ZPp=CdH!k6rmc_=Q|qsFiY4b0#hC0Sh`Juou5xjJQS1?0dza_f8jYIfb5!!6xU$dI{RSBga!A=!#~Y z!)VC}BB&Uh<>lueww-8BK+6->+Qg3$7cZZyZtaRyJpq)TH8f55Ui9@xRJ%Kqzklzp zgl!TzfErWdf=qWZ($m-GwIqs?!xnqY1TqI`e8W)dLRfetLn#>740)1u$hEPqww8=Sbqf!qBGU_xge6q6-~R!^A$wm~ zjo|X~XL>KlaJe)NK2Y?JtEu>+oM;D*@7T5QGFwwi>jqjwG*Cqf#<%yo0g)BR{2A(2)BSfyfix!=?6o$?L z_sAM5$LHeATp>UoFJHd=2_5=3AgxHfl>?5-clj`iCQ2gZZi(#GT8;Ptbl1s_9JD{W{*FPTuQ+du1^XbaXi#)^GFarp)N*Xe%upo%MU|*{ZRs z$w+eC9IjpxyENuQNQ~F zO41=Y_4RHq9qeTU0$51WK~bZmxOn8gd}2zk{J}&~T^Q34c^7*}kd+Q)BZ-{zcO{Zg zj7nj7e@n0uzaK(_U6tf4mHSep%$OxnWxHCSGLc)LAn~B20@(kJq1CmuM)OyH;S}^2 z$3hQ4gT1^{%w}*?DP5Ux9|RRp@s0m3fX2_o0sR z7cVt?obw?dO6w(FC(3lCOeQKe0)w(KB&Er3BXy!XZ-F9S%D45SaUR1$>=_3uxU7@Z2RzsjgV z-_PpnKN5l56^Z&bfohosX~4&cbe~M6o*039d#{Z#H4`7rUmQ4qf674bPjGz(n;s=t zuk-tLcNzLdi&oc6jKEU;v{q;Iihba9vv(eg^Im|aKBGIoXMCT5wzh3XV!R^SxrKhbWTIy^(?7!a=&_QV7{@DL-YDq@dju$l|x2_rj!zfl|Uq+8r zOCZJ_-M#rA9J;pLUtE)w4muX|U*ZBxH!I!Ox3bzfXsePWYh0GSTW!vrTaVzs0Eur6 zCg(_pA6kNJa2>|SkatpM60{_dCqQ}#!H;MWK&iH#PKLCjqP|`S^7rcGz6OwckTC76 z+%D^eD=+jUz*`0zAOm4}k|KTc(Fl`|uB72t8F_2@^bQSa4BzH6`pV4Cp7R8iL}2s7 zLqS*MEYYw008UVX4@UHRXW^= z&UO$CxatX80Fj!#{rxq`k^P9TyM~C)C~F^YZ+a&8Vv_HSrUhkj${)yJNUYN8?KcZM z1NjBo<8T5KgS{|Ka^aM{eIRZ>Ya*uhEPIxbajrKl#MhxUV9Z*2SJS|6R6KSDhl32Z zJ{IfKPd&cv;AJDU>Z%Lc$0kfeT65a%u)?BnA7q@nxN~4Svsqwk8$z>*mW|Q&ZHzs7 zbTnSk)^M1uyZWe;xj$j;VO$i|1#ZrMm7(0I4}Nu{VP5t zVt6-_oCU%z|Em?YVCXr(_X-(QsyS^=DT`h+KY4}@I(|x_fV~ov+)_qCahs}IE{1YtDYqmBEi_ z5m}(ck}0XDsv7t$paVxcN!o-)&hZB(V(+v}T{iY&3B7=RhASFH$7j8y&&H3>5bx+g z7;ZBb1gR09`1Hz%-Omh%a>@-8_KiY z4^2%>NaQg*^GZv8i(Xb~xWhgN0W74eYsx=^sehXBq9V$w%^6*W`j09y({+E>qNl<* z@|~9`oM88smc}r6os9PS>4A0IE50@n3K{fRM}l9$@OZ){OU8z})@>93m0fM`LCxJc z0Di#XN|Rp>%G~uZ4sR7(RfpjAIALE&``SYQ(imtlqoIz2knw6j&Y!2?JtKx2f4c$^ z8#?NABy>wkZUgK_S$8G&<^HUBb27u06p6a3{H+5=N`>gcgMxS}Sp*G^^lQZ+4mAL~ zXf+khXBs9?Gupm$PlM=<62^AH%}orFWCn?-2*Fx$4u8P(2FZ}(B2&h;K9FM5aOV;oxKCj(mmnT!&VzZd(E!N$F4E9IyF< zo>~_O?Fh6~H=G+oK#XY~qaFHU{0O#!46e~>+pliKe5<=!JkC!6lJ$m4RTU$%h#<_y zwp1O~$)1`W0Mo z@#foQyP)bVMkGKbb+ZK8KkpEJMFP>_&{&*af`hA~rzdr)M-(EaE&N)IGP=q{`d85t zvjM5ZIzRlfD8w-+4ZBEQ?9Kpl3^XP*l9j~?l`@@215UFT!gCm=u5&@=;7pmZ6Ha^>h zqGSz~l;*%Z;lpTX$Ym$i*&J`N= zatoN>{)N7K(vV+aaLqa4QI3&NEvP`|7r0A1+gab&bqwItL5(9A9`Y!0zd%3{-gdC_ zuc(9s^-q2|IN?Zi?dYsn%i)qS20uKdn&j##f!_+iT!J6+*#aL4Wl7Z_JdC{_%v^`f z=zf5408u1(J5ucA$&(cc=%&LCxVjHDtBCO*Jh+e%5FL1 z@9F7zTFM^Bk-97L5y{%wK0W!(U*kJYHImVQYTBjeqlPqJ3Ftv4Dh3WQLZGI#H>m~f5Gye`dmMMBv$CE{&LhYkUyE6(!_($ zm8omh3;uuzg@vZEL&nCejum0K9$)SWyNUf;Zgr?@01<$`1{DEijoDZ7;8_rm2)_;G zA{q8c=>Q@_1PWe@K8V90Nj#C^QV4%c@z`ouLp+FE2bR6YvnK`{uPvKT0qyS%cmom{ zi?_k9e$XYRCkL|wbkEgB9e4QZJ25pC^Q!R%@*ELyfp27<1Z;X<~Kg2qN4qpUw`9f$Kn#c5T@)dvDcIYIT*i^*P2Kn!_ z{W^x|2w;IFOy~9VHbU~V`-19(M87P*@_FEw1{UZrZR>AvJi+yqPA(W%+ybxha_s8t zpu?xgXg=9U%|RiiTz1#kZT<9$e`VA$75^~{0{TJX z0S(;Q{r5fu9MVWJW?~lb0|@DK@UDX5eQQ5hj=&`IvZL17eI|Ywhb^?*K#ef>8LUfT zU)l`>UPkR-UyG4B^W8T}vkv9WI$2@}8_(Ih$05Cf;@tp;mI8@?C+=f*hqab|VP4@H zJxFjQDWnt=nAsAaoTAo3{7NJjp%}Ba!(}5S2!{UVE+4E-s7_XNPFQ8ZcfS%I6W&T3 zt!()8v9cMyM-hwwIF5k^<|*^genJ_z{x4r36q1&xi`6 z+0o2!hNT^iS@jhq)87+KsT7D7Kyb^a+W>zNvqES1k}edBl*(E>#W<-5{J%Bvorj;w zgDZY7J7!`F|4A=K!uOu$wmYwmrztV~HC7_JmK_yZlvF(Eoo^_z;yu=8rC?kqk?o+@ ziodahgH;c>FN zW`P|x?;HhL_P(1z=D>li=v-qx)+*a!00SV1HPnS?S0pl%+_28{Ay^H&AbA9~*_(-` zixKvuI-C10WlL1IV1KZ|7?z-0S8pE*Rw~Jk`g7M5G#C=Ha1+FNYzqc>7PVh^58%4_ zg$0eRTTlq>KtLj9;P@Bd22N1$krOPO zj$&K?&J#&-Hi)~Rbl@Y^l%`qZfX9wL63hjq$=B)ASBVcGI7z{$baY@V#6HdT`sh3S z;A#Cx8=8C~^lQ6E%WG_bsM5^fSPWqO+x0;-yk~Ys6IcDNOYG*4t*!|#)hY4;qqn$i zKNzsOAyu&o9f?K(R@)J1QEcmP4Kd+ghG_jd^O?cF3wVuZxsK*Z5tGM$MQKkoGbLtv z%(JeL_4TES3<57aJEiH<@4OZ^Ek$&~*1*Gi2UHLnEa5O!fR$Y_8xFD{1J8`n?i~On zj=lf+vnuYf`s=e<2;_p8qj24Z_fzWf43w5GkhrReK~A&+?Brtmn|;c}DpV2F1x;NF z^I;;WMgg=r^bg`b?99JP!iNKMxpJJ1FQeVFL$a5C>tfIc=8h4_`!jo1ZAHbkqDI~N z1{tJ>0n_PPW_$`DJ)p3fz;1OAsl5iDuulT<+kcm z`8Z)yf3lb_dMm398G(ZI>MHl;rXxYSWZ+d4jdLrU0Tp2sj3&T%i99`3EvJ|({Qy(e zTzvoWZ~t=Qr)W0n^iyaH{axWnL=YO0*Ufeyz?cYI1uqh^%zbd*X<}i;b@C=34rAj5w2m*~hpZPu2Gjyx;dcxwmg3P;J{P`EYwtB;A z^p8a+LKP54(>(8LWW^xFx%1O13pv&EY zzwn1@i4u0$2^=qQSN<#1tgfyu?7E35nL$%ykBmhunHhb!QORWR>WCz6&32OXPs0w0ib%oW4``~#cXB2I zYXy0!9k(+Pnrfn#hEXYYzC+j-Guwrp;;njt`MC3_gh~jJ{zheXrC$3W^)Wjqm zT0cJp{sw63_!=Cs`!Ql=Q>fwnHY8%^^{Htj(~_KPJ(qMd=t zlb)u)tiZ5xCF8|IMR2>KwW6pueAO$Pj8WO5rKtZS8)vupnUBJz)D4V`%^^KSc*ca( z-%+WPD8T>@ishgxz%P;`R3TGr7Dl?Y{riol*aOpnG7zaw_4sa`X06^4SJgIHdzhj2gEvw#}QBt}5&U`Who* zZhU_n0?tsVN&=Z*U|a&sMyI8^v!Nslu=v^zYN@((;TXcl#Z-?sB{OeDL}+0;CQ?e2legLcI~_Ji7&lE*h^>T5rB1#s06GB;D^D9sk#4GHtP96dEGY5 ze?i0e;ZB4Fdgf~wHF3Lt_~C;GKd}eSv@N9g`}$5rKzNB_8N3>5qdgZ?wG45Us{)E@ z$~D~ms$<_zJX5lHT>M;ulMdDJ@bcc6I&h};OLs1pC#HN%<*)l(#KOT51o$t~8bXgV zru~I8lgGR9i98Cg?fiN5LO6noz7pWB+#Vicigs4!MfgcT3wO@n0=n2D_1|@H7G=c*$8&?#hSe%y^aQ3R91HO+p4NnKq=!#6GmGEQeAP& z;$jtcY-)n)2f}Ly4Yn_0n1i|p`twNZ-6*MN{kwqG5pi*|jl_2{G#z_J8J9tUbEia; zN)DFz8|*5(>N-fCKsE7*#C^c$?ux+%t@e)4H#t3_3;`oEAL|Eaw`0=811c z%FyobM7qb_ZN9{f0{jcVH&*=qZ-x#s6%^>BMo-WN(#m`P>U5B>=MQZz=z~g_$SrdJ zxZw7xZuc^91fW_X*#pp@hyl^+sP#Ws6v34b6j2SGm^emAqWl(+D>Fc|^mjZQ;xF*l z)Gl6pYHb5}`fh7v)Y$iZk~kg=#?8?jV=6)rUQ;zy0b}z@X3}Bs>D{@52U>vLmt40h zc*{U5u)F#>V#YqA&c6YOv%&;0m@sCg6cz|Jkf}0(XqJ!e=iic#bp$VKqLl@HE=ECw zpdfZSXb;gg>Bi>Hy1;LV zp(+cD6$w+|cliOY2PIy6Tf!+P1TTVE{+k&@Qud0rPojCoOu++~0ZVTK`~OYsxYGyu zTQ(qOO9{(V{L&ALca@cb`_F;?MJXVZH-q8s=}}+CLdIdfw7_lL!%l<^3j|=J-uNGC zyS!K+&dl~c6Y*|}+>-H{;6>*p#Yuy3O9g0^Mgc~{DM8UgQrN?&n*m&0ClEL&TOwu! z@@8Cx2fQV;1QP(r%|ByZkDfKE^b{X2?>%&vW^BuRO=LO&dZjQ6xeqp8D@vFJ5ere% zb>1y$xDAx>G~TDYPP|ASyHL&n?0>vv!Rklx7;E8H9a1uDe0EBh$>JIG0F)mEpP;McRa6HSQ2_*@ z2?s#)8;7$Lg!zbxZ3MWE@d4tr^5Ut$n*g?)W{d_(VA*~ zw9pE}VG3|equrd249CVTy$ZXlkj>k&{3;h2uZ?bM11k6GU`d4hX$(JJMc3o=n~Uh0 zs-L5rA)&nB9(GobhjL{azJR)y8UO-9Da=Zd4}sy^7%{GK;^iKa{L(nL)bXNWMyO_LiPjT+`z~D?Z!7)g)i?B% z^8J|wgX!6Zv;&SE30AZ?%wWO7#&THS#6-U_^MPNCK(jv26n$XR;w6`z-o;^?I z=HV44F~)tRcQe9$z>Fa3t*_SXH~RcM^Jk9~7N!i7Ht;JV2n*jh1ARMk!S20gu7$iQ z4+UYKNkKZ6h(pVTCSb(txa5rRBi?&h0#=$HY7B42|r*eMhXNyR@PC7gb@Mc2eG z>I2%Rk=*RN1^}o`N6LS9U$I|e?WHy}=t97rYdV6{AO}L0J8~XQWi&_u%|y(K#IAg6 zI)1{7un^Ukx~||TzcaFB9}bg;DB(W$K4+Xv(Bj9@-S!|m1)>5dFp8V;PbRk^*tmPN zx>LCN`>Ba%6;HjYp~wR+N0#^V^yyzVVb7zrUlTaf+S!?LF0` z#<+gHF*ZvP<<i69b?s`e zC#XuX4Ygt3Yd3d!l?i+*sp=&L6?c12Y6EwzP5-letnAMtNVc65I2i9BrY*5;Lqb$k zI*!sLsU}w)Oz_A>S&`tQi#t8YzAx}*6@J)s{edw7I7$AGz4r{NYTLR+mw~Nf+HS=F zh#3SVD3X(zBp_Kbih$${l2Ny!BA_53*+7nxGpHyz$dVkDoRPGUeB1P#{e9=$vv1Y= z@#jbbrN=TZtO!KzC{Iz^}q zGy%_5Mn6@{2{zzBZge}JE_6d#DN*uFoZ*t1nsK+Ap(rEKHjNOltsGlHpZe#g5ycaO z))u;$tRbDK7@N<(8gzzeVluPG08af1T)CAAa=MkdrRFF&DVn!OIIBNtj=|JkP#X*~ z*J6iw*>`ik;8Xrf3*gd>EMR5o3Yt8R;t{doixT`OChiF?=N9GsH7I#9LgA5b3;w zwh&$@6vv$S`MrJ>x1iw^(C*%f3Zz^6u>`3n#gKw0hM|^1t&tc|20Zl?pkhC49WQjm z6Li_YQ+uSkxjEsyTKSC#cssQP4qn4zfzY9!(7t(Em z=+N1kB5Fzy*11I-ZUuV_y8mEcm>ANuYfCE@hi&80gaUTaD#A%(lqc_{{r9!i z$+ha$BJjiqP=}ZrD~j${RUk!zQJ7+C7m6UE-NNVK(t_KM51aO`Fo>VQRxnJ&Ot!ky zX!~L2JYB(bMMvk=Wy{XaPGX?Rb<4>~*sawFKEPToxVBpe7(eEKFAHynTT8*%ok#Rb zq1I|(Qq7v3`l;sT%R;RWSEQ~y!dAK>F8)Z>fdZ{e_tcQ?;^a-Qq5#p=tiB9j>aQ5~ z5K17D1TBRKLHkTgpw%O^l#^=X#{G4|^P#CaAJ+FG&ROur z6F#7e4j5Mew%As~{BH@(RCDbZm2&z1V4qcuIV6=kDz=l{#de{Zg7kivaCC_~yZ|@_ z1R6D46H&w1vPC(DUCM8f#J1u0MTg|pTKqh(@ghT`fgxCpjNBw_SRp}~C$Xd(J; z9CdK}k!N<%`JQqd=b{>Piea*4k{rny5t`?3+~W4;XJtcp*qZN}pe%+Hr&bTsNWPrZ z$oa9M-Nw@LG|cXpTD8J8YWLoro>L65?MRdAg44|1aT{GT(o$`P<)PWTdCqX-ECKdD1q9xYaDmt9 zFw~vVgr-avHoTP1yx@iqrA1eNdvvzlx*wB)F!cuz(VbmgsB@!50LYW9k$Y2l39R-R zI5~r>p?vkX(XQ_DWCR@1u0w~+r$kiq+^8~1Eu5!9ZVk*!VOLM}cyiDJ3uMNA>4Whq z1={ce5Z(`VmJ{hs17#uOgZpX@ezG=4d%ZK56=d3xXInM4ADSPv4EZTxz_Tp8^6+l`#-fhs5x%qmYlQ%dX>)!i2ML3bRsumC{vKtRhwHsIK1ji})Vxk{tDS zMqawwXd*{n$XaUO?P4G|)lnFQnBoe8UShaQ)0_2hlqt0E3_x2iZwSqISYH8aTm3}k z3$^=N&Yuq+9N;MUagQhlCt9iK%l?jbFZ$4t(M}f3c<(xJz_8u`&4C{~ud(l)U9VG; z({5l^L9!g4*r*3!&y5Q8h4<@*v9U|B!d_S+I`qNa`x(tU$`xLx@`EtYZ;Fg8)`o-i zf`EYzvFU02FhIARc(f>HGcQ=4uG(2JZ&Uoas;UY#!9LQI)(+QT(N%A_&K81ctS@x3 zPhXtDX9dM9QyZ=8S|OY!g01YK^ms&VQ?MKd;EtZb`muX8lLYUarHv4Ji_l@0X(1CQ>X0m$4(aV428mj%E&wk>!p)#3Nx&3YisJyNxQeeL0jw&u6E2~! zmV-A=l6bbwEX^V}`4ql8J_xxuC{1EL5+W$S^XVA|AxyS^HTg`V>L- zV9Nlag{LquszSL6KFT*9 zwD7v!D3P#^baIG#3+(G-XeZQRl203VqNcosFJze*(g@;#=Fp+F_j3eh1@90KF5Te? zmr=t>MCQs7E|j3l?c<>0u^Sta6+lbbXcSMMgrt+`HJ+WFja=D_@bF}WmP0r|0+v00 zZYwEQ@OB^~!WG!$y{6W%ns~+^-^<<;h`Toxc{$^fXtyu zSa4wtmNgUTUqT+0Yb+T2;O6Frakj%yFyz5*Ba-)j@!}T6ybR67lF=tZXneyorrQ{{ zp?N0WUcYG(fua#A0#IZS5A^zL%FNE4D!>mA(j)nljKuN?E)%cubN%_%iv4R*p-ezP!-G}#DL_jx(Y7qUkBqaJ-(9(qv z@IkkTv2w$(2pGIBhtQ4~9e{KJdN%bl4}fM%ME7aq@%0l#f-n!zsLN$u(=!XqLjla# zYjk%J_eD8&GI1R!kVc#~{o}_qcol}?`yt;UF3ftH~@aZWar z?=|>HL-fnXAX#~k8;a zdQFSqP0;hj54~iMJ2*PVgRf^nO+C>Y7HMxNTZVAv1kfoRIg4r|_|f2CH0MW#D+b-hBW3X>MCL1&3QXsrj8G!u8+r8dlUQ^|Wl_&c1aAi^a2%)r6v7eQ5fNBpKNw`YR*KbtezHaHZ!nNj zzPHWkc+T)#zAypEj-b#i4mlQF;z?#^XoMv45LbMjLMTd1E5#fURVNkdP$UA3 zVb+bhiwdDwGHl|38Y>u6n~5qtbR8v5Kce6lxMjQ$^Q@9#Ku3wa9-*)tjt@dB)kGAN zsud*h6Nej~0)0t45|{RqJC|HBrTht!_UAdy#X}oD+iqU08Y+d1bp}wf!<{?V3&u-6Vo(weyfPvq zHW6O1xiP3rVjiAYsfB(YH+q#guedE>t2b~oqp)kpL0&JKkhVt`Q=ri58H$5{KtMD? zc|$-39v>Qd`a}Q-D7~zBd>(j+0nE;=E=>+D(%GRmVU^M4-`QyGcrcFt}CO6;? z($@w?M-xB*5swT(+cbqzJ7JDf>`2M%Ac|uT7NhZ}TCP z0|<2dg-hd*rhfA1(KEuT(y+YfEVk_{-{o1yg(sg0xK9I&#*u$l>^-{sRWqpQO2h5e zBSq6cIA}26;+uift+BL@$bwyXa8hYK>Af0X{CW~8CJU|1(#`%@Tv)(m$k>&iTyvbC zNJ6~H)jWqo=0CVzMK2K%ny>Dz5~ze#Mk1V|BWVB;p%AF3 zt3bG1P9cCwkhtCPS%U~* zaX7PCt7>Wv(B23k&|c}YRD&2KpA6Gw2%>qfIqGqx$5ErMJp}({aM zpGCpY2g8!<`i*W|4!W_wbvLEuBk{CQnA{RMelHf4vuenDBOo}%-cpE;vV_tZ5KsNY zK9noDpocPI$OCLp$8$W3L@4oNH2dM75-~<~#_SuRvHq%QL(D zz$JnW7y>Zi@j{29SD@452y)14!yYy@MI@6H;NJ->QlHh7S88W%{T02F8sNd4v#GAX z!CxYw>kk{%|BfCuGjvn{r8nsp8A+r)^z7a;;1R!_uRa*s6eYDUfBWs~6vPQ3bH_d5 zoV3ubq*f(yr^wH9+Nk0@#{G7d=&cBQB^LAiEnFHwqS$#3LO%u`H4cW!&eOpMHkW8_ zuM{W$c_J0kQ!JxCf2YC?25xw8P#!^G|Hm1Y{8hB-F&}4)Vc!}-c*1<6g0Y?33^hSS z_6+l4+PT?Jfm?Zvx{ndu{0@%Q!Wh7mMWC};=q&{W{KeW(@(-2OS+N+oSEy0G4#R0* ze!8`ba0ozztbBYe6RGF`l!9uR7U78!#$s7cn}0r{)!kTHymc)1&HjnIupS&E{5v&ER;j*rZ>63CLVfHae5jvZ7!lH zv;k(S_l4|yBE~L)WSeOCTukniSi`}XE^t9Pb6C7v7S1I+I`i)j#LI&`Jw1tJ4_33W zK2FFAI>{8cfb#C{?i>6s(60@fLLTAk*dHmtUc?RW*|XRIpy3e5Du`kAe83o?C z^Nwgagcq}@WyEUsbcQs%*Sf#^20y4>hz||nexD$0*vbJ729y^ubE0^9XxVa#4arZC zy*4%iYj2S+^_DrJ4gAiHLKW$tGY=&A=!q;^8~8Z*pS~f*RWa<~L=n|Xu%wwV^Z7Er zokjpvI8{n#=Q+=5+?p1JGU;bArl>Uvn-ClmM~pJkkvp@YSvB?M1Jp;|hShtL2abI2g16JIpevLo|l)y6Ol5}?#1-0$ri z+V6vUkjKmE!=6Ou4~`KT8Dtit5jpb-glQ}+E)E#`{%#Pu{00sH?l}-N{5Qox3LFNU zgttuZ^L?;20OfMv;O%W#d=jxKfMJ`GR|e*Z{>$hqZdCu~foAWOD_2<9*=67gb2NJ; z<-t25Dj~3RE875~z&V88t!xa_F>q#Wsk$DTn_i)x|3$oL%p0A-y-*Zo1a+=0K%H#}$iq{+d4OP_zOK0< zscZ-$3@wvwM=F-5ZUY1>p{oyCznW&hBmzVr*|}=2x)wG@#KW<$S%z@Xb`hV}e2C6H zIH1B7VYtdxW;zmydIz=pI+FX>V2r#%iMh3A3d(_u@bnIzNn^0y8c^f1-pUL;-V-1v z89B7})1y=HE`TbbNPr(uPpW~FI0?uP; z-iVmD0X#}bDds#hAkl(?tmC;k7RyeG2Ie0J$PLWR_Ny8R6656DCR9jDcnV~|MH;0D6 zumVJr@>5+!a1&sX!%H^xXPdSwqc*Zpdu>t0V?gc;*xVuLVVZ$*ln{-14E%B6Kpb3~ zBDj3zFag`duGK>8Y6QJ%h2!1Uz}0Z_1V(E+Tl@AC0+NL|HJBr-N@G5;%JB|V-ZZlK z-Tz>T<%+%<^ahTkJwvt>quQ|3RIXlqsu}TX;Ij{?YeaqzLW))P;SEMvbm9d*^a5vIN(-KwipmutR_c@rlP&LKHM+(@o}rZCM(^;*WetR zcN{pvi#%Eru<9)O-l;?1JUumKX(QPRUZ4SEF9^H}S6_tuC4JZ*)Ukwt1%_Gtc7Lad z2xBrda*LogmC(QmTdtRXv1?g)eo-OJ(5ei9q|lE!M05O~7nn&TpJ0!{WEK+Xqy?cA zO>aWy=D~~H*RSTOKf77$?t_E{cABR0<6)qM>@G(sc;#laWLHeQemWr|#19QTpzW3f z{%eFWN)l-)L4(>uF0;>(v6=01n&dAa_4pvd;C7;z5b%x2SU0w@q3P7>T#B0^9+V8X z#d~C)!P++#NnNg3V?4tm53>tCV$b2W(W$WkND109RiZc!k7y507&tT` z8`+yI@{x})#r_ph--}2A%+)(74QLsNdOAoO2$D4h(Ru=qg@b^BDLL{nSY#WFlO$qk zv_na)I;=K4;Z+05XE;#XwI1g!$@QsN7xeYYX!;NTno+|v^s^8@AH`E?28aPm$6kmn z&9hPr5B(B6(k5J6D`WQ(NE*U5C(8~vD`FapsOq(ER~f(*lctSK0KkObC-{(~PIY92U3+bad8)nDx5g?i1NdW##8NRkLxGhf!(KHBeD=R|! z!Wd~~!reE3G7Zs~@0P_;o2_I`xeaX z^QE8mU{66SU<6I_;(YO1(jO-zTTZY~h-^27SYE*S=Q~2Y2Hc-ehAcE0V>gJ1wQyko zX&aNX9)S9oxAo%X%UGbeuZ+!BP+iJ{H3Aiyf)I#*c32G0Mh@W_sJ|E(4#Ab(i_`*` zf+HQuCx^RL205Q35Zit0OdJ6P5ZYta#uTa4yc?idBrX?5DqZSz5z-?FT;jFeR+NZT z$Y}0o0#65OIZD6_WE#=~>IfqV05}*y^bOCKA^H1(gh{7%SI@Y8qq*qna!`JLeyi*{ zt&H2xF{#)zbXT=pr1&m47FjSJ2nm}2^k!k;;t?_LV7|5${sfeX?d*`;%An|)WxOTp z$sBC#IV5?85P^+!=4UsicoLoj`06&aS!l@-snq_^8r;K6ya&X@J!4EtH(GI9x2;+}zsZc{w?;0K!N} zhru`y^1ODvR}#o7fptp&%>dF{fq;&H4sYQ@Mn65?orfYbf=WS5%fiK_0Cbw_AXD57 zje+n&pC3Vt5L_h=Vg=_m&o<7WtAy**a-O;jpV%B1@p3M(c=@C93W5?V+6766K76r|@RKUO&-E5bO0gzi}V~2jbXZtzm=+2c$q` zvRW2KdwSl0L>p{lFhN>H3dv%0slA`(b7WyfItdX(*PY(&EBzd9sqz6okKxr|ke2J@ z@tom@Z*dTuHh>M>JSZxF2kzl`84C_k11A&nqf5_$qlfmk<~?cJu7HkLe^ne z3{HRmj|4mfI^NU5r2h~#jbK-3As#2{+xG1XbkPLx;z`hq$;;1AK-7$|ARUt&%(Azn zTDYA*e|`~1IL^MyL5%Qmh)EBbb{BQ_I8n_*F~yDfoOo*TFo9udvH8ee(Tchj5IYG4 zPS**L1UoxpTd0QNi16=H#NQ$TmH5(hbq|Z;Nx>9k&Jn;%V|@vWi>*ZLpA$?>tlZr2 z{+(%U+=A06#l8TO{1uy*DBB>`2>tge71UwAl#t}(zE%Egy)C=p78RA|v9;&u>Nv)< z0mC25SmsU9@L?8t7J}OYY7Rky!0bUHoBbqx8Rs@|OBWGzH^IKb)n#c+-WVvw!GKr% z%2g-y7H+QH^q#mi@n^`fm)jNsu(ckc>(fUi5OJI6$+z-;ZbF#qCn0oE(C75<@DQWC zq$fzSCY%hsDG$~P*{pFg9A+ZzSCFyL3pg%Mm7%hj33$8jwUhV;YHtvuHDQ7(1n>YT zk0ugKNDw&~C7}KO2-2Ne4*fKZDcaqYK_6QQD7w^Da2(jd7z<3;eNeiD3&3o{5~C>~ ztUbWVc-+M4A#_A)?M<_gCl4W#;xC#Q7%2TzMIyC4swf{lNCk^2bO!meG*5AYs{+~0 z3R{a@gq)gMFp^(=6BF!!639SR0OP_4#H(e-6R9OsR}mEU4PM1VjKJefD64scvp51b zw}{-%i_p+S=y(r2Jc3sfT@IjQjMpm6gE9RT7c>bc-8c1Y~+$x86L2-Oay&KJQ_%I8}Kdhfgsp}u11g5q13kr z2{;9S07Xn{#sR4`)Q`Q?MK5S~m7q-s`V{d~aG@rm#&Fj~L*b>dbb^`N&b86X9@VJO zY#RbL{<@JDFCy`pljvdr4O^bW43T?0Zf`$7)}4l)o-E)gz@aE&9va>t4y)oJdSej5 zlmPmVdou_J7eeSJk6CfepeA2{Q$vOVNygm#{Hn4tF$DOE@FzfbikQWYsWS1Xijm=U z-xeStE!~KSB3QVE56^>0-5`<#4gyf88UO- zBu37^0W!Y=?@Z(cTd9~aH1dm|tVkSIb`+4u?&sR6A5JKWS0*qI5(oV`wf{^(wsA1G z5KZdAm^%W=T_$i9>MGLfE+e)+L45GyVm!!tLfeSD2GcW#%Fscz*{ywzFhS`N<-x!- zNZb(#H|V=sJweS8sh!^5W7rE+R8-8++Cv#fYzIJqkC#k*&=YqXT!<8Q0m}%sAg^&0~IX3`zsMOj2(?1xG;z_9(sLtNsmPf^THsCWzb`Vo8cHjzO|j z$yDC^o#-tE*Q$k5U?PwLnDAd|XJuYuFhm85Qj!`s9@!9jLJ?WO`&@2!Fk(&>>D$)H z1xVa%fzUMz?#Mw&QCVL8g;)YSdGJO!jBzmR2qhHl)`-@LiinfILhw7sXvjB(2aTOes3IU zM&dNW*rrdq;Pzw))he<1kUGX=!ife^MeN_ID%K^2mckh%p*e9cN-%K)ZR>Yt;sF>T z-2^zPZP#5|xD5wJTK6$Tv&CfaJ2J`UM10of*M(D;%15G-6K#8<^e9Fd}@v;6b1ydtKLjm>k>^ahgz4bC=e_h>##?xy&`vYtPTkHG&vE8N1=vr^xg_W(xm;@)3rdT7ta9 z&@(~3jrf(ZI%bH&aWA~LCBhtV9Ied9!0zlN*qwiV(GS7#fVKC99|`LffNZ_NIHgd( zEb$+|x3U8mp#jy7XUCsB)8{8kWJ&C*sqyQkCb$ofFsI6z^U*~Op?&M=|9JZ`L_>jy z-TUdaIRMo#ahx4bPEen)`6QBs8<7ryCUX^+IM(tSH_^s)1i!eh>FiuU*s{<{Z(w$` zZWSR|aegj>oZ2VG^y}5c|6Th6M0ySfnZL*t34S8!<$d5Ech@%t9P03G6x%2I=RQ#V zN9Kv#+4W^s3G|zIP5g+icgy?#dMgAdQ=hp`g(4i$wz(;Uu8z%*}yj3 z>23ztC6<#QU-?<_tLs&;Ou(bjsAgOuTw64x$x4aW>uZD7k*>Ytyg)pQUtjOHVEB&| z%HD9Xh{B)+kG90(sP>xV6bFf9_kQ<( zKfBOR$RjrbuFz|zAiIyq`2+;Ke?7WYf-E*_&l-2pwzjma#|A}ZEVrNmvGT^4-|!S+ zjV*llQju1U#SP^7Fm_Acu67&tuLl$9A6pB5%J(=1jQ3rt_Xxtl-OY@>1h|VlUv)bkDG{_W zK{K06K*N<&bC^U`uAv)NMn!w_11$B zK>=zQ0SW(f(dGch0B%hwr0PDFKv++oBVwZ^H7!T>ta3AEA*ps81{B zLeyyzg#SS1O!A@BE zdff9{(*D2x?BD*iIQoyY*1!GmAK$!plOt{Wo1fzm@A?;m@Na*?bYUImzy08^Z@yhR zN&3eU{PmN+{tews_5QE_{$Bt#_1f zCh3?nmT+zpV_HW#cm5lcMSw42G5_U%|9Xo%;$S)mU+gWjfuytP|JEs{<`=-FP!nUc zA$M9Ho&?zmhQ;>W6^jf+#hp+{$-3EFT0Zyj@!5dl8!}j#9fL#Pu1>plQ-RUM zbVWtQ6IHhdJy?*UHhDDn7@FY({j>5vRll9Od14-=xNU@&Ra$mpno zX4A6u$Ooz z?}u(XTagiBFZgjGGb4i!{eb@S>(l9||9nrkgN6I!zWjj>N?r&9cnZ z$mdF>q&=I(aNZaP!T~EjEN|+Okp;@ zXe2j_Z8_RuT_G&)_m!|H#xVf1C&MInM8= zMb;MTMg!E%>N#AeJl~lTCu!w}hiC)%*^nQ9w=XzDe<%I+jDl6wS5j6sf-XBgG4ZM` z|HV@1zSyeLK2AhH**B3lnjBfSP$BF326ZVKID}hryVFi}y3BVjmK<7rHhcYV9yBL? zj)EqMbjccLav0*Y6U%fS$mQNfA=j?<_0KB)@p{z% z9GfVnv>BtnjA{EFtrQjQrM70@_`f^JI#?R_ZPwr3uOqZbyV^Bu8TT4s*qAL=w^mI_m{m0iCDp;Fx&O^>W&VO1l2(^5us|y9<@UHn3 zjTsjiuz`n35|_>^=8{uW|HiZ&R`_*`Ju?d#$iqA`l@Xe{R8|@Ro#>|(GzSRmp0qb{ z{*TWjk;*p`XZSvbdmp*^zNvTWHo9GSdx=6fmfQK=E%T?dh?0^LKaa@Yy!6(3;{MJ< zOHXgP2Jv*?oZ~^d?$J3TFjBkPq5b=uI`wx~y8G9arh)%@w1i~n$er!=rH_>VBQVA% zZnOV&abq31Ts^B`ECsYmAb>tP!SuH*&U3vexE^;GBO{}u6NiKyGkUo%(H&Fs!pfDX z24pOpFzij2UtyA0Q5dpQ<(FTmC;zDs<=}bT{KL1V$3Lkyki~o?+Pj~P@Jb4gzixM! ziF#fpsZbj*puy(A$NikLtVtf(6gg5XF&7fmHSuNKN-9#WOrlKV)Iq1meOB9zf_^R0 zpN&P@YAXhDc1aEIE>lw;nyCmW$A_M%$-5BD>1JVk>B4lLQPkSXYsKvIMqPTfq6`)N zzLJdM{#;RhdnITTHWgp{WIpLZ&J&AVp^IwbY<}6vVEAc|VYP|jYID?^$`47q9=9&W zXG|T4OO_lF`aRF9%s6@1(+G~5Vwp;2+78-X#X8s2*8a>eeUMQsIbyiAlU-1omR~d2 z=Hc0SR`~#Xi_uHVj!u!>QjwaIxRc{<219napULIDk%s%kxkQ+9RYMrZZL=j4R^g}E zxJ~@m7kwG0W~t6BRNWf&w)Q|Z_4C*!wV944*W=vdoXwUOnHh|e$7>3&&~h1A7;ijo zIKM<@stYM@RHs}q8?}E+dy! zMcPmLC;t@Q_u^|Sr8z35m@QMWtf^?=qTzT69&IG++HwD<))_*-p357xnP;=)oskm* zL#A}u5`x{ns}xc4mS*vY6%OW@FAKE0M61ZDnXt{^@vI>qD+81YhlNo+t&Zm0Nx8Cxc+Uj=0QP$MVl3DO%QEuS}k#&mFO(3-=8#mL4&A)Rko!5_FtWA}Xc8!P!iimJCbT_1Iz3)$p^= z2{*CXERWUIg>Uxc4i2fnj*?H?_R|ZGlUeP>S=|nGTW-n<2F+HVOYLh^C*@R{O>2AXz!VE>&Dpk?jiw-l#i=w+d|fg?GcA0Zt_KyQij#> zgd6FzUufie?UqI_OdBiR%L&zjjje~-@|D{t!NgAwZYN*d`s=3|7ae~}rpKQm*R9G%Mrl74UT#;Zp`Ed= z*D`n06z|HSA@{EBSN}OLuC5)xu;S~WEw-pS$21%@`FZc^c-fiVOu{p!>2CzT9j`j$ z=UGOFEBbP*aCwp(V&ATU6c6cH>GgH{NoT|f^t-ar{o+z%ifa@Uz1>rm(1h=`auO5s zKuP8IpFhP#4<39in=`|;?(pt|g)4Qziu0B|2WRaPX6i@hR+pEK@8ime_G=w=d-EhK z_>jLDPgS5t2V=9_kIhP~uHEJVCc{F}6E)#G@#QO(8|LU?+*hdECN# z1L>K!l_RZ9WxSirMD(NWRhjjo%9(HXwJ7cVqhWsLieZ`E!R*P3J^|;!K($5@wWJee zjH(C56m!?4YnE@R%DZfg$d{gM+E+1n@P>lYyOI}SK1Pyr-G59T9#W~(^_-okD1P2w zo0YGV`ENCiO^;z*j4amOuY;l zPpG<4@_qTC;Lz9MNo|f48u0=@&B@#CCE13}pIFCOw@FkDCpQ}&T9&d(xZpDTQiLKa zzf%5njAiToS7{U5YdU5N*j%W(e+DUMdMi2|VXf62+P@=$SEtxQl$YfG{XXG(pG{1Z zr?UiGA!Oa!%-HDWr(>#g~u3uUzkn75lqtbNpV=$O4Qkj$c z+?~+u7ifcgj?U0``c0(6{wyQi*OXsz4ZB`xDtJ>v71MHU*VviVDQWe^xQ>-XiVTB+ zl=i!_DW}z7n?q&^Dl~!-_0gxdn#OL?*0oTcJ6hsy5BUq`k*Pj+}e(@_4)7gh9h*?RW1bf^1xMHF}+< zDU5682h!)MOiv1H@7>KCyQB{6HTHtqG%!x_1abuCSS?bNp$k`0su zEuWjZtdH}RAXZd|bD?{R+Z1{9?j2|KGx3LMs9vN&`7-VqgvC-nSXr$>yw58Y^SdmX3cU(JJ78AcJ@q`gFoBK zom0gu>Z0Le#6}K;=pE?&GQfeO9eaOn<15GrwjPRSIOaH0|>>7#z(?)ZLBs zxH)RwUi6q`5&UDLlVV3Nt?hft*tu+(PD=OmZvuZz3VwNApEUX=E2MDn zyzLz^!;%(`Sf>2rx9Eyv&V}(Gqp=t~u2FY{h9{}*umpdhDa&X}d_citk8G+=)ijM| zhY)JJt`{mzsShmdgDp0#unf29sk`-?M&KTBH6&7MrA&`d`}1j+?M5tzNufK&gba=Z zS!`JMZC1zNaK#BJy@TqTlOwkX)*Tz9WS#8J)(+$MClG_|bK=Yubb{>VhW$4ySXHix)r^))I>cPp{bI!GxCB+v zih#r5nr92+&~$9{t)eVNt@x(p$4A<8?z__1HJ|KmJ}mo%*P@u_nnbgix{*lVWY%&{ z_k4iH$gJ{h?TW{3JR@(;Yj)n@v)<&wGSX$N?$&iK=1JasJe&DFQGl(|I7BSgH+t5S=H~gPo%mHdHi7PZZt1Rrh_(CHt1n%;IkqiC zLf&DCX`>4H&#)tM6@PBoLW)_(dVAC#=3?Thle_a2IijZxNeOK@)e zOswXMmeqVaF2AMdE$wd2cE5LQ!iTxrd<+W!NGs4XuiWtdd1>HPuVH;O7zjp#u-;yx zjij)!@P@4XPBR)B8h#NGvMeUam;2-UY-(z1`D?pKOfR^T>#Jp5lTGN%`RGrXvA&wB znKX8uS@OMlxW&q0F?$Q8GV1Q6-hDi0sv^gOnrpt^$!-$94cF{^?@2t|dOuuauJ1)f zpeBn{@-cmBk(=Q27g{<+qbJS;|~;$9x_p_q-3+?XS3bpvi}m(G2!UoQX^-u-%fR% z9+g1<78~RD)~%qd9E|q_Cp{#?Z?WPEi62S|u!ry3gAGmc=%-anj8jHh3 z^Tkach*fkC8tf*KX3O|@kj~{z&Dyo(tyg~B_%SndkKn9B$pq;~themh!d`Qa;_N+{(d7iAvN2#waSNCIjWzZyG1pzJml3g&@*YfjX7x5 zVMDD&evkzf>7n4SVDn8<^61QV4gWf`i>FD>U!{4$4w_jxheFsCA0Kb@o^tQrdgw?T zFe`mF9p&+vncKH9PjRig^=!asxVc&KBIh#QlXhxM3ZNc|d{WvN$9}{?HCMj1o;=hW zRe3;u_|p%r+k<-~`W2)@KBQUYXEb%OZxytc3fo}b6PjU=yKu8~F!FgBrMtE9B)3U` zQIlk64P|fN{=l<0eb4H9pEY`@D5QMkO~RFmJBDLh+ zO2owE{Q>K}V-U2DVT@tSY_dzI7wb?XpKDB1!|OV_6JeBxm#m$o1Fe)!mexEQv2zq9qh+eW{QB*{i`Gcl&9d zZO_A{{Zt#|N44UFKRsy^P9leF&)PAVx;*_ec+s?KJg)gs0L#J5QMvRR0~eT=9+5n0 z&JI#`ns5)&u_e^;vo?Q7+39*{WV9qE`=%jXw03q`=stRfM1E1Bn`wPptiw9}*l2vX zd=$HWr{5-7c%+tlLX)jfck+_2gYc4nbGqAm%44SpZf$z&)U#6!cQ;WMBNx3kMYIR} zE9S@6tT8Jiugjme5>5R93AtiVE<$OGQOpCT%sF>2YSn*lqhzp;J<|SC&?7KsDv1MNPY{2A_*^Is9xb1+;k-fPm z$V08<*xqU1J)xXdS6ZxVA8>P(7C;ZY32p{WfY# zjQE1y^LBv~-*}77HyqjfIQGELuAsyo%J_yXFQIqx3U(Y^-Ju!cEc^L?ys!NYLB3JK zY3@TjKO7zxNT1Hyn#z{apy3(jT>4?uXIGcsR+dQLE%M4wCY?sdx2%L`Of6;Y=*?Qs zVy?!evvj@ijc)d8sq@6kZ1L$n`udN)YLu6QS%osx6bCb(WqLuKkLcAVc=Mu6sv^&2 zFa)`F48seR9K4gv{13ik1b5Y$wUjmrbK9Q{9{nmW>z-V+BtOn$sTfe_?_jswL3@$9 zS>f5{kKak8Uq=(F<;D(rk=frze6HkYW@TOJ(7w*MQ6_O6Nhffh*-q=-TYkUaWoE5V zvbsI>kb;PGuv^&K6|V0bKl}Y9azD$JPCQp$J>NF73G1Tr|wGzf6gB z%#Y-C70A&oP00T&l$|P4%g`y;M1z9I(p6x$QtemFdU#&-Xk%TWlcv)7NI!p+Yn}MC(OYVO@dUSHlZ~jc$^* zRL{W^xhw~^v^iQ;55``*J8)5h-CEjwSz=(`)XvOmPBp-R!*$KoaMDA*?6AvT?`YeU zjGnUlq7$pz!4zS>Y=1y$E%)v-mwf$=yNuJVjur3FWZ;UMd68ayX=lZVnSa-kf5ym8 zd9g=Ztlm`69XaSyWb@r8s^{cdX~rMA`yZV@~?_+XxokUEBj{fF}ghiL(Ve=5W>SrQt^AaK9 zygs*uwBoFy6|cv&Zr?sKKCYx%w%1|9!P@4asZ+z5hot;u{1_vGMs5C7Jc0M+lD z{c%ay?mh;2QYXwyLA1j9UJ=A)gal>==hrhn>MLv$U z$xIj#hd|JQv(+_>pUyhk4bj}5k(9O={#h3?Q!X}g`@bPsIBhpKi^lvMB!E5~lYt zPAtrr@!J7Tt(4iGadNyUqvFIn1FD*(nB78Jh9m0@d*Z11A78W!54vM8*6}6cd5B$5 zUHKf{?v&RF6$Nf43);ie-Qs0hp?46k!#Ohi3T^uPkI3ww+hu60lmAcZ_tw+Gglg*K za{@-KY=urK4u@wpI_vLslc13cK6<`xHQgrtA}`cP`0_QdC-HsbVjX8pPm`Ao2|CO9 zBFtREZ6!R2WD*;vY0SVn@uZ_x{kZgk;O@O5R#YV;J0tb9t+Ql~n^j4rQb}1$RX?%! z2ycH_^Jg`=GugiSSTOl9xi9@HN&3u@>FrfvN!u%i#{($Nzq_st6bJj~p4crTa8~Yi zuU(vF$PDN{ul8de51ZMz@18e*z9qVUPw;qw{#WhM@bcaIio&LhB#{hiQ)O?}gLdr+ z_f?MdG-oI*e&elg*W35ORJBj~XwPvP%{rd^xkZjZ(IS!GO0 znSAcHa8!%x=N0dEuG(1pHLU+V^?R9FB3lx9;FkesVL95}RcszH!@Iqqsp(3GEQFVw zCK+SWw#X^R(6_K;HZj`wLdS)~8Nb~o_Y>)9Hw)Z0@t8ch2hq zxeUoVH?h0{OM^1PP(M2}p@=B)T^;IWj!mQ_Bv=1b{YFU~jk_j;M8GYou;E`Z9Er4lB$SVL z{=;OXw3|Oaufg`^$=50B@lg|dm&%B^i*z_N%Ox)P@a4@k2-pwL>>|=uXHXpZXo-%N zwxOjZHZARpSgHB#+t(Bn`si2)*8E)QyBWq3udd00Z?Ynz_TM)&s7hqbvp#JBH%kiQ0uP`^pvJh~p= zKK_-;cXvT)Elq<-=i9@2*I#>M*k(!{&S8mZKKXk%_^#_V**Tk zq3%1v@(u5GJXao@%A%52L33T`w~FU7MMoNy-fwZxBR6a%esg9I9tXbu_(+X})s2DL zumt4vxW`r@%^XEdwEe9y{FhjVC?*<+l~R!ov)S^LHoG=#8%~^jnWD)McdOv+^nT`; zlM8CoRadY5?3k2-=IwtN_+!1LETIFXq=eKh|Z&JIT3SRU`adbqZ~Ow)K^*buH=h)(ID8#eg(-hJgmhzDh?DAb*6po8I(Ma=wU18tL=5avXD$y4LJ0tUs zw)DR+7vI-$g2v~0*RpwXnZEB=bDj??gXVrs!bchNYdA}|N!9TmaUuJEBl4~f`O$>< z*l+Hr$hLKv&+oRqHHK~sY(1+eJN)|Gave!rYO3qjbrGdt+Xq~k^gR^;l|DQ^7SZ7x zY|CL8E4Fd2ZySn49gA~MMAtnTKAqe#>ieWjvTON=G__bT-KJ>v&D{fIlai*k1B@xb z+~4olJl;%^G+oNsbwU-JEO7Ox!`8^42)}5}!%3Pfjmdtr*-{^V=LHfuYRkLRHR*Xy zdd(Ww-oXcjUtw{R>}?ajQs;Fa1`m{Au#gM4%*- zq;>Hr>9wbDiBWBtn0pXp$*4}wRQ?{thaG#DBs zIVnr6dY|W@u@o4%Im2Js?^|1-B=Eh8T;>xpTFU0MDJ%OPuwM>^YY+XJ!%S$N2DyLj zSeWD6j2pSRJai-B?pE{~ZtAo@_ zE-pWc$sfjd742v*+ckJ(r-|2iLF=_as}N2yl_)J=u3p9#juVF8%_Av}!${!?cAXuJ zeiIfrb4%*7ZuP>ujz1)tK3JdMRJTc0Y&m;!^;-LmY_A(`oQMAxRc`?m)%U#*kBK0H zii9Abf}kKJ-73=E-6{>z9To^kNJ@8i4h$tCAl)6Kk~2dyLktZ3&!C_0?|tuDES

z&pmhN^X#+Fy6ywo$(!{Z3S8S@p;Vg8g3_@|67zzlT`(BsSuKEk;;!WGryrHsc4dhZ z8>z8e&2ENjT^bq$*mZq@EIc{R=SI>hzU??TMP?$`0+U_VUf$$-VETV^0nCTi#fl!`HRYL+&Lr%F!wppy%zP&&zs_< z8kd<1nv|vw-Bx9vZ57-DP8Y~QuB_f_F`Oflrd*WF-tL3F-u3L2m6?3+e+TR@5 zwSumGaT}G_R8F7?w4O-ZOi_9A47Rv3jJ`5ZGzZLz1zgNyq5Zxv$Jkk%16linihOsX zq0Mz5$0SFlOzR=W^oyS#3DrpI+PJ^%PCT>~(sS`mo*`oj&hSyoW0$Jr%%9O6zI%C0 zpLC$D3cV9EWS%<8wHhMxA84K{#w}Ny3@SXCs53;`UxW7(C7MjnkNrM1Jh3le?suN< zaeLw?67aNe5@K?J8syVYkGT@{m zwewOXdf{1CIrBmNDCokGQ+>{j=swp-L2V4FZYP8A#0OdB6WAz9*uzhx`@?6!_GMAA zp)}?O^xlUwh}M&VnQ;Ezml<|78D%$k)?@Zcor-@%O3`zq_(&Y!Qf&)-5KKIN&fvbdu>b zg$HxIb>tk?N$Qh2;sxS+LodUxh?Cn>>yFDX{cjFpBh~AnBC-zhHPtBE0!L|d zaK^iHWQptcgubF;lQaI6TdkE_`^!yx_5NR`twiikr24paX;*DMWndC&P_>u${1>--wU({Th65bNT&vE#IXJIEQpXm%qRf)f&zXIU!cdrtx$B(ORdn(PrGAlbYLreQ0(oF_K@S1!PNlJ3r;`xUSpY`oAs&3VluO{x9tphJ#4m0}C`&dn% z-~E(Z(qCLxzsW!*L`+_61$1{9;=0vgRp}tns5E6Z*w|qAmOfm{+M-%${|ybtXH*MmgHJ-G(~L9q}nEnB_imDVeo$5WoKpI1smM}2f&E@67yh%)5nGOW8U z(e~P^Q(vtu_duJ1J%ur4*C9yz3VJD~pp$>=_!EELL*Amz*M-4(UxQxuKald8pGIY` zJA73!?MYo7a5PE~gbSdE3Oqjh@-py|De*;Ep7$$2T9G|0!9A=6+ui3R{M^Zw9Ok05 z&`NiB_^>dh{~&L2dPDbt?{OVrOovO@FH0-5t@B2`rOQsueKGUpuhKl{TF_m)!yOjA zL^&r{ScBxFdd#)Zcf}=*OzZ7t_xXV(sJy|fdpl&HLpN9X5fbx_D^~_s#-{X$=FBKuZk}f zYiOU(PIzWigU|UOzmhX-LB$q~%>F zeTNJH8dE!;FKWw8oMCwM-C5;{QDP6{;O)+6TDQt)F9WuBdoLukN3-=ECwtzldg+;S z`_zQ)=VS9_nfMctG0nR-fWow41V2`ksND%o{&O%*8cZILV1mca{Vf^Y1xUa>{IfVa zBB_IulajUtyHf1@*`%p`8_}^#ZLG&<)uo?|nJx#gfqHfD&6}a$<_=lnak} zx*C)oMEpJv2x|c2s7pZ5{2M=M7&!##>Iqgs7D(`z%=Ij(O zp@rA)KkBz}!k-ji`jENbn;k@1CXp?Ic&|YWJOJd$WElT^J{-5Bi**23`gYOq5u)idAfEY!nveLGLA@lY@oz17fP6jGYsdlX1cZ)mI)-H>+A8(&iF9~xJ1iDLi74ggz&Gj?*LVzx?I|F;-#srjgl6} zs*cuzwGnz?s^U0|Q@1<-Tbfr2X6!=*0mS4d%KCGeDF5yAPeZsEc+P&HiQoUV|AF?O z**o}`cX5ojAokD}5@D{EC*XDDb$2}YMH~(~XQJR>hd5gLm2lyWL0b3O-v@xN%&zg! zhV*kd=aS&h2IrHF+C|Pc&LlJw{#}qWtoZ!gFRddK{=-NoAk!vPx{V$cblz)RpgY3! zyt}Ds2B-zk72a$d*=s%rp>q0j4YCp|q)q@(ND6fgd|}JC^r_=0Jj#~zR}b&b;Rgw9 zoW7uoZ!D@7eC6jG{7-*9{7%`N4obI?A*`k4B?GKwjcQ;u=_qKeY^9$DZo|rvAfUeM zIz+8|2~ZpOF$KuDwX7Jx4`1~I%>&2N`;7@y|Cb?f5`&iBMxf(D9ezg!U>l@Br*Fso zFY)ntWj;%+Sb&$+fc;$YeZSv=1v6Cd-aRWQ5^OgAR~iKPgPJwh(#>~7E7-G@@po_B zu0M}ACIK&A;>(#owO=3=NhhH5xI6ZW(Qaq4tMW1H*sD8kz+qd1t%tDd4*o@;0(}*z z>mcY?h3}txw(6%Z`8o>=i<+)(0_d+?}dAI!1c@O02RDuO%!pO%A@ zk(Ex#h<_uiH+W6{Yh!sbVp|Xmt+KlUR&)FZT!Q~lsfl^E&Tp0BE!x>}B@Zf1gk9g< z|6r3%)?)47a`x`zy*z>DJyE;(I3GFc0YqEOZ;pF;+SpfrSnTP~d4CxT<-{I`o|IL!xqZ5p_7otlkUFTM3me(30l z*uTk8i2Ql2S2~5YPtVey?Q9Ulamn8griC5F!8AewVw~~ou)sm}#uv@vJB2bx+T<_I(!fTS$5QKUtD6 zXgp`qb$l%)*8K0}so__8fa3?tuh7%4jW>p4su=6DZ$#&CRpk_1&7Qs4P=vQL;CKRT z|8ZyenTkS8^5q#JjeDkuRp*=#^X$iEINk^C8H8~Ob@(XecKClkx*Bo%wJ1(5S}9`k zK_ONca&Z{(-?hYJbd`!~% zc;AZR$i(T!L(i&N!u<=7Pn6uUe~sp z5ZLYzyu)@9XcZQ4zkTXR;5$bk%VhR5c%O;%IxUo*T(*Yzp;3)e+ChOe}SH#XWjF< zd@_ak5#(+6kg2*MwTP%;v$ud8hIxk&vKqe9*+CF+uj_w4<&BTy<$xyOk?@1P{jDFe z)er5v*l9p{W@7K0xm3K&GXQadU~D}(ol8e+mKfv zA4W@fG1zXHrW!pEQ96WeVtWL(y*fKSC2-6`IR9zxlYkipMUk=Q6TQN96#mz~rGw>+ z`0rH^?SV@7xsW#2v0bJRZUcWG@SoW0e_uVxle4zYV4nO z!ku~TX$F{3_Qm&$>L_eNZ{_7wt60kG>mAg>9m1x|h%|a)iBkBxK$sa zIv!pD&ym2psJfxJxuxOXZMv}iif;^C4$t_f*5zNFt2Evu^4ej%FPTv2;EnM2->aTy zMlgV}Ym>|OXYI~wUIJX_NwbrGO{^#~w#t9E)Lz_IA#di%&Dq4n_~J+PT_LVu_fiY| z1c7JC7}14niCX-dbU>&WZQT$%Ei&?DQQfuZ(voNT=f0lV(aZe*o={=H0Qw#!&NTLX zrDQty_yKOGY0iE?#s$?ZpNC9-G!+Ln|IA?UGF>oTFSAuKl;0OuZ|EDW>%FMhBR_s= z#5v~HLUl1cWRUgQ;xR&Od@GI5W>;P9^?>Ecr< z!`~gMaaMMb)+Dn2x{nV5?&m!iL$6T>=gGpY@%A-_x%RcYYC#{Dzaoj@GVXrM0aN`?qHBzXK!| zf*%0oKR59HtMIe##K&Rc6SI!IAHN`!{j)0ZZs4*Y%bBlwntxtQy}|p{CgzdFVxCM? ze^O#e&+BDGJ*K_Mp8L+*beGMlBn)zbqU*IyQH<`)+8A71Bz=WHX4OP9tMR1ywnqI* zLZ24~6&iB~wHCd5PN08<^e5%&N&QCk%uA@M>X|^9oKtQ(G@t!v3?!a9y{*S36+KYS zS`3L$@b`M5g8$YPg8$D0aX03;@Xe9Eq2m>kToiHJpl`gQrlVq&*7_#wrUTWp%&h90ChF{ELQ zPw}VH=-Q0}*uv)u>bPGUS*d$c0&ibk&j0_34;2r|1fPw&?t2!be#6`VXZE{l0mW`v zwZ^0Z6);e$`)WIV^y=ylUnx~L<9#&beqh5q{@?3`0rikK4y+L6K6!g>N$&ooL2(B` zN#!!u;WYSEk#B4m(VpW;ab2#iyf!UzCfe=KTj*YX=@e_;+<1|jnW39vzw9vj_|{U+ z553Wbj7L<&$fmhiFK>&FdzyUt1!M5_6Z<^Hg{qspz8;nA$#D$Q9A!D0?^@FnMNa6l zQXG|zDy%2pPYr7Zp%*Bj1w$h^jL4Tx`oZNtdUoukV=er*P(|buh2?)&%mj38uceR>rFRoK|)bX+D!Bes! zt{8ifYhT9JwowIRLDgmsu_PLNg=3VfZl?nAhGbP_yf!ZiOOum0pzl#MC2}_U=$}VN z)qB5g&=%UqaSY;W6hj=Xos^=KXoMBC2Uu4z0&Ms5+EEjsNhCJ%jwK=CJgk##+3(O7 zp-d}GR=?|9!um~~<(zvU_!;uXPW*Dfk=HxCJ?E5pqkRj1=g(hNo-c>S8`mp!DS_ySXy}liNt@uLa$(gQbnRj zSur)0^)7R}5HBCYvlWG|@kUiEEmvM-%y{i8t8(c`;(KWY+Wq+rIoaW~`Ki1#Lor2e zp~DnX>ClNXu$h_VTn4o!e{CR7_$r2=x~lk@H!Jlb!gMEuv0cE9Iw>K&=QYVhP2Mfy zZo!pLD1A7~oMVV-AclNpT6^Dq4#o288{SsTtv6Jq-GOH9vLECPn5LGQTg$Bu+ zus`58^BSKK6j3)68*HG*5tVfMXQ38ako24h+SbCV$t`BQpf0z*^XTc6ELUQ3Qnq6P zp=#A#+G%eK?T_}jBkCFt?`G+J+17OQpWHStckPd zcC4~md|u-9Ouv$Mek-vvJCoP$)WKaQAvz~HI(t#X=4d?c3IzxjP2Mp4_4FA}ZbSAi zdGkMX>t5X;Xfp>|*=c#4;>Sk?ULd{VAbhdWaX|+a0aWBUt_O#eM-Ae^?bkP)>!;`%i z!+I1xVNv?d-e7>1wFIz74E!HyDf`mD{O>+D=-wCcO76 z{|518OdBN>Q9(}dU1)xRboGSa9aU43$9s&~-5$7?&)vd#b?yJy#2 zDq~-BbbN(QiRYsoPdPP!FPJqLZe!njy*Z>?FS8zfuRZV?yR9H2_lVQKw?BUR#Ao<( zQO>R(OS_x+GCpxi-*k*W%SoP-uQm{U1Dc@6!`_B=3^ZNc8|g%b=b+le`0p>MxJH+H zztogDVydIXj()x~2ebSvl`Fmf;Zs^mWn0uYyXelcnKYd|fB#p0LDn$faa=oxF{-q- z{%(d9sfOBjhMT!})LjM+$y~cvO>b;y9;E6S=C{?b#nnI?8lSm~)EmY3_loZ6I4Xwv zq5ssD&!7q3nJSxr5rSa}1cLc^bDSHuBNk8Hc5ARpE&Stng{zY;5xOc9R7A0PsoIg zha8kWo8mU}2V0R+yx!+K{q~rR_}c`w4__s}xhC9F3U(^oo?qV=|Lra*b+ir)Em2^* zP1lF$8aEJs|E&cee$Xz!cDOH{ZDQE3Nj3SNoG(>AHJjMKzp{_5c=l zyt;9b~#4({if&l-MvZYg9SI@+tdkkWd)wHdIIbcT@~+lMMrOPJ&Iyg-O=F; zZ+0xG-n2u+L9??#kq#-Tc>@r?rvm>ljQn0Lh}HpFMYG?YfZ+E#9*ve>;V1RjNUgPs z=0rBE6mW_1+T_UguprF0mDf^syzei>hI!fhT4qeBtUWB5aE&M)=4Ga*S1|HT*E>B} zjeNE8=`zh#8<+JqR?J9G9-@juk@K2niL_VMWNyyIvGF!Iw zs$I!x4r6$Mf8%x{vFxR`KfJvBvhf4mBWpJ_NY4CQ&({*jn%wGR&ERLbQ_P~(BkaoQ z`x9920f(XL#+M+FLzc6F$ZCl#$IH|_*e!0nC^MsGrdF@%oTm`siC&jIH;)*rsN=4RQSjX$kIliXk3l<*y<3QzhTy1pwq%0#HHjhCj{H$7AviUY@D>xQk+dU~1oLO0Cb;=4JSl;8b77fk{^zhx)ivD#gqQkF|Y)W(V4!Z>4= zn8%UpDdWZY5hto}*yVF;!qT70|BRzdrU8{U(=#j zw5P2lXlVkma7Yx zS~e^9eCzE4&E4&z?_YAM?H(5oMHi7E0@bCF!Yj&mM#ntxmiw+5AZNW=7I6Zc+WIdy zJlx-5e4mecu9RmmrSV1&>HD5D++HEYlyRhZHGVIeK5qzYX6x|vkL1U1(`)HVM<`F5 zwbY%W(V+th+P3`rcMV9AoTANNp>n59jUSac3~f|ijvcRcf%#4)KKHy|t}}PiE!8vg zIa?bVhZrk)CFE~i+wtmwTfK2(PbuM4aH5!qq}6t**jk3C!{%e{SET2>s`x0zkd@*- zCRRyb-11?v;@+OpKaV1mA|@g@QVK^pa;3|)o2q=IKa#j_CzDKEiztoiu@~05C3>^$ z>X)tG%`Cpl%Jh46#!kiR7D~ONO_WN={q&Yj%GGMKCPvYd)^j}r{MRW7!KOMIla}#| zv9)#^j;E3f+~@`Q+`XQ!bE+p#RUYv6r5MemXP@pPm3jv1Z56-7m2e%_H__V(8{}Qx z@K+uQVn%US1-aL!nNm>;K30l$io)U!r^)>9=I2f5`ClvbTV?2(;VEit)-*ntp_Uyk z36+K(^=_2k?v@W5oBd)%og~QFa+R+dTMcb|1}=9mVm7zEfk%*ER+fuiTS}>x6Y^Nr zd*1Shd&3qrEfSKBZ+CN@;y}(NqC{Z9L|%o}e-w8Uu`{D8bS!Nm8>DR>#+I+p?b4x8?3!$9HO+ z1u&`c{Q0no-N?dYF#V%>nNl8cx)D1HGV6gJWQ5Ybrd98E(_M*iz>7gvsEax?Yp zh$@CLIm}DQ`KwHixF0cnZ$jp0jOD#5x>^I~AgGXLX>&2SVM9eRZNEtT_%OxS&|aTM zOk&@NQF$;trC-?92_?p$xA;2gcXR+Q=R`@ zrh+zP!^=dh!)he0EQz7OF6YECAy_WF$}N3@lQ@NoOWs1E7wOjW^lm=4AEuT>gICwf zuje1jw~!?v&2sM8L^iiucisb;zSXcHyjP89L;tuE6` z!;J*VDZfDl#Vc49l^zmq+Xr=6Jh1%wk$gjoK7Sk&QLI)4T{!PiE>*;lZrs!?-{R#P z&;B*8Qrf@#x@m1vRXbauDd6d_TX&+&+9Aw%IZxJolPA`%Bv&*S<##F1P}Q z#cGr7iBsFhL;R;TU*1^Kd-yBo%)`~EmfVu=`ED$ppL5;&V5IFxdig!}#J?6adG5JBtTlglCz%ck&o-3FxU|Hzh9 zTOT>EQ~vRq6*_}+zW`XV+HN30svLmDZBX7dpy_5+^9Fnj8jo238R=hp0xhn;=9_C)KEs1{LAeu_quvj8pEP6iQGkvx0H=}H#CqyGaP)&p>n`f zHJ>=m*`^2<97&pbtAUVrCRL|sj38WRRQLnKb=#uzxGa!>;-MyVoVpkJFMoh&Y^L6u7t}M1p!=MeET6lXl}!UYz-5l1$cy$wv>QY?86|wU zRwU0;o2K?_bmRrbmZ=ZHBc_`D&nTQ;KeNvH4Y47ipa)MT>oDJ{y@2reA=eftK8sFDFvNgKLsv=&o zbN4s=q4vlq1~vGFsSF=Efc(N`!HOY5^SzO=IfAIZa;+>sdS4brH6sPDxD{WKhQ-blaAY zf9PU#%WMUU=^M)xgKYF+Q>?I!0un7@koPW_7r7oG%<(cCIM<)GxvA~TtSK?%Pp#*R zJ!BPjNv~8DKSEcRvre%YdVbn+xCNLnm@~pl)c?pQtcPe5R}LG>DmvN80NKCZtT4I* zC_LE1ug2?7T=bHgi|F2DEU=dJO?6@5T$Uo6G0Kx#J!O9cPrE>$@eEQb;$&+t^$ME! zH__!Bi*a(Rv9~Ou?lV3)LAPhi>~@eFdHgp{!fpZ(32#^&>^Vl7C>4e&DZ)t_N`M>C zG#Ifp-OP6Pjb3sUSd96Y*7RN@6kp1dN%%hnCHgk!vs7tqmK?j$V4L`7jzqMg(*4{Z z2Rn61?~e@vZs#a--h0B&%*DBa2Z8d24)hKlws>o^8C{P3UQ=IJJG0J#ET_|HmNqsJ z&~r}_HR4OkV2V&~@pg8n$6WuicR)aZ27fMN7xVbEq~WMO6&0PiVy!gsVnSUo5>U`{ z$HRDsM`vakQUF;ay$BNdXCT2$*}NVjw!hWgygth8fqMpmrwK$YFgWO5*nJ!#rRgj< z-}qT=l!E#gW;fRN^MPbMoC98T0~pWtWS@~v?D07Y>d$7%C67jbB)^#B@sB~6 zsDAEFSJ)h9_H2xf;!imZdpX+%yUq22(Nw2Uap%@2`XMNuZSOLGyS52~rW&_dWI`uK z8yWlPquGml3Y>n3G1nnyl#8$mR}tp$Sx=#r9A)K^87PICx@N( zYqihpsb6TcXqr+&hY~KgTh;pq_E(hEln%*U3OMY?Ke`Ve|MJuyx?e)-0LWvgX|b*h z+!p@nfpd#a?Zt}w+G|)uhIf%w00E*-i_N!Del*zoZq#VsT*Ir8uEh#$X;~J=LiGFi zN(Ash?|b%t0$>XS5eSUkt3ul?v^&(K!heHjA9l&+@c3DM{Sls1gQU!ymSXH+nZgjC zx>{XvAJe4ydEJcHo8Qs~{mTnw`NeDXP8%_|6uT5jio$lV6u!I0H26tuNSn|0_i<54 z2IF4># z*j+AeL(Czw<7KrkyO*=KZg#`vtB>{7M;F9KcA_xv<#R2^I~OW?++(C+`l}ynz+>)h zI@NrpXOK6O;wF(byub?}poui0=fPZ^@Mz;{gJJEt7gQStFr$HDHZ?c3m9#HsXsYZe za8zMELd|!*hQ2VZhY!9ZhGXW7A8ZpWSr=62KKn~eseXL)2|t5?RBU}7}=5A$0ZhFM$L3r$@*ub2i~r=?Bx;IA;412aR-DEzE$Rt#;dC{Zx>wti3j z7}iP7hSc|kZJq49PE0M3uONM%y?~CC4k5Pj?l?8i<3>8t%VqX#BLv=s)#%VXOKYRb z`I)|5xAIBwgl*`J3YeSURCc^%0*pf9$;Qp+Z}MRUJ$4{w!gTC8i5}03;nqe*TsLBD zHTk`&YqCp8y+6JAfc4x*dLCl?J)>jptc*4^+~4;yDAgztIef-8dtg_vY_du7SqCEU z+&u4D$4d~QaMt~c4O9|}A#3Zo=gV0`E_@rhKfgYx-A_eXv3Ip72@Qser<(eQy*wq7 zC(WqT-pyoqKqcJtI|qL~O_sTV*m6kjDfNeo8B>aFHH+YQGDcoOABnb(t&4FfHSDOF z^9nM{A_zA~X83Q7t>!2OF^sjJTRAS667qeX3y8q5ys*&)`a7$e?2@z&0fcAefP*<5 zS7s%;#HX-)Y$|Fa#bq2cK7bnqdutksZbXAv0_5*_heWHtzC7rzv0Gzqg4tqS8 zb6;Rj%p{rjk^DmCO$<(1aj0p)uC@`!b$k2C=RH$fXj?8oPg4XR$pd;&)s~XnvKNaX z_Y>V7x+hu#Q#oRxS)|P*H`-M*!+;Ex?x@~>5yDlo#NiM_@IWC!1V+K-!y!)U}m*ISRg1DDqxDrKsb$1kD0v;MQ_VI!>Z$Wu)2$Kqh zxE$~U=m_5MrqVjG(Q9L&@b@YWRJ4LUbKTfk?rkoq@(^ua#2C(DJ$SW#a9&(2WOjG_ z6%^53e@LB5oj1@+SDH6LA-QHC(2pWTc64g7&S!G<^-mHbc62@Ef}N4;hU7vzW3H}d zIyQZ+3^&99H^?Dqo+AmjK61{?NsD%CzU5_JjKojC3-W((1WQXjxo#5(K{C&8{fdjf zS(N7g8n)5&CTcH+AJA;Nt@f9@0EghF$ydE+N_sR-DNdqiEXrYg#6peUIyz#r+LsUQ zT-|VH{z=g)Ymv6-HtD+iP8H_a`p^@1juv5>vkY&p&{r<~ytY`-?1pJPKj+>0;z5T% zgeb*AH42F2>PN*OOdfRK+TF7W@x~={Cc`sp*k#}n8809A5YpZq<-k7>>u0_3RmBhW zyyWp&`YEB7)vn1na9Y0@0qO9cd1gd<)`SAR5``tdDa`o zjN9tmPQ3oMF!sh%(J>xR1}}DW7|5|U1k8&WyFgTxhkA{QFWVRe)a)SY^K)QmSeF-B z=jSM3gqL&D-*rx3OWm3rBABMTnp%FkUHk$hn?THIt#($Up`YHhn*4Y_{N+#RuaJ0r z02bvkzW8{~b6H^SblF~hW(UcbcUax-nIVPwxJVo8=EoQCo6N``mi7>wn6AO z{D650KMWw{*3OP4VCvCbp1==+u)y=7YXp{!;8s`hMa8D39?-4wPk`TCHer+ zD={#a9qs}%hW(%*JDdW_Oj?mlIB$vISL-Wz?JR8bYy~*n0U1Z0;~H01o4NG_i3wBz6Mub!RRB~s38whB(vQ0xRsgbBWzeugzSlGB`4lTu|T5%6M zpncq=%i=R?R}d9F7S;YI)Ykg87n?@b)|cIxf9!uZzpr^tz^v8mJl=i&Us7|te3`Hb z>E&t^p90xZiM)ftms%u>-mjU#;e#x^vovn3R8M_ILDlG_)SSEgK;D|>8*W1~+V!N` z7Kf}coCer*pqBHP!yP_}yztw(_<;K3!jt<$OOb->e6N@~Tp9+H*^_bw8PqUU@$UJJ zVpxfJ3&rly#o0xYhz43v-yt_z4N`VFaRFv6YF8!rVyai-5cX6E>3( zMm8)ixY<-Cd|)W&wSC=Yed9yD)mzE)StywvKdtb6PB$ zfbBmdi}-j;yo+<10$n`}tf1GCzC5~U!VMu#BOmB8>Fwgx=;yp7+qr=dUgN`U6ehqH zvkgQ+&TPk8z>RB0Rnq{@R07IQmj&#={h@VxVA)rXl$*0iCcR zhjo3L;O|d(v$i=B$czeWpg=L7&dnE1RO9_>ICm!^`#8pE-%(q)sky>7i;r?*4_1>Ms(>bsRGjQH;kgj4NARDnCzD16lK0h zWpWPNV{vUla>N;rTdkK^s%SEgrP6y1Bo_W`QjMg@3o1=Bm%TEvUT$Nc1=rdRlM-Wc zz>`)_R}u?f$$m_&9vZF}|H70EKdSv+zWlVN)YIcZEF^2NChxO~wU2(fbJqujrW1gV zo?O+h@v-ond|S1f_ZkHVhqc{b-Qc>_wu%{kC*4Z&tku_U>B`yz34P;h+PZ2!fsV#k z#yHul(eD?#+ww^m>xoDK=yBAXb6kc0Z`2g`w8Afj7t}nOP237y*>O z1|ar?NhS)!ezY^L2WI>(sOVM>jjl@Dc+e@Z4zoIWh))&u8vQiUC52koWL1|QeH$h;aFbvFOz-$7jWD^*nTbDH zU?MR+1O0=fU^V4?O~t~sMZeQvqj|MLAj}xm&HDrP+%8kSB6$9`TgJtG(y!ykV?2y1 z=Ku7gbfQGFG~Gh={?UQ5mfB}A;rW7HC%sW*yq*#jEF?mC@ZF`|nf245W|p}c+pOdF zFYgV0egU?r;L+nx<*RISqUO+G;nPp_`G4lZ#f(4vei7Pfv078c zHtqnQ&57941O;NaNP|XKfY)H>G`V9_2TwecfE06x3rmPM_#}dot-^BHqeVXTKL*q( zbnvB>syCkp^8esK za`J#1rniIb=W1Wt#?Pb~c*^XHLF-AqUmBTxmQZ(&#=o9??Vj z;h!JvPB%m1EAwQx5#xJ39{?`rds1d|igvOwXG+*;mNh$$7!$^LEW*XXkE$k%xCM$34DY$r+7&v#{NwK>Qm^HIGl7UYS- zb8*z0YtS@ri;QU`<*h;H3rY^;J(3*2NbQy*`c zul-jG(ED319Cbp?Tt}P8UAbBGR_{TFmA0SWil%i05Y3SghqR1WHbj^o-4fHfTH?Ph zC;_6;_w>&rn2DZJ-VBINV?o%ooBMj-aiI9drrU?=t#6>35MLLFh5I`UB?*5w{*YOg z%>Mwi4|6I0V+Eb!xzDDgz8e*ra%aR`7(hkv=hIqmW@b+A#8R0*WG%q897RR%xQu5% z#zzoMHCYBA{kqjxKU|h7sFcMmWJDG}m-_{=O`URsUTw@asbpc`{`7-RL5zP|;{Ae> z=icU|AbADchJ$!h!4c=HTM3$xnI7()1;0Qogp>v2>gV8u#F@6E{5Ja$z;A>_yleMO zaZ9pK7MJ7i->eh(sR|T8xmYCIxVcsx!?sM}NdFM92-en^gu=SH*|}zovy~Q?dHyek zL=w&0H#^nexfozNKeoG51FG#rt4i~YkG8ufC|I~F7JfC)amL(2-F-oQIcP2yZonnM z5Y&$NvcF%{^~0o;+yGo&#O`HUDmU!wX$tRios4NplQ(B;sD#EetWLgiS;#C5)HHLL zdi}|IUuee%HAx=>byDcLtIV=d)S_beYQk~KapEqP3h6!;nW41Oq`6lQDnY(jMI=PZ zC?(v+sloYJ=~5ev^rqaf<}MK$SXB@wq)cn6QI5rK^e2D4J={WQmr=yQaXTwCcV%^m z{0L9ufIxTJ5N@J^JDGMF1=@_K;js-g7eLFB)k4opFl(c?jVA%1%24Qoq<@P~M5>

dTeUNwtcwoBb47(d4v^lOImzlNq=6vY8UT_UJ z+OXH`)S&|kG&VNviK+0AQoTtO{tsVAXk~qR`|(3Wh`4Y5pTy;UnpFl6L>L=A30%pZ zrg*iASb4Mk*&s#qkvwS=R2d%!NLw`_^`={(Qu1HnOXYYsbK7ZR+!Trk9Fal}NAKXR z`~0L)?ssHvB!xwx%{IxWOFonl1A{ZdtO}O`^dFZ%M80(hWG%_!n_j)R@(-|-{KoO| z`kv4ij!DeZB(Q+&y9rewfW8Wc$qc>FI2`VYK)s1AjOq1$W1(oT^Q0ZNLy*j+&58k^ zCgD?x(xfggJaX3@A|>DN+morDQ;=IuHo%elpQFoX+}wG>EHP2+9E+ zv^q7j%=-I-wQ+pkol-z_g3>olm+Te7tr^k@1gXPjn2R=B^eQpS23eJXEnkvT-~$_g zUG=9#m2fk?t`wN-qyV?|XZyA_=Fm00vOt1&NR%9d#j4XB6}We@rA7|H4XNJjjQk1L ze6rTNQR!uP{42z-%%IN17Tsu1%A?d!GE&$oUhk9Gjnc37v7p+_qQGvYa@VEZ3B=2n zbhg#rr|_BO&kAEXEyfw$fhYPu%yk;&qn)Wv3AKxRN_Dh5SK3F6#WdqZ>Yf8^6*pMK zw=0!%tvkZ&~5`;|>KvY0xjRFXcgjfgt zl|qo_5)@KvP7SianLBofB6v`sCQg4&a|C~z-8jwM@Y~nVnY_a%~x1ldiwkh zz8+%79ebk)lyCeJtrtbkO^b>EW=Zz6zcQy?fx9Q|W=YUpr~M&GfVClF!vKjTmE_@yawRm$=}rWFb_R*NKoXc z8w@-rGh*Docpdurqp3_@*gc3XFR1ayX%CDV_V6JAw2B)Jnqp7`km$FqQ32c%RuGit zkE8Xkcz_z;Dci@HrZs@46!ls#@WmBen>L&u(NGV!Xj6|AVJBa~e_C#;nW(xn%ElCyU)v zFY~keLg(d>cG7V8<|o;Ev$f$h)ixJ^LM41+uIZEE@s_!Aba1}d>}>5;3Q^wqHwI`Q ze?#YAGA+scTpbxjE99%;+#M`j9ag#xKwPc&K8>s+Vql;J=y=pZv3JUM$6zic zJcrl>ZFqhs!_{8u(1pqe|!Eq1&pV{8J^44{{|KoYW95?`;qHz?{KTx~aJ zy>{ZFK|yFOqQ*}rrj;|>IqxOr&@<@W)x4Gb4A(>eRqU~+6@76TYxDsgQBm97e$S0; znwJ(5K1y@lJP$9b|5czpJikof<};@OaTD&nHV*ks9sMOe$l+@iie7gNSJ)!@RW~wI z+>l>iit3r{3oSprWIvBC4ct~#L7~HTVFl*E)u_VkBQ^DO*+U1YtY875&~C3f7FHw? z9#8ZQTn92JSar@s``scE_FUaq-??1q{`v`K+0)6r;*AOTHBftlU7GLhyDC+XJ5>Zw zr#T1B^4G7XA2k0zuD%1F%J=>MJ`^P*O_3C7$tZjKd`LrRNs^ov*&?H?)1;6}qO2l> ztRyl|A(g$iBYThR{lD(#===Tt{-4*YKE2L4&;8u@b-%CcdSByy9;3r~ezt3FLXK6~ zKqA{H!P(-OQj>lJ7QS3X)wPaq zMQwNArd|7ey|Cfm?oCe$%f8)E)OFqe!LkBdsF?39hBRn4kh3~wpV0VE?Yb*LxJ-!u zn2yfs)K*Niv5H!WR4*+U#|m~US`>*D_Zl5oJ01djp<7F&tovWbVJGN!8#)E&yR;k@T)91_PiHaYdF}F%!oRyyHPV@`X7ru6yH z;?M)%Pma!||HLoaK-S)_<%K!Ksg}^4b@Hf1cl9pNi=TSG9w(g6lKgV|Ccj`w1WnAx9M3pnI#<-6DVqf?@ zn3bi}jkD3;Zj_%+ad}?|tkcjcBr29~cF#cfhn+b06E0okSNuJzGkab8CxD3V0I2ky>>QLkB{L#Ke4d+wu6P0g2lV+Oqowp4&x<9XZFhNRgNfF zsNt0h!)g9q+S8s=8c<5{TAT{|nPtkTr~!Q#f!$iGOlaU^p~^E+>7VMp;3_XDeUyVH zb{LfJ`MYyMj8y0!=J-TJ!T(L;uP9=sWW=HYe&nU}(r-gJ&LX-__L}UAwm5l>BX(^g ztLm-jq+^~A6DK+D+{s^cNzlZQ^7RJZgq|1Bq~JV!Hwj4Yc+cEiN(7LuUpyWCVd>F3 zS8g2mXsY|Jh{rE7u*;{f()QsMs9r5P4w@ge*kNKNO>=Tvs@b+M)9jL^WDG$JO~K*r zpnLcZjQ~LOt(9*@p5>%_t;^Rk{=Qae^P>H$yR;} zJF-O@EgnL~x5mKOrxp^~ncEJ(g0B4A9S^_Ee*egJN%TE#hv0Cvj09e?e~9-syxtl& zoCHhCo?esT(M?jz)V(U3f}VE`-R&%2hlYO3 zWB*JkxuHv>PXGNq6`+*I^Nv9*%;yrVPadeb27QEUw!1=B-bQ{9_my4>6_Blo zF0gzZJF53+Ujw(jxX06?cU(B$baPPuHB*4klJsYMlaqShcEKJiaFkI; zUxV*qIDj(`#{uG#3;LV(>dodhI;A8fsvkOhn|)n6FVQBX=X-GC!GrMVBdf;m4Rk=m zUsu}V5EFl%80)p&1$*RWBXcqs*3_Fn1YoTC&2h>;@GXRb3(aij_Ix*~wTtp9gFijP z@!KEgrxyW_&uqSLAHE9})$N4|u4P{i*&eG*#a?sxUTc8rw4lk1N#5$kS$~{8qPTXN z`N5M=c-O11Y=w?%+){j;&sZ||Y0F~Qy8H|u?b0Kjwrs!3tc)SK*gq8-C>TBH^ijEN z;l7oBv(!~r;@PNWeq6pADf$m>h;j@0>EH7(BTmQpD&U?LHi=AV?LX==>ph(=zHO+@ zeP;ysMqJNd#}x75J44UuulD|>qlN1~u9LjXwXt#MPm|O~jbZp#W#Y-CRwH5|)HjEI z;&q`_4`{}-Yqh1#L~xmkNtus+Xz@+>cb2h&`zJ|``7L61zjKN?Ts`mRfHM_HjGFhF z70ogJb1Q>8Py+Zt8GpeuQ+#@mtK9B`tiM0*g~O!o;DSu&Z=E$yPmb(t$Xzh#0-g8IoQ=wCDR0H1L!61I7YkKVvun6p zuUPDz?_sw7VN3W4oWBg%;A0r|eLOp5j2H06CxG`T{4 z=~t&s03RGtWL2QgL~LhDjfPvs8M%+NbSX_H3M5YY&d(|%=dQft0Jm`mY2qG?$BzeW zq{ttlZ>P$Y8d?1DeSWe9d_ryQrtdF#&+UneX1O`fHyFo1wuFS|SJ%a3U7vVn|2$7x zXvAS8qEa^WALK)pqxPIlyaS}xMR-OD{HMm1jNf&Swr{v}1`Wv}bJsV34+GW-g{K2+ zSQD2Wg|Jofr%TZ(7T@0;v5$&YHGQpEGr5B`XMTXSc-ylES~DIAv8p89OJWfF#{dtv z|H`oC!K$67%n`N0Vx|{%=#}9tNdKcgKwPXy79}5`^-W+HFkaEvRcxC*{sc zwO4BLovOU5gq+LAw{}M69eW;RuiCrX^4iYy&cp|wub(ju(tuN#e%!+cUFiF%wLuG| z2{s5Jp;Ml_llO?j{Qq;znI&iD=)G(a$g~6l7b5Q&S;=M21V0eVa}4}oCEmTW(!C1M zJ`FWFT-fhzCl;T0-rS9eBDk09g;&|8Jgntw^@`+hGYjR!iXv_9ai(YhJmbBYuVw=G z{oZ9QL!-)3|AUq7z^h1(Xf^>9w60sig=qFd&(^O0{_RikOD2kdSjm>FqgP?1?OXqj z2=}jR1f=-iOSp{0HcZd6UdFbO>+*+q6eOv`o$_P+Qi|rb%7S-!Uyk$PuaL^ly!0aI zZIwe?)dgus=rr&C1HEqi<=V$$3{)jMrS0vzV3w+PrKwaI_?WWeyYZ!!P{bXtFA#KZ z9DfVCG1OUa@vtp7-~tf|!KiY@Zig*K?GH$8(OTK6viVZmb+v1k;9^#rzq4KOEgCh= zP*?#9+kf3p>a*K(_yhn1+wvjRnm{#P#p>$%mww_r}0%-7&*W%-0)V1vvQf@^r3L6*A z9FD$PkB<+Y^c2*e_Ux$+U`4wNWOJ41w&Sd=y!k;^+kA^a#qwt7~&Bo zk;P4nY}pRKCsajFte@~~|8j~+o0Rc<(l{vB+=b8IGlp<}Q~Bsak7*uqLri0Au9kkX z(%kYu&hn$8DSOuU_c@o(#D7wATGoyLJ9aFCwOL7h%^u9^GZ33SZ1Q@6wg+L+?>RYJumXK&YE(57=_&e=?t1+3IoM4@?53=j#We zX=K%dpDfUV$v_oh#!HO3f1t;LOOa!z)AIb@k4n92q-`;~wb?YVxVgah-HYW%-oOd} zD+f{2KyM6#HJ9xfeonOOJw96eU+7axtA;MhrZ;uj2k^j?Ay|(u>t=_ee$n8tM^fe* zNlm)CAjZ&o7HVVI+#S4i7>xE`MgQ zra#VreB$!5tiD;r+jt~^q~K25e{nsWQT?~Bpx>B`@d8*D=Rr?WGS{ROcL@P@)AtW! z%YslAXFosM%Dw3tz?RzjeOXk8sK%xaq3PQ^ZeVM<%bgl3Hy<64O?`Lk2NMO0{Hyn}QDE`)-JI3Df`Ub?dao2eeIJi<`SWbThF2_9 z&EIDbHW%=phlr67l6DGHKwGa4-~-#MnEyH(SKIZ>SvEJn6kqF(n}@^{WV$eL>-W%=n_VVWN*FQByi+Wfk!pH@%==nwN@`Vw#aj<91-)=VEC9O{R5 zrpAu#Y=}($^VdG#cMK$m4H-_gr`o?TgDS1PzvPe2*Om9)GS^*t1z=jcUx10h@t$zczkh$#{O|vVZWI2%DrY`Dv?ecqrFh^L^U7FYy}B)4eKO z#~8xbY`_0KU7(oi6(KAB+BV%OK||@tb*jMMqH4G$lDmtsT zkXjXC7}7EMncFqL@AqX(N5DR@HZbu}thVWn>bm`L;ki|sZhr`)hw@vtuGkD^=bm7o z4n`V98GS^^E08`~mFK&{%{OMZ!{fHd+?%|8li($QtM!_W=NNY%iz-~~v{K~cbLsms zJ|SO*K}TIXIPA3_|LbZJwyJMDXJvZ-^m(C?c;KBoKgDe#<5g{P@11%v7c4U8?c*lp zGWbLSYp$4@EU8t$KifVwU9Q7$>H5SpKUeJnrdAGx#pAOLyv?!LlTk==KUSfoI#D;7?8RsOoSdU06GEfa z9ERS^#>pkg#i9*IP~F#`@PHmwEQU9px1Zgd39AMor51s&4|u$9H*zlP{it7H;yxBJ z{fBwDzODi0^i(K{G(9-%rqHsuSfD*WAgVa+G+KLlb3-Ik>wVP_c#{!NJ@x`+hkQ4o zczBxx#UrLA?6(Za=hjt8JDz`>38g;jmd!*i6tYWH%fzUN%S#c%BIN8HSslWXZ>ZvwzmDcsfvl8R<%pG_7 z6%VYG7Pl?USafkx->`8G=h4gDvp$A0weB)zZ?J6J9hdsfRN=R5wRSoCvCy`XidMJPCTg_xjc1E!P#9{F*f`W@0!mOfhq zHX-MwW~b5Ctlha;4ugK9eeOfvhYf8Mvj-(P@|}mCD#73n`^ixW$ojj|MiLna7%Tpp zV%PU+lIG!YC}Y;nEOo$Gg;Ax{DB0uw#}>T;&scRvP(m@zYKX2p)4ioetNTh9n0@jZ zvpfAvq+uVZlneF3ZL@yC(*wohibAPo?iDC#)&|U$np(%!UJPH}!#cdmGebT*X}Tte zX*+@G^&j6dwdTfXxxUEarG15Q5}S>Z^%Q2G&y{3pRkFiV!S>$G2W<< zaTlN9rsOt(mA9$81<*_Ub~t4If^#WtDaCPsLwU3ONkLkUhfQax!%7N?X`jVN^F&`v zeOM*vGb#~~L>Gn}(g*fLk?I_*VN@?_=;CYlcKw_`cWmRzJMvb3j>Zb1UQz{4ntZhR z(`fA?Z7Tow=7vMRj?k{2123_ba}9m#cS<9^o9P25ut3pz$-v?^w*~P8Z>!s#3-x9l zD=Eb?pdWh%6u?)W`?E-MlWQ4!6qPeglTRK;Bm8Hr4pu2Khza{)qbRmf#}rM2ouS)@ zYocjRqKm%`9aWu|9I`}O#{X>2%bJVjc&DtnK6#v@S&ebz`@i{JNicu?27+#`$Q<_7 zF4+G%P1!O}p~10y;Ae+qjJ+K?$0$aXDUxG*hYH{nzx<|N2J%WcU9%)pcFH!ck zTCC=KG&SfVHWVyqc|Nna?L}?eJ>G;%=$=F&m$SnOGX(ZKl3x}z#gV41pOvG`_O%$Z z-%X?f^HYQ}I5}?szReP>1loCT36RLPr{NKIm%6e3s^$F_=Tu(s7jT^l%`fEV??zRP z!k6s|f0%8{o^oEpn5gqt{g@~kcsIZj_H8m@X#sx9JObI~j1evuNH7Lq619oHjItuD(<%Fx4E;cq` zpl-Qw2Y8(11h#mDnsUq^AJ*6=x{@;7Al$~hG|(>>oXtXYBxbYgtZys6OO1ucKj zF;MDi3=Qh^tJ|sK`QMML_xkCNgLgiwy(yS}L+W%VSZmUg`+IRVn zSl+A;vAk7IPh_+RSgl)Jxt*UshHe-sBuP|i#F_DczB{zDk|>p33ryYxe(HIV-t zE291&g!T#CM)$S6R5!Q0g@hhsMI=&YB;_tjDCOxBohv9)@&@*2BC>P`{SM70!!XoM z`{Z_#UI(R7)fuR`9Q!mpa{zPWw3{vxNO?TnLwRC~f7|WBnOX+2L`=hWP}Tqnn-sXk z3LeaM$t;g&W*u60b#L#mFok`lJR=@D8X0H8Kk=e`cSHYZZguEP+fw%MHJ|Ssi}_2| zj2z6=&-xNrnW;ajbn;H~J$9UT;VgBX9aEm8YDXm`+kzvnVrpIBB^2Yh>H&SeAzn9B zcc%ydO*{}*%);XK+^}+dw&3FMY_Z||u<{oNw@~dB)N4IrTa|CzD(EMc9R4TCZT+bD z(zQHeC7Z>RUw}nk;R-2ULb1vFU6FsuMZo7>is(YY&rQ!h7OJhJ z9F6I-kmH4Ax3Uh;D)TRPx;4{o%j?P+*q@7Vaf>3@OLWgiL%{^nxpT1h55I}nfmj+2 za#Q*vbfYha9N14HuiHfT-VECF_IafX-mbMxgl3`c^3KfJ58(eU&Gx?v1kGaig-2|W z8$NPVw6l--0lgAsGa(j^( z(vtV;KV>2WufXm&o(*beQg|I%zGS50BSEpkuZ6kc{qyKUMHOeLvu=)ANf&3nWt0ZT zdLGJDA%FKHjI90*yzG!vX=4DntReUf)^>8k?dwRS>tY-_7gvEb#5^NPX~T{AFRr!w zIr!y1Z8${eJ*D#IYUGnm_dy+N04<-lfyTJsfwyNI^tAliatwQ$#6fne@tm#+|C`z4 z?~gepG!U9cRm0~6snZ0MD{Cg#A`!6HpDz}4MW3O&tk1DeW(~*ktp=QXfAd>Zj%H(> zM7u7xT>4%Qz7Jb>vKW2YFd~&nCk2zH#Lm9<#oGCpVYuw1-{e9taaCkkp({Z;>L4lx zEPlEsfkZhDKmMXCgwDot6BhAhe+FrqZRt>+M$VV9&ciwlk?mO(4zRx<@AADU=*D}O zj5}Mpch#%_t}Qmh0PaFKij)S#R7}Yvr!eDU7Qwa6Gx`#9QZ6oKaazsr$r-jtSZs}A zqBzifC0la+ej_s`|68P1;nz1<;NeVSHl5dSl7SlWYc&!LjyQwQ<$pL^%~S%Py^QrK zby!L{3`%K{7Y=s4(@HCSLZgfRs*Gj&Q z#Y7R-<&B_?eWrP(&4zgd9D0#a&*$=q$iz~Ti-3B{nC+7Fj110qekqpP1niq2EW~-v z${JNh>jSCLYsvk^73{VFc3V&AZn4mT3Ez8Oi839m)V??j`6zv;$jNA=?X59f0pAFm zyeac3`;lJJX@)dzVwVO^ftiUE4kx8O^3C-P{uf{otCQmU0Z+}p5;;Gqp*7MSN3tCo z+Fh@P(weK9suVUM$_;Ts(s9wxt-d6a&H-t!-sFw>5iF`3Y@E|fPq-ITt0G+>NBk9q zEKIMeVBE11PlXk;*z)y5C$ioP+a#O(WcN|R9(=xN7v!p4uFW`dNu6c~-* zd3P%NRnW&K`jX>*!lp{1%^-$z7Uf(rppNg$7`2PWml2H~*DP zkTa?yb|YDX7pwW?Jc$fr2Su8GHo+oE{MU~Q4J83{dW)xvN)8ThKw8eaEl1Ef`~*as z0B7(Y1ep9Q&ycv%KhZjqpD^|vYF2OLHo{W*prni57Ly;XeRKf|3U6}MmB_);rm>2M;Eoq8@pjNYMEVqas}%SG*EUG zXd3a<&g1$VY*b>ITDpYMY5Z`^0u716;l(2~>kou&-`l&1m~|u*`Rip&tm(TEc`W;y zEP|go4`+RhdCLC(s5RI5s*^#} z!>1q)n=7tx^)C&ZJ6d75KwG*nupxO*SF$6#9W)Q9qV(c?;6-l3#cxihLgB&Gt!)-3 z0h*JBFzT+z!Vo`uXrj{00(j<*ufcn;EAG(Fwh|_C96$Py{Jv4Z^7qk5WI!qd60@|Ah9yYxJZ|u(ZZt&M z`3EyHT<8jX928iy@1|`mVK|xy>t$jV)1i-9>v)HCd0x)+V1eiyWLA)te*?NOFfmz< ze~Vhp54p3nVjM6 zLYGR0{FTSAR&YDXAF46N2>iTHZa~lE`&RTnG)a>KoQ`@r>uJQ5R^PcGlE58x3VzF2 zEx}pLKNyn7)EZ;i#y1}b1RQd8U5@O2Ev|tj^RGN2yr0rsBysYo8A%}nsDjy)%St7x6SkGpCVQQt#Pa9X(UR1^MK&MX^rAr`=?XY;& zXS|>PL%%C)-mRqc+iyzRibBjbk?L;qGPUn^zVy_&_Tm;R$6lAwhyE>7`EIiV#fRqe zGL*}2?ZvpHl64OEPTe#|u6bW@4qmRk>%-~uI-W7PH}yZ6F^O1ZNC>Enr$#snEf%)Qo929-;O{l4MyvLN0?g@ zmb{_i6L^x-CmkN^6`j%-AaSMej}G6R2ihriPDfqCs$Lk)kH@+4Pz;@EevT9VEsg!J zVKQPj54oT2Z|p#cq+K|LN#_-s4bc%g8+I>d6mDNhIUwiKqo_UKSat+x98&eGL`{;Y z33#gWrcqVe!ff4M^E)sS`Mew`)}!G<9uw5EA^9u>)Wvl3Wh;gJZ4-1*dl~HxJ9xL0 z^`8L3ZviwS=_@H#;~P-6Q-W8{LQQQx#IRZZ6L_@17rgAdEuZsHq}L*;^(+6!%$im( zP$y2|6ap$dwIo%Ap#`Ivq800jJvczbZW zlQ0ZjXJlaHdynub%g)rSLW*02nc~0#lGJ*=n~A~`Wq_Beb8Q7hUINk5{8|?0bZLKL zrnOt9kEp2)3~#uRsJ}A-WA94kHK}@beq_Fj1tHmGfLC%;cmMLzUiWEmXdt z@8+z`LWqqEn(htkCAGT84;4&g)TFM#R^$a%ly0*G*-L@k6gv0>7jtgGRzEYTc(|#$ z!t9Lf)cKXvqlYdBoLdCL%k|*{Q|rWzW}eiFd-=8Tt8l)Z`tg=~{Z(;H2*ErD6Tk{i zCZ+8M(_&qr5YC(Zi~$t(;dK=@YHj?$JK_}tUKh%vNsfp_Za?u~YlHKqjlKyd4Vd;K z^Ltga?kMf|r+Fv>{Czd>Y7@luhD{OyDN9&`F+t@`AJ8{BEx@Q>jm%3}5H*d?^5pev`Np_;U^R@2n?-InhuBau!lV&J$#pL`)(gjRe@J#k&}&U2p#zuSFiqPz{R-kScn)F_~=zB{c^B;Crza5vRQdZP@pC{ZiIx zh+hKUi8Ex#c8(B8`R5oLDlPP2XYO*DG&;{XVvuoY;N@p&m<9Etw*;OnsBXYh*xSmN zGM~~2CQ9BQ7v$Akt#Czn2AnkcX;*cxP*@iA}`=K{qz4JPA0ML)v{ zl~NhxMaYVua7wK>$ zkwi+f^k<}Aj792~UdoLtErfPOn;lZS@(?D-deVk*WHz#eCw0?LpBsZJI3D z;x|a6&wg|jNO?qR1zCgvp$7d?Uuj*5Z-JPuGqO>&X~!>!^T!+N@$H9?D0}zGZPikM za>>K4w_P6~F|izJY5LjU+D||kz=+bM0`N8v*BeV9!>lljJ$&nTq=u>=6s&*rq&K$NcSYBK2!9a8VQR}%l78IC_sU+d2Kc#f9LH=8WeIVsq68g|6(5MF#>E=!;v{d14 zm3QUv!b3L!{`hT#5>WSbI=iH$Y67uRdw-UQ7ItpKEMDv&$ajX9L3dnm zk0VH$XG<7-8+6((;O0zm`jYsMDTl74oYUjkA|P$AfBY?kG;L5_Z$6B$!9E6lT3HhW z=8o9sF?eRSFx}$#)gb4s3(S-R-hs*NUHH;N<-gywcjgY&HmD)T(_<&DfV)!1?P$QZ z^WGlf-QB2ebAB6%D^)~w@|xzAgKPk{6D}`q&YT<=UtCoiKb}J$#@|JVU^Y(62Co4% ziAdt@_EPH`9;;-`kabtBA_P_T$wJL#hK;JrfqevOl>jFchk;-Y-4L)n4Gno{q~gT8 zAg4Hn)_1qm8LgYaQ~+i4G{tcp1}9pREX4V@YZ zC$9m8qxjnV`px5h9j;Y9%_~T=*#Ilg8TFf*T3)(;?j!%H^baXIY*czmdfDfj0*9)7 zFS0wDLF`{+iOH^ci|Yg+F=)_@{0ed_jAobQBs5R0NC4A%h z$-`hSZ~^s3&uHz8Lc5i!MJpDbCd6|$USzq&{q zO9rpTL?~{+XS&iPekgqEqF2fF1`Fb}F}wram79|DJ7OxoG;`1=zc9OF=wc0gM@j0l zk-1T6q{bvw&Hx5!XaDfD0eoyx6(Wi*Y$(wIk@833oC4_O>pq#8m+@>=j;7?zR<~!? zXw92P1r)??%iMi&Y^2(;y>Q4=@B8m#AZ9U1SfdqikoGmCR{n+T%FP2e;u`%WjaNe0 zPj~ei=ExGHXmfO-xlI!WHJ7w} zHQcb*R2*j>PRh$lf|)q~jCPW%e0xV%-sPbb7V_3v`LeeGo$$lSQMjyM=P;+c^lih*=tlACaw+0upi+0><2 zN2|HVpY%2KH-ePki1v5+4$>1^FaLZ5bfVS@3Fx!1k0zzzg}Gyv%53kcr^RUfM;N}I zvEioBru_x7+ZvUZauQti@=`V*E;1Tz8di9g`GSs@()5|Dl}20hQosr`3*#g$U3spt z3IX@THN5?=jEhPM_qcf`P)*r?uk#Jcla8aY9D z>im!b{UU${QdlUyT|jY&VOPemR}SyB*Ik?*ky()cya1UZxO(>E(7>V4q977nl@z56V%k1w_R(9ny9wTAMeppI!rbkxx_knBUV4_g_rx}l!p*9@(9 zR{XDDx(Q7s4~jjUx*#u9K^)qgRd+@^0k^HQby5BlXJ+fX3J3%tiUQU9Hr6kKZ^ zbGg|3CBIG_Ff&5LrOay=eUBru7+)yM2l1jg3ZFk9GG|1<>KEH%R%M98Jq); zJ<5S}2Y<3XhQ+J%A4tp?y5D!Jjpj}?IsnvxV?v(5-SZRMSG*_ajbT3{b<49mk;91a zsU3i67)A(i1f3P8QW_kNBr&#rFkv`BhNy>Po&c7#RwG>#S`uVOB4HZH<#mGWKpL+d zW1_4OPTqWkA&%>QH;G6MeVi^nb!;Wo6pzqn@hTMX(f+gnDToSa&4>)t+&GV>$%p9% zD0+X5B=V8P`rB@lDu<0P*7`w6Dh)nCUO(%1AKm;K{FR>y64s6%=U+4#Hn|&@JJw>nL7Z0y#x6kW=`R1hY+8BZ(#OMj04}aH5OvTnauL z&T0W=L9?GMrSwv_47cI!A+KG=P=))(;zu}hN+~~LK49SR{H7^Nd$|Ot6FCJ83ha@7 z0kNO02jc=YrBtt@8r-u%&ouPP88cd&rmdm$9$8pVq}$R?KtPqhg^jA?yxkTGd-Ps_ zhKEolU0%m58VTT`6zf4v{D0h9BO_$Efw;vA5W&}sSwQ>(t`I8!UcaIjfru{IXS5wTGNU%S7?;fYNja0$xK>A9Tw zXQDU;c?|J@OXG>FQJ4*Uki6Gn7iBIQTO0w~@A-loDW#BP6j5f*6)4w2bCgN5`A1%Y zi~hJw$n6_smfYrQ`Q%2E4^~L;sewKIZc;NmJYFTv|C$Kq(^Tw~*{FJ?)>F$`bWXe< z(-^#3u~qnQ>dyI=^`+l`w{=)w4yi`-^Gx|RLw+oj>Qfw#-eaFj@jQcpILU=t2zo_P z@-s8?E#Cf@>^Jw}L7ZDhjfbZ7o^3>~i;|{M&@4kW9m`Yyoh~^7DkE|NU8Tb!F)HmVWOJ{HSJO?^_y zL*bwgLnw5r>MA6^b_+suyXbo&Vb$5-RMPZ>q5a^6(iK!kxKNs@1)Ha15ak)nwCC>o zU#Yqv|>JNGN2`H_@+j$^t?)Cpd{ zduVpb>@UeX{Y45XP?%aZInOXbL7dR+qvtlFklk?i!ToJ(RG;OH864RG8ecoNj<)xEE1T0rykuTzsj(LhCA7 zpRgSr%bk>-i7|QyQb>*$UyRz)rV85o?sOTVlFybuvOnlm?g49C76|FBZbqs_qwDC} zaAS_xj)+Nz;M0)mKrZ_{C85xQmZ9KD1Z}G)9)D4TY>M8CZ#l^MYds^~HIQ}Of2Qsa z^Wt+UxH1~c=ekd6q}LeoqT{VrYI)|HlJp6urV?7itJRc;7^pl~{+qOeEtNU?$xF`S z*)4d9HWE|VqB<;22bQ5a9b$c(roX%bWvkS6l*3;L#y7hbY zt|82RrM{J?W2jaY2k-VRfi{FIT^m^_mR*n7s4N)gYfkg+ru~UFo~s|v$Z4l2!Vo?B z2b7(ZHNb0=8BYT5y)=a#53#~$+$h9+UQmGh0mtXAyQ)0`V1SiSlI`HiW_D z$VJG=m}58CsAV42OTer6@mDoS5?xSTO}!pbl3B}|30X`+)zMdv19>~rqz(A_D4(YDoCBe;()zA6D!!=7oE= z-sKPKkL`f2=3Hq32u5%hTimHC$6yu0=)*pD;b;9g(+XPrV3OWSUk+a@jT{?mOq#gcKmKZC!I#qL5}8a*mYQ_XhNj;{5~4*QK>+o~r0H>d-Qq z-r)e;7m>5{SQIR zcD?mSBTYgZP;=3GMyfaAHc$2yL$x5;@H_5WmDMH`BNzPlT5JURZp6;+W~LBw z{e2Yb1H5&bMN1DEVAZYP&J_Gig-)Aczt1?npPrxu@H0YMb-fHoY29rT z6aopSGR*@TJYfm5@<2WkIYG5NKYK*x*4%CWHi`EnjTHzbr(GZyL(A*ssJ?gwKqBD& z?feU20nmj(7VnDQNaZYFMS|aN-T`GMnO|D9gG6$aqEX&y-6rDh6kO(n>h|Nl)&MF9 z*Y||91N*MW?<+UGy7hp8D=zPQ%k|Q2C%~8RN5 z%)i*orxZAM#Npr?TuItxjcwBhQ=Q|Mgdj%_mux#>+~KB5f;n36kg7tN`gN`_1LXfU z02=b5*u+A=*lo3%do=a^hF@ALhM(WxmH4W8O8$~~plh(?k7RWMVC1r}G5$iCP-34~zUv6=?XmeNvNxk_d+W0R~*|FDB2c)c>P+F*L zq#h19#O}aNcl`svGuB`m2vK}f@?%LZ2#}S=6=;e?%$4DCO5q>r>~^8{5b^UA;5wmv z7v+9Hm?5H_8jd?!Mb6u87|pXftgsm3VXTxj`})?F8%wd!q~!vgm@>9sZXb%-CyNwP zA8}GFAAiAHO@4EVhoVn#Qn8yH28teh)A6qR-%P$o zsH=XSxAx7PZlP>}w#IDbwifrZi?+#^xejQvBc}%pZ?H>afstGJ&12{(Oe9hrIvun5 zd#Ni;x_~y{OMB#?Gl(~Q_mgbvGzvF5g;R#p^6Be%Ll`f|C zPPvSP9(EoG=3JT)J=8Q+A;0*=pQ%;v+2RFsyu$hAHgwVM9GDc9VOWX0r4V86D1}pD z{kqVyFq7Z|1&4ygR@>1$?_3WL$FGf30wMj`B?F%oB{9lc{}B6^JIc)G;aEWXm9sRW zo~ONF%sJ8a#Le{VRTn4|*+L{=evEA(UiK}$72#au%?lqUk{nt%QM{80s=3UdBE4lLwg1=yz(soO69LywW&ziU;X_-Mo#G>&G(yV- zB;~Q;Ni#AT9vo|&tYU@Z#6SM}AL>$ROO|_~PW7#COTjU|Yrc?HuUNHiX!E1(kKU|p z*cNtov%1Bq=CJo~{%ySbUc9uDO;k~?Ps7LFEcNrML9sZt_jRA{&OTO|GVXK4?f?jF0fEi@`F%QVhAE=9ZA%B9xF#E%?H9baDWAYJJDCJU%^H9yaDV^m*Y+nn;3 z?M&O*n%Z9%bA(-(4iIE{dyvgbS((|t?1)N7YZYu z=$#Qh;|&Sh#TvZ`aB^?17w1`K4w}2lg_V1}pQp9uf8X8a)s@=T={w}@BE*sZ?tMPl zbc(i$mqMD=GbKB`u*|C7&r2bwp=Gm!!O&?-6Rp1MLF~lRFaIR9Di6focnaM}qpy24MJ?H|TAnw@{i*eWOP`Xw? zA0EBQT-Wc(tYW=&4ooacPkhiR6TD#jmgBFm0j zo4`zq9Z*c(HMLh)+SoyY?pu%T|H3%JH#u5$6TAZ@L`9UPK~GLIGel zhy^_L3HIWk#%=NG{Ff_zXG-*7nmvZmkD4bRbR2uQ!rI^l*wUV}iZnD*%9B9sZrxrv zZ0S{Q*_D&hLI41Gc^^*@^V%_mMjXb1MgL_cBe}D@M>vrGY==4Mi}Up=+rYlwE~(Ml z+~Hxz`Kxq@BtSt-WeER!yXV)7G(e4tS_dC;wKvEfJEV3zBxETFjYpWiWT&z~q^Oe0 zJ#!PaD41kS_lQU3=O$e#7^Wx0*J%u)d3P6u2_ts9B84tc_ti(Rs_$_(a&11!l3Xa{ zxHA0$7#QJ_9C-@gR3n?a9$*3+1)77Z3cNUJ*B@KMA`4W69Zlblww1GY<3 zpLqF=6lzDOdi#gGJs{^o$Jj*(+V70w(}k2pqVoSjwVsihu%xDDcPe3+fpUXibx{{& zhu%2BFM~O_N6RvVQ^sk1k*sHZX&`mv_3X|khAx#MUP|@9P#auxc!UA;^F&u!3tl%KR?C|W z*v8Cfe7u zjWLl5u<5yhrae>EU)Hhpp)Jkj1Ue*+h@w|I2Z1JPWx+Di%il-jL>>I|@{aJtI3awM zM;QOGULrwqTYV##kUj3(ph6*GoYg}!UTsMdd&0KUb;xI3OT6YFN}g z$HHGOhGfbid1yC;&584bink9t)$}cdpO5wt`l~qq)=ks4=4^tF5KM5rMqjt^N<_HhM8-wwt1)2lUtNv^UZ-`J_d6vY2Kg$Ax2=mRh*gZEcuju3gVo?|XD z3yQbwmYJyyp=C6tb)~C$^yQ$XsjU0VZ-Bnd^(v>&7S2k4F~zb(FV082mYQG5OX>GkSVv#PgXKjG;7%2lclNG)f*%4Se4V4UOE4Nm zHJDpti2W1WvC|%HbG(G={`n5$|DE_jv{j#(f>(a??epKd(qQZnCB6f&J(!xlm%d|` z;MI=J|4zMgf&HM!hfOiSm{isto?*3%%WMyr@)YH(M(M(bN+X*zz~qkcu#(#BH^|n5agz1Y+qt-l}s8u zn}7qri*t#Vg1NS8%w(9D&@FoeeL>n=K13#fQ9@q9dB|EVulL>(&336kfO9l%jQ~>& z=V4cgw)e>bOi?>aA~!)Wt|#*l>h1t`d&LWlL0_uPu(X6G^uln!R_3Sv1UBRmFNN6x zCuu0Bcz#^sJD$94G-qi?TWolz4qoW8U@Pe<0Wb&-W2%`>lVf<>~P3gHm8Qoo`qOa^k~4 z)s{--9ks*Tc~%gjQkWemp}H0?1&pU#R3#k@mgN52(TvZxuPxewB^3>$U!A}}Jz$ns z3(jNL>#EX)^4xU4JmW_gyDGW|S5i`kkir>_rC`g)L{RghF(_*+)b{$7|1(B%i|@5i z^OCKj6ERjA=;q!DvDI`ySGiZxPB+V;OhHw24r2lB`EtwiPpEijqFc%dU|?#?_RJ1l zYz`7{>-Qt!MQHUUziSCRyaPlk%Dshw>UUH>>yu!vzwb}2O4u%nO<=0nS&wO3TQ$ zrMW%kdfz2&TybfMFi(Fqy9Z^y{i4}a#x-;EGz0~!ccqLuF*EC)S>J6g6O8GFx+2)B zgK5lh=e`0(|;16574(sxfz zkQ2bF9+%j%h>x`FQ3+Qv(x?t(ym4_ME$!nCwZa3-nBwrgE{Z!~f6F(?L3-J_08KOHQ`CF1%5yctX* zVKfK2kvIa$I4y6P(ZJH+wdudhJ%md?ZM{A7*u8D6aGO{40eLw#$6hd~si#Vxmk}U7 z7Kuh`^qC&^^^#im-m4x@0fS5ldH<d%IN3ut0vef`6db>EDG}CxhFiCw}A(V9N97i zw_$ll-@F=R&CI>Ub%3t(3r)kV^%Z>`184glSHi-ixxqmGddF#4vJQpNJNnzzW95v( zU!51%Tw;T9j)Y@_b%K2*6UA(c+`dSAixm|AV=gZx=#*Zf?`UqSMC^^eTFb{NrL0*! z6LzILnH~vTw$Z_45PkPNYgYthV6~G=6(&#Xi6v}(Jb;3BprD2ns15G>!f5@l8+s9_ z!_}2{GfHa&7Tbq*+vuGqRE|rTNgoJCG^zCj4bF{)MSp`yb)F!Dr){{QSNT5AbNp*Z=bWwTQ)b4(h?IB`Gw#?#F}({RadldK8Dg>0nhxSkGN|8 zC>N){mbv!w3C3@Ze;p}pQ+3lzdS+-ey!!2QK7LdQWk22i?MZ}M zi8__>6B{5c z=|0%UAUW)%)C5Q8FmEZ7k7NI?J%oa`Z7B)mhUL4Ie747ChGl@Tv6O8`;LGVuu%?dB z)P+r^t+hz4E60pF58|uEr2h1ypg-)yBnV=%$GrntcfXCPQt^8th&pym+&ZN@hFRY; zSW@=}bWy@>?m`!=0DV{QN7k1=ZMVak{*-v-=^l3mSm1N5t=?QvfDWLXQl2~P_W8{E zD09M?-3(U>lE{3iiX6Yc_$qU2belmbY$v!{*g)x1W|5EP{vTWK0Tor!ybs?2g*5=H zh$3+n1r-qx1thx$R3s=WNrIrFWK?pP*>x3Ef}%)H1`x?P!zc)%^^vB{Q(GbGVZU$N z=Ih$A^opJQzowgQ9$kr(eCY1b~(eBVKP*8AFjiS z>OcCmpPLYiE#8D-XYhSy-}Znh51sL9@_UMi87m$}B%1*({nO(Y=UJ;f>PrN9Tc!t`@A+mZ3+Q0-1s6xoB4t9{TWB5~%+$#o_tH z8w)&8-(#iLJY&x)JAL&kIOe_Qu92q=(PrzPXH8kDKOFyMAhz@9&)CoVAHmpEPC#xV zPnT;vr*I~-`FtEUm(f(aULPeE4;}U3Q_-Tnne60w>CTP9I@bH)<|NOnckLxS;a=qzr1%q0t@H)&;YuV!aF6+%N&XDQCJ)p_@~#ccnU>YzgnHdY$2fmK67vK+$q|HM~4C~vU#%!0=PFp;V#)SPeUfxLJl<9|m zRx)mXr>U`ABJ{z3KtEX4FXMo1cQ~=+jtg)Nw)XKVmRo-q zV4}B&AN0i&4~tMwJd*dhd*BnE4XT)jN zOxM7tiy>9aHT)Ivei}6I^b+#_&W>*_ojZZg9pC1yn9O!&@>SS8f3NPNUC+12G5Uoo z2{L}p);-zUeWz5%`9+FuJF#AcK?!}A#1!z_8K@TUJ$;ghM0kMS@zdbcsZ;ig-A)y! zI23pAN?UoWhe?0QyxV9xSQRpz9#nLAfkLDQE9kMl57N)Lt-diXn2Mo+$r{Hk}i=;ZYKk$8g1r$b;h=30v{ z=EM5>D8^jMg&q#>^Zli!v>nPQQxU%;sKKLzvLWCH=aLq_>~q5WUaiT>;XM=_H#2z* zJm$6Wp7fY>o9+{&%U(;;=bCpd8fde~;@PtEuy;=3fY|gxPKhGB^6HdiVdIQ$mc`Z8 zDKBLo%akJNYl*ts{FT?8RVTybooo*4XC8QcSZ{lUfSc7}-PC9*8tridm5%kY2Cw_v9zu?>d=R3weOgeE=GU#2_J=CHGYps%dEG zJ2aZve{Kmfbkr*xxtj7+$WM0f`hqQ8+H*d^IE#&b_H@(e{8Dp@Cs)+kn0cSKke@e9 z`>`VhW9gFleLWrNx76I>lfI|ePwX?AeyUTZXCA?&W9V?T0x5kJf<%Sn{E?5cqlp>4 zTq(|H`0jn(Go6*Xz= zFBDDULaV*ciVcg6Gm-JsNrld1b*aJ%T$OX7Z=XOxFN?_O3wqlSMs|e^vghzOdPU>m5bwLo6ZMs90m^f!q zElr?)OxgfeP?z#iY~c&;qXTa(SbYq1uG^pCb8Nd|-|f&kAU9d-xsV|{S9hwffU;(j zJiE|Q?#tWPJ?ZIm*f9T?fHU>4&n%z z`rzk_z0w`|!NISf|I|G^akX3fi#kAukFxKN{+uS$)Pds&$FXQ4TIC|+*eN6z;Qe{X%ksCsN?;<7-l;~K%az{8iYT-Xk^6hlwRcI_1YYU*2xRe#vgYYe^n=F zEheBuNS)Aso-Qb2Jqbgc;=3wu(v`Q=`>d}@s@CVWsYuC{>f2IEt3Nm@_6J?R{8R2s zXX=epeD|v))7+P5B#l?fd2M}UN|vjq$1-aDmOC(?QdoTXwhnJwz2p^15Lw-CncX=>u zHg_%3nX=NeE2rDhK-DZxGfH66rPi(Y^A>R*1KXnG0-j4hoEO^7%^G9Xr|V8}e3=>e z-uL&GBi>HMvk{UG7UmI&Hu=M`OH@|nwrXW2jPuM0$IK=I^=xlfl7`&I=qL!9{_9pQ z%SWWlCaMm$+nDe0Eh`lRfK>|GgDLPm6iWfh4iC4MASZFpI`ajO*tvFpA%+eQ=3m~Z zsmwp=Tp@4j?3_EE>#^7^<4J3bDz7E3&&u}sNSXfl{3va0p|gTYHL(KwpZ=&*bf`vQ zwrXiWoVZ)Z*u!D0XtBq7s1qE!u#bPzJ1)vou9g@sY2SV;=*vKmvC>FxymnkUWwn}8 zh5$I|`n~hvjvaUHzwYrWD|DGP9chYBtCsF8OD>q;dA3vRDTl|;Q})B}gUTm87Ymk_ zDwG9Y3aj%ttfvsyM(qazbq1&XH>fCsY}DnVl@JS%q$qJKl_$#3Rcp`vRvvw%Ba3U< z8Y}aj7t?oIX6%Q;gJ)_eL}1*oWt66$XqLgVwmMev_DnrS3)MHDLiA9*F95b=|6MGn zEMUJ{hhM>D@k;N@sMVWsIr^Kk^u^X`DRkE+`<1Z_%`WFYU;CO9LuHPg)~(a4@?)u| z++pJUqUftblEn4ZOBGQb3+?r(C;3T^fLVbpygQ5!WvQ9sp3pqX-ga<(w0`AGkGa|% zv_6IBgg_79!3fX>NlawlbB8Tn!;9N?xUQ7NT>eOYB3B4`WVV@~Y_Ipy`eKP71S9K) zu1@P5H~@rI*;}WC)@)q?faWqiYD|~AJ7JVR^G&p`$8FMD{`N#y-ZVVQK6a%gYSk!0 z8T`lFwUOP9T_3L|^oCj{R~E8koGKZS(w@f;u%N%BL^I*mzmYU*}xU%$<2Iku{ z%qwmM8SVsI|9*@KIx*RPnNCcY}i}B zWm;>AfZIf#d8_4k34PtZ{>-i~ojnWLmnMgOZQadUM+tRtmo+!4|Axg$$D{z90)z2f z5D_?H|JA1ROAg)Cerqf5bXbKn_G;;%Kx{T`>(i2x-I zr!I9d*E&skUR=vKe1_G;K^xV4KJsf>%)2VWW7@)O7_WaPKC#G}#kAxfK72S`@9&v8 z9;_x_bd1M$`|6$ga=?qu1sa*G!sjtppO@lRC0S9X^6cf0$VCVw!ix@spPccvI!I}X zci&POPoO?VdKY=iaecwq&I@=U920)`Y3C;Dpffakg&la>FbUS}>9^8c=SN<*#%V zkOw|Ov!J~6iKD|vd7;hB4A^B}a^84$XL(r9Tx_=4*@6@!ULGC`w<7PU$yvuP`-<#V z1QDNGSWLpz*fA%g2j|8EbkC1{{tfHC;IYs&x)~@sc?&AAWDS~pxBSIrK4!Mvf7wIG z-Fp1{Q9MYgHnShdLWX6XBIq`j_9#)lqpyZdV_& zvc}5uP`d5l6%ce`Jm3SgRNL^1)*f|V(f~as=)q3EwE5!Wy1SR%h;Q{ws;?lu>?kre z%lVOJgf98x!7_zE*d8UqBC6&T6af*#{h$E6Fd9q_ zod-<^cw4-PBbJQx9&Us9+Q=qz-~n|*JUEIJRXhI05ZCK+^!tf#Uvv>-8ot?o^3Fe-D&eEu?V%Jr`uF0xb-vuU*Y;s^Lk;&X?v>cJ29 zC-a6PA0@J>2%Zz$ykj@k0x6c{Yuead**$P)=NMO4R;vEi>_X|hj(mAU%q5DiiVC#~ zhdp8;HOru47{Meu6S#H#0`1M2XPXV_5TmW#)>;f~#U8BLR7EPvvnx!IU$;iNj>P9e zoV;)BH1I7j&2x?Rx)rdZHWs!4Ci(F@eJ(jH`T#t6=r5aYU?!K=%k|6O3i!nc zS!Oq5L3^4;sW*RlmOf$*oujOR?shSwB{P93R&GUA1gf{UnZIK8_`KlSPu0AX~f zUhUn5h)Z5l4sgSzhM?jm$0{$SxtOjN=4g)NPlvJVwRL+gfmxO7CunDPR?eV%)2;{& zVN=n+o>zbT*at)mG7D32>*9(E$C^U zp}qB2;u(r`v#}ZV=;e$;Nkiel{98Y{Lp#OvUv;`7{>x5|;NlUfk5_MX{-CFnpNP=95dblDY*x3Aqi3L<4sq06J5Qs5&U3$$4EunrcZ z@6;{EOMi}KHfo5a5C^5Ao~RwkdpGJ(469MLt9a@W19Wy>w>#N73ib>|UZjt_W#@Rk zR22TKT`y7*cis{m*tNvLD4B6yPUyIq@s*u?>58>>^$sZBqEOQyAoMPidp| znIMr`4)TVVJXmsOPxR8CAxz}>JrdZ@%dgG-5xJjo^L2%37-u5?yYvG)v7N(hetwDC4HW+hs^|LuGyOgQ*vePK)xMfRl zS4E;;2FgyvQv4mGZsFN+a?wJE?C`sny`NYG`RuDudM60%2+ttSJlpx@h8O?N`$ILp z<2e+i(CXWX25@pKz-I1rId2~T3vZU$6mZ>e;2ZWWdgfd>+q?id@(oaAW7@O==^KMd zu5O_Yuc0xMIg~={;_x(PCxLptnZVi)<5v;1yc)(xH)%Vrc3zR%h(*^z-R*s*O?Q5F zYsFD)6~a+wp^_03dD}MPoGNh#$|e1Yt9{cY>#g*sF)=aQDj=Zkx5@qS82;lunv!Mm z>F=c>i0!hgQ>9Y1lCKdHL}7ii@envC|Ma|hq>C^xk84Y`SG7{L3XL-k^azu^u7>c= zL-C5B_ln#Sn2_o?9@m*C`js=m0?wx9ABpzraASxS%_tCx$JfQ zEH)f_lTo@9rIXOyt1P$bqhQrn9vpJa&3vM8G}-y)!`i#$tVG-AXA$WIn7)i@P59(@)11t7RroIWGo zSGzt|`{wfbl|3JVP#Oveu)J%w=i7R3HeTsDE01p#M3La^3Oa;geXb#nsC_(IC%B7 zfz7aMO`xbw`3qHn-Ne-jBHu1!cl&!ohq12>gxvNU7iCJDLjKf6WmDybTex4Y#Rq^C z?prr74(bI*iO`R_`dvglLH8 zz^r_BD!BSn9VRm*M=Ub(A5AGy(l{~js?CYw(PwGAqMtm=Tt_+TfK5nXU9f}Dgzsl+ z+S;?5jQih>4snznwaZNY>sL;j)T~24>*Z!2Df9gI;w&zpW$BmlnJ?VUtSK;SzTueZ zAgmsGOn9+A3Ec-JKDj^NJS*Rq=}uo;tYB4|`pbFLfWo7xFn#*RC_!SK?dFM7527H}=0P;dZv&lghNk+h+fROin^nNs(S_H4=&Zwzm8XM~Y$k8ww<_??2lYE?_Z2eNkLBLhkKdu) z8ZPJXaV^M)cfIG2XK$303EawKcUaL1es9x*#u=<;8f2P7uw!- z65st9ZeP9|{xjcET=VzFExj;fZ6ou;jd8d_^|>|99iVb2h{0_m2qypRC{*g*b=S7t ziLz!&5jsn!d`r<$=AV8x`f|{7;3VspQTC4g$L z6NEgo_6{q02`r2_FCWRcSHOyW{YK%#_NV@M>fIc{VY>_Kxv{V?o!`p;qE!8)=V}oF z+fhy7C7+hc9jmyMQY7o$c5w_-_#I)%Wazf(iw$%9?ZgrfGrG=7_-%K99lhVYn5hST zi+**xDj2BfIb+YKQ*(`)IYmkx9t#a9g?sl>gXj3F+hB-!xmZrub`gL@?;n(Fv5*WA zr*{#zp$PL{Ehw9Rh5C@Ayy3l?D%%xiiNB8LD7D*NVUF;Kh?lusE8>xyAcXn6|E5CA z5cw_z65LO1U;T!uYV453@!-W^Up@m4pBz3$L$@{${jpOr+}u)Ap<)EM0Bi$U>qb*nadvOyY-mJ`~oy_ z^b%Cahc3eVV}NgvRw1Oz^PeAWWlYew^jqJ1KPDtw$PWTfwsY?n5`?r|+;jSw{a9K> zHveo$t-G**OaF_mmJQMV$3})H4?=Y#>kzyl*Y<4(c5NR3OQepV25(O+^VCg-S~}_5 zMv#R%RP}Z+|9AI*x}mDT0&G6dNR<0g@c9PEi+aptB7KoaS)hT~)q6i`<$AK^ zwL^iqQ=hk(g;{6cJ#pLFSr!HJ>#ZB3H6OV0{M^FzZ=SLr>%!~o&PEoD+BgE+yXywd+c`r={%z7L`hL4iyJ&VOT zVX z?;}SHa5r5m4-(K?#YHQ(wMe&#gAdl~2L;F1T?c5RDYkBF$5UL?tsp^sltioppJn8R zcNTvmZ)i%4D~W5!SF7A|>#jly$QWkU5^9)i>7HG{)}k!lIbt?NS559^W#C6Lk)|!* zl}<}R5ITlk|HaOgV6Wz@7J!ltqY@|yKq3f&57>O>%4i^EeIds>1+=%6BdY>n1*woK z0e$&ANg&zBg1ICVA0$YW<7K@3%bH_YR};SFM>zeHg%RwzJPZNk+#x5GyJGs8AI9fF z70#-g*TGZH&yTijF;q?fYf2xV=XdH#n{o?=>Q3kA+ioF@Q|kqRx>bynz-1hW35Rdf z$h8q2`qS~a!J3KkwCZ#!!ci;~rtVW9OgTs27^l*!@0AVI8A5W}^sKB4I z3Dackoh{bc9iyaYg?1@?{c`}4NmK&@E9{t|K?%bQLLBG@jp{OAAidHzijs4%K*gj( zH^*(RCcu9E)2Fwxv2meWOa5_XBUz0LcHSxSy@ztHnHX#iMs`769Jx!Nx)!jLuPXZ? z&RxRG7o*hv70wUL%&>*ynvNqz5(eO;uN|l13u#sQc(7%1UhMNMBFMDaMe9hAvzE;Z ziq(wjS)g%hDqLDp^vN!V!rQwk=8*GR&UH^wqtC6p>>~|uY~Q6@=1C-ckI}y!UCC2Jm7FPC>6#Ji_0zX2fE8sPUtk!OQfBgl3vr`hO95+UpB{Xh9g93fq z%kFz1S1*6~=^}y3WU~RnO$w{$w&_42A`4BB3D9=CTGv5M-O*}H z^yrjS6>zy}1=>(v3LAvWfn#;-%w)aKm(U8foIR9U^u|OLq%-XN>62Idg})=DBg6&f+P7j_Sd@6L77ObB9~U{7t03UaFhufStmk;nLZ&b_s+xPGs4|1?w_a}pei z*T!ut-Uk_VI963CEuWQj#}*(DbVjToOIRc90eWU52&kdiKmCo zXki^FzPx~8GaveTmTQ~_vxPB_eE=n7eD^cRGmnjjEs#J$E}N>W-sZo4sP&+wWZMkd ziwBNYg5u8z)-`+TnOl((IG5T0JNGUag8!G*H2+=NMGsn z3qeuwWPiHs+FYY5+o2TwtV6&7b9HlU3|mLnpo;E`%IRsht3$Kv=i z-=}$Q#GF|CsQ=T}P1M7Nu-gpUQpFhDi%M^~ok0Foqj58%K*wfKMNv>He{{Do_6vo+ zM#iSKTd&Tpn?e-40zK z)bnoHb;QRQ#G8;-8jO!0)xto7b8AW)3cs&$F-%%)Rv(*7L$CzllNAh++W>?my-0hs zvU6pId78^snM&sz?`4IqxWdG#iNoA8vu;xkub~9=YCj>A-H% zrjHO0MRAlldJOYB3yp38Xa1pSO=u@ujMdL{{L8Mco|TQxt*@F1QvvtMQinKl6YXbu z-b-AsrSBHKmUxGE!df~EFBF1N@}S8>;{jT*Tk3Wd(g9F`Z|7XI;xB!M$64N*G7nb#Du$`P{h5>Dp8~Mi;Ivy;zF;4WRt3L z;qhi`Uk`mFd@B`cT}IXvFvYc-pbNb$NlGG5Hu{L7ktd`S%Neb7w3a{QP?8;4LPcVm zqWPAp(dsB=IOBje5-e$UcJPGjU8v03FAoG&OjigBo;no~!CnGJsGDu2ci15NaFAQ@ zam#DhT?PWvT8-QWjtYXRR>w{r*4A<3V`4Vp`7J<*ULEgE=&>ZR)PY`y4A8s*> zyJPF}-JrKZdEFirR?LbQK*!nn{k7OLm}GxcjF+l*rMVqy_IupSJG=?)Z|AnuV~@In zYF*^A=VsVaPx+DQkPdlp-|JZn95=jGhS@=~!Ou!+mPUF!KUncybl))B;u8o?%3;wW zR#t6Y8^d}V)WmUJZ!yp9MrFW$v?%~3jeSts-2L)+&=Er(`kW?x2LM4|a3U*Nw)GY( zwYqdZcPP!*zG7s4x+(U@F1CW{;;c$-*d;E}0z!mis5ETX**gEDzTyGZ*i!Wi{X@i# z+VZCCzSxWSkzSCA$eMZ_MRYPU>Uw+#y!Apsu4cJ1p5vd8oPX#@@lx+nLJ2Lwd3Cy? zAo4yc#OBp{9O+rUeo*KSs$uBqcYi}Dh`#XZ`)0H zKAg^I_YsAy8cOpIjLgII3=DYr7`KY`gA$bhS3zP(L zKW}gI(9W`tg92%9(rmlh!zuM{_!c|Ty3X#e@yvE{4%%KI=%BsD+Ma}ztC#dwFzNu_& zl^1tM`}4^gE~V^equ*L1FSSj1Nr^!vit#?_CX;t5^lJNd#Gq-=TC8pt@HYWe>O&UiH(r=zW zte3uTeL0GL0!%m?DX@q|`9rcQg3?51$Qn&y20(e)!OYBz>lEOWs6HTR+f&#EL9s9T zA^TGVE&!BmqeMQeyx^?jvKW1($HBf{d}frkQuuM91e^PMKh8>I14(VF8}dkQ<|j~L zd>iT#5BpTle3>)@6t7$S7?{LK4w1tW^iTo@rd6Cl@m%@hxia25+Q}`$!oq@Y(g1

~y$9etlqJB|Ylua7{$^x3K2^@L1O+Tl6BuyC{1IUSb{I^QDy0Z7>!rnIs~ zD7I*Hbxln-iR~{DY5sP%yqsiaEy4204y*ZO-)#~{QgPx9D=tIE>L+rPe8S-&jfNXT zKnPmzNfqw6t|ALzBE5w^FW&uPgpJanTs$M4Z7xM>!c5i2EUcl<0rfD5vm{>J+I;5c)Hv)tdcnH!kKeb8CK!P8 zx=AfV>d{mZ)u|zfK1h4e9?It@;88`{32Os`WlMC2Zk&+O<|T;*3^MXZ3}F-zVb3uY z5tugU1H@tdVAqr?IMdGMJpeNR$+Ds7wabzphY2$NZ5acrxZb47iDwzGF|$(&ZB;cq zkpeIv9wOsB>j9~)n1(YA=qF~N;}|~9iVu-)zy1QC4?&ER6)6LwkR>EL@23<3UX7;`GuaZL0gYX@PeN6g*Pzpl%F8`oira|Z64 zUE^Zy+uu|ZJQ;Flhsth=0uv7+?}m&{obqiv4aCn#w-2W#Cr_MEY{z*Rh2W~()takLH%^9Il!Jw=07BCu-)0hn(>QKa#4Y|}tTn3vqZ`Q1l z=+VKfE?R1ur5XDnhRt=g-Q?`174MI5zR%#s>2{)4(IrXaxSt<|)FHQ21@L2TwwP6+ z>IukS&5AuOUst-Zxpd@!K7tWJ%z7Jjf*~(DlQD2T=X?1`Dm9)rF2EJA)L42h4&%!b zYuSb>K+3N2#&8@KUFgIdDNyecEqPSkt7&t7ePQ^I;F<^i`henGm>Nl-R(-QPFx7@6 zkbcG9hQXS=Rc@t1gY8MKNY1?kKC^@Zq(l3Zr)B77!LQIswZwPm;`i1Bs%=Shn#MV^ zxA0YQK};uAiV+3vp84YZWQwX!=@^AQ7E^I7>rOO~eC@^^KnHP<8J~^f64`f)YrQ^{ zDo5%s?qqlV$Q`)sT@VSl2IewzF64^L>NPLfY$y09mDRp`eDm=2clHO3vjNqw`{O)w{8Tb{ zIg)<3HHvBLR^B?XuC1&Y+#cw1_)T?9 zO*YDLY~;I-AN9`LR;HUgpL#Gk3o z71!-0z@j99Klj%vp-2!t$6!OehAIa9W2K@N3!`I>X0YZmR9cSmUy`U5=3L%!o1{&@ zRC+Fx!hyDMJnYlXK~DC|!p3{uBeqr$ycpY*lp{h5hHRHzL)T5u9$HO24f|x&DK))F zDr`ssPSg^;HZH8Ljs_n`tRt5}Ll@r4imeoq>mUu1rF`dph-;)j(od}$3%->i-d}%a zBGztMf@apHPn#rz0i~>wcnY|zq+jv=m6KEr-uV`^4R%m%58@$m2@WM-jBc4bLVQ}x+E*e#A6qw9tg!p)vD z;_drxiS}0-(kt^%(Y#uJ?jAo2v?kYABUtlNU?81&(=jcrT>*(XFAc@I?JpWJ1_C~e zK(D)oW>z!qO1LCo$5nP*d8XDZE!B<~8O$n9HNEjYSr0qo-4^!N$oJdezqV2-)8?A^DqJxQ5nXgIGG!^$-)}%T=rt}!)c@t% zw{Op_oq*)LorKu|;WuAGnwG=s?Lli7aRQ|=^v*;-SOBOVeqPa&G8 zl7=q736=UCq)Huk<07wKT@3(#cIlyck>!-l48YT%KJ^f(aYqjiGQLroV+D~E*sH$* z#o?cJ=f<8DuNC6$4G)k!8R7&-2XpZL$#mLj2Sb0{h9pt9qtJ{WyDqpf{ghMpSs%Jl zJaW{Vmd`8`9_)4dGagj=ho|fm>I9<%ofBG!q$7F;1|&?Bew37PpfqN*T;|OM`T2xV z$)^6Sh6F85$x~D63-ZPJyieMYHZYesG*_$k3g4y|Q($mMqSQ=v>q=kM69haeAw zxIf8H%|hUeQ9^WdAbOE!vCqM{>kaP!uLBRo!i8nV@BmgP9Y^^&<>S*QX5z0sQM2Y{ zd(-!r_|&!jnxdua!D!%Sk=w>E2|sU8DupCQ0;bs-g@T4){$mYFw&{oN9q-V*qk3Ox zJaMwTq9Xpp$?>jpXfZ7~;0_Lg>Y+J4W(g+EmuLd5X|dei7R+``9H zmay{>t5J#^6IC_fPpwX7PCQ>fdRpWcSbwIt-Q0a?ImvpULMLJNfS-p#^>0R7sppA4 zRemz^Dv!F~Zd^<&6{nWQ-gwlLbsGY0VP?T0A&9vFBTwI|i-0d55qDFwG#{Eh<~0KE|e$2&c-nWzXa{`uu>2?#wSBLgze z^4w9gFiUT1I`=~EKzKdA!b8JRevEXzjBIqW=nD)b5mB06p;gB|7@+ZOW=6Bl@7K!F z!t~G{Ph_2T&h|Jpuu~R{vrN~VW$3x56g$D1clq+bZBO*6j)!V>Uq9ND+PHwqiN8C< zE-fwGe%V*eO)GS5D@=CU&2u@H6-lt|B{nH3ox#RW!2H>$uhH(o-Ivwt`T9D`P8-YK z#+FA-gA>6ghw!MffEUX+&Y2MHl-h7-uHGn~Wso$%b;UO^5fi8$_g%wgJWzVJd&_t{ z27Urpnj->(^7q@8~K?YIu|mVIG&D=QO}w)n2`7GBH9$j@Sz3*Q+y zTAPT*xv7*EFvBQw{I({99RU8f8!7-a=a*4i*Qn=%OC_rKr+QYBW;HigM1Ox^;ojZo z+ATpj+6msN!7UMPKN6ZZDm|k)v8o5+2WBx#y-{i0zS=3m(Tgg7w}8X#F0r<7Y(>cA zvuPhAd8nFxOxw0p4x&>*3&*FWFyjVeAUJIYj(wBADuB#&KDMf6$k5PD-qQT+*(1<4 zJt|*tMKE!4?qDyt-OfP=g}Xr86=|nWa17i5USwX9#{KqvVtRT6VCGSf;<@txB)0;* zFMet*?cay75!Pty-WS{Qw##i~K`0H{lITdmGyWgnzjr*v>6aj3yA|!bE?!auP>WQp zjkQEt(=wozWH1&Ul@%($u=5VeCS9NpOk7+gQ)dhfaP0sI7#NwDf}o$rrPkH@E!W`rMk`$=O+$eG3oI?Qh>;kJncpx7QjZ4eUpI zrirbERgvw3du?I9%nbAf@gi9=AE1zS9jr1!&?B(dm7`;S{)pPvRM_na6J7ZIbC_t& z8>)aS64ez_^jIgVNSg0~qyBj(&ab*u^EC%GWV18hM*Lp_eTG3^tmVr4|7%X(|GEHH z9nq5}Ib24eb+#7dssH)&CwKY{Di^W3tVQCl*YpOzF$IC zb_$0ORmM~Jl&b{&@JB|8u@RSq;YngcA}OAyurIU;n#zdVT`H? zy!?Y??nZRGVc5?7CG5y4YEBK28SMfaNT>x=sl6EVz0)Im$+cI1(LX^NoffNF8_8vX z7(78bq;|r#+UxzDGZW@Sf{k!L6eirqiSk#0H^ZEA49dRp$mg%daha{gjgz1;G&DrK zJVf)3y63j!@g9^0j4Et|m9XZ$nf2|*kNv;ykxt)oa7{&$<&an|NVm#ALN;v za?hTLJH;=YLi@8z*T>vdRrCJx>eYuK96)J?(T8zupSW#qI+zRLqF3#qVV^5W)>faV8b%M8RMMgVl=D8V6M zKEBc$A`spkJNET9@3n|WJ`;MZcaX-A@EeE`uHbImj*$Ts6CzS8WuVvYDv&L<~?TQgQh z{=!C#8xGB}xsTI;dapn|yNnJB5|!5ROIwlZ6Zwf^UNb&fBT{*=%w8grZSqtJ-K>=YEyhcnpia~IjDQ)r$S zW@v5Dl=PvCAf@bam|bBf!K2Q{@Pk-f#)iiF?$U@%(+t_KWzTd^Vo=?K%t`w3L*4#u zROufcKs&cLuE!^G=KQ690*v-6=p#k%;k_rJ&^XA#p8E}l;p3nnF_B%yVU25dVb;`{ zy^82=5j)4*K8$&if*BQUooR-&X5UpHvM-x`6JQ=Md5MUKFdCf+bt zmN}v)fOmT@kXTF~g-$e@Bb+m?8Xv%{pi_`RA-)6qz1qd4q@`Dw(H;XR){W$1`YwBT zm@%-3Qv5)zFIQ8Xea) zr9<*sV#ko3!@@LVzSuOt0YRV{&^Wo{FX>QQX;>n11)UX1(ITl={|grr*Z(#xOez@n zoA^N}a)1_J0hh+WCb14jlqC0)wF0>3NK&Vo-#mfsbH+<2CQLF?)PaZxgNAqqc8fTeFcX9V34xkupZOBw#}6sLAZOnT zv~RC+FUEfF@@R{b-Ps4UGFHSC)4duTOt0_^tqGT#jYSoLfNBj5a*~)DO0j(yrn#4m zzV%4muo<=`6%1Y?a<9o9|IHYu{{LElmvo@uci~*XI>c`qyICgxR|N@|Nx})A8XIV9 zX$d>S{T;^R%E*1bZP+anUvcUvi@~Mpn)YOAnmQWB^&n0CvnWJPUV+uBD0Dqb-YJZn*DJo2 zGtZULC8_wd4weIeNaiaQA&qpBF_hoO@H+%~l0F^-+{e*FHa6KP<3XPIe~s8JwU_gH z=Pu*E@am)qGqHqMaBGqm0S}xwc~SB@e?2W%V61tiL4FkOo_Q?jA-1d5j9r}ISmH~n zu4{hjyN@M3ZR5;s-$yGf=^v2mc zEaB!wd)?hj>;?ewo%vCR>6FNH>>?*??~DG;fHufLJtJv;QP{(t`4#wPJ3tNP8731e zTKJZGE7D&2plxLnFFas%aD00DwpT+K7)~2TkGW=Oc!^9P9=#7tn6J=rfN{v_N;~8E z!W}9ioYY5cZN|l;sL7%C_FSs7=-Ku0w3p8r)-Ccrlf!(H$Tt25&!bl<7GdlK3KIp* zaDp^L@N%$RHc{Hj?KWlh!N%=7MY#{kRi8A!Ixzk_lenjIetO^nL3ex=Gu90}O_Du_ zV|fjo9Eaik&6E_A9OlBQ$@8mjym()9$iXD^HtvevRQBTrVdJgrl+2uyIz!;P(@&a; zCg6S}`(ttsf<6UJnGF)v3YwY9<+@t3|@}QkI7MuCIYY524`nySYt=P z_^Z6J{krdrb(*Uo;_6HR0KoFa4wrd{w@N_V;&=J{5h^D4wX~0}Wnt11vC=H@KUuz( zozmrwe_^ujl2EEWkgrXEyR-q<%5PKLwTqiTx2Qtz-o3j7UN8rxk6fIPKT#nJaP@Pi zj35_y>KtAuZ6~Mv5{iL#`cH*`zwD)u&>sJ;NW90e!U!GFTou$AY}?kj(Tizv|7I?( zwDHHPU~LnkzR%3Wx<~4YA=LxNM;oujor}NEKeRbhSnT!zz`mROf&GQ1yesMHIR-B5 zvFHwJM0(7=v`{&`63x?%!0g?2ZOfB=gYTE925vQFpV^E%Rj|mdU{gz48E^D?**(?m ziyERw>(rq1tQ3ni1SW)@gWz#hH8qdHRFMlBNf(y^{nh#}?te;cq`1zy)QHIxL>i?( zFcUs9oOv43rHR@!Y1*Hicq(KzZNyxAaKwG=K0Ypy_%aupirhiIA_imKk&>h=ay6h? z+q7+4>6GPOLAh}jy$v6kPA#YTfG;8TM z-=R(f_h)M3K{n!%3$_^6n=u@rma#W9HLb=^crp7Bf`}l*R{s@GS%;1daxlwnspeG$ zCS*Mb8lUicQ}wUT_`VnbX@-c5ttg%5i)Cb3DH_czyOE*6Ir%GCCH+q0tGPQk_r!>d z*)CUx_%jeH5l0&(0k@8@#8m6*4Ak_ zzojhOb##{FD%Qt6D}OYI1wW|Q*ZsKihf(abY7%$YRES`^i-eZW3;}WoD^ceJY@ynW zbq{AMK#ClAeR5xc(FGb$Qi@TZn{XA7l_aQEgaA21l71oZU4|i=kd+nswjRhOcr-Mm z-mXKBApj#Wwt5U{{P~Oam2|%eO$rstl0`5xFDJ^~cHiIX!NKb17m7%kHKn^5xU zu|0G>40dZ}91XVtZP7u4Kx)GL^zI@{d%$T3tO74*EeMM5C#5j%j2_LH0 zTg-5Id@04t_-Q~XmKCXRTz8p9yMpVSF%a?}Iepz}xX4|XUO{m)0u2B(l!>{;U6_lB z>6D0Afzm#PpIi!BmN*-(9X_k~{CAMQ<0QAWZNQ~DM(>_q2n84sV#CB|aM2KqTg8{N z&d)@+2O{$9rcVF(@dMzeX?4s?+>w7R=7hS}zPISe;58LXK-SJbXwkMHyAP(vAhaL+ zfNYkM5R`?rW(OXZ%x(O>^b0R7{_v`w$;EB8muvbq`*KLx1==k;MXs08QNkuf(8zX( zx4znt>Vg6&>iDMNd=p@9=hf18c$>8GnaCn7|?dK&<_4s;sWBuWt!D57j9VRCXVZ(8nSblEXvVJdM9g zvKJAgg4s8gClf6>rnYZt+_LBJS3beKN}#NU=?U;X1fE168zZVZN|OI!;mpP-twL_1 z-4gD`N(s9BHvLK0S+mKil(t*0LFYf4RQog$bd6KiR`?MCH@e*oAOu8C$Y<8R_H);Olq?i+E$b4oO)d86<3fw@SAJX&W@Dh<FN`qwoH=+J`mhj_R7> z{oZpcKoXduu+MuLop^iBJade4O!>ZMho=_O_arc$9t+LuaQ3E87o*z-({`s2f*z-(BShT0+B$G0uN?aA=) zQK@|N9NElHDU;QCHDl`I?csnyfYuNPvwl-(SlDAsNoJ*om5F*hn~f_q1>>|i+f)1+ z&CxHeo0U2v#k@x>@rGaB$HmjD=1<2;=hu;e=VW>&yT$k$e1ls6PK~XfA%hu&VFqa| zUBWODCn=v6f>v7Zi(fj}51>5kFKF7D>E|i-_K3Rv@iSmYf&nIwLO&{&fVLZL0YpCHRUJ0Q~VK0Sf0l|fZ%1{i|K@G1*Av5}CFM0YpDRDVH0|~RweZdyRqhTz@yg#_+ z*bJU)$sUE@rt(~r$0<%B z?~`^#7c7R@!?Wey1K)zS6yH1(QEK8l6n-5Pj9UY$VN(A|`$3ACK26#xf1xg4&BIo5 z+xYDBTGa0bm<(>U`2ls)#q1=|YEW;+#spZOV^BF7Y#=_z%%{V*EybXT`aNuOax(ctFImdl0 zsUhz6&!a~X(2corGj4DtV@DLckP_S)5F(PsIubvY4EeDUEZBiKUAMTQ9-*SJDKY{> zZl=jNb)UAgWlgb|W-L0bZW1bgj|?MpcRWXRI%yk$RG3cr*=BM>z=-BwXi#H$Aogm! zy~=YjT4_iAZD87$Fjo*L>R`23p4}2AUn$6*bE z^J52pLX%vs(exZq*pu@D1T#)i6K=Cz@FpX-Ma=UoReu`W#{t!Gu2kG#b^f~;ajgNd zeIB3u%?;82D3!tZyBKJzR<0y#*tSMl-E+4#AHX#zw@r&Pe)(IR>}UPUlFmn6XAJx| zQU7EsMZ|Jen_70dO`N z+4<+1ilAj$$#(mr>oG3xyNvlqp_ADYb{DV(NT_a=dkUF?v=-3P1cO7&7q0m`r^k&G z!i_4>m|erC9);e2&6+iDIqmtRdw$A09;=dIbDH&uc17=P^&sghb{7Z2-boTm&Gs)C zr7yPw!g!xsi@7>3SLgMf0mb$*aY}l-8~hx`IS=38dJ^ZB z_UOfn^$6=AcpU`yWhe*@BXmYkO=aU{A^K5P$s;9-+%fCvz3;Mm*Gz>))Nllo+Q|lWmj1SxhIHbWdSVy^l=&=kf^>G}j?clTPN+h#0ImF6a9DhUUF#8! zg?8 zE4_90s#eRdC|nw_t(NwBM(iQ|1ckPah{W16HAql9>8sIw@Is!`U4|C@^8d6_*BICB z-M#B}09H1%T$hyeRG7(1lVpE9;%QLN-JL-H2$D4*&{~jf(6c>ZHxQ18j3ZXj@h;qGIN}6WL$ZtZNb4MsqAM^}>4e7- zGY#-AvMpt^Lw+VO36#nx7?K(edMlpjszi1N=C3H`9cP!F!V6@YZ^!{!=qB||t?$3) zXvPz0ihiFEfSfT3LsrHiWN|D^OIRA#lRzM{DE8vQgfQ9AMSwc=_oz*}Hl{_9s9e0t z${fTG_q~eN1_LEDJwdii-qp%G9NqDFMVJ|8q(%EqE&NGaM#@alIDQAR7}V}CK^Bo@ zr=`=Wf-G5t!x&_+kz5C)G4J%;-x>`I(FPdGXqZ&#DHz)hVKZpwTgAt-z#0J=&!{P) z-`4@C36B6_MrRI&$c*PjArU>CJh8qzri$Ast(%ajlWs}Jg|)PZGi!;CnIIc>ApJ(# z{|%WhD4dvqJI+NM4`yJ|^E5vpP|yNiQExo5dwe@Oo68myoHt9rsX3?CC;!7 z!?3vW!QWEQ2c)rkchV{JoZd&V!d7NtQifUe-1kWq==}pR zVqy==Mqqucj#Ow8jzLY7&GkIql=X8Rq=_MhbyTmTdV|4Dw6AH)zGo^@S}RVxx^s!S z4@v+yV)W7?DsW$tsc+_c4q^a$Zy&wg>$JIb9`3+nD1BoWl=1Q=@a}M7kvxKMv;1gp!l7?*kLKk9pt}NQgRB0T++(Sq}C(JEOy&)H(@`aMGW#p z_d;Gpa-q4X;{?IvV=VOnuz`$2w#KN;3ph|>{=R_e$nx{3#aTP~-p8UR@ZPLK3*U&} zgA5g9gAKkB;vWViC9nPkTrW}DGRevtb*BeMe11sgirUc5>yA!NFqtyq2D9NFN5_W2 zG(^vuV*}=X5N?b#Ggd)%u`CH8e2GD`0sxq?duX%t4j1ABB=G=B#3l&AP@Ei(|HFI) zJ3m6oO@(?JKu!I@U}`Whe^CjCOEp<^wk^MG^O8GWQLOVno);HC8MTJn$lZa{j39?`mp(-FyRY^yCYe*Nxf0X{K zs~FHOJF3KZC5Bsmb}e7f@KcMYB@W)X;gA|HL!-6>sUjNRFtm1ep1#(@_KMS(&$k~{ zMV;S*COO+(u9<3r(f^t4!9Eb2U`zDUV&<-Vs73d18M1I|M?+F&@$s4N%Iwk(W9Ds7 zCX!l@@#pLo*P-H?$Vin?beC~LX%lXAnf)ngp1a0nXdE0fR9B*tNjUNeN^t?%t^QzI z5J|-<NRZM~V{7aZ%0-{7h506q{$?mCAKy4;bc)--rt$b%$}?I)O$}W`;ALUYX&{ zoOEw|`jp+WK-L!W?>*@G??7aYhq0PeA56sZV!33!X>@Apjy;L_Ik=UcU6;(X8$jFZ z_)JHA={MyZk`qF3PhayY!A(K*Sa^$J;yoCBcC+G#AaQU=aAbe@wTNq-1Z2OL7NI|1 zL-aKG8H_YI!x&IG;&}Og*XA358G>$Egu6lGgej`oY9^Vk0DRB7Ks5BoO0QTYPESnv z3Ms{~%#&0Cc5opkDno!5^wS>&vxXJ#%QC&;{<=KKlXmu`%T3a&N!+Ny;8w~Qy zXEHHePc0P5aD$573$)zsFjN{OxPe0^mIeZiM4Tq1>udC(E)n%txL}e2np43+4-%b- zSJUB{o((BRiqi+g5`y~dh@5gwA^jt|;njAu#-X7jQdlW^X?nsSaOVE%K=jsb@@){n zfJ={#-oEJV3zkK+4T`!E!#|N-gcG;bYumQyv-TwIzQirB>cc5t)=-8`PoAfK+tlC8hUKD z6aB}RemF*ltyM(=MdSN{d{JdfY(qHhe^iu-f5Rfd*E{0G0WsdGf*YghX z)0`C5`wl#KQ#TS?mS8Zz|A@VHtO@YZ^2)Wnt6z2fO!)*6}E~C%G#=sD5Va7vBdZ%{v)~8K!z#=S>(x0AjO> zPkLnuSPWxGZB~4aDp=CNj>;w2m=5h)&gk7J?)T6zk?nt8Y*&%j5PDbUV*Jm0We;zQ z4r`#x%{AU(KRTTma2||C^$LRWdm^d^lkr*_4U<$;Q&aBQG(rX1wF379*WgnzaYpp) zb;Bal(gIK~4u`(RCMSnN4)siiwFhT41Q&Qi6&ynR5IhkMC;d862^L5ESQiSTg(zA5 zi7_})frE*-q?w)F+=_d2mTQt^0RWK+(zteEw7&YbOe8%Bz>Lumfx-s~K)p;yw=u9{@lrK=cUM~6izBaf&0J5rKTH|E~q`_HG1=V&~{6 z=;_o-bXzfsoasmh#6xmNa=;Sur|L0B@QpB6e1Gv#42 z$Ys@LBp(|Wr=QwPOf{geuk+^o)wR~puXg?iU-JJq|GT4IMA${)l-%BbcP*?RIZft1 zUo|{OuIMy5KNi_y>BUM1cdG7;v$$3JSf2DqT=e;{$q^pIZVcSRPe$8x{%-5D}<@jI?hIytxAb>y9&04YP|WufD!0i6@gRtcfD`EA92;i1Nv>PBRnH>>!| zo{)%$^-#tMu?t%cT)@`}r?%EtrGD{E2ZFs$CL^^KEvLSWdKV9XJ92MIVIhpU+R-;1 zW{NW}8|!5!?T>mZ@^_4n`yu?peA(3j?yKySknkD~Btm{R!^jqTmuVQEk@&;Gyqo(W z;(-WRFT7hN>(~9_I6ljXuRpyp|1bh&iP+{Qk~+k(9H_Wg2{Wgcbp8$;QJ?_8!P|Pi%CQSr$ke)Q44LrL62bi!wwEMMSn=AsS<;5S7=$BnL_V{1WPJ z!#Ks!F&J}^K}yp&GJ?e39Lx{wOdz4ZM4QOVN%m(7n`Fd0id$$;tb>e?_X6(^GI}6p z$-2oQWf5tD`s2=zn!eOStMl?WSFq-u{=pyU2FMV1eBF<~An*x#*H8uIFlYLpXeB|= zMnncTuh&MyrpLH`?1);arI`Mps!=1xF|fB1?08yN(Ki1b%(@HYg{Y8RsCY~G#l;Pa z)z;I$SN#MdSZ?Hrke2^dWmk>1!9i{yL$TZWznPU5iHyIs?eZ?zQfHI(52vw*hGDR{QGsU*;l)IUX=*D37e>9n8p3w zdHD3X%Eu_@p_c24$3{PBI->vch>kn}e~iePXFqQvUJtwBmPy1@wz`1xoY=O4t~Fit zz=(Tpfj+MXd_>P|xs#<_g^lUTZ~536x}xWYQD_Tw$C28qb+41QP4=6f`1^-odY!qU zb^}CTJ*7~g{qT{x_7uIss!zidzqRYv z3mVaWA1bqN)Qe-nIHPB1Xt_AQ@R%4kbq=H(q9x;HKaEy_LuMK5uEvvcx$6xSN6~f0 zF?2P8N7tGxeEd=5c9{_O13577LT*eCMQRdz>JNgIh}pY)^m++P!6xRk6czjs00;vyM!w%Vq0 zt^)i!ez|b9KG> zl%r@G_QA0TMyOOo_q|I5e#ynnO+Pv#HuIvThGNG3Y- zAPhFPE&%bCzOp;B;n9o@yNP^H;&9T^;epyI=0i6Dx_4YRt%nTeryXT4dw6j)_;tO78gQ$d> z+Q3`I;2&VVyq%ZQcwhK(1c4li86oRX(laTB20%Y^$?A8#v``o5zcz~+Q|klJysyNg z%M(xi^Zvt!SXxB(430xi+a0SWjnq;yJ`_u#73S6}7WWLX^+u#6Bpo$CpkB9F)_Y^#k8vA6ZZ`qe2S6r>Km!v=U9%Yk7(HSm5Db&d0)bY&!wYAOyva#kE>(m~ zXP91&O0}UFp^3P9>(=LhiwDXb^r42*gkNOaI5O507rx{J$rT7VOQX>yZ58uCxj_Sw z!gaeXU#lO-TZ`<-KJPz%*Y34g>kr(mzaXH>q%Fn=G%!{pkQf;t&k}Ki78djs24?t^E zv2EWo9LlcHinXdI5iIklAlGjgm>H?Q?;0SlY7PV|7x>N!27d?_?N+|7~^8+L- z21O~z6RTN}G}m)p&B7VM_)tx(p$Q5JwM0jF=4A9ew_4&`-SX1}Bc^+>D3sQ@BXX1i zOR)|-Ui14`fZLl^ebY9Rq`msyC z2SwG9L-!fJUm^i8{{$5M?Z`;%`1Bk2pD+u?Mv|!tIZ#)a-3qaz#OR9zpja6!6S3*P z(k+FMsF}wDctPH#dep@zp|$))4U35QJwg-r^~u`_A}chG3#GN@|E2Hx(a!*5)$bEL;g~30bvktc2j}$d$11^0tKEBhNj2WwH}k9+DA=@iKgg9fr_^ zMy^SsU=%%xIehHPQ$tm+=>az?0o=t_DkF&wjw4>6@TbAs>>9^+z$+}QJL3n0`s>1X zx8|k}9}@fE(sa(%^R{Ws*KvaBkg?l-J^t*im6XC%H+C5yIm{A=*^zA*q=9nM?Oo%V zb=U&Q>xMIG7?ZE=JakV_Ju(_)h_p!1%m$SaWf$`QR*qhrf492R*Ac==3}Vsv9$I=f z0s7ql>yU6G6g1>T$z8uK_bj>=@uPKV%x+i>ctQFC6dWBDE*1?{0g^L0XBXmgru=al z$k+DIC`5rIJ$C%by47g0VfBt>C`O}16g2xX+HpQkVeMr@6`)z18><{?bfqCEKWk|y z&nAgey%_(Fq3;gz#G9-OZmD9MN#?W_>ewFJ@R#^oFNOM5@%KrfO7t6q>N zf|MTNs0+S$57vTgG!)>z>>`X&58pr8^MWOH!(i0z_QCd>bH3iyNcjU!8X0~48cJaYZk#m#QH2lE;m_fBRRqTFLIx({T4k7 zR~&gkMbCn$`Z)CPfgRcDho5{IpEWwt?Ha;nk2&QpB({Le)ysSsQUWgy5wV{?U-Q-k z{fl>csf|dVrTI}=h(*?MDy%~}jg8cj#_Gb(5Jy3S_}z$Da-s0So&v~@tn~iJ;1UCx z=m9Nxq<>&%LNYUnvLQRW;9}V9oNyodd!&%WD6*!4m<2g5*fv=&lDZM7_B79+`TY}b zgbtoMNug*h7&AWs;GmDZ^cQipJJxjVa_uldPb|>(^c-OICy3f*R>eorSF~(JzX!*T zei^3bEowYgjqUAG%!;VJ&GjCz4(j!bqx(Gxptj?@nt$DaM)s~FU?xD5>y@FfCjuJ< z<44RT|J=l6vcRAv;6EgtFX4J@8hQ<~f&p}RBlBCtu$!DDAR(1Bt%FYmviS zplIIVdnB2WH(46{3FSYuCToRxW6e7TA%V7M6%bQjs+bU@Gt-#Hw;KiUbS(|9xKX)$ zHcXEKw&5GORV+_!IaY?doDt>+3l0n1@edCjf~bPp9QwafDx~bn%kJF}oJPC>|E|5y z*hC3P!jzXee%woqfdeEve~LaaO((qbcywS=+mG_d(7{N4@0{Hx&t`9imYWd5(EL7HQa zl{v9>3IILdN8URB30(Yfn7>_g`^a@flDOhwC9fb7Z?X>0{1cE)^1pV_6y(8@3O1UB z(pQpTjDh-vNb+^TX$r0A6!M7(->dU&IWw}KpT?%_=&E+4*aK9+S0 z=oi`k1e7BzGG6lN5veawv?4^V%BD#{0HuRvK#%OG#L^2H$EQzqs-4uaVjhn{;Q2AY zAZs>my#8t45;d$5JtqAq2w{?fo4t4KOc_AcD2TVC?XN>m2qH5s>cnvdW|2VXfiBPa zGti;+_=tVo#tMfZeG@{M%I+gv2l5P95WHy8pF2Z*QVqt1cz)<_78dLO4l>Q}BXwIN z;NpoceoVU?F9HdJBBHA02 z=FQX{#HSA)OiQPqtPjRs$;HiV$=u(e~>fGTxC+g|ZTF zrYH7H+ZN1hgjwqeKA>J1n#k=Z=Gv3gLBa-tZ?MZ66$Ta^t-!nGE^714!U~vk5h-!B zq73WBq~NG%r~=eY@>u68cj5cU{caEH{t4n`w7FA>B^@H)i1Q>mgF+h)LcwN_vxKq{ zTif)*dYb;JacaN>A%z~7751+sf?^rmJthZinKOdUFNWn{M?I>94*`K4RjYN1%y4|70w`tsog zAHuQBQDl3dchP551z;3`d)6TK2@tSvwF=gi3EcHDC7P=5qJXYZgl=r9J>axSJyFN|4K^NZ#M zENZ~Jq*b8(2*(BmIC#IR9*DCoa3OA@UceWIi#P9^(oO8k^!$0$@6!>ji8U6m=~UJ{ z3a|$_gEE4kIZY`Nt1iJrj#^Ty;onxw9z})_?KmUZ2BB0#F2moZ5XDj3maJuF6oCBOPrd^A+ ziUxMBV(auitX?pXa5#%z6}OZ&$9+7aAnBSKlkd&{Q}LF6$xwNkTK6Bcz$I6 z#QZQO2rA?#arTmjtLU&_+gjy=kbr<4t|uEw5%=!G7(1#^_{+wZSRP?M05pYZ%NG9r zD&nEWCFEG2rMYuttBk|7LPmX{2Qb)@ec>IE&2`k7tXrrGn+fE z1I_qG^m+n~#u;kXbM(~!HQ1%?uM{>p^j|=XyHi_QC=h5n3}LQpS&{70n&s*JaPO8O zy|vS50YE+MJO=w~OIz@RI*=_)b{b(sbJh5R^GjSZ7zv2g#5#NzzB^-^G{e{Hf;-kj zH-rQY-o|apUMmT;`@Z(iX@GNNuPabBDn#J?NChk&eUT)6nfbo|;#u({wFisK{(MI7 z2d_eEvri^gSjfA)yMmH}_FnD?*K2gLt(h8`|5g;^x6{q>oa26fI<8#r(nJA{Toy5O zdXk`bo$*ySiQfvIQmj!Coaw$sWVtz)U53N}&PSJ^67lLPF~ zB7j&;Jn;!KZlZh+^7K1VkPK#*WD!bX*$pRpeO*K$AE#uhcr!q>kUM=J4FxgfWm8ol zTA0xsg7;;+fWY2(&r4B^FVN^-Lj%!p5TaJHuq`{nsM^FEQSvYq?5>dJpv;_`{jk0| zRnR+!-xhl(cB2XrzSGB)6ygn4n1QiB)nJP6 ztqG&>gEJG^ahk!X?QyKKm_Tv>wBZ3q^inR?cxruK*;awX9euIFe-F@SIubqq@m<7N zP1XVEtLVzs;Lg1PS4og3+Ir#MU&y7 zQdPRxjYya!ya+-e$7Vr9MR;pt+wRl71;KrqN*0=_51Ip)ZU!>51o3t5p=S~upm{%@TK?3JMD&Uga3t&+8V9Ei$s_=Z>Gi z&HLso`n_&Yv_>!1WpJS5_Md&Bn9pzd*%iB&f9$j`)4k z?vkDDA0Z$aa`{T2d9cDvkbnQe`-B7CXhQYU9qL5|{|uAfkKZu_%%0MRm1 zyHelab+SS_l>gU;)d~-tl|4Vbl8(TJH`Lt8u7Y-d3n?}PmH>S%f}m(CLIt(jwLQ@L zAjX+=>96m7|M~L(kXWw7=MTl@oG*+rT$D z-%sYg927Lyu$m{yH8nOi8|Wjl{9LLdv2SPVuDO?5`8;YWXrMsH3io+VW2`7E=`Fdc zJ6Pv`2qnqq*|Zp4(=Y5PGqT;My?1XRCKBUkBF@mIltPH+hF&$lAIJDG7>EPtHM!F` zz8-aAya06C^}6~Nr6K5udT^~Ih?r?&_Upy%$h}QgUfv24_fm8XlrF6j$j9@cj#ZVC z9oX2}*(rw!#tN!Z1ci2xFK5>c5k=$}l#mEDJQuvy*C#&1k}d}zaJAD1KOh63Qgeun z0&?Cr?|#m&d-4+hRE!?+I69jA`*#nD!)$JIuP<6z9$|h7;?^>6&f*hx%C@WJAQ@Gt zsSG@-eb@XAd^xEtFNWX;D@Ir4`1-@8)!R&=z(|W{qN6+6LPtk;DjIJVXKcAG<_uzD zJ5Z3Chi8(kl8FCyT#1I)X?=L3y;xg%9v~?lOH0ersA-%6@-HGFw`E6Z4+w{&t?2OQ zMbx7Fs409ma>&qdJB$mlugReoqqWiBhx_71j-jRAuIq_G!9i{Q?d9Yz4^Tf|(>#y? zQyTRX_6P<4TFhVakXxtaDB%pq51pUd2^L?n>-Tk03mVCmxaT|eL-t$~I_iuQB>$D9YzMH0+nN%~A7A38+WGP!A zv`mChC`%-feapUNnQ2B-Q?ydn$`-O@U$QhpC6pU?2$f_D*|WdLNi)+tzvuny{r&eo z_vbTB;l6#p*Y~>4A9<$KD=l&NLz!}de z#C-zX%WacQP*LOnA$=Rnm;@mHU8@RcP(Exc_MRM%ZrNHTY-+J5KiVvgjLY)N-OVIX|T0R;+dF!UG? z29zz;HWq`$M@vd0XatZkZ2QGyA33*gZaZ*DLdQ*}+yze3TDM3JK?MGt)T5g(#-RC=k zy>}6LT3xqmuWSDk9_yzONUlo2<+bt~Kz(y1Qr)fhj>LCpBaZD{wj%_55gi&)&Qdy-IHs_>5^mQeoZbzs3#a9Dmy@#vs8!2d%c0U_P$u+ONcQbb9+S4B&>Xq7?cwdUY zAvu!H>V33#iHtG-5fHO4fV#a3HPHKAljlJvT#5Rq2y)`%W8*y)>QGMKi0v!nc4N}- zRA#e@hsbyVcjM|2^&VcmtdIKs+qQ0fPWO5d)a+NkU%Z&Ed=I13sL8nmTD`X5JU2|- z9O>^D0S;~$s5kXwS+DnzNq*e?_NLPVDn?)+I*-fAo&J=(4O4?Shf5~=2;7;H zf+|R`{VMcYo&sef_yowV6}(!BAss8hTuf>3I3ACv;bd?#7WTuHSFmF|?2Ne###y(a z8Z8y4bvyeWElpGvKZ^3Fh?4+lMG|P`32oUiJvCC`P(7-N44B%7qNN|97se2ZKC7`r zKV!g;Il9`6b8J1>)zSF%=X;~?7J+t`W@d=yzlQ{ZzCeU*6^O{DA>^pK`W2D~3bwaI zwVrz7TVVEedd9IiOMt$o2uxfzhG_a~s5$Froa#Qr01{^Eu)qO#a6wIWbW_96R!GvQ z8Jz2yR`$I&ps`lB8`= znlJ`n+lZO;63c`I19wOlaUc{ z*l61(jJ#cipjWiXqgRG`#->LA{-Xp=)mnD*QU6{q@YdNHxI_k6+?zH%Li!p`rln5P zte*}LEQ%P~d@bm*c@M{3!}RGfeKF~SqZL1{T4jO!vvj|Tiujrqa8~3|mrC7PdG5l6 zXO7>O8U%V6K3Bq*R3;PP2T3FAN#cFv(w1YV9Y9WSzSzAOJ~FubR6}aJlr%eI+T}jW zrxI{M{b1-3tc4N6trEn_sT0RQ_Q<%8_NW#J`$`-xlta&m#=N%S9X+5RaUd;<_H%(E zQ?}oT8h9#pbuK}S7#+xE?1xcsVOr$p7N-v zs0_6sALmyXJ;eAB_UxE#w!0go(e>?LB?=XS;}sFR6H|0j@?yG_+*%#p-y4xjIz9D4 zFo~U!1amNGYK#&^_W6BtK642?HZaY|)0ZGz4eEA{{SY9W|LIRd?*%UWjHx!XBpX3C z<+*EL@rsKmurvcu$o^r?8tX^J#T?jwqTmi*#KiH9;^H-+>4*`}48_GV2ut1U1CMPL zLe|XK*F!eSC);Co>v|W+U4~43 zf3M(ar(x|CHe1_XkEwh_dM2*lF&Kq&U z4~$EMZKHzZ`$tfRjl-PgC(+h`(Ai-CnGz^lWk9gYj41*5%N@R~8mw(*0|8nHbFLJh zID~G7Wk3FS2XGMv&GPf{DWX78gTf+Cew5Y7vhTmYg~|!PtZY;C1BW<#5ux!lHW~%^8bBT@-Y%!H;Fxb*`C{9;Hrdg4OOb^g z#>a23k(H9tMOju8b`t{d9)J}N0Lc1o@!|mV(^E?eB5fe-2XVVq_{7vn!Fv$3n;J^; zhQHPs-Vy2X6!QPjr54hP>67E~o;Za_K?OX2C-)C{_U0sWR+kb5o}Y!gbkSB3FMsYQ zOr{2uZ4P0D&}6nFU}BN9w@{xA^(JDU9<|Lo$#ljM zc@F4R3~hXh>M*B=L8zq9gmdce>%)M+AcUNbP~--GMHQ!>31pn})XHc$sr?v``~uUF zj>mcG>4m^2MNtBZI*CQogKVI&(I8myW4wF|=Kv^wX#S~1t!N10nXwy}I(Wq@;j;QL zgqbYE>;#0?RnUx*4}ncA5-l?f;i}8H^e_MbU^KhV;EF zeilK^{qgLk$-6kih_Wu@G)ACbMWZ1yGSUp~x+IBD4aA7(@eEYKxJl6#0H~9r8nWXy zDiA@kF`u@8ZjV{R+T6+kX>LbFahzfh@5Nz6Lv)YPe($Ccnuv_iY5d@>qHl{2)Kl#I zK;(ucreg>da-c#{F6rj#+Kz3di6K!|O|=&Q*mYjq-jv*t*^6c6n0#*nm#Bgi{=T>j zL-P1A*H4Hn**Q5syteWg-wP5zHDEECbJ~!BjHA3SizDkSAOuUqbh>ESD6xd4;|B;2 z7E%;Q`?N4PuP94lV%)(!dwzkV7(%?&=6>J`3S&rsPa6!57J2GDa6Ke9@$pQ@xc>04 z_w7_hgd~pw07IO*!OhK0lDi4JjvXWYV0dm=p!N5p3Lr0F>6&yT z5y>wT($j{62RS7Org#uy&vn%2EyylJ}O;vAR$XQGufJ|#%h)K8^>!}s#GT2cb6xIv^N(N__A@F7@2(QeG#(>5&Es# z>1yXUe^40_b09V}HxOkedWNVswK`I9DHfq}Py&n=mT9EAr6G42?@D}@*!3ZZPoyP`Qa8?E#yp804`MTZ2*N~5K60$ zSu9qMBq|UV&@QuhnS2|kJjE*a^r*cj9Gv@TYhZWS*<9X3cYYbxA!i6*=c}W%^GunQX4Cvqbq=wLk zi6h2oANuq3$(8aYb3HiUK!}*e(XUDA9e;uBG!p(s6^=k+#Rm*ECC)KmJs*AhzM-KS z^we`Y3whH}jX_Xi;s6>+3~f~MUOu<&ebZw(9f9Sbb00-4lTtR-Q&L*0fEXhT5>GwJ zD;Xg?>(}q5m^wBCGm1{xNfb`DVhuDAV5L}tJ|dBDEH7w*(JLdkX>-;<;WH$JW>}YK zS*FD$mF3%?K%-S%MhAe~r6O|}g_An^p@__~w%=S6Qj45DW|7&m1QaHMgPxoK*qwtX zka&Vlak%I3O$bTar>}Jp0i1YU*r2J#+}Hveo*ozTt(%93C0Z_pvJDaZ-$s0O1WRM@ z{sH^m3{?o5?OUGZZQi=|AX+Z+Fup5<3j@7>CN!4W^0oljV;aPaVUwiA6Jugxpt}_b zs(ehzZ{2WpWJqavh=W^S?;0$04ML=QZDAf2HLxcOO9;lq%nDa?%Y~Z$cHb)i<5)7H0 z;oZoB;a~M6HZFK|rpBTM9fN~UwM~rY$XveTrv9>HcRNlkGa2Xf zDWI^DPLs?GP%+Q$JaT1oT)$p?mJcEr1hY}_@RI4DM*I+Gv?Kl1#C{IpYQPReimd^T zaR}FVQc7;%5r}cgK!QQ_>3jxbM1Iaz1|vBa4eS=Mv(fd#?JtTR*1c3iSO^1~YSjQG zQZsCoY(K}#>H!7lS@rNC(e?cAAO39=-?tJsKI=@0$4DwuerK# zS-igY@LY1}Y*8Z}tJ>XMU_hBKoPd64Z8IG&4>~x&k>^(J+sJdPY${gYd zFjYdOuAjBb+C>iq-P8pA*2GR+#I|i*yPVJ%x~149XI#6}Sz^$Hi79r70t6QnbUz6? zDPxFljMJqu#^q3IAf&6t8R3{NII?>OPDLYSa02JPOak6c6HfW6$S)f)(M$zS)?OFA z;hlV&Ht;9+WepyN@)vwk*=< zCV38oJd!(B-*}O1xHphJv+mCm_wNEft_LWMMyRe%N5<&qWG1 zj=LZ(MB1R6(XA99aI;M+`Pp)T;Ltge(pbeBv{4LINcZmW+^m4r0Y-ycJnh_I3WK=} zr6vTgH3=q_S)^HCpKN#rbheJ=j6nkyZqy8)-4s{ri8%p}mDIEB)Y` zIo`y^Ld>m?RMy2T1mlt?QHlns?C#!{LJ7o%Rrr0JQ?Gx+nKVQCpt|Pn0tb})*)i)7 zaW^v3W5AaV!;R^O9?5`xh(wTTfet<)83PFD97Oz*4yF?kj3qGSTWJ|`m&(>N{lN93 zu!%Z7Lmdt%$b~k;7NEFMQ!qVg zd$#1%3LN@clweY=P48=q0hfqb^vh|0vnq?e-^#WZN)uJM#E?tZ9gJOiJitoH-O0(8 zXoMeywkz_e#@n7E=#VDD1}tHS#6Z#}N=l?W#~d@dQH?U|94|daULN6%X+sY{&Q63t zOGWJSK<+}i=7#a-xu|BfT^T4th`VU5tRA8!ca#zPHK$co|8RwejRS$cVLOL3y11)x zE9oFoV3gL&sBFNbmcV1B&<=@er+&~M5j#H?&W+Q{PEmG9)=fYR9!OXRPh!_V4)`Bt zh>upGmZLGojgg?@a4`E66yni!zS!SoJ0daN0V^BTTMBV9=>B^b99o*S|Br2tpP0k zQatnVb7Ah3g}Zwf{~TWXEs6+~00u*J}vPH;pP zU#tN3tx*3y&demB8jn zol7T7(9zeJi_lRh_Yp-X;DaP0DKGns1Q}V z5QDt?xWULc5$rT@!a`-oKZqhWc$PR$x)4+bARhqMLULEW;aY^R=g*yc0pUl^{%hkf zlNKoXxb^(ZHL?Mo1#v|@E;UHxS*&FZM_zzoEIT1_9T%JI{dNy)4PSeY@baXKo> zxzi;Z+kluxf%QSZYO(jOQUgi_Q8i`364AQm^*`ORc(Q;VbbzoyA`+n;?;H$JVX&@C zDUKC&$f-gBDiH{Oki~eC_oOnymQ!}}-rIpFfI7RS!5N#0AOZx`p_i_=P+#s6*-ys< ztbriBiL`pXAD9*k&k(y;I=43$Z4|UZh)~|OwV94gnwn5in9B~i2^D`!V&@7&iSI6M zHaN)15a)6X`8{X&wP3U7w|=Gz1g6+UhUV$(LYl{bV@E?k#KEli?bly-?2OKnftsKs z|6PaDI`8RNh_%3%UnP+u__2rPsSSXac2ge$OraxWgQ?mN;OUf-l@>|6LfZE(`Y0%K zp#93^I?{^C3P7_gP+K2E;r%dTsF+8;y=!fa0)?aUetMICp^+ zJ2p+$1rp;DVq6xO$Fev(U|?`ilgua>n!sb~I+o;5#)AaFk0cEtr3OynJE-TT=rLZF zeE3iRkGXa7j@xtComB8C_RNFPF8j7_-4+wmIT)=#XwsUHMbADC3@{PiBtV@@myR}S z(G)yjuuUO%Y7|m71L3^ED~KFp@a%7P8qK%2KwUTof)51B05S%ZV28|EKy!e-k5$3N zr6F7xe=pjMsGhbrk7~$sg|(iMASOvpjv=(&iw*xAhLe5u>i8AMTpw~bd(@$z=#Q@c zdw6^Oq!$fuPD5UdK&&dUWxWGGXl@Pplb{UTbl2uZsJD>Sv>VyONC<*6v=XUC*Gt(4 z99DP&;0CrY5jcxUg9M_G#QW$F5J$Z_4>Lc<5ErD`z1ahYqC|msjaR~vc%nN3?~KRB zr+h+Veh?~(W{~7sC2Dd3m~;Z%p(Pew%KqK&gyLdq4UQf!#ts77QC+(UQ;9rehF==d z`NyUu$;&5O*@A}+?`sp@hNxQ&=f|;3$G_LLGd2b@^`r&CylQcE=--~HEdZP^0N_$I z%K669D`BYfk+oX{SoiC`2$BZi1Hr9uWN(RZU!5o`vT$S_(u4u$$iPRCYk-fx*}9HG zPeez?xpF%KU_wzTibG+^bi()Duyi`M@hb2L2~(3kdCt2Z{T}}QmCXS_v0y0T&o&`! zUdK@UX}9JMBNXKhVVo^O^n1|x%A5*)5=(gp4hpRYL=5AR;CBM9VF88ykm8L79l8<= zs44@(i$zlOa&jjxm~E9ZBOzfPJ(7^)Gso_)hYu(@@%}*-8?KbXNf8ls2vD4gU*Pw; z7nNanzGVm`$QGlCN*A!zornlR_i`VBQFbqAyKN#|)?FlFLVUF-vy-a^niH4V3xztBYX%N z>oaYWux06vbTX__ZzjC>WH6p+J^M8Air`>O;<|xOg~)CR-vpYc2^M|wZcqm_H=T7A4f)r-XFs1q?Pu|xif>Pd4 z?a}DWK9~h)adF*+Zfb}76_3|LnKMla#jVX6?_g~%+wAJtz`3oy=BUPdt9Wm+N#6&HGcClEeSUd!@ z>|R@wTE0e2t@6SHl%sE>s)tNN9s@LLK|FPW?iY56B2Mc;G%hzL*3EgR3S4pMeXy-b z0|n`-kLM3N0^l>=h6^)Bq1lw`tS` zz+>Y!=}9ACYY}3BTDpUF0BQKa+6G2=f}9+STcl7E&&#~+fCB~kb@^?8^PDL5dADf! z#u%5)Fodt|QG|NRyFn5-5#hryfSs`KN=o$WuOPu(#?BszYzkez{5YHdl#if31Hq8n zC?DNLq?IVkp6LQ5#Yw1e;;hCKY6!$cpYlC?0$b5R0Pg*5l}YGqyNjS84pX+!ixv;# zkR>(5nGJW~HPNSl?2Bd^VU95q&)f-GU{NtKTY#Zs1|S6q`0o}RZ!8V~wjuYKs{Y?0 zB1nlwJ*u_jKk?6*CvMwxt@y+fSAT$?WQiaau84qx{M=#GKD1)|^@#QhnaHTMUY~ZO z@-LpJkDWn*f(+7m^va!^EBbYc3t&3BDCDf<>4~yJ@Gu<4kKcngIhYMwoD|8YaZQJST!n|2of zlP1p8%+*@dRLxzo^K}}B?;GeUzj_V_8?^1^Cs4wW99<(C9FYDC16$EciArA_5JP_T z$lqzaDlk5NK=pX`hvBPU^-oOUSyCuNSQQFwHIBQLz+@YIY2+V^y?`7zv~1e+=Yky6 z=V^sWU4$ut3T_P`nw|%dui3#ZrGyau19vC{f{rCe+Xj5Ge`x6N@#D7$v%-VrMGGE+ zP|(L$T`)Br6Eog+w@1(a8Fp`!|1)cFokjUU2)JHTzu1d z`LF{n=)&9Ik$-lgU&ebp|N6B){iC2_0X#egl+Yc7%^DOfVxGOWv4zLunA_6JUK$47 z=N5-hG{yn~!VMY^YSB<30C05V2i~#uGZ<~-$VF<9t_n1uK~D!AX>D_ge3pjDc^|{y zStx0Vlx(0425!4TiS|wDC5o7DR*~g$=KPPGN6n(Nj@GBaVm*3nshOLZyZ> z$6H+z<$8DSl3BNIU5l;3ouAHK=ncl{&MFqj9JYr7OM-sx5u6iJG>S$KEG0@DBO6gf zTLy6+WZj74csFd=L%9L&w{dv)LTtV&{FJDEGwdCJ4asdA8H`tJp&Ul9S202;P9V5x zhrkrayoG2|-uo-uveo?(8>A{tbF(lJi&47p2Gry6cW3JZnKZ?)k;O&KB$Gk>Q0(}!_4k3otK<2bm^eepMc<0xDeYg)N z8Z2svnrAhD$+ufTYEa~u{nhUTao;-2r&%T-Y*1BG8pkx7Eh1$d zCv)=gsYGs`xxn6AjFo>~;JUM5xr!lk6lj2cy&_7p6^frfa>+x#LDs4N!szDDMvT27C@K1Oy zi0iu$rru2S{&2sP3WYo-Uo&nf0C|Nbm$%jqHrduIeJNw-U zZx9Y~Xk4SaQ1nSatS(L4kns|u6s~}l3hzIfn>Yfb18(>*!YCfo`S=YF*$QXhk3X{q z;b2U47!T05fH0@>+~+5gl?hXBnv)2l#XgPOcz25ElF`KlSHw_>f}jWE@qAID*3G_N zKE(DojN}$%h-N2Gl$9t49R2iZhotE2PmC~8qw)mx+(mx`ITf}2t5(n|5C4b<4rl<> zu2)W;0N%*1A^w)8clIwgVF16LeI=iPG44VUu*`9iU>gSX$?|U0v~% zX)=e;G9ld|_<<^_}f|s50?iUjMt9|2>)G|7Bmmr2pUDW;Hl(*rq3Xpqh6Uz$CvUtB}sn&RSOK0(25?_o*&zfAV4B>=3h zU%B$OQ|ybk&HmNx8p>NRJNlvX8HL~8OH}acDoTTygpVm3WIAmzd{n$A>vd%%pvE+fkpU^ zS%~dA9;ih0N=>~gD=V7^_XBhBIs3#;kgPYsdvY$|Ws8 zGy`)l^cd#;mF13R+-F6hV3K1$u_>>eC4=E{~CuS@lMy;6ZrfAmyU2kN@Oh^G( zSSW&caAZ}*b~`!L;QEonX@fC@s)NFzf4lN^Y7rD4zkEj*xPSk1fE3rRU3-TLFN}o;e$P&%76Z6pGQN*p-2fF2clsPUJ`}qi-fF;^WXUL-hw_ zK>N{XQNuSI1OD~iOM)}+C6=QjKoXNlCm$alhE@!|-*YO&mfXl*HG` z>|Y|YKCiOZf5P!(xuk}@$>wjHE1k-VTX*)lHA%0R4qoq85f5R?lcuIyq@|Cdoba@~ z+$pCNcp!0Bk@_y#Jdf`5?^mG=8!g0^m)*|Difd!j!7?V=3bLSgy}i9}jHA?`S@>p` zs-0c(k{|Irs(gF5+lk+A=zjY6@j-A<;h95qy`fNr7SYm$9e;oD%wOyl%`Jon{0^|t z(`U~dvq1H?Cz$W6uRb}`KJ)3VvywoWjL>~htg29V;SBpG1V|6$w?NCSRsN4HW#<>3 zgk$LQw)p1N6hg+J4)05O3xi#G{rdHB;GJvq>V&v0`S&64$=pW4ftP7!!*x)Qb4pB7 zV*$hV541GQB&@|+fFdE%wkA%XP1Ye#^lw3vla zcJ8xZ_~%^}Mq~me(E1N~Kme@(Q-q`FK7H z!kU>&+kd6MzyDfzxNQ!YaL<*^>1PV1{O0=%3=FKvU;7_cBzPqQC+y0*YT?`kUw`fT z`S#0hj)?pp*R=HSYm(M$X)Dddx-%F`T&7KBTmK`#<5j)!7E7Xkhp@DMbxPf$MFcAs#AdgBh~_kCV>m{pO?7%%^U(M`Lk} z>Z&!+vO>+Yw{IuopdL7=yHPOMk|sf|;^=%RJ9lpYWq9hoha<~*JBnsTORzyg_9OQH z@}) zs?zlsIx~Ccu=4o$yqIt=T|^gC%mL?Ied^bOar3G&&|&tZ92B4`H$olN1QkRj z$oXVK?hc|&^?JF9=xGqp@Z=agq^5w`Y2X0|CZbN64RE~uHm$v0 zmfdc`>29ZYCFZIE6z6K3CMxQ&V_}AkopWA;$4;Ek-)g}MA=;$!$iEFKyLRU8F*a8MOLEy4u?Gbw{QPHUZZ(keJ=>d4JKRpEl066^4$`Qm8TF^;^p&iZ2{Q!YB04EOjFS<- z8UEG3y#(W6)l7WAxb>1+1>YPD-UM3yE|hh0upii1)Hj0Oi71}8b9^f6x}8;SiWDc? zNUXGs0ulX2t&9v~f>khe7-2AP+At~&W@yCbYFzst7tj3b;?W-+T#G*Z#81pdS;j$i zs-n=`ptR+yR>gVrWS4G{d^X<)ig1zO0Ju3$L%lK^D;tG{)ljkUb+TQ=!0gDq$XA5Z0?-+UimnGY5RETiK0IH4lA8I# z{&{l?P0+3FT3ct8u2($hjQ2;2JJ^Lngzuid&=`rw^LuWbe_g=RQY z<>8cu?itz>WWN$HCJ47^(su?!!OYZ0!eb5sj@nRc;NcplS8UWYr%MX!>~hdC6N^^6SGSa1ioBe{5}7X?LxBIAG2XX zneGr?xm_u}YO6yvYc+B4hCbA3fW*N>C4J4}X{jsMu0>*NcG-H52NN9}MOfsZ6+y|# zk5DWcdgV|_Y?GYsj0S3JFatwHbCAgvBsJOJ_S^48OS)Un(jW`gX-vC)Z@?Wh8x z!O7IR?-F2nJP`;S`RO0$ zitaR`Z861(d5PS8(E{yhYCCyaRwjDysFVGW?FZ*vmaWk9dpe?lY8glpQ%EC1n@FFB zjQ$D5cl9}sMvCRdi%rY&+2lJ;Ea-T&yyI+a6;EU2vP#9e{Lx7cdg}X%X5t4%INdVr z(4sDIuBa#by9A)5WrNja7=M8l$E?R3`a@Jw!vPDDbcm*l7&+VP>ah|6`Pp>BNeZRL zQ#lCC)Ob`!qb-lQcW{>tABBE3trT;55|2y;;h<>Vxrb|SE=nP{3$~tu{wlVS+ojsob{f+@GKC z0)4F#2{3=lVteiu)DYz#UcLjy?pWgrtt4<;$kYRt$oEsf2LjQP!AL?ebnSINphG@s z_nG+=5!tE0>XAX7w_t&E4bvtwIBZiBPJE2&56;DiNvzD}OvP-QUL|zF^N5Owq`@?} zZ2WTRGi)9>zPZ)nbZQ_9Fs}}IF1V@5T^)4 z#&-1Sit16U9*?-+W(gA$B)|h75|ufXfnq00me;9z(P`=Y)B(LXdQUqpz|iY7F@JDT zW8~wgALt?;6*WK{`6B4y%@DZ~nKiE>sd?yT_32A(U~~W+9-$De;M;vFhB!r6bB9^r)axgTlG>tE@wyD^=q# zsVrcdZU>KA%h>qcvdT3(>~@hN(Hrpy`HSi>iJ_g-1*p=u);dM$;A}au^j%^>{Up*b zBL9}bbOi2XRAnazHP-Aj^D1pZF4T2ZO_sU?HLD*-QK6LxvY5HCOc$e*{%Twc^nl8> zrc0As41ldgEE;o2jTC@u^g8oSmMv%Izx|8aT1Tb82f$bQ9A?z+%ip~yJR)NIY9Gn)C)?9&O? zuJ%mi7kKfUj8b}7(VR?pgpciP#8$|Ilm&tS0!(p?uTmWXHBn^EWYpWr2fW{s9q`cuEl7VJvwR2*ki6)2BySLp?g z2&l5wtD)&S8G45Z^((TE?Yy9+>+{!;-( zw7rNXc${ElfsBkt$P5o_F7PgRBaV>fIeKw-4(nP*gS_fHw-C+K>NYlsK-EmYK$2yh z%@Wcq(j57kCb@oIuimyI>QO|Zeqi`U?kU}^KT!mH>!*(cv$?KT4A!t6-p_XkeB1Vn z1{;SsEfCX)Z(KBn(tR4deW0jR7r3g36k-mrz#dhhzRxDF@$L;vOu>Xd276OLyd1QS z--S)x*SVmJekv({ERIex`t|mMQ<-eMvI@lX%AErjz+j9<#JDOk7hFF|XEyX|1z`ni z2Y;;xf7Aj^5~?FWgM#M{SC5Cll6~`=6Oel1upgy z^qdwpFN*x7G_f-B*ByLvNoJ$8J+*yjlSf%Y=MzbrAV~eJZhmef<=D5qtG zV~WIYo4y9fBAy6fa!}P1Y-}(|HHUhJJDTSNx)+X+s2{c2fC$=od5YSfaB4Ksj9(;9 zY_P{oQTw1(fM7`YW+DfEE+r*}bNDGjRM2j%rP#s!)WNJwJ;bo~l3lhQPzWeZ?m`WLs(`zXpFDr$*x%D6;nolMpC=}S$vn?08w+PeRN z*Pe$)brDtGQcBF+{X7?KH3_#U^q4j6yRMW7PVe(j;~AIo)k41a#AbRxuD#w$0`0Bi z>wdWRJkohyUTsork`cQHj5ZMp53sUC7y^nojYQQooFs}l;(f6B-m4oZ046cg9YKEp zx;WAIxKVkexQ4W+sCzaH?Nxia$cRG;26Eo7TaCF(VWDEN;oy#qeyddj50$nNa=m+o z{(v?XaftkcQ|fC8&RIG_ai4Z$Zy?_VqDK-yteQ%pm5{iDt(Ko8OprT(zlsT^T9wxig%ATA%fl{Or1)JmQ$* zH8FH0$%ygs3h47eVTo=H)|nm15*=dOAaHOOdA<%PiAJ}F0AN!aF2VrE*rb~P7bsAc z&>#47p)eh==UeUwzCrwT?6phY(or*MaG<&;@x?SlwIeMyR8}=}vY|I{V?DL*i>kJ=f^BnHgwJw#iLzOW2Nl30^AI5m!p>qQ?sv zMPt~p4{k&olauN=mrmXHFd7RJNX3SFz|5!VS>=!SY*CkweaFTKgvzHa%1HCY^#{->AM}3C`8yzW`KHr!Tj$)yKg^Z5g3F`f z;cq6o;bcNmr+7rflie7NtNXBoHGG=1qK$LA}pK^}IX%capN5Z!(4M|$D1<1xViHliY= z<4Er`dM4aKe&VRbR3@`09pOHgVeUC<5ui%;Rewt)cOVptx-fMk2;{2XX&E>**odcT zZKOj96RaE12kL3`5GQ`>@`N(&{d0kj@Ff4?yMp=`0{aIx1*^nW?fNcPUL^Ysu@!yp z%%U?stQpYfEE~riAD=sUD%7zFimNz!MVXxY)-akNTWUUu76c)6?`yJjtgwBCkbql4 z!-JF>L_|b(W;7!wm8s255ypgtPR%yk8`? z7Y8`+N)g*^I7%xF6md!bum$kIeHw8Ay^OgES($YUEsP)pBv#Ngxd@*0p2Yd}^cilq|D1zuVoUyejwbE-?{+I?I7xMbzKRQ1}E=96D{$gPPQRL)nW zwD_9RY(eScd8FKw`6NTfWhot#D|zUwv2|Z{5}tvyH=U<}RNSbAep4=MBlACYV9)Dlqi2q@UZ+?3*>cXgTMYg zV(B{!HTYb3!{xw}9_AL-svkQyXk*k7x;nD`nEHW&UrP6ExAAQ@dN9~;9^0kemFoWI zZ)d9BF8EG%3B5(2csBJ*x`C|JyfKczIm`uTx})W~ArDrIX(e1Z%X^ zR{>`53@Cc>nm17sjd|2XshU*qKFBf+eV2h}ef3-0H5;BiJK*0VyzIey9EFv&2{~?i z4@pW5<>+PqXm{3%e)a5&TUphYovAg}*{lB4+|vDst?tJ*>&pF3HYw3DF>B6Ue_Jr* zL`8yI)w5u)Pw6B;VJvUBVIx92L`DHUNObw+ z{@{shk<)HSb#M7aZgOsvM?@6=cI}2{jbVWyC(5vIRew8M$x*aW&;2E7qpLpP{149K z;bEC|R{bL*BfB?fzpKHtX$%ADE|7dQe-xijn`N5~g7%fk2{ z-$u&(k|_jR;wHz9gW>H&v*YJcTD`7QBtuaSrL*A>CcM?jaqjaZg3E~9sKCnt@5;% z2#%UOC~{$yxDpJdgGB;#HAoi|UUhV%$am6V3isRv$k z@`i4mmwf$pm7tchFI#rF{i5V|OCje3jfNx0j|c2TV&Ukchmc*n?mScXZ6W%I`#w!o zh>Yt&x+e}DMaK^OgR|YL9v_nK@~GuCW_H@EX7?M{AF}>2E_KM5=0q`^}~VetCcVKt^la%DcSw)5c<}cX zzY4mQm(O~0cfjlI>zQK?PzkE^moPXuB!4r|bIkSaJ03Sp1PAj;WMC*zVR?vFWS9r2 zn5(gQnMwE`I5<5|}gzVUP#?V@CibGjrmT3=&18C$;!xc^C%hyn|)%by7G}O}}vV z_4evg}5iCpz+)SAXdGN%?;Q|sn~wwg^) zmLToVH7}QZ`|Y;wK6I#gOo&&oco@Np7@ujESW+E7*(HASzwkwc+@^2u^}2O;t7~U@ zu$)(QH+4MBzjj@qd$Nkfhb#3tad9?RvP==kHsf*a9i_GuE~cdnDgDA5WqzAvs{J z+l&b`hc;Yyhctw5I>1!_?k=u;^dN1ck=>u8rc`%^L zoI?$SmN0Wy;(5Z7>G}?#7s}nrR*}4hVZzMjZdgXJjCtOU zlmCE52fy2-?fO-+fsfOoZ{rT&-sNa->j#MIsLfVCHB?%mGD$Q6>2(Wf@Kp2iZF z6GD(B%7;o$^K=gZ#(6*mkk=l(-G%vncV-e{CGce z3=+-P1Kv+8F?AnoH`EOW)Q?Ctq^C^<41?$)jGOW|#nihT!)_>!an*@}lm=)b{ei8$ zeTrcM+HwMVc@(Ju5{d>pt8&wxK6&!OXU^OMXA9>dp+{AVz~KV96)==2%moj7O%Ab~ zK+r2onMxY&zS!Fz5*XNaU&CkQL*2&QMjLHgG$JbuJDsg#*a7sXY~jmv=-}J#N%b+U zE#^$)j!!0hlP4ZN@3mc`CEhK(Xu7k&UtznlF!%nwE8J|fYfP?w^~*wU&Fm&okDQGi zpRP|^XDXj7jZ9BcvaJcsIL)iS!%P-UGEZV6^U5OqrPT^MX=K?42%mnl3S-G| z#Nwa7nF7d;uHgEQ^`u_~&CUR0!3z;g%W_pQq3;xmK85XkQ@<=bJ9{>8v-0_Z=QZ_? zb+PKof~W%vZNF~36|6ZeJndO+#y{@{%Fqfm7JN_M=T1(ypIs8=xh1lDTh*O6RpWw@ ze1eg^FCd$f9O_6kS z4WSI^5YQWV`SNY_h8=Cn6!Um{jwcPnIhf+4Lq2~Am!4UE~Fj5n>NAM5m*^jR=UQZ<-)Q`rEHzrL5fIEf98(` zkmwWjHZ#Q$D<4yu)zqpj81IorAzQl97Co5JL!^-c)n?U^fdHV)H)~-t-uAH}P!>t3 z43}%Jnxs!4O}whGf^FlcQIM?ZpDcmWAwnAMrp&ZeDB_Y-I8z*X4b#Y9#v~^iIX;rM ztA;WgH|~XpK7W*B4SEzcQ14*t3LC4>2M%jk{-W#m?WpWFr8Qv^l`!`|so24{YjlLU zr!1`13U!LKmQ2wPR8PX6C*PT&n85?h&w#hNUhz?TnVah*!;?r2 zrNb+6>uN?uLpPV?yd9VbkqiKbZ-x#cqYtskBvQanuIMPhk{xGa5zj}ClF%{s?a=AZt z)Xu?XhqTYBQQxmI)orWiA{_|R@CTQN@I_N^0Gge1$Ied^+n`)}ke=l;SYHX~kkX z>Wo=#Evg5b5&ow&-PyMg0rfN3IxXO!%&Vr{rE5#4-Jx7Y<9?XpxK_Fa5)XzlO?lMR zH2QrH2d>nP>+8W$C*#ubZ3$>*q@Y1lhM)t~=-P78*RtC= z*K2CjloYg4%-Q0|7$n9DGPTgBZ8RyA6eQ3(f9*{W$`+(#2K|kj^8Q>i0;OR)G15L3 zd$I$)+b_UKTBtvOozMw`By2xbWelBy96X2XH*cC}MdR{Fc#-|bAKwn+1hvW07^>EH z?^eFQvE4STXt$vj2?oNS3Z_v{IKVbZ&U&YP=!#$mksMfPkvIv)P=9yhsnRtlyWd1w zNeU6G5|^Nz&DA1jOMrmR3GLMo#6e9lM)#A#i8CgN8eY0VFrcE3%wgb<8SdD59E_B^aD|^eBPUCCdUjR384viQ8S@kzG^oOiRq4IX6NGS3EjGw6fD4-V8R5m5v-jn zhP7o|4q54gxHk!zZ3F%gChxHORHH%B2+2&LR4H3$z`yb*6y^`X8^h`J+D(EXLb_vt zBOQ?8#-P(XNOrQ9GH;{Tfdq$xCg|;>`;8B6^v>_9JD70 z=6@3ekec#J>Mh~+$OraGgq}CIhDrJi7&|F127DL^#PjkOo3)=KCz>~K(MU4beo4L?_`D1*01K^*j-=qM)A=;999=Il&`+~=HmyM zWSi{P;PZ}8hll!Sb~iIex&~Z`f= z*_i)Bt%7EmMAS?v9tY3IaKk=*#Ppq6>7!N zL(q^hgSzrDrIrxDk3zjFaB2SXNphBGoxHq6j2bd{}&ySL)z=+V!3D>myWf%#vpk#4l+)|&G zw{O#69`;z`h`P7mJ}Xf7k3-zWclk1JIfv%fLCfp4m#adTVy*hGR9pFI-cNM$VCUK0 z8flY+z~b8ca^98m^E=*bS(_;*yl6u6$^x4(F1_8IJCt$~Q!QDok%}=c6CV$#zcqMW;WbQ2VaHtB`VGVn;(}lEVBAe{6ti^+=OPQU}h*dtPLZ2~)@| zS+Kbz&q$$~&5)gmKaNdT-bm9H^>9eL@(Ky5!lh{d!V*ww%OM605rAL<{&*D+b}`ZH zXj}(`pq9&o{6B16XFycf)*Ur!EJzYHDu~1e(v>P8ph+x?>%Rqz1LoA?JXlYefx-^Q0l3-;NTLw zZNxy}IvL#k>P+Bm_XC<1-n-WC5cr3rLyp8|=G<+RT*eSO#F$9Vb*`(c`@L-(B+EUG z#2^(-3z=D;sC^PnhA^*mf+b+9@ zbUvrij=kDkm3xlpMPH^7EceAl4*j$i`7!87;Y-}&~S%@^d= z7!g9uVJw1-c0e5m3gKyF8)eniS=Xyy+kkCIfG|SJMB?=ssu^A_%!<(>`2-WDM`Je2 zXy7Bc?5^9)Sbr)>06>X<89bUkT0KO2!wVCBAD)=FgMRL%&rE6ib?rR`Wq$pGM*$RC zKuZMXAZ^yw68kDA>J{aUP%A_3cqBax3kfY~T&cSMa1$)qN#?MCe&vc1Iw#)5r4%Je z`OKm$T4TgO){9k28?7~xc410QED$jcp!e|eIWHq4;NoQn01yP%yCDZrh+@a;z-2TZCC}MJBk3b3t4$@C zaCNrn1^q?^Q$4@ZeI5Pa9={SIDj<}|c6$zXubxIP6JmpoztiTOv6J`#pH0?Q@9 zhxPC-1&>LF5Nu6_gHs|`rSYQ}HkyJ`ZV>1hvB!j96r#?!OjZus|lCDisYD}(5n>iO`lhz!>Z`$ve?U33?aoERBmmYfTLXa3})Uaqs z%4#1NJW>)?sm~=8o&e6-bL2WCRJyRNkNz1wPU6xF3%zCe3{;2%M2v&<#`RIfq~y~3 zxnv|qOR2kj{#+>7n%~MT8M;;vQq?-r1mhaYmQ5@^n`@`EMqIff!dJd5v7)N&Z)4+Q zqsutxL{9bZ|75;_b1*{qHi?K-HTR_R`p}sq(~7nvG3-5l5fAde6k;XqzlSFd_wD*2 z!?~zAEV^>KEy{yGS%(&p0H)$R(<&vd*=wYS-`XvFS_0w7fT1#ah815IhMVs=An zhGuXWyZi9rtkr>P0VdNKaG{{jk>~q|u4 zr*IBKeAVog`R(<+onw2Jox&XV<@Y&P&tA{|O5U7t8;tth(U4 zd-3~~E!c$m*_H3u@K{`YVM9A$)aa$~>a?}7-dch}<$c3Y^yOPga-(4dxP#+mjXi`U zPH+PzmXC}|`eB$IAtxL>9RCS@c0!`t$oY5D+9^~!dyY%z(TtmsTtSS8^!_e|hBpeu zgUKh>uB|B5(pHXh@2Odko3v^)+}{>($aTio#@M-O@)+IlN&C)*D_=gHRRjSY2D|3~ zM$a{jzkdBAq4pxaO4yt8?=fK{+NaM@9oP-O{2KY^if#w3_G6dAji;jX zA1!=t^Bra1mAH#`$;lxpebKuAKPnuqDN0I~hy7p5i@Cp>*9@pSUvgUE%A>>4f0-kC zlk;3g^ONB1VcXU3o@oye=%q_NeNRQi{*RCdzgT4S);s$332W=d{v+!>gYZj=@tcbJ z|M-8}6$A4p_E$5(p@y-tIk_>CB+N3zL zZ;l-PbF=^XOZc;(Ye<_zsxCxRcH_B+Zd?t9SLGxf0^X_78U?}Gvb=64K+fkHNon6`J zhg-`0eC&BTN{J?e)>zLa3Rfb8rpXuOefBT6$q_$L`>9uWwQ-cU!B|&Ya&DU{JEi4r zRF;^`nnEMWwiNCLQy!rK9wF8v>%V%UydQ6L<*&U--uBDOqi=Zia`QN!we=fYei2re zvq}uK>e3IY6XPh(x@VIG*K{nr@%x>`IggUHEPQ`w%YVE<(Y0WM;P5o_U6aA=R>kiLjI+i}(NFvi$KoV~MX_IL!R!9Rn$vZl_hU*hWzg-j!1KATj9Xql%8RQ1o6tsO&#Cu<-Dbw%DdW>-`GP| z_0Rv`3a+T`0b6hY*VSx6hnOAj-u9H|2W@KXsgl&yGRH5RRCw_(d(Br@+$ZWDdzpWv z3Ui#?#<<~p1G^ErX^&%U?biHhs^@0SOwc;@NLM?d8Cc6j{2arKF4PUmWJ z&MBtAL&|2?&9&LcYA?EW;r|B$wNF;b>2thz3gqzMP`)F`$GW8RNwQX#Im%T>%joCo z4}48`-Sd0v?fNx?CPl5Q&It$a_~wdv623r@`@gKD7jLSfxV*ge<6D|qU5>E+_&VzQ zEGke=0ef%l%w)x)!wf;0~P7r2j*YGc>nuS@Nb>5nS95j4E8bbw!vt;lD4f{g*g789nO1nKvjn ztzTB5q`9~Et3w?8jeo^J+kg9z(a&twlj}WY^1}o~*vHbI4$hBFN#)TcmvHWwH?EOThmA z-}Wb!!9rSRIs7^oKYK?T>-kD^e)e4#nI6APPO6Tfukl74DMvg}2?0#?g{%}No1jDx za(yKDBEw+>I)$3#9nUn(ZU!*~$g*5JdK_4f6ZNZDGE;OEDKMIq`?Xe`8m; z9*``37apfy3&|1vBo-LVXsL_^(`XR>*i@L~hoT@S{J_OzY+B!Sn8i465jjdsy&Wg@ zwX!W=)#)|a!taL62MXgY=GCDef%NzM;~y`6zKRAhYh|T+#>*Y*m8~Hj37Vl4%_m&T z`3H<~n!>-nbNpB8;5zPAA|kcZW+4Ofb)r$#$; zP|Ee$>IS<>-j0bJ2W^^E-;> zdziz^2mJFo@%K*kvm$}Pe8)A7k9}wjIcfBB&j_1Ip$RL&2^2diTq2eU))FkJ9;&vC1RI1*%@v=<_;PFFfvf9-AGWNNQ zo%(+_!9`l`cKVF6wbgp%N7NGsv}Qwg>@}8?i%9%2GP?6<+|laRygf!=cA_5s=(zy8 zE&yA0(hLR2t%UBo62yO`5df{(xQ*jJ0s9fn;$9tTv^s1Qh5o)U`rov>Ti5ibNuAr+ z=*uHNY^Tb$(rCn2V(ZV@a4h;nk>Hv&3Q3u@HLMkt!PakDUGOVMb|Ew^sX?;q)-VL? z`m^ZVRo3Y_vOpIB7;ty8QA=hLNFbvzcmL<3P9$clQ7zRjPkX0Z8#P%m1ntkD{e|9E*= zz0&uwbLUNRIVBdLGUH-)_T2CpUkS!eUbB(M!WECKssjTA*xT|n@jFLE$OUZmiccmM zC|BWfsC4km*gf`tydC~}aa&^8A=gE!<(B?c{8FdXoYCf!Ib<#rnd4?z3BVB3o;&~l zbMAg`-`i(eTa6$fawl=5c_GBcWB~8rp%b}g_sJY0uq<{!OBir(PuMm5k1Ii_w>W&}-@HpZM!iuEa!= zQep>Z2Fq1*xgw398!XM1dt?;cGKDhmLq!&dz7d+BGQNkj#3H-*HnTaIozbd9cNZ<9 zNlaD<022GC{FcmqKsoLd@hmj~Ld!6RkH3GXi;n+$bn)6W=|4{YRPIZf+$=3P@!Q>f z55%J|8v7onRJf1zn>@8gYzafv1Zvkm?tT%CICOwR#d~aq^ym5cYb$pK z_JP8ihTgkN!#EIX(m>w#oNgvY|F9VG+_PoXf_yr(x6%9DkMgm0nxT$xlS3v)6qiLQ z>&baO_8aIad)|Py9fN8zCyoiRi438I33L~K&)1-l8ybFgX9YiXaUCI z*8m~WglL+PV3qpBZ=@8xL|wi-VqeI0tP%KZc;PE0z!=jYln%D!(bzGt_Ca(lisd22+GIVw>OCsb@pY#Lrq9M{2c-6`%iHs%9^8P?b;O>K zPr&|VO5Ovw8G`|^mQIWkwGF|nq0U2ldFRfZ9A8}jNoy3d?Gn)UcA#FMoD{`Uc#f}$ zX7$qS2jGx0n#?eYC$n-0F$n+}x-Ur|J}4}`Mux;rdg&OMa^#pWdb&`3<>VZgBtkO+ zY2mZR6Fz}NQ@GeRO7a8ZZKsS=?~hmP&hO846z)%2_4Ex_o^i=4JSg;;cfE2p|F=Rv zL=1_p(fLOGZuLREI(lwQLp~bO3h${0m@>gYn_IA9Gspv1^D>0~#2>q1W44S!j+GvK zLbTEGtph``9;3=6TNx;0sP9Vt@O~s?fo zSDyOB)fTe)RSgNUcT9RljdAvNuXT~7C%n>M65cr>u`G%&7w!(AbsKNgmic6b@Jn^`zB!v=&k=aqW(Pzj^R`Lvq`GfP! z(725{(2-+$WjoNfN&e4=@Rcd{^4UW40J;iI(Blv=OCdjr6NcxQFkmCdK7;<@@N~h> z;ih1p{$!B*pndH8t{x4;(;P?YGpwJ`pTjQto(FBq!Un9KVxgX^3n_cZs)Bki4kA%9 z9Fa)EF|wPUHZXAe;h~BoQx%@ou7Y7FUHyB%m+kx7(!t`D3`p=sPkX|Ka51 zOl1~HTXP&EaNuC>5Z?Fwn?2d5na!Q9QlU1H~W}Hc23x205L$oI=yQm*OUW2Na16P32_C(T0`cB|MnxILK*lX!Him*4p=stIo zkhw^^j!+dUkp>>|BtN=GK;L)wJ*e#=NN-i}ytK{|3_Hv;y3oc4o)M;H0PD}URR-9l zOF(HMn5HSt5?V3+b#hO)-gyqzC*dLwkg4`;Dgtt)%B1a@ca0@ZpDPa4d)-QJJ*n3V zPp&)aVWkV?99%geO`j)EKF1g@;kMS{0?FLuT-M)a&k$OR#(=Dh4A-~=R9;xyX7ei# zFa%XosFaJJe?oONJTx>3V4l5y4-H#=cwco{nU%E=+zw@F!{9|?wW!2Mz*vIt63AG| z%W3*v=y^pV!pByxcKgVKzPFJa5x9LkiacX^2ytRdlYNWahnhlL7t-Lp8D6O3kbgB4 zi1CL|J7+A=goua;C6QQ5Wps_&)Uc^}=B*0=+ny)+`yX;y>+&gGRZTdtg1S>E=I`S( znXn3zm{FDj^EDLTp{x!?cgI#{x6$>$#aUBCa4&{Dag>$QL-&=*aM&=^0yj7AQoR;N6d?tYX}~$fO(k!5B0^$r{GMbEUf#@> zpVwNCpC}GLZXETp$yBeP7p!kG2niz!AWHI5fMAP^*n^o4VcN*`oRg8MLo193p%d)P z0^Ecci_YeJTJ#Z_>`SRMMx(VhMAUld&1mkZWY&p7Y%e(8J#2Fz_dG5VUJ1n1McAU< zMR^EvYC^yQHQ02aK<`rR7ymP7(Jc z`iLvIjDR3dEa-?rkMwNO6MBxc3X=_t;lX2zXd>(Ixj(kGr zmA(;{ap>Cn;WL&#$F+_UaUG@zWOf-oD+WdHk04Xo4&)&{Gs4jF3ngDsc9T;C&c8a> z5^>CuF-95#b2w(U#%^VYBsO!F&}&76;cHhug9Y~G$M z>@?0ZVguQheMvX52`*P#KVi{jnvN1JAy(_*H$?6W!B|uKpBF)~^iEP!wyM1#nxOdrRoLSyibgTb%CPJ8t=lH%prRskDwo}v^A^J}$gJzn zh+@j9hC4=J&y`3fsS^uBmgIc2WI=Hr_Q`tAf7KI3+k$0}?Xr(A z?XUK=vTDoHIMz0M5jl0iDjK=QA~V>KT;jnZk$=@ut(Irmx|L8lz3vhnOnrXcdGPBJv<(oSg-ADysehT6LTc#4aFy6gNugS z9b1N?HK`n_o%i+T@m`(GiG$nLQTUEI&zKfFpq8|SO;~Om(<(oh;~-SZUj`Gdi;7rF zl#u4}Wwyi)1Z5d_2Ro>I5Q(X>FmBzd1mSGYqWE_xeJn5App1#z9$lV`voH5pn8BQn zhX=*;hQ0PAx>_|zUY={1=bUzQoEf!pMy^4&DWUGQsRT=9yUeFzZf*pK8J|I!fu*q$ zA{2O{Wa=5{6_^`!32nH$US75it`wDt%u#uj>7Z0IV{w<8#M}AO zwtx2>cS;YK=c@RE=-KGG+=0~qKR>5dlJHPV}1&WDB52 zl#_w;XywbInz(rC)GvyCw{P7dqgV;Knv8seCg3^xzBsi~vyH1UD6JluK)P`QCo)3lX0&EH{i_EcZhI zoXDCK2+0Ff4N@Ku_Hfs9_h&Zlu(_4%!rB&32qOcQR|>zs#5y8u4)etv1H^q?KnC+D z+`}|h?!zO}(4KRG3_gWpMa2YD$YYTAkzMGpEDlfBfiU6LzQ#iV+z;E|MSdIe?{LNz z>UcW{K>Lc2wnY&aizd74tbPCWc$?CdzR3$azl*ENYUNu$9(caUXphLbTyJjawwN0{ zaT2TB=C^2DL&`dB|IUfA)_%N8l=VvP+^Gk1o3@`qO{Ex=>P~$G!&@Bh>?(% z2+0=i0Exg1E)l*G-E8SXLmM=v+V0D?WEw6uAGh)YP?tcSJWC!C9`hk-C=!YL7@l4X zITgUIxgk1=FIE4dtHJ)@N)yrpX!xHiG;m9!G$O;bhTkw^5Fh%vnzk+gi-ROxslCa4|C>m)5pnk^}-M;0PZWIa0Ly(kE81%5i=d zPZ5tmBuwVX&8~#RhRJ@p;|MeaNg$`z^;Og}Mibqow@q*Z6EN4a&3n1c2vN*V7evsk zZrOkiRP#=QNm-hbL=S{i;dU|m$Wh-6N3#!R6m8_EVDdl1iu8*oy$<@z!zwQO z+~t|yd=(~~kNU^gh4tzbDYu3B+PSms+!Yiq-glqgPU=*AvYxTX0-f#3P;pqq5!MZo zuh|{lZ}&NU-tWn3vx-uzl|WEc#IORSn<2|KGTrp`k6YYM@%7_BC}E8@WLfB-H0XFC zT6ga1)u&_~0L_R4o0p`|Ik#4R#OfeEDd)!?(>D4pmFaJ zKHg#~j2K?(ogXV3-1}nQ9)v=oh&jBNTSpcbveevh?0WUoQ8-U=mzu~!JppW@dujmz zt2zIeN2UJaD8s%#ZzH8MDuvxCW?t2Mz;33Zz=QAJ;E}d5Z=syDx};Ll6$w8@&e#kX z_YgsnrB{tF_i;Y#cA~H73IZ23n;<$NG)!D3${x!~h`mw&iz&`ZxGtm*FpD8$A^~hAWM_Ziab6ghp4I?A zO%deXX_#gD&gZ}kop7It=^Yd-K}t_&aafSich|CsR41m8%^gu)2t=e}A+U{e+g)e1 z9$t7L+ya-!=x5IkmrO<07FjvUc@M{`LyJDA@@Mn(!j0E_x!b+79O zSFE@Z4wQqtB<4DAZlk#%b&44#>1YBDgaw>4vgPXD#FdRWI66^9?bpHpC;}FIrG@>x zYFJ!kjxj8jvd!dm@(bJu06`25eEt3PjoZl}GKftVFkM!*a*%=Kbzoo8EWH91Jup~| z3^gy;PixYuOVN=6{Gx^-7%{_x(r3I9iR=bK(thWC$1RJ7eGUOmD%7w17b^^SIy@=p#wV(avI;Ouo<+JrtGXu8-A zfTM^HO{7zF{Mi~NeH;f4yq4WLUkK3$^Bd@#Y|#c1QN~Dy$=i&q$wV?P6z)0`$l*+6 zFVK<_VHL;x-X@qWF3b#T^s-eF@h6kuIS3*Jwtf`a0)`#3N-z>KU9WrcRAF4P*Q zo-V||~=178^%t2y<{tO0UcF1igZHd{N>a#ijo_U0_F zasP(tuuzWn!1%^~e-2eCW9pn6H@$1nqfG}cxVS+r0+{m$=^Mnn#C9LWg0vdA73FI{>} z-Ud9ZV~GGGMDsRCKUB zI-mbAs|jBlrI(&ady9)y@X62Oun1eL&`UgVmC7`O`0OxhS!`lTz857=e8&+@+qVz2~d@7o1N?#91H+BM68krD)zj!&?e@< z_#nmAm1Txly7dBakVHwu9b7q+@ByO=BM9CYr*A=`^=V@757DR0{a8${;o#_3bzh}> z6;GoP3umXS+!&leM8Tz$6y)BvX9*?8(fa{0MvZ$wsaHg#OBP#!ddmnzKf7vYlpX|h zQ5bGQ<1U~YrX@i@jm_-W&O=ozqx@GCKAB@>7p^qaDjP0KbBU-ozGE=6q0HyVE@ltw zYMmU>laIy?PGEC(7NX11X^%{r5X6gxF02ZL3vBNQ2|c$F<8VX;a&CZT8*NOf0$vS+ zDwg)IKly8z*TBoE0lPBRS_FV5p_G%!?{FtO4`?MVcP4ywDfad@mUtqR3)S%^(lRXg z8uJrCjUYnG0UZ8Wp}oTx{(HoGW_7V}RS{?ynJEv1)R!YR)@8mYK$RsI!^fwg4-k_$ zO~no%>1DBPft%}cEv8vd4QF*QC6ke=#2AnGj>Ux_sc%36HVylsLHu4L4p{e{?pXNe zwNkQ(sVurdn~L8o7p_dF5UrGqBe5?*S~(uyHx>ZdV+JY%GPx$YwcrY>jN3O7m^_@P z2ci+|v}|3lCG4u>;I)Jq?t6-R9k>o1I)tpN9h(Lq;m*AkDF^9O{XZ*=Z82LmrgNk95LbnrP6925NAxy`r_U4Zf_9;A1L`r)Tcd z?=TvUhOzdZCU(P|ZOmrXu!q1{Pg9Y7NQNN~lO-N|GL?aa^?-Ss z6&1*#W_*L{ZXwEBGTS+GhefUbFEz3$NJIu_dUZ;(H;IXes6ww}qx*M5Tk_q&hR!>? zgCA@!_>&93k-Fe_Hc43FwN~x(p4zeX3SWm0uWLP!x?_~bAp97e&oj4`gdIPedmyDk zDQA||7W3rEZV_cAw-DG;cad^aLea9QnM_tXtXR4(n<8~b36jnX zc%hznS>hN_=n05|A2X4d!Y<4>&U)@H#ugtB`C%C*;YZ*ob~X9SS^e%smmoT1Ub39*?R#E*MagEi&>GQoKT*wS|ep%f8O zRxB9mDD3D80_LAhmfiVS_y^n`uN9;`WR+^a+FC(lgEIoTIhYAOl#Ic&ckAY@ke)!- zm^)6Il}b8}ijbbrDA`RRZN8!*L zoYSLkj91>)OkSz~nGm(UyaJ`x9OqY|j`P(%vX74V#@c$_5tc8!snf3rQLI9c4j`d7 zVV*aBhFm=yTWgN)+rGW{t1G(~KR&FD8xBi;opj*t=EEABexXR8%DXVB4wlZkmEL~N zi<^;m@ZV>Za%+ut!8un07n|WXpD+ppAVq+c*g>>9`0}T`Ve#_Icb|}s*P*2oYW$5r z&^u0PzyVy!UOgqa2Rm3;%%siTvkTmWVGlwAq@}z-p+Ah`uTy>#>f5cKMha>k*9hvDT5tDY zkzhos@z3?5U7_z&t0IH;3i#=lUadaRu^eCa&6Wc@GDT8*|Bvy_YH0ax-o)ixNvYVb ze0M|V9|ydEm<(mk3u}7-hq$n&02)W@H}EgDZYELv>WTgPU&;Cv8H6_TvdoO03F-KF zYj>yCHC-?FSK1dZMj#q-9r{mB?#BX{+}|EYjjQ$QRig`gHWX;2(fA?sGEsKMG6|Yx zdXFfKNuef;j!!vZh~e`afOV+5k$aU1Ti4<_m{VgCfL?&HO*dRT#?*YG#EF=R^xc3X z{63B*1Ey&!^W}}bR(=WV=ZDDD{jaVdYafL7{IO^ii(VOqA~e#8+?hFHJ{%P#7sPPr z-X4C#BJuFgl|*qHtuXJOd|BHy-P>&hiA33Pe8k8t(T@pT9^nOgsVjpn4d z&Js&h!mcg>X=!n=(b2ytrM@P+9-Nyr7fM0Ndrc!KV2g+IR~xj9*4nNAQpgFBxV!#O z)=)oCeR8nJ+${^hxht+&hYXd(-IM)zkfNHOOxKN}c1r*XmOG9`F0Q3&G(FPRVs47h zC*$Cr90ZXEkXbr&_%YqvT?}evo*rDipRzY4PMu5m*XfYye2us3JmcWiV z1YIwlW3g}TQVL7`+?W*n>#x6_zfYtEQBlYJVzH_1bjbt|lBdQmEU6C(M+yXM~8OyLzI%eGsZzM6gHAoj?Y8pQ#a z)wJctogN>5Aho0G`BMo_&iH!UoB@De#I}JMF7f#-#vIb9bFQ{F1^?A~pv?LCv_ySU zE!0tF+xaZIY`UUyQ<228_}t8uPO<(Trd7v!Uws=Nf5`(ZO@^|BpfJYS^T{Wfvecfa zp0@Q9z_%KtY$GwoWe?GVAgaRK3~Rloz|rIcaY$Bq4dtR3uny!tw{MI2nS464Sa{{( z-Mb2D`jsKc3F%*eU0sm^ObLmd*e$!wkKQc>TyAfCSKsmK^jC7YFDNDScaNe`DPx=S z3?MLRZ|TkFOXJot1jkKIOxSd|&KhBy7Es;vTyvCuBr?bsWOhKnulyG0G#M4++1CpL zg*U~;#WGp}3FnQkuN;<_hu^E_aVNS}7(F~J)joJwS-ppuZ@zQUj&kU9gXMC_>%7$y zR?!0D(e;c`O(N&RA3WY1%1jr)bP$etxIJ13%kXDG>_owXeUTG)U~wCZSQN0p;=Iz_uB*$cY zbvsN-VzK6Y3s7y)Qfvav==vC0W+Eem8+i>77p?fZ4mHtV>cW%xux*iWl$z(^CZR*Y zqij}1^6}{T{8F^JwibF4nK)8WyHCK48c~!O+E1iqamB6q&{UX!)++z~+_W{>Q7NAS zY>x}nd^nFiK));ahi~WH!`{C8(?g3tQp$d)E!k9bCbPn?Anb~^B>t~M=oR^0xP%PY zZ+J3@V=R?NaQt{8uyjHc1e>#lkVuGgx3?>i%_39`!n$J{4W{w!FGK+kS#&*rC1aIb zI*9uPK@Pv>By4{~wN%x2%L++CjiV@vBxMQ)F{EVNMoUI38g+>xngaw6KvD7>@=v1A zM4zV1rmY|u*}Z?yOzhww3d!4*9wUZTX1En_pg&kXJH7#5tA-Snq{+t{P6(5(cn)&% zr)JL_maQ_w>7>}_RQJ`D$PJzNz7Bb(T57DjDhdg0?aRw8I$KT5&)BU!D5)kh-CqL#=h31nAq7$*mU-Eqwjo9G z6CDM3IsMRm=_mK)K^^6b7dtIoG5#wI!gc=9Eff#&5Da!YirKZvombvU{fO>J{n4;5 z17ZV=(|(O)tJMjD-8BKIfo_Oq6g+=^ZjhEjLra<@8eHhzBHzCRe-I?GjHK8lFpF8g zb_(kFFSiNYn%m=OcLXUvI6FJWCNDAV3y?eoyE?WSb!rZg%AY=aRzoc?gY=m{R^AH% z;aN%P`fhuJx};0%Uij6$4ej~dQHqoxHxB9MA1}TeD-ph{={PQ_wTQf)x(ao+j~y`SiyLyf3Yw5%(Ic*FY=VdPZIcv40I zcTI26ITu}G6*8M(pYzZ$A`M%&Ve3UWr4xxQ^rvEe;LKelc^qoU2;?I2ctg2RRiqc> z?&B=ho5xqQWIkJY2TS1wXEi(Sk8#G-4G}w-^REJQ z>^qeUtNFbf;-0Ox+c1wgUjpknFtcna1ov@lGq$UnA(k5ksD#CdV#EvR>x?-r?dXVb zn^D5(yjpJV3xw;ex43v0yVDhHD{`b9(wcv7i zBgV8`2t1l=-6sbdH$^fm0@F|835g8A$_sh&sMiP`bh+|dTBf>eM}wpsD`P1!Da^9fQw-OB#2 zHOODm>auh2Tvoo3xg2F=r*iR92=buQ0ntC)p25AFVADwOKDH92=-|4@p#mY2 zZj_%mr=)TGibVTkWe)@zgw+tk7t$1hosxNAjFBIR6y;Wnb<=(U0S3G6&;F$6Xi5nq z4nLso1%Z4=hQ!>yo2Xh_Edg-TdcozaY{JNbv(eO~2A&OE8M^$%?*B8p(-7SQodCx& zJBQSw`&)Z=^Y(oiEiyL^&eaH2mTxLrz7{0C^I6odrf*HO9$WkOcjDUJh|o-u3r2+K z^9cOGyZS*IzNC=BazLIaCZyp^U7N+l&FOo7;Nj*+zut5R>`g1{${1pV`gp`r7Uyti z87v!nQvE+QkRlI|9I+oDvuF^lBYk&RkEprelq4Q4#1D(uR2`9&Z1>Gu`A>Lq3cB>g z4(IMn+eh2J-Phg?OSDEzlo+jVCc%&igTG34=A4!GN&^~Uzu;oPM#;Td^HnFT#!|Aw z{-Mn1sp>h=zbFztT~}e$yXAM^c;TgvRnChI7a|}hYzjB>paF%wy zkax=CP)`V5)mX$>qrSEXliP&KkG5lC1xaBgN_?#e>jwB#nEQ%jcv#~`M&>aQdDTw4 zfYj9Urf!?JZsiWxzG;m-XosIL%DiwWtw zkyw0ibTW@-&8YsaBGEP_*ZMQ4ssL*XTVWWNT*B;^aXR;zpc!Xh+Z>?KKMH{>S^(tYBMr2 z<`-y%VE`s`Sh!3=1GJqu;NoP6(GP*Js?rCsXOEDvQu|{2tZ=j1!n=bHqY4V#yatnu zDDBsMWP>zeoGN!Ot+5eRb{K+#FtuG>lKW|#`}fRd>6gk}4@l4-)cerZ<y4XVP%xLM32`sIvYdp#26rL39#w$Qxz7?iAQ@J3&nJ!O1Br4P2U{>Fc}@0iLie(Qb(aAGcT&MD@a9sTm5G2M zd}hh6#vcK;U*^pnN?rQ6tMDCQ6sA^1b@f0PI2j;>Ht7XuwP!TGuWzjsZs7)X-uMOs z{3VTi1`&SEZ!|U=8!uSYin3Ao)LulCGCng-e*9(GN64sW9B}MR{b()n;pNq>T&>6{}bO0Wh2Dfr)eKCj1ckKwzJ=L!>yGHDN<0qfW8R=e0?+W(=j*~jt_Mr=f(wE1> zbQy{$ls4}TS3LGz`_G+k_Z++SGjX^WP@qI8&No%NH4cR}3Q{amOWDBFFq!&E3P4ZJ z_Xf6S(fF-6_I9t2?gLRava1cG7Mlq6DBErg^B`l&%BpQ_9}R+%C*WAuH#7)k!*udt zmNNsm?rOQ=mpE~6%1>=%@dYtHr$z$f=B}C-F3$`VuC90qTSy{t%0a?r{hx2ormM!8 zJi*qLoO$_B4-Ykono>|8xl7aX6gVHD07YW+^73B2X$rM#j#JLjFnxI%>r#K`m~=&@ zVf-2gboEAeu-4YM9_j{`mv{4zT<$YPV3bSJ`dzPd_`pZ&U#gN+JFfdkv^y;&oOSc# zc24RMl@X#Z&Yoyso0JG8Sb_Po1;=}5u_b55%-dk(R1>mLW-Y)fXFLV(*{&aT?pWkU zE<1!tMY1E<#VumbpH-!ZOB9loh#r^_RTB0RiRg4_nS4%WC<3vi0#z#@4)k`oPbcUsbHZ!%D(0vKVI3#FY;WGs$sqh8 zqV)F$)C)=pCZ>_np5HXUCj|jN#OBUaw?{#i2BH)Efx` z8UuLprm2C>W(8q0?_29fVpjHi5z5(cB&ZykZ0;()owaasJn$r~0XH-{B~u;{lrIbz z@Zir<$6jxl#Aza!6ANkpIR-C>x)!b3D464hNRcU)Cf;J4kYv^Q%SPcG1N0MFlw|v8 zpQ(Ux$!mZfYvOL8z^Y z4{oQc9h%chYDuf+;Hw25zj5v6YVt#75nl3y$#}=Tn59EbI<&Dv(dxa9=~$I8NDBcj z#|di7l=y6YeSP;mou!XV1jMQanA0(^5EP`Ot)bD9tmqMr5n%N+ng~@Ae&TlGxk5q4 z^b?XFR?XWIi4p*p%~I*i9jBpesy{k#z2)~3{k2*e?gXF&d67byI*F!D`RY>js$lM@ zjLt&sWg%`@`y506-YZ!?kpJ*QiNCYGzm32Zg zD4Sd;QJUim(LyNk!K#^#VS4_hwxfoqGwukV?_yS~z$Lrjsm^l}kU5vR|4L>ueZdK&u{ zo%8ywK_@24-6dBvI|pC-xq5Hvkj-2@cO&rR?0ffomG+CPD%)Y6({`7>L*Ak#voRH{ z(%xxW@T%VIY{6{4lB#OTv^smJje^f0ZWk*Y27NQCM$LnQ$HWcaM{J9aGWpC~or3SZ z*Y3kr*%9@YGfOcc)>WeFsn?~ua-t_HE!+f1iy^pmvSW3*gKWE?RspxAITXv1UdhBo zYpizyZmvCK{V~x%_@rst)SOPLYOyS4u!hN%FmTK59vc~$d?jW+MAl5_j!;dKtTdj* zt?DObX`ASbnX!^2%4bm4)$q$2I2k)to8EnQ+54XT1vhI4t53UD=GB<>cCNZ8&B)$< zC}%fsGg0E{-6qGKX&2#aIQ&)TA@zmx#t^OWRdUZia|KpO}E`6r`k`7Nuv z%LCEgC&HnQxJ&v7%(5e*AMYHT0CzE?KV;-tPJdvqS*H3%IWD) z`NgERL)WdP&W%z>xKrwRsh^*bdn7wDUtu8WQzs{$bQ)|Tdu^XVuy3ls5w7{T5H#5~ z>Lvnc(vg;dCi2qfvr^{~ts6NfZ?Z03i8L`0Uvu1u`uj9Ks2U8vMzLHDuxQL|%&;7X zt@KTnd-&XqY|QTQWWM`e!?fl`2|XTA(iZW z52LG;x6S^Ujgy2JEP!larHAJI7uK^p?UtAJ)9Y5B6!R%VecjvZ|`80rDc# zSutu*^2(A^%adcesQ{vca{7D~<&0{&M|$fU8+)ZNLop4cD`5lM4dgwn!EF)F=>r~9 ziEOOnV+GhB5~w~*ZSwJ1C6)iFBrETxq8sv)59A0p32jlcUIINMtv@C>+16Z zlG%O^Lna@K)i9QpOT|rV6YO&QlMAq*+5vCJV9jt*YyEAa-H*N(8W-sSeo%#ue`C!3 zs*gBi%QmrxJX%;-I5Ud|tt7sXJV?cj@k3aP>^(hRt7SyIQHef8dwj)hO~)QTN1Tl9 zwn-?B3_@<43AXZNFqu<))WW|k;yAeOfN-m2@fljnU`N_?qshYQHk|)2w5rVFaCq5x z6~1*x%lEgx4kE9Si(VRj|dd;WAlv!Wh_&8yYSpwQ;ZINjca${>UyW zIrBkxen7P_2;cko+r8EoFgCI#qbvsvLu*nsVNF(w6pVYFfFk-{(3&uYO!b!lXUE?OxmZONbG}>2*P-lIFhyw~sZ^6dx;EmsZLaoX%m7%#%U8 z1N*+kH~7%my*GZ2G|6hUk_nz<=EtN|HX7tfA6UN;joeiej-@mF!gAAv`~;17E+Ru-@05L6~D>Kh%gF zNlq)?oNn*ExU=MEQ}NER?yD<2l7momR>4CtKzt`#VN*Bl zMzzH3budhFkkDC!-7X>;J!6JjuUaq_&DVo?sH1C!eP(8?$$N`%nMA>t4PLT0Km}3F zlhx{tVzP(O0TQgMunaUoK~cx-lStd8UXenh%uCtFfH#}obY~||jK(>t10?gst3k6+ zO30z`rEc~~Btt2$GT^c(NnndKhTNnKEU#G9p{1);T9&WY&(}P3^If;?_z$Cw)z18; zA6@`Y$f{XJRwar)#pbwC5|(U+NiO<|^hgn2#q{N51_lvou6Rbp&&?j7NSr*K5;gkh z`uwl{9o8L(EhJXjBD}n(JA8&#Ze6d}E@}9hax!;v8)#|~QOS7|Wn{M=7Ins415v2! ztufOhb5In>kL${qr_}YOxp8$^@%cEL7#p|G8z=x10Ij4~V$@Oo_SQY#Ko_n<{}z{& zREe8Efke|_Wodp?@KklMNQzeB1NUik>HDC9t3owR3PDUr8K#wdE+@)Yt4tY>tIpXxO0&D={RB|a~aP?Q@kZZajA<<9Cr&evzAdd{x ztB&i6qlj}sBvZ!)nTbKxd`WctKif$$D@^UfWmG@)+!usrrP89tn<h-0oc-wet7v(MB0vQ%EwTuks=;O48)EStR=rtBg*9y(l+`g+ z`Q{+rOUkPBa6mUXr)_6|MW?;V(6Vbf45-G)wz1F|^h8=Vp!-78j0P36D!KNcwM%{} zF43Up#DKg7o0oy|OT2NPLtVPhmh`Tryyq>G(ZWxkJlju8(J7cK;p;_6 zFW;%ES#!0r(4qzTvH-r^5X_BOoXl0hy;#+B9?qD5?4Je*=2q1N(LsESY-nN- z3LC|TCRG`|yUCb5UpfRLkes9AvBC}Fy-##&bL~er&`2ASfGf8`CR51asfm`HiI7>& z{?iwJlJmyLW!7X61BzQAe=ME-Dk&FwB~&!E^*Xxm=&cp~VhWtom;RSsu z-+G#}P4q^}`-61jG8+@b7)-;~l*9w>d-T(`Qsg}{m#fK^z%eIIz!qScd9PzcGk?aq zM=j3?9mBKYD$^u9Mgfu$q{7P~fa=Q|Cw`(3sFoETrU9Z#PUo*%Hph>IR{_Bc!DZa) z%M5@U{PowrZNf%3U}~$w6}Do!Lz7W#=w_)^0(Z%~P55w=;5m(ftKC?7l?WdnK30G@ zNaBl$CSUvtG~LNJlAhnD9a2Y8WZnJvY;Sx*va#iItkklR8`k>{yY?19S&s;CKVKg! z=?52{bdCgUQbN?ZS=lJff2GJH#PanfGs!Pa_K4yN)VxU?YzZCI(yOY6BWHNo7(eH1 zNC%t8d&y>Xrab1M_%fB>GC|b8R6=4BoDS!rlO!rN9l#g85sM~BV zIUxz6gUspTL~loyvWiMCi6U6N0oAS}*8P|>pBt8ih285d!&{0m4OXaN;Fz3vdX~j` z=w%LgMb_{3dqz>IR4tReFco%#N0GiV`5cJs#vzz?W?%}R-V2ZEWVww ze5)Ke9*_w$uffwIXTz<^IJ}aV2_TH%zFA__Y$J=!MY0rKJ~4N^1Eku>`Du7nF0%p0 zcl+n&Sjp+QtxST?D-Fm7q)^g>7Z$EJOt?#G=OsL8O_F-zvf@@*c=Fgnis}HAut$y& zIKe|M1xX^hb8dad@Hi5YsF3H0QLHaa(`(K&L7SBZ(D`~oQs#M#CO)rab#E)H0cWhRYI{k#0ZVF) z(3&iZ4wnJN@G|(0VA!=*->sL;&CPoqyC3IZj!aOiJ+?vLLDuovD_-fcXYu`dICw=qIsXzX&^*f)k?GXkWGNvlJr0f0Dd~6_L_jySr6$P zsj|@8_s2@xy8Gx44Gj%@j$2-VML-Bo=7$3`P^k$+HdKae*_&WJpkW13 zfv{BwGei>h%I~^^*zoy1f0S3vGwylK_w~NvoN+2tQx$=!B#zBio`w@&-hik31lduj zgb^L~J_Mdr3jl=sGs_^s0+wMb6rU8fs!Z5{YfZkWN}p+crk?%|Ajs*N`T5dn^X{HX zXZ`nCeO&wy0XEDKujaz(S_nxw0^qm;+&vV=g-brb0Q@i}gfpat!5l)tXuHw26uv1} z#)yt3Qnz67Nc#$C_q+U+sOs-=9g95anfTHrh@6);lz_G17jrxWd7fRE`05W&`>gru zJSC;2DF6mSQBFVgjGy2XI(@K)9&PK~1+@Hb(0ie;d`en!rqwYkOJD40#h+wJE4Pg< z&6?h|#$s<(U_5)A%8blF?)<^=fkuBp))*W&fy8Q>RGK!>1ED+zM7)g0jhyb~F;`qb z7N0@sxe@T~F6!&+qdFbQF15* zhC2Tis*y1O1rS##C=0QehY-~Q0Ku1ot|%V@A*X_eht(^;c&pwOUL8IEC@%qoh0vAt z;Ir0__jx*bi@y}KkSv3L6sXp|g~jlh`-j;jJR&MNL{%bu^g3f`TUxdH+YDR8dlhrwU@BLnNsu=5x6AYFJ~AozA6s~{~8AoKr$3N`pu>jCvf*a@(yD;j1|{v(&^;_AwR zrK1R`PQJXd5r{9r?)E-d4T0M@M$m{VJ;3jLAXvZNAPp4C{U8Bj2jXI4Fm(NEu?0cb zWhd5d$Tdk2exNTO+*?;U`qR_o<7on~#4nP(%D8oPCy9)8+ zX7G|?02@&v!GQRB3&bb|ucEaI5XR2Rj;Jm$Gtiv(f=G7Fu>z|uM&8*7>gW3N6nr88 zjFbOz0#=6d=ZA7Cr4adn3m^4#_2zVp6(y*`jq>cdCzsq za?wGS{y+#(G}6yO*a$A6@#MR^ES~Y4($;`9#4woMjey{dZF!!bPw51|>}t?-{i7)q z?`!TH<5rz!c~@hQJVYv@sTH|I42xEow; z-xX!>Csj;jfPwAwN7fp-fj!;vOlDsVF|fAhmIB1O^VZEn3`V^P#11sSP$7>3kr*I8 zdjrGKF|-OMUNgX^y*}RKul3HY4r;OSrh~!lE?v5{w9l`HW9{9fhf3zXfv{!IPrk(& z5VSb~fh5e(wlw<8yx8dy;LnhqGlXI`;3LO@+bRnxbwYI>xy*cu z%Tr)q(dQIas?bh?grDnG8>nQ5z=o&K6(Ra{IEtbIEa`(+m%%|9_{lhG-JZ0_&6A2* zHN1tj4L8`OBJMnR*MmppQK&UJg)L2;ClRxF((<-p@QPW-eK`-zsG&d$@;tU>tV&&Z z@gqvnfQF21p@MVb4G01|(CU`9z^aRflVSfv8wt5^9akV|GT{ZbiajW3#*2VZBO9Bf z{9w8(UmhKtdSy_DD&-r)^*rAoeeK6g^WM3fMh)_B3^7&QUvzVfP>NYnnHUdaF2=6) z6*-$CqM)m5WfDIBcbIfKROc$>naxfmw48h7vP6?DVq=ms+Q05bI7;IRik$(msf=!P zUf+&K2%R7uG9A_&uUz!<;bS+p%?pk z)sZm%{Kc1hk!E*To-(@=ioxe0mJzr_Wk6-Qo!5X7=zFuV`;qI0TID1ex>Vh0E2 zmG3-s>PtciU^jAP9{E9#g>IpQo`zP>^(GOs!?njRA!07D-d2S0)xOF0yE}d!5pk+L-?Z^PM)K_1kgXa z3}u`6#Yn1o<+K42>P^QM68xKwM2OB-_?v8e6lz7mb%{rr!S`wCe)w{X`chn~gLXlT zAl=jrm7*74!e%1q&BoQ&k_PDhdYtQ=KAj{dlwI^VeSM`LNJ z(#5iBS%Cs$(EaeyUpIX;tz_lVkn{+DT*b@B+WEDRas(C0yRIs~z9XXJbEimlG~Dvm zqn-wXs>Qp$dB6S6^52_OF^$`sgp3ZMO$_9QDq!2fpgYV75!_~fU7wUKT<|sMisQ>2 zWE%QWz#_dTFaJSZZO;54>d^dC6;|y7+M_>oA9vKL+jV)zwloC{%kOAeNoSIX^sN$ z2bx>3FN~ntdhzgzvyn~bTs7Zov83{!#^j!ZpoAIVgwP2hkZf$3%FLD=jAp>U3gw7u zHbq27`)i4!S76$<I5BiXE?Y@&oBNgZLH?QZIc*Sf?GUFDo0p$Yhc$$6eO{4d4|X=nN1R?ay0msP zn@?!B5N^nwpR(ZWZXcAL!~0)0F;S?f1(49LEST5i1E7W1gPXC-=If-QS9IkV(i+~` z^ZcCklkg|(|3RUanz0&)-UD0DWU>o1u-gNWmgb-~iGg1iu$F3!LQPk-#)L=@uDA* zI=j9Stp@zQXdo880x&Ld_oidn7w)@7J?vGWE=!UtO@ zN+J|8DlVs-^ArT<5=`Bm)<}+c)>1OHNoroOWp;TIGdx`a`$sZL)X}P|{2rulT~!1y zCjrQS0%(-?ll|byBQ*pOax*YB*)vmps$k(}W@YIBLIGByO7f>XIJ(p%GdtVza{&As zfJV)c#-3`J7xXcM^##8)L4g(WuV9rQx2h~Yy9YNgH%CD=8$c*!VZqd4R(&Q$Pn{5B zs6W_CL~ZH&4QBruAIv_22NnVU?tXec7{B1)76OjMFE1w$BJS=!Ex*`flK)*hfN$Uv zQjrHNiG=U^rf*Zoy-HYF`b_RUAKG-N!txepuk%GjqgCMDeeEt^wE#$s(Ws?)MiThH z5tYatfq$q>UrX*nYSgLo1`GZnIShID^3P$JK{@v=2>`xYZHFCt9XIIY14U^$n@s@E(u3+ScC}O2@6^{VjmUX1ClH+yprC;9T@wKU;egIU5Gh8{ z@ZA^pVNn3`A)~TV1*$+!_$qT=)fW7|lV6pm+>A8zJe!!cR&S3qn-T&(J4HgGA_v?R zh|BpF0$>8!^X3gN*pq-&vf9`goI%0lM3M#)dxN}~ z4b7#F?xmhy?-jJuIy2DFD{Qh0w1b1amf0fn)|ao+o|w6!3C5RfGH(JZmzIV)^2K+r zq?V(lRI{`<8pX5JFKo8zblhmGn^e-_O$Ne@&piA2Lh~cP6P!g8@a-TW)ZjMahvWK* zi?-7h>ow07>#WA;C%Dw9@g%X?l6r?-{qh3xh3hKdGX|32j2dcUWiLqd-mneL3d!1{MGe34h-bGCTMP zlJ=BtJBr;rh0UVeJtuaiOebL0Jx~#z_;b^!`B)Vl)}yJ#S1TUL%yqtP5KK6aGw+Q7 z_r|T*m1F1C9o#e!W~?O^IoHM@F|NH}#PqW0EC0zZj)A-xTQ6EJ+k3K7?6RlfY9RP5_R@W*Grw7zb7kR-?ID7AOLrRDYh!@UStVHlrv z_Mxx$wh8q5UiTVNt{>*>DMbi+O!ApXq>a8^qtk~;=}7emlm-_dqebh%Cd)tVvRQO* zh{JTngr`{$vbx)T+O(*St$v=edz%BHFQ@}5gNz^CGJ0~;KtxzqS1mOAmgz}k1Hcb{ zS3!FA+jTSz8xGN+HNSdCWSI$ljYh5i9?@R?I+W7ulm7{=RQxUuwrS&09sB7OyD`an z2UyHKxKz&OPd>x#Sm2GE!^cR0!J=cTkh3 zFU%?DuD|HjrWef>-?-$(I7@zqyRg6d&-b1Ca1Cv_#8py)8|!6iPR;^ayZ`6gbFw4( zu6o_09zn2yVdyp{ z!Dy2_#e0n9?I5P*?~hXs@>!p>j7`2$Xlc-Oh<$`n`qm>DGymE&Ax`Y4fK$2@H1$OY zB5?426*%Dn{(QX*i>dFzD2Gm|37pJXAGCLymc-e(54-s41Z&C`king7yvY+hYhgu% z9ly{kbAH{H_tDw(?F-VHPvF~bv@bGb+VVb*)$L=k`Ie%?#})Gf>|jl6pS3TjfRAWp z43}**5B|1Uz_#}`CXg;(w8lzcy{9xgLxFY1H1VOjlz@LgJI+Za20azMX>=`Yhd&L) z8i-K_F6mh_PLp{C)<%*bV(VLW;l6wHj7`~7Id}*!wP~vrU#4db#oC6suIUpV`RV$p zr*M4i_tj!NC23z$Cg-0Pls5HOG^(1=j4khK zE@axhD&QDn7^_6?E#mZtIm}4!P_Q=R*ZL8(ORQqKe_vpCRk4n$PRLqy`J0GFVt@3$ zAaQ-?|4aXW|Gv{Ed*Fwyk>uZXb`(E<{^(OmfxFuFw{xFe3$}iI=ZCGd{IlZwGpfl! zKmWV<=$|Lg)cp?=^W#sftJ-NUNt!R*BT^-_YpVSCI!jDD{<}Qiv8r~@e4&u)U!!{C zlEC&l#)957XPh5oa3XooE_A8h_}F}d)o?iOVW3R`=l6_c?%z*1yIrsjEG(}scr7N( z4o^+DytRH;%BH)_nQnz8wX@15AILKN;<#Wlqn?aeEWBSUW9a;Sv@O=JI$@K@gK}>4 zB7ssbXD>>EcIH^iT}Kb+;M;wd$bq#_9%9c=6v3_di~8IXLfC1w9JI?i$av`kX^yso zWhroKDwzCYmH4YI;mHHBXS+OSAH!2xo!o8LidOQWvy{h&aTk3v3!c^`ZXpzTYG-AK zkvYE1UdGX{je{#_R70VB3#ezV3ohMD zTv4Lrrg4&oN0yO<;>@4Nw8Ph%KnNBW<8F#F!VkN7D&@wk|4n>9H?koW`dJ|Z#(eVjMF ziqBF>T+&ASV3~;Ih^T+Oncmb-j^YfqU%R)K3}<$uxfhexh>3)#cSvM&xvV)e$jHSl zn1+`j<1dlhR*6Si4bC0zUP3|$UuMYNXKxo5ovB4P=A?VQz4b|T@W*eVS7Uk%t;Uc7 z`g$cFPscs$VtSS(l7GJ&)`SMXYZv$6t0ejA5(ccz+-Oq|MEhLAP*@7nwQch)86G;Z zr67s}j5zxq)5E=twMJOXho9tLA2Q)6&pO4U>#-J23)(8=J@of$UIMKDPh<_^*Vk`u zL3A2LoKG;UMU82!U3Pd~IJiCFp1p*ozhdfXbesz_Pj~$lPUkky%sq=QPBO}U0iukR zo}qjx?JU<&GN&gzn`Y*4SmK4mq>ilLXVuRQMb@;EUozO2+dY3d9fmgBFP8X$! z=4%j+2Ogsq{)C;<^i$4?$U5FlAFVE5Hm6=z6+v`w9G_6)9M`tPKek^LBnL-}Qu;1k z=q0Q@aOggfz;&{fo@D`J)`~m9FEP#ufI%3;8k9 z?nOb_pb4X92WJO4o!HdW`?H=RlmT-$J4U4&y(6QIvtT-mxEGA=?T?A6nJH~=N>=A3 zB6z2c^!acdLmI)gj z{45pa+3|=hm(V6O{zrf3?k#=buh(Hs;~kQVgTCYthNKiSrINM!Bx>OA#^u&|=RDDz zov0QVD1#+RU053@q_U^#IfEDR>!#OH8Y0Q+NxHO^!ddgcq^CiHf#f=wTnf@2PFprL zZ}+S#@qBG`^GauGi0=eTEHQ3!zSgdntZia4!9ri|-qg^@vV}i}XvfG6!}UW#A^mX% zt7uP+;nm8Y|<^Jg9j)#(A@UwQGDkn;baXPc<=T>O_j`_WD zR98dU+YC<37}NbHcLyU`jjyyn({9L3^gp?5vM#pT?sLn>=kaId!YJ`y-g1n`|ND5+ zm+2cUzn&vh#_IaEDwg41HWIcIw4vFIu%?L;OJ;#8A$DqA>|MrlH^MzXMFab3DfO1F z3^tIYs?0Vcx7}Kwj?0FdcA*x3p}no_=fxG86IR{l25EyT6NirJoe z|E#H_n14*MXzC3oR)y(4#yxJKAIcT5OHmL+b|LhMuZLCJE*|3&dxkk6(`K{7S`K;p zv_JFYmb_h!TnVakiL1C9d7|+PYRt*t8;59j4ex)oXeMF}_d#t)AfAD@z)cB!cUZP39nB@d6K!cj@Mp|13HCz71&7oJ^k%bxizj1V2tzm$`*%%<4P3q|cz|514%Cw1yg z2MRb~d~R^d6)Q;nX}?ORC*=p8sQ7qSdv&~nqVh4De9Oioco*EQ#h=P$gto=x1}I>^ zG}^6s5*2oIdrXaLyDRO$s1z*SZ&+b2cCsd@x~y^LBkKFMuJLB0%*%BS+A_zqPfw&? zZaa66&UzgWXsZYv1y9xdtSke{>kOs1w>9Y!a#HFkPw#;@dzNeHl8XYE;;_@DoO^p4 z?q(A%Jt&*j!;GGajn%<^nfJ8o-V?@rpw!{`q2a!}b(zDvD0%t)CPit5S*6n!$1(@r zPn!AWQ#+tM!-`uCXgSJz1~7}lh(;4h|0#cW|B*q!oab@{ri~}3zg(2RZ|U-y>l9Nb zA22Ga>D)c1$}5O!F5j?kBxxHdWy*T!yc-bGlpxf(klZ62LAp{Nwt=ed@=umhvj z#JxyV;_iiuW%FP5SQ|YesU(Q$Hq5--7%q%e=0K$VKD-Rv*B1%UTKpzND%>vv_f+pgtKX_BfP$*$3WuvS&J>V`Smw$x(jJtjmM zil#_s&VV1{a~-u2vRs1(X9u93-yV*GLJ79C&cA+!yonbyZUitiPNg$7N8qfuKZT(p z4j{)N1b}_gpgt0T`cKCpb;P-gXl=F+R27yfM${ zLi*aw)?ph^bFEd!+sKfXk%xg^3K=SGmanz{F5}C0vsJx|3xTDXMF2aOTXbo>pLwPlRd!#pPLr5A~Bg7#}rGBTUr}VHg3acq~%K96+iFY|Mf9LM>VpkQmFyaZ10TI*0;G&*c3-!I+h@B?WT6 zlx||JvUcVy_SJ5^$19g7yrGWS!gAnG*4pZ{TE#WrG&AaT;n){}OEU|s%JU|K)4?us zDIV7zQynh^_~mCddrcC?-kI6;RknBr*4U7`<8OaT+1K@N%;>-O;(y&Wu|;@6OJm{X z?kL{|U;=E49oUb`u>qg1-eL_2nn(l{s(^%{+|9wdvV_hLAE1m;N_e4;*9$U;9Lz8j z6m+`Lpji?_Yr;62lqS;{yDeo?xdV3x%RU?T=uaA!me4a8H znGYT|mr+ziYFtg!A#IMi4|aT(1e6~boO^sI2DqHc+b1R?fWm@yXNT1DnS=ChD3$jH z?hb`OeJIICz+wczSB2pUn%Jv=!EciSo;@L8UbSZgv3Z)j(#=#u~)a zZ!cusXd-FLPS$~;m7MT&tzB@DUcE2U`iSq{fV4p0Sw+gW+02&yGs_N*sc&OWIg~-B zy=2-C{3tWn*YyZ`hOmOD4Cc_S|NWr6^5vBrfW1*oqj>zypVK;@T|;O+*x4`oSRjEA z#8CC>T5vYP@qvT|96fbP0f;jwY0=iPfV{$Hu)Z~q)CPv$r=?Hc55kd|*8MAPxkYkc zf{mqdf~98gmOKGde^ zdNl|*PBI@NaC`-TV-cd>Z9W!Yb_zDj-JOL1LS`@zZA{pYdO+tP|(mwTJ3?uFZOSI(#JV0>9|G_!yXMo;R=!Gk8`bmj*|s5El9yJ0LG%M99t;ZGq!3Zjl=;{` zCtf&1_6Z!rlty($_`g&*wk$XC15{(^C8(58H3OCUe2h^ucOD$l+`IApIw?!0+jPv4 z-N(>a*Ug4k6FmEtAtzr;oa;J~aky|fsYWr!Cj6n`Tj{`EQ^fJ{tkB7=7_AYAMznq3 z7qU!8#9@Av^N$WjqD_CVMHLXP%n$h?3ZPl3v_-&%qiW3|xuiwC>nPaHxssc(t1%G2 zz&(dx@6jUm(~6U3D{g-Ev~YpKk%_J1^{7&;sk<&|yN!v!!e*xZnmWJBxrz^m@*Oz>@vQ z<2}hlb2yI=K#Btjfh|x3V71U2B`XY2wHzR-`%Gvu@?hxhJpt! z&S?~s>tURZ%-6g~9S&<89K5uJ+462z<8PI}?u*$C!Ng}U8)P*ok7!ARlNl=9ir`?2 zc!WW&8i5mFNdNdiZWQl#gysAT9mkK0c@F)ST1jgm{k-NI>~;tMWMWAKz572Tm;@2<5DUDG{>F5 z09SmGThX_PJ`=bCx!yIaTTr_to|K4O>gew=_H(^|DPX-`W>pskohg-9tf8-rP^zOE z(v3cPvlm}IpbgzUw>J?C{am!p{(ywMD1wI+bpn>Nz>O6SlE;ApbjpkJ^75&H{+c}B zXlU2$UfPmtq9Jhh>HmRApz`pZq!NvpRQuG;6YiSaYA?>gaUxXIZ~fMUTBZlt-!bf zEv6Of(_?97X-E&fI&|5tN>UAXm;$OKB}k20Zx8Wo-t(K+89<0K?H&;(IM7B zQ*X|MQvQX%0|w#Mpq_W;)d9w5X(aaG56X;$KvO$NTo(Vrb71rZ;?_ZxAy|O4vOvYz z1L(EI+6J&eVCN41e&q2RATD8{(g-*>!u6SZPXio((>}QfWnRW}Lcq6{__x-weecUMSG701ivJTc7^7@=kNrSj-^t>R5@zFjOA7&IN(dZ$FTdCa|fu zf4_!I31cX=``u0+rvdPuV%C*?;B1zW`#c0Di9sI@Fz&IA1Le zMJ*u+f(+;qQoAIb0L0Dmff}F}3mI+g52O4x#1~%bS!Sl10Y+mo9)e2A`xM>!W22+p z-!z=CWY2VahjrRfD_iX2u)XCejev*saf03FISouIr%>r}$XrnpBGby7QBie=a*CG3 zva>9uN5;HVtq;|lOGlk2r z{fZa$z|tjrce2jrHZUf8zrS?e9_mj}4VGk0>qYaDtVN~sd+}v-1lLCedJ(~`Q1w>2 zxCAUJNW2wNGFGW@s+XV5JY-;x-dX0uB%dfB!C)F&R<~gi&W0}yk5%0Y3Fwg4*YT_^ zU2f-X&->oSlJsW`2*{yNqn#;&Y$d+Waso=Dq-qAeV7yp($K+TX)(6xRulU5`t zE4)Tn=JTtcTkFNN`9k1Bs2vedK?%7UxLh|;`3>4ZVB8~s9zbPKSu)Ty{TEKMIEVNE z)WC2-_~b%3i$|!@1`JeK2=V6+V@04Q%PfWz_X*MJ1ondth4})uAP0(Ncfo&9xf8WW za(>}1N*ROq@+R?Uoqy}dYJZ5MYZfk#$J`ro&z*W= zl(n`{mE|@mBkvmcxK;AZ0MR6P?xLcbgx#(wC5(k_M`4!U@)`ZJ4*uB^!w(A{QD4-i z{Fimzv3wv|88AeV);##_5S3E-4cw@BsAEwEug|;jSVk(4UQj21!9EcgCQ$393}s_1 zD7F;^)LI1`Z^KGp1UXh2+z8HwYR#c$IZ87E=_8`U=bmXfz{c7>i7oROX1@;6m9yyn z=JKk9g~aV2&Zn)}Rw{WM7x8p8ai3BjvN6hHP8(pl^V5yI7=Mq4Hc$2CMtILTHHFMknqZxs>uK~PVb+DGUS4atl=I0r%6+3Wvd6@ zKZ{u9l^^+IHz&Q!}#>#J-~n)NBZM&l;h4&MhI! z9qm)JUVffG`Tzuk0|n~i8*9(#${iFGY^wd{8D8!ljSNpUd)4@}oY^cjqfHG?bmlkP zXS0^8bBula7u%)Ml@(zKEy%0!9B}GvT>M`*DldSFs++KL-c9<#$yzO_ z#J#VwWKy+Q-u8TA_0Em%3iWmE+s&U?VFV`VuEDeq_5AqPbB~baV)a-Yv&E_#_)$3J zj^JSelxo#4e;HWoVu7HJQxp1%?uV=+P&}o9{rk5L(rDtIQ(gUVytO?OC|u5^Q^{Nr|70{qV<;$_yJ) z|Gkl)EpL%t<~`4w>phRpy9la)38nT=q2xS=nz5p&pfHRIT%ba!=VnntXZt(fGB>Kx zoRG>5o&{DCI|y+@MF+P6cjQwj9V5|ap)6tOe|rp$qo$*3&%R1u&%iziJSHE7U4$o4@J~5P=%Jr_iag3n)ex;OHNw_>UoDL4g3>$;cjH;1^pQ<(<6o>!3V z6b1H{5G3~NEZ=tkU_ao@nKOd!g|556KX9PHsc(r8?sI_BQ2Q7X@Hat~T^7}qOXPRw zmH_n9#sp=jkFmcqywud`+4{;G5Z~>y<`vgjN!B(6A-b_T!*PLY1%VOL;6AJHpdNGq z*LBed;FevW2Q5%N`UK*gsJyeMhKBfjs$dxwHsioHic=Scl?b+Pqbx98tY3{&nSw+k z+k%*9;``!wF{;lCG9!dFe<{oUzBnqI$H%?ZCH>4Q0;b>0}|+`EaO&Ey07 zp=w*P+pbdxxW`%&HG${DKCaKmPq%8rUe>Cbd$1fv$x$tY4e4|mLdW|wgMTvXn_pIx zW+!@mc@s1-bGO?^3{0zEK=XJ`KhRuBp|XJFvE;2-)f6yhxX%TF47ZP4g+hGA!2WiR zjdr(rxc3pN=YWbromV7~RMmxc{JdJtDJ2aRQVVT1Gnf1%aA#vUB`$)^uziqb`3R1- z#uTSoLblmS8Va2_#J{sjSA@$|~|@ zunWYrOrZam(dLz|LwL;qMDvFAW_h*=11Y0>aZ4WJmud&T4tk7e?t#V(vkNid|k@j^5I%g$~jEI(G~jTVK>WTgZwLlHO-1aT6_ z*3hgN0cK!nP|pdLw7v$e69)=#54BdqnFjY-ED=F3@N{s65a=DQ2I56=?4agds^i{d z>^$&nAgqb%*dL2X3-6jr_+g7m!-yO32R{39^c-FU1^mE5h^ujcLQD5z{R#aM zz&1ohwJ82o8rT9XbrQJt;Vl7-O0 z8{R;qnF<9&_DQ}_6*|OVuQ4pEr@WJvuWs9UpluurRP`>1LkgmE5LopFda2@o4xsoL z3!1PTK)lCg*#5S*KT!=NoZWN*jCOzL1|V2~e;AQpo*6(H6bOfQrG4|ro%UqY#FY}G za%?QF(#F_?$;G@+Oic1tef_lF)%TxPR;Zn_j$=#5ElG>+oe-k?dn9Bycsawvkny)S zOk{R;9;h(f7|^n5&jA@RqGJHB<&3!la{dv$10qV1hu}aU{maK!{?A2v`w=ZPaOAqr z#X@dl7^2sn(~Or8#ZaU{&svNP6xe$V5D9TQuve-kfHYpe+-Y!ViQ8gXmI^ia2IN@V z?xeX+cz5qUOcwQ5Bl6-%$HUA#8>4ddJ(oYUUAf9rUYf1~>byK?$tsXP3hIbfcEd1R z1wcUyt6n-p1{T_4dvt9CBJ6rG3H$&y{Z7#Gcw}20eX!Z>clSfnKr~XP5pRvqs30%p4CsQmuw(4t9f$l;{)23 zHbvx`k}5(R60M5Uk1rnKomqL8e`!nL@Mz7p5#sBq7+xu5DO}*ETKgDiu?R|!8&*Rw z`xKb^)Xe-vIE-sxauJTvU?HYY)tV+Cb&Ccce->AOO30A2jM#7xc@3g+gNXef%1{g~ z2PBh1t%z)53hIUt!5VgD`nCVU1maKxTi)Kx)RQ04bOTWxO^9*({5YI09@vK>^FR$w ziyK&RK#Vou?|8>`f&q67QLIUkR+vzrQBI{I;#MeWc?vtnH2B+u8JbG>8VAt;X+rrI zp1$z*mGsEHPQR7YCsl1H2m7(3?Ry#tU}?!4@ElM{!LjFY6rim&bfO_DkW7PMmkiPr zh@D&6+v_|P99!dqAl}#lWVwA1PDhypIQ9q!#8}~|v&mcZWnWT@rS7xZ|8pyv>n z8cje-=pWDzU$?3JJ~T^kOi9~6?y!`U#}px=Pa z1gPyOc2G^Gx{^AGoE+p7|1hv&qhcZ`AW$j2j$YF-kZF1Z+eOCpI+eLwxX6-P2uvieyu4cT|RgRXnjr&EHo%tRQmxra0O7nd80~i zX0>Eq`G1kD_g|dYP{PUjko*lxI;vR2er`7aC;}MN+tafpSa3Ev`IiGC3u9D#T@c*>B4_(D35QzK zp#J#{a7JCajbQ(rE218OsIsP_s@Yj~D-V$J*&k7a>CHc1HmOu?LuGy)FM2Dm6GlN2 zDZ7P+2y_vxE--;bLHM_r+N%TWRL2@5Gb)U}XP*f1Un~l(0E^E)w7=Ic`}sk(v0m$G zN3o>9kWF$0SXa0p*^S=N7+{N z-gj+nhHoAsmU$Fa0|6S3n1=7!`H27}RV(7L2kHGI_4kBSS z+NC=ALe?GX!`82@-PIb@YDH?b)Z!RFVOG~)-F0AIEMvu6_C;R#D(0HFTYvY{=%}0% zx_<8Zz8be?x(e;U(oqGRo=OUs{~CzfD6P|}1ge#SKJ7_*gUHcD$Pi6of(S*t(=8Bk zBtWGf>I_86Z-JDGgJ#*oIkMDhtT!lwci<`^ni(J}YX%+*L?SZ+23ad`$0q<=)8(PS zZWwMzvPsAWS|S${%G_jts68A7q||_f9C4#TZa5ySUI{qvNS81((J2iK_>I8ef+(M9 zh)@V|LqLqyWI=VK@A&;WHc@ITbi3Ak!iOCeN&bJE5vMam&%7?t*n#mgv^74q!_=eM zHCt(zq#0Uy^FsrmDA*P6v$BT9!}Z>1yjt3q2!aA(9g|-@2X;NgdkDcto&5H(893`O zBi>5~RrVvm#Mi4Hi#_MnqfCzS1vK0;iSW7hs@{Gu?Lhl_^=wE~wyi54J&WA>Xn)IU!X(Y) z1qVL5Hvg--oX2g_AsN3iNWDm*GTTj{V9193>bc)?9lq7F1y8?X25H!QTy-1MlXSSx zs~(8|e0@!>$ACq;xbRkOqZ^PZDs;FcJ70T4j+Y)eBVYvfsoQHS1F6<(d%^83YEJJl zC`>b|#fA02x7zpL)y~Z9YA#?LSKN(>m7)J}_MYQm*#NDNocI6Z5kU<@6YNZi+TGK5sXyWVNbr8YTDEi1 z32EkkJPU_KE*?@fovXjN{rg{Eh}{ZepB)0F`nYMM8 zeX?Ql-hiLK*X<%`y}7tQ=YM|`o$@=*2m|xOZY+lX`p-8%ov37o6bET|{#QLbpRtO| z(5*;J`sROJa~ti8>Ros#QX*Ru7NU;rDI<`J8fP$rM}6E!kM#$w-V19V3^xam)ARPL zjBoN1gEI$R-htDqZi!6hAevpPw$fibH`GYdQ?ZFD|LF(3%9!TK2wo+IR7ae0g=kX1L}>g; z-x~$+lAA#XxUhQ9nzHgmI#;!UK}WX6zdx~AMbz0%;@uYfnJYzDe~rK<+X_;ke+Q#C zuKP59=k8q}WKW)2>6y&Xb84KBx*9PM@XEN`;$4{T-M)3)E#osAqOW`HwFm) zo*$->bdBaZ{&(EsQYkNnw}SqbzPLOgoR!+w-5yb2lySLz8wNApgjuK6K~El7oTKYa zu`Q?$O+$A5G4^qon}168m*y4DjnUt=zwa_Mhd{w|;VswD&7AAnkR>kANbq=%+VG;b zu`X2%qjomev`NX#Jtt>?+HYzOp7nF-E!WoXhX0}mTo-Bg*cCy0Fo`!-9|w<(sT!KI zA8vgo=?a2+)}DJDgC@4`#z)s2SDwAcX^e?rfCN3M?>f52Hj?L`savkpnAHt*}Jt?wJx1ZT6ty;em?$QDvgVL6$2;Re>~p$GC3| z@{+dkTti@JQ)0oqyIZW2ZQ_+&XP9NL(_Y}UAcQ$}r+<}~Ip3)n5#IOZ=A7_>gMN(O zvvOXI@y84TgFA-4H&?`2NGZGfb!U|AT0VrPNbXyT3l_-416*9tNbqpL4vIl+&@V8o z^lqg;J40sD)ylC31+*$_AB#kin@0gi>yrTr9m^Y*7C;_vxqYr7mkn5!R=lB;FqgAU zvxgIss)|Mzl(bu~oUCyIBlkcJ_gY`7SS1d}32m#xT%Krs?KjlGTejc5HAYd!J6->H zHzcagaWAH14VMzT52SsM6-9(3w=3}sjs%ZAejTQy+S3yX$OQab?#2B)+HSv4GI+ma1uVrIdA@3 z_#T7#d?7b##zTA8q=9L0g`W2fOJ=pdIHjUeZ#QPwGuJZ)(==9e3pw6-PniGzuM_>< z!lIfh!sH`LB3o)+x$4I!9*6Gas>cKd6i%j*BdGR?doYiavjffE_P_t5WwA!`qBLjR zG`ZWXQqx25TfvUyesq^W1LyEj?&Rf5efx;#?mKg01Ts*M_`o zyGkdI^#3{8XOTW%X&?ZBxlF6&ZA_|V2d#g$iutCaf9K9!>huA%N_WN!N{p)e4JplF zkB|{jT{-{m)awA5!56&dk~l{_>H1_xo9G$FF(BH%Rk0s)XehQyX{e?%r*W=-?XSM< zR>m7uX&dIyyqtxltasyYe>uX?+lF&5{Ek5_X1=Gi>RLkWQD;}_&Mo+ih5pqzRvv|Y z>P!if9=4y-_=#%V_y9&zCbys;R^7(+P-fnWIHP7=N-g-yZ8s()%b)%0RjaqKK2`XO zP4>W^ZIIt`ZR2iCa!!?|O>Kpf{h}B~WO2zr(ZPSMn_?jE{=4li-sMFDB zQ5)Fq-K50xBe|17&&#Q?n|iP3;+&NO?RaRlt?t{~wUm20M1obD6niMzv?P<#?=hMs zE@uqv>8*36jooN29JuBpqNw&x4^BGRzrD?{c1K-#nLB08ZE`F-2WR?vX8rb#O{%s5 zpYqZU)aKCr!an{r?e@h`*aHih%a#6S9Uf4%=4Tpc9}L@nQx6go`r-(d8nM0X61(Li zS_%_CP6;@LFW6PQ!KS>#6XRV^{wXzF8v2ZEThs=_^&R&t^f6*O@xx(PA; z-A2`5^ga~cR`;z@C;LHJ%m@9nI2TA%7Yt`m!%PnkurLSA?%#K*piS{Xjmqw!0(#(s zKFd?j6h;zHeRj?_@NjNy$G$7PF`W}%H9E$C?R-d*tDy%NwTp>EQKWndl_R~LfvDR} z^77Qc^;F(y0q(GqjM^LKNJiGB$ZwL7DwQm`SwVK|DVZ3>d=1AfCuysF^THA;VCA-M zbw3N{0Or9Bu6h4#k{h)$cz0HH0EtvP{{gMFwWSB4{;EBEU^L)Azv9|n4cV_57fLm+ zl2`^y_m&d)>YnTZ`fo2<6h4w?}C4eD~@JBoT>}@+O z#ocOnMcwUUXA^}!IqQV#C1C>Xj}J3EgC`YdXNGI168~z+mbM{u=3lv74F2;?5$6vS`|wzA~EPj&*8E1YNUI zF(0_JEi_&(B~u2L-x1u+;jxNAk+M!$b+41SMBhV`DkZUjRZp@(ZT!wjA?xfE8SMOB z?RURrkTkCAw6~qC*1#Nk37Tuj%BEa$K4-wBc=^1vWn!3t@<%emQe1vG)tvaQcWAc- zbaB>}Yn9o)t?VICswKt-jMJ4S-rF@!qTP0GqLk4Rr*TWS(tmazT~Sdazv|khbOVoL z-GI(MAcZ4*L*`%_Vuf6ZxDeZlX-`74>a(jmFpu9RSr=t3Al+{z|7ro&(Saviy8l{E z#n>5gf3AHTjNg0mmN>tWs(H`6)L?3RMWhcH75BNdc>`g~GBJ>JxmLBT2rS9Re|Jue z<>drZ3zZ{F(7l^>0pZcS7|2!s5dq8=L*Y)%7iom4X7UMT*N-zgAXhQ3xNSOH?fJgp zxD&<%0r6t=faXMaCa&IRg8baxncr`u?N9E_#J*)>Ba5N! zIwvt82G=iq!Ht_gQj4?Pyg%L}GXaeAUEL*EFBKnOGPevm?}=lTd7e^w^oXy%2kuXk z@8mYV95YRIm;5xQfq7?1OSa1XSn(*=@9KWqx$8rrpQWeYl;8zIZ)YFz zMAbaMx-B$hvCfs!8nYvVpANe(f?MT0BexkAjyI8Wg>@ANq9+;0a1H+}9r^^U8_SmD z-;ND0W4`QlEt{oDlR|K{WdYtx+wR~0pkhB4QA~L{dRBx@#Ddt#rrCj zk{CMd!7uko?AJEdzJ8`si6*JA1Pu+g)xm4luagIN9=@Ej4==jvJZdLcG_s8Sk zS|EwDx!3KvRcS$BRLc5e7o{+V?&a~>^VU&pXmd75w{r{nCmwyd!*PzaV$O+IYIk7H z8)kn9-GvtvBq&+=7;#k91#aW-hQ4k_2I$llBAt!kqp45d4@MzbeiIczphg>*!m zl4z6z2EfVxaL?$4QdWT-CH>CJ`$JgV8sHuYiywQF0*3=jxTb?=cTvczfd3RuiXksMX?@ zbCWpcY)MbRgT6$tI@j{~6Qh)_mLJ^{+ZP542z&lWCqGg}_-8wQttZ--ldf@;Uq(SBdVyK?d{ zNX3nz(NfPfooj6zLyPTb>f(lvXVnafr+pN;ft3B$?7$g0NF$eT0&O0_qtP{bViyKc~M zZH!j37~Rw9*b=3FwxPBt0}iq6ND7XxNlE!B%%RkQx>CCGATrFW{d?p4!Jr}PoVaCk z+N_7J#%ictPpnr<+10rCm0mAc65Hbfmze1Wy#xq{9qV3wZ)rBveD7VDB8+hZp&>wX zV~k;kD6{7t7k(aSpxM2|4hO(8nVa2BqbJqYEG+m_tDTi?Pg|lmT-_D!eu=tU5!DuQ z3tJW)MfZpy_4Gr~RL5&C%92%mRenwK5k5XX&LXh=gKH5)_%QgJlvGWlK%D&$H1>G5 zK2HA;A9fhKgERXL2e(}N*07^v1#wME1{FD=<#*Y#rfNY~8CM5V+m*q)G~&$RrWU2` zp(@IeHD1PInDEvQtcY#e~dk}VqtV1NLEY)IH)gN#53N&e@F(9+-af3Ek^_p+aS=JTBA zoco+}-0aZEyz!C+PsFs$(CB2gj_P;+SQiN7HGmZUwJ!S*=lY+|84|_ zB5+L2|2E%`U0zaG}WN1yw0DepVe|PWPJpx|$d{s)Hx32@Wl|ud0lW3ON zU@BuGFIq_)88@X+j6}e*JE6DPuzxC9)+QNK9`D>0KCU{u99qwLsRK^lyN7#RNz97w z2=0vYtH$Ut8x6e&%mZ zv(t@kzVyb6-EO6}IXU1bXqqo1lK^Zd2qp61>EGHa%AGfcRhvS--43v+n`skIdQTRR9-JSEfdz1dg7IzJD&Xk6 zs3`?!zW8rz`A1u+6r;sFkXk&?(b6kBZhDh4XO6k~;8n?%l?Pj0yld@JjZk2IaCXz9 z{-8y7)o=Gz?&^)0>I!vUxs~hPmN!dQJz6~26lNeJvkcJbgTm>q#D}VW)uj%2ou*of z@6{BY#mBc{jfk(fKy>zX1blJ1e!Q4*l(a;Qn4(@uVU(tar7eWszb^~+>o=wXeRxPg zB{XX$L8UNL;ckIhsO?M7sZ2oEPRXmW96ICD_U1XW^UD@9=w*PlHm$h9X^(I6p8~#2 z_YgyS7YE$ScTgjBVzF7gn807t+vfQ?C{dhQ-Vl}aoLM;rn8wl2R{N+wVZqO3Y?|mN z{5>oUJRx}%EG^!{6Yzdz4&MQ{q;@&KxXjP&6GZfw+N^(pN*=fcO(;Fh8O|6KrR~ z+Y0tuz?6%;it_w?P*nc^p4D$)%N(OJPO>b?8K&6PrIfxyuOem>zM}2_a_Ua7cTQ=` zQ_QpQU`3)>x`03-f9zAi(^M~9HAyb-diyZ4g_uW{|BBro#j2Wz3i+L3e4+}UXwNJ$*hFuBt-VRt0~39S?L1%vzS*NK!)ZiXB(V>9|liY;1-X zLH6qW90BnCQu^*;_CrY;^Kb)GFvr|YG-wB+_j5!C{uEDlF^KU2< zW4L*R=Gd@cPu=y9biUFIogA!Y;*6zV#8MPLa!ns7ZL9kGULFWcx=QpAx_HCx@r8rG zadu{MCM};+mW&ghM)z&?uNikg(@5JhOIL8kCz`T&9&k%Z0JV@|d62cMZC60k%##GW zh19S2e|Ym%tkA6Ch*G`ua|!SBW&x~;zIC~!@Q3J96;of+7TL63+&5KMZ(q61Gxz&w z&DwZ<)5{m|Ej0=@uWP^Ei=wgqp}xT1c$1Sio3Eqg@1`qz)x8*|t&L&zuBuEaT?P@0 z*8_Ld{tK$}XxoGyTQ7E2Dl-NGL;2M%r7VwTALM*<(_(6d|6?jKUml;;_xQ9q{ROA0 zIc(NtYFxsz@!g@!Vq4PG8a+75o_)Kh3%xm`&Cj%(>8WySXf~2rzZfHO48l~$Emc>2 zOPvhZlTowecGdT93fN-o1sor(Lt1$RFwbaYUHyJWIU&ip9)Z8V!BJR^z60cuno82% zA?g8zqu*T0>=Eiqpsq~Cj|&}9npao5$d{lZx6r+|6Yk<*{l9{on?HxJfAC(c$t6FE zu!9x&*W0INS!|jRAKL%H;&Dyt(ai||QEGgmG}R*i8M0%8yiSE^MLZ*m?Tv9C%ph^s z`~#KEPwHG?#^@pPn}>$UaOa+{QyZAbk!cr4XXoP-@ByuDHwD7hwmk)EU452?U5p?A zx{&?-_-dCbL{dAtQ633%(0lV&?P{l*6)HITxOc&dfC;!Q@J2DwhOuR?OF-`b_wYWW ztkYM`=4+aSagh-Ky~uglI=KNh5+pAwuP`d?&>(>_G}g8^{uRVDb>%8~_w$qJfnn@& zQaSdBKhBJRay$#vFr9e0HE?>)8sp(HvrCeWx`df=UFUz_=^;eh|Qu*br)cHo>zoUSqT4V38mrYAfy8!j^ z0gszDZC|TtZJ}?3?Gm&dIe-Y)ehHHKu6GI72 zqD*{*i)V(;;ltoU{y=&}Vf&7bYD!GvrMbXezr&`<@-if_!Wa@p=eY@^2~~dC6DH{y zmAxpM#;Dxew8PcHngVpicX=@iP#%rY9>Km}O-pU;od9w$M0pkK#Z6PTf2D_ElIvj5 zH9A-y+NF(r+0+vGsaF|&;|S-$?B0|ysQO~ON~eVKV&J<4X0jVbCx9~R#ZglUB z;a>>K<1^fgZtwFZS35}wCQd6@F1AuvrIS}CM9`7#q7?}zPDkfSn)*7r&%}nNL=LD+ zV2=D`jE4*twep&2ias3&dHsOIO{El7d2*-1cTTA;G7Fv#r&mT~tj^ChnccLSPp1m` z^I{SJ-D=wzK=mgLmQ9CNbK%p2eVg9@86RG{Xwlj^Dir%ts4!v6%v;7J7A65H|GE8c>VfucLW04YzB@s z3-JWNJ3Ab}zZ8&|z)53lD3JFo8xe9Nce@aRPdAM}d3-)kgb&p(o?!ngb98WP7DpqO z^>j5()x!$l(bYJ}?<`kjXZaGc1aIMP&pViR{|N&DJ<|RNS#( zhCQq<{R$jmc5XJkfgOIvEv3o+G#P>;t8tsP4wF4WhWZ*qs3h$Ct94XYifg;pHqXsD z`OH_;t}y#!4rL|&G@cVFncd9>WyL7%>Fg@bHNU?9J|5pT-hY31zmT4p+2n0CjE$x7 zR-XPmIv!ZZhB;WC}iB|*snvPqx!1|f9h zVB+Rkl&=~aR&HL8j};Ly_ItMr@L*lYdp;{iLHvpg_DM?3{b$I>s@ZHScDvxV7I8c? zE@Z6)+kUE>cfoiCB~;u|d3_7-v$`#TPEqjB&FNI+OE@JrOBjJlqQ=kHbkRu^c&y>C zuOqY~!FH*DlyZfX<)KdStL?UN%Umn4^{H*eCd#XWHxiAvZ|V2^8S@H9vr(R>R(fJ* zOiG_$U$%27qH)%~jcxw?#DJzp?h6p*kVVk%r9=IZ=`Bo0p>) zjq~9m>dcaKevCSv^c}3}mne&m;oao69So7D7*rGwpGO&yQi#5xh^MzQr)0~Vlg!vl zWN!bTS2&Snjq#m{Mfk#TRP^J=b1ouZM%BeL0pA_R%}@O+jX9*78F`y(S?JBqK30#l zLWosbdTC4#5vpG1A1lNsj*1ACLb%?)@-Khl($ma6YA5M^UoOZlw#I(HXG)vyBGc-2 zT}Rr>$$bP1*1!&+g8ziLPLn%`xhK;V=(hCSd~>A`&r8KNy*9lEmWP58Yu?<6%ZJCalGXlqom}mK2-_kK02+7PgtxwzkQ>7 zd4A@FZkAJK#(4^B*x!GA;)bXEEJ_EDJ!+S};O}WFJKK0|e)W;g>LPJq0Z6O94;0o+ zh<%{)?1?JITETPb28oZTq)uhGJ)7#hGI7%?yDq5L=abXrrDqD+FEd_#^uIePo0L`Z zo&cXkLvvG2=WPWizGGA$n_OTZk9Om@=2FvvMK!=vJmMnb^MhL4LWb}?JHZoWZYfg= zFJG&`&ySng8KcSYb!go2bk(m|E(DUBvaju~q2+~t zSkjV|qwx;8u2*xS&+We8vn&Ozh27)oLTi2l(P6)EiR@nE4gP_%#`Nqt4qu|5iy$iM z>DM<}+Z!y(vgRyMAt~l{(dHwi&CEiD_W+~J#7ETFFCd65%#keCL+7$~+f=CAY?%=q z<=kWFJ97cf(tJ9>>$Hi32=udt&N|KNk=wF%DXkM3@>pkpk6k=b<{;U&ucpJCpi#{e~+u0tGLG%by8fM zn1Ji9kIr+-MWRlLdI^5AT?MRSC-Zh;r$lkrkhgoo7F_iv0uKQHhm6foq=0GPn4x=Nm|tf}#!*%lc0Sf~8N z_!R?i$p510Ewfft^=Y8OD=8sgk-x^gC?K1QU8Vca92l<)3VI-55q0htdcCP;2&vyk zy#p@MiQhEorgp%jVJ}RR-VuW8Rc1$rt6HsA%AO4t@4*~@o(iT_Ig6=lq~I!{!Ze?a zj`_snv;&dO2Q)&P?Z%V8mRU*Um^(8Rv}%sT8X6&z%1o1veAU_Vt45}El{`1nTTdkE z4-~`k&HKyT|Hk277xm<;cn{ZHlM6iZ*XKQAX!_lJpM79td9pBEn9%Z)opv)+6@JzC z`#*D_iZX+z>R&7kA|D}G07Y=~{m976?8(P=cJ+y$n=75W&{euNl|R!xgOM20R1Q>1 zYe*c(bg9eTMTUb%rQsy(LuA?`3DhM2T%nEYSZ3$TwJ4q-8Jy#nBvZ zez^I~k=q-z3-?<*iSgCDto#!CAFsdf-9I9M*^`mpc<1P9Bz(qg|^A9JFx?k?BwNaV0P1e!7?;^W-UyZ4^gO2!??PCyS%QyP`z>wjJ|07aA0F%^fJ9Dt%VFEN<1tsTBC&e)Jad z9y;4a?9{F=KgwJtojuA-CMHh&M2GbjQ2zLv6R-8Vb8IxBLoTXTh^T`26o8W_0i<>8 zfyV_kvdO#lK7p>_&+YA~=NIpedVv{0wvH@?s{RkGT%@zg#g`$I&E%H+DN zbbb}rav%04{q-lP1!ySuE)U0)E#EioYP&2hx!{IXmA*UCHwoc~MiX#bsv4{eu4$jZdABJ8?ml+UY?*;y}V(8&$1##Yqj;Y>a zxt>Codf*R19EEEW#=w7=1KlEVJ`-u)&^#5dP(H2;BF;<}&I>vRk$B-$E(;M%i~^6> zY%Xiv2w5l2h3W4@%?c+Cfc!i_KBM=|X(FdwbGsBre&^V8?j{=2&N}Q?rM(8in8b=P zCiKm4rAgu9B|aJQ({L})WM+(%-Vv`E^omGG5}+G5`lQV-pse#4I(mkIf5l50nxLSc zYkwiU3GUEHZ*R~~5L+P^@XjWF-oxEX=CC1>FyZ3w+3VdH!(K>No3yq}EzgYMc9=sUAC4*B#Wl21qHz^_)I21~1j zn2ur80>lfdyLwc#QqdT@8rdkRw(zG;>5!scWoF05_8KUVQ(<#3e(vVty8D%}k(CJ*97Pjd}NbDrXsgPk;J zM;-w^?0S%djX?xipv4Sw&P_n6k_U_|h^Yn0tB9jbiPV{fCTLAW>RYIfS5^;2b7(A@ z@JAhsH9ip4kuI+|X|82=1zCsPxF|Pqm4&|^vvR5ZC8*64V~vIWj;S!D9*ml=6j_U{ zNIx9f@TU1z5pkLubXP;~p%dbQk?+6)HBq#Rw>!|c8GZOjKG!3)GK=9XCT2(D%|YHWsf$IzKi9`K*UmC` z{*&!c=p&j@hiEPFxc78mSj_4p+7=D|!s*_K%i~Si(>KKI*sp5d(a$jc8eq&TY9^Pw z%6+W^H{5BAX0SZ8Myg9N1#t~056RkIFb-*RMcVaXU{%dSZ|d!qQ(qq#Q>EtA7H3Na_P)tLQJz{vx?Xy#=e>4)q+ivXf7~w}}uTkNe7Ght8&uayL5l`G6 zYc>*cb9J40p|yU~0eP!3=Cwtr8VE632w0J)gg z6%Z=|G*0TJ8Q$=U}yS)wE$D&CCZrZPU8@FoE zOv)XdMkT4?Tb<+`YO`qmkr9{cemfnzqtC&ll2SaJe|Mo!%w{_oP1J-ci5iWNj+T~C zL>|$08nKXqxS_J+v&LJ~1s$Uf>P%BXul_rd*ordp64GK07c+2&26EbBtA0~DmNnsu zILf|`%R2{crEW>-IyNHKK=fe_Vt6P7HOM-i-mwZP%hY(+3 z)JX?MN-t+I@1A{ohoRk6Qpry!bPeExg{s;v*Q62_LR=fl%tG9N>a13EkCvaAg-CW3 zm`E5?4(dH^&(}|@kt3h2XH>x6Hbls1s%KA&NCQWe3@=;Gx+(xz1=Y!9vT3QO3%qtj zzbuY8Tabrg3yhJ|lp%iV$}b?78jDE1?bh^y^1#_tU1bNgx3sj_ABs37 zv%9n-7>#1@in9)fnNv3RMyE4glGfOw$t3F4fO0ducSTNmxTH(Q#miHU+L8Sf4C;RRO1k!xd-gSCr*g7Qp@P2sdY@mfa8OhJuU(x$?+`RjRzni7yHxrTDt5BMtP?)CaEkh_X;4!|}vS;=-n zzDgXhf!y=k@Ku}lZ#%7OX<{U{-`ndQH94*6<2wk=PCLbf2_ypqv|r4wrRp-=DmY__ z=~DnyD76Bs0*>NMD`4oIL9`8t3P6|}f9i_2p^?$33};>j2aL70(1gyV*9g;BD{h;2 zb3$~-h^{hP!OaT1r|zum;<=v{YJbd_&@ljJP6tVu!DXuSwBnxpfPy4}`#Nqyk zqEzGh!re4g#leP*BPWC>Cq<6!Z*&IHSSc6rLX3s^l{(YCX6nDAzX%Z>s-8H)OP`O?~2KZ(|+B+x4`O&*2~4S)Ie~KolFgGnfehT z<`eFk$v#7TR)C(4KV3tq2?9CAH72aR&!L8hdaZ? z(}&!|swi$)|B4)MO)+(Xy~6<)XHrngWzWKJtK5`Znzi(oSvrR&B-}fjU+M5uB|O@y z6OQl1sJ^XO^Szs8U<%RmQA~5S_{HQFZDK30PaH6jDr6H`lX&I|Fc9Q|HgF^V%OAkS zLJn8ApZIeHt7zo^M7vfec@>>*jed8Oi`Irg-YF>C4jCZd()mFQO&ld+hwKm3*$+bru@ zG>liop|L_Rq7)8$xyY2AnUT=|WFartnA>+9K6M;1f~Pyh#KtZ_*!(6;WPQ60@a!&B zWUv*hBaky{2xI_tGkp44Bu!VAS}vY zx5YA|7(#jl%2%JwOoF5Byl|TeF+plr%KEMr;OR5PtJNBFO|DkZ9Ec6dJ{HE8x_^<% zgI(M(65KpieJDEh)FD^^=BvP_9i8nvBH@z7MC3ZaQu%tX$OHw6PLF<9w?}18LsWMI zXqsLeld5)j6m8}U$=yFo6HMYgbbIO})g8a8&P?qBnt4|mm%$u#r$AC>PUqZa5#)IXI{^cnmbwdoI)n8UyND_L0+QYFao2h$F&+of&Ye z8ceiA>WnK_+kDrCgxqj_C{jaoig2rnDLTn{_c^T+ekf&xr<<{_|(# zW6Q|GCY)<0G_i<sx&@o)YW+={#Sup?E>b z42m8R(T`rtD~CfTlBW6mf$y>9yD&H$4Gm>Usn-}4>&oHy)-ZpNxJB*)(ay%qtWr1Y z9DCyB{rP+73lLry1M1)Wt2$8ly92LBYI1UNn+Gi(Z-w}A3=Iu$x7ey`18Zumljl_D zr@zl%<(i*=EQAs&Stc62KozKem8E}QAWp{zhY&)K#B2871{gJ1=A=1yxt+1~s@at$ zV~&FU*ADPC{kjG4y^kvyv6UpCP%^Vzjw~t@R-kyo&E(kH}zMNU2vf)iRXY-fYp!bz)Ma( z*%8{oqFx*QCP03wvn}*|ll%zj%EPYQ>3ck~f+lYY=gKL*hUe67tv)?;$=H(1bTe1y z_$iTg#eD(j}UeUN9yG$Pr zhu!WY6d8k> zT@61TW#YZi?wRDZy{bx$1{|Ls(f%_!ItteYzo&TUk#Y++c*<}f0C%;ypD(~f+yn}` zb`nmqOrd!Cw-tPp#=Qjoky(8|nYlwb7W#|SsIGH$LYX~EEQ z2`0}VP}z~-X%fh>3PmNZ6Q9!75QLz`l#9dGi4HH0lrll3@lSX=Ss@ zZ+4j`0H;+$%<1$tF8uoU0@VnS=hTu$BdYBmDHekF?e%zC*?j&X^T56YWyj9}@3{VP zBe;rFdlTTJ#JSgrAUG7qf#nr1Y4~8x zim-~xyAeIreTA|gL9X1zqYwB)aUGU;J7CCd@t$T002CT^v~_gQ5TR*m!@Aki z*kimnUJ2<4z2Y)Rc6dF8AgQ=MSO$}LySaJO^&^n7je)-EX?>M1Kc`P3Q4cUn5_?5- z#$J%bV6(BQJ-<>jj&z?TrCy^>3pUagaOu{Xp%$$`o5dI<; z0!ZNdCQ6>33mgT=&U?4gSdw0hGxa2JBk3fnsfs3eT|)>G(j`E~B@hQ*Lt?i7QaW7$*0*%Bp0qswRwhWD_hA zU#aS93=(}nyKd|xVz5FQ2h(Qezaymdfn4KQczMt~0;MX~Mr0PiRXu^GuKVhED(&~Z zdLQ9!Ce+o@1-_{S>=dzm7c)j<5&G=_FJyYPihcd-gxZ9Eo?d*JfEl5^7#BV~0T%WtSghI~ozY z+fQ;Gz*_}=!_AP&8ALTL$QK|)n9A|YghWL}VeP{050h5QC4O0$HBFcV#qfYQ*tA5n zfU*t;7LJy5clSl$Y`qU;-jMuQoas}BJv4sgTi*DJwVq3pz7Q9a4p zqIIuCL%+b$+r8C1?DRqqDb_a&sH5!)aK_px>ba7YW^>M?+0Htx^mrN5yb4Fnz~w_G z#_?jzU3HoiuS>gyRFmF&!y{>QKp;1E2f?WykA{F_FDRx$fb4h{h6{)E%qlR?hpD<5Sv5td&y{Iwbbt8QNj z!bh4503SQv0J;Nmeyg`dxhkCS&zH(d)hxM5RIa}qKWLqR5_=1NyI0`9YIBo-m(rpInj_^JGUEY`my`N&6eD}&W4i)VHb<^w_GY~i!B_T@lFTNFYPH2k>^2fPBS}85EC#6c{i@K7PyZ9 z`>u(Ar>gJIn#4K)52tB)$rHYCxR`s3mgopTG>t%l7Vpnm-OqJM(Zxy&ZUd3@kiI0y zvxKfq{dvVvEJ6m$%_aJPVC>j^*Ea+AdvCtqWvN;tQ3y5-;9uvO5TV4&X%Die*k@tp zpzjrTyG5%BYYyNX(t$t};G|IDCL)r>iaX8oVxtzoywDl(v9FMv>W=wbAFlL`m_( zp`E4R(sF+Ue-HvQ`NN_+ghPB4x-QM7Rr+a)h;nf5pQ#8pwdbi4lJqGQGsovc#{D{# zqR5(iY)3*EFGh%UMUay{OjM6> zHft|tK8o)yW^QR7QmJsZQS+nqHdy3my*DivmzX!!lrJ0hv9mibvNN;k#eKHoc-7Uk zSGR*ufx+UbP3OxIT-9@@Ra@pQKd~vb$6|bb?{Sc+uP$l;AX$e3nf(!JqvES4s46AN zoVyU$?AXojW>9aj++c3$m9-aDsRi`?irE1AF+n-5XLDT);P??s%OV9#U-!|bjHbrO%LB#S z$F7>$G+nAqPNz=N1w9PitHdme)ZyU05<$ef!6*)cvL$X!P7+~LxlB-wk88)2G9*0( zibNu=SmwcRD7~`#0`$*VUq{4s7>#A{-ZpN2pUo9fz5oe=aIIyyg_j!$BGYDeX@p#U z^vzt)qeBK>B5+`{-{#7i0M~0var1VGo>y8Ns&E`j(}J32sz=5W!>M>(gW zeKCv_(sTEQH)pw}IhelSf66YJZ$Xw2{H8=@_J`rP*ibWJF-%DflrG#GE%)KPWej#{ zraXK0tQncbB*LcmM%PITKb57^E_3msRFkE7sdW?X#;WjX51Dc+g=3IwL~DpQA?Emn zEth_2a=t<0(H771)z0;<-Jy9K-~JbWdQYbRlA7Dn zgpxx^9-C$zbE-FTZIqvsovl@<((|RPl5Ow)G5-+_!lKu9%tllgvDW|8MJ##V&L}+e zA-~nHbn-0GV_QeZF)eWkaasFIE`S$!Seu~}r*3+R?)I`D8IAe2OL2p;nmXdrJ1}$& zZEZ0=s){m48GmJ<>+ZxWT<`C1({BETmO}FunPpFucKSMGu6ITBu4VyzciJy(3v+)I zFNV-x!+Rhq8S00_4zEgZw=aQB)j;{KZ~I8km;k2xU%xy~7se=Ip+;iaL0Zh5{o+?v zJvTgFJYscrqjCUarobdrJM31^Ux6B$zsEgpJ$jEWa#fx)=;9 zX+lN-KIFe2s+W&EO>B9&#g2^5hc<_eW389vrSuCkq}1>qUJRmYo6)RJ!@{ZViC0tV z85Lgv1q4BF96v>=(*&;cEbYT7`#@}UdhSC|O|BhhWZ+A8~%z4+&7#BLjQArM)K7wcV*xmrZHuTm^a!?&lI)Bk<7rCb{ zl$B$!r!HsjwkTm_xW~MGJRnG0A5~TvAK_O^T8(T^*{P&KAq4#8!B2zx%xmeYGL?stXIaU1Q z`_-kHIc_Zgky}6Y^;Ugy1Klq8&;My#8+mR1k(#>VS~hm2%->7a_S)qumO5&X#O=C2 zTE?OZeT3pG7a7;o**K!}w$H1I$VlCm{^z5OrHwXR@b|hEdiho~Ds(%O_C^JBJvGHe z8TWQq9)z5a1WnSpkl5`%>%i047-Qck$Ak&7&vAp&k0eO$YAEXxZ5>B5oh4792j0 z6YktZIn=p^AN{xsnOiD{ncjSLa;R(^+g$mKVt+W&%M*YMWd+99_uLh6aq;b_A`jBU zo8F=$w~nQAN0`-VNDONzH%P5~+rQ;>a-2$`F*hfGA%HT~#>?}G5#GuduqPq1Y$g%W z6MJ?SrwcC_$sdU9D18;aER-w34h)>-6l(F zg|KN+(i2rcd7xTs`1jzjx>pdV^`DO^nyqU}G>KqH@aNrTMTT3Aet{@osZ8JQyqG~? zq=M1h_&{Ft>z~BEAnNMxDPv(%?c(D`fmwkD> zn6d{#swMwRWPR$Dq`oO=?%l(#{%}P3>dnw$d>%21B4sXHrr(mD+w6i)Xtha_d`wSX zTGw@T^2IIhThXu=9r;p-_|pZTkVukqb73miwvzGk{t?++V(5$f4Dp8#?Yhuh?ccwk z_P2Fxj_+lJpmG9rb$B~UZy`;KBkkF)L}H)6@k(6omI;+xq=(tJ>C2Y{F9nCC`Wrdh zSN=*0I0>Gk2ES{3!Lc5ELAWq8>9HRen*+#*ThF$qr}HKedUEZwQ863%;y}j^xj?Bd zsCL1lEqc6RP)@X>0-5mYiJDB)oLf#^^ZU8Jh#yEO6P!`e)NBQFzBQ43 zYLD8AHS)*-?ou~55TEW+Cb?28R8i*Q-Mt;y`A$d*$U-&<`R}M^2@xLSuluh*V1R3y z;l;>(7MK~(rXHN;zQP2PPbTdEYV*{^pcw1Yw_B~d?Z#V@i&^xZ1$EAXIubtPWXzS8 z=DM9fUoAMh;BHD((OoI*an%k*HA?6*Na6oNu*GkW%-M#P9T_dB4-WrML{VJ#)tMl8qfIfg zBIU1+sGu-pidFX8TkVE8MY&m@j#62uzlj5JK#+GJK%z4gVj1`!q$1Us7v|S&WZ2iU z`}|l!a#m$DAt7_nCC;i?oj~P~C~1vo!BK8ll8E3c?jRHh%LS9tvh*8QiiX1_LX9W~ z1u=DYGxHDaNUH8rRTjQ=cfQ67$7A*eXw6$}!2_zmn2)NA8bACSGL+ru(U(xLs>|d{^6iZ+SqE=Sk8KNSZ=Amm{X{E%8k-B1+{eC@!?Q=pnvwEgYdvGvGM(y4k zC_FL7`gx!aR5l{zMnZb6#^n=Nreii{ymj^!ap4ePAoj4!y`^XUJ>4k zlZX6npDc!21zx@^G6y_)2n@w0V+!%doo@Q+t}c6zOXb|1aDuuCwxUPNA8XZb-&=hd z5J8V_d3MX2z#EQ^B&3>wL?K^et26uYkBnf(5CXGKi0q%+QBWg=;S|+S=OLJ z!VAY3iE`kU3BXMzQ~9F&K>mYUW($%aASq{y;^$A#HB*672I?LODm|cqfRe{Zts2Kx zC*TDw@s|A@jz`#SE#sedoa!?%+a50cLpWLBXN^nW?>~E0BmR5MTbB++9U7@M-ikjW zFhFa%#c$F1?fHF-?YsZ@PeFLWz3`t*ONzo<{M_7$#1m4<=9gECiyard;#%)6i>Rp2 zE_&^z<$I5?R)&y#FM^E$aL(iz+uHKb;NzBtG;-~+jn z2)(IGr*(_=p{~y#HTMH6gZ!JpM``yS0n1DC9l!0?dO8TKz?fK{E7@bIDA?hP?-6eD`n^w^VhsZH;Tl!k+cWeHxOQnDsr;A zSMW~YCGS>Wn?uC}4WNq{=h&Juf@(r)9`YA`ne3eN=C3FuV?nZ2Zq{#>fI~3Ucxo`~ z&)?QxBIaK7E$kOE%PQ)i_Lkmh@n!qT9VelL6bVZ32R6h~wp+}HIc)$?mgI)-s_EN= zBBnU^uf<}TgB-9Xk55mUZ=bEOr`~@Ti(ZAmoh>&-4W*-y!O@m3J_aIrO-NVgfuL$h zcdfX^@=PBpD6xC@J2zqF{_Z2eCVnFGm_M?@-2B|#rdAp)gkQvhZ1Hw!*QnN zU91i7GI_3?uphN%f-E^a%ww22kh8adyadX-RV*gUBx5W6+tiFo&kX#&7l|p`4u1Gk zap-|u=!b_@=)GFBc-pXWICB_k*TJmtdmH)vAXt%}<@>X%yQU>m!UV2bVdVze|WxhmTm_~_P>?Y6%m^tx%emrxaPVqQQbJuZ1jE8A{{P_wKV`zlbosbov za#&O(NHINh`ykq8Q8h;|$VW3k77{x>gq{J7_^y&R((gjY_HbmqzeK<2y{wTRerhUe zr(jgsmpm;F&yMTgR28b`S$m5#S%snxwL~_zYWyCuf$Fb1f3HX&bg$-&!3E^~ zBt4hKP{_Klv!4sxok>5blu=Z%l<5rxNiiTKXw3Y(WZfa()@YuZDiWL^k<#IC(|zE> zixla!Ni&_jm_nQOXAz8U7yaROE!>W2!2)W6qKD2c8s#I}^T8NTy1tHvLfoY`s&{rf{KRzhguzi)k_#_B z`d*R#A=Mvf0!7#XOZY{AIyUESUR4C2}1q11rQHEJhoWlXhY!l+J29Gs5 zfX5pC;EwBVdD{gsiHmJ7ZaL@ZVmj}qEkq?JTNJa+cXy?_--2TTEPu8vK%e&Oh_CD3 zPwLeScJ!EyEo1B;ed5~(A_DT)WAgH^O~c1&eCo=D|G4x3+@Az^wzh=!g7OgckguWa zsw!!0SwxlI%Mb)@jg(?-@s?>yvIy0usS_%qgBH;z^%UM##r-M#ap}7ecUc=>+1VW1 zPdHLcGU_c~}Qq+r6PS)U|xOG6=A}yx5EBZGNs@!J_0GQhnn#fTFGd%g6ta z4(xLo{V>e&mj?5HvV55(d&u*rmIBR_st`1UUYVQ^BP5VM&<>2G(V`rdN=6?FnOE4e zb}!#>DlBU&(v0eUaIjffbGp(&ZT0@u@t)`Pdhv(g3fA~d+ym!hPX5SXD2Fbk2ahkg z>g-mN5_3_E`zGMx3a)j{m!6{KeXF|rCm)(n5tiMgyju#9cw(AO4`K{%K{#Xz(upX4 zTHw@?Vj*4BlNY#KpxdlMJc;JvH;8f8V=}mvdW5PV_)Ww+$6R z!3nHjU`O$kG$|C>VVohAZ)$8%=V-%w05J?;#w2$JIOd@Z9mTDM-b1sa&#^^YHg>nt zazH=kcad80BKj;x8etbxRMY>2;>2$+w3p*&q08emS&B`k;*ZFmU=chd%Fqooqx<`s z3xh&(mxXpJnL68D;PlIbgO48{)kH$8<9(%gpQVY21XV%_G(3MDovICP7hM@Y%QEl8 zy9xN~%@;~M@Za(><{595&9-IoNNR}m*WCwbvRg%pR>Ur(yr=8$^)jJ`sQYF1Z z-tEg5lzAr^7b`~gv+Obv3V zxV9_CcD-+IwJCAq8+5Fl?#fknrm)sR%rzg*iaM$PXfUt>$)73;$Gzu~!&OfkEWDd9 zxaYy|bDMN1`%u{z55K7HBX9Jx%j~b8yFbL`uR{!`O zcb0hpYh>nX50y<1>PWuqIK)xw58#qE_Dqze`2Ucbn4LRPzh zNMRVFoyq-zO=1w@kH&au=@#q(9|fQc;|Km>&Sk7+0+pHYMFu?qjMs$NwMpCQ`D?M~ z9*M&S2aR!sis}`#uAn8&-KV%F{N*toYqQh%nR<1WTkDT=R)pz@qVj2%wlf=LNE*y& zAM-EdA2s>F;n(e@oRX>U$bfC;1(&V>BVLDjVw7o;Gq^unp_fentwQ7RpTAxmgPDF| zp=YlvS!hcAYo~e++WqVYaWY03eWe7;Z3>@_xl{uITTZxK!d5P+zW~8JR`>D`fB)KL zAm6s_*|k_r-xK34<>==rj*Trr1)B17&|-UKB7~0QvF=U+$IIN0nCM4$q-|8YVe<2$ zm-%}5J$>g#i85eXVjW$@Xn%Uwi?;6I_EaZf5bqL*GgoYoUIT992KM`vj*tC1*y$C#Brb}a-9 zHvR|G^XU}cvAR3)47=(SJu{p8d;w9gTH1k@k>uWnSN{>g?7f4nNSShM_8fR1Q54r`hA^7*4z zgX3Q>2#&zJKB~@4N!c4pvrUi_EY$|HeA&dZna3(8{C@qhe1NcA*Cy0GPuNoWIXu^R z)-`*Dau)rzTN5UKRn`DVk5eX?97ZCit5I}g{T%;zwBrDZrr-MirG$wnxV=>3J60)r zKpy_-Mf=>3%Zn1{I!aT;T+ftS729$G3xT4AR*p3ax~ zyip5KW-J}WZE6cXuzxx1+l~7bckLD+nbnH6X zEl`{f#={f#rO+tXEqbAV+M+gI(_(kK(;+BBg+{Yy(^~S%=oU9|-~x#~$XR?RX|;iyrOFh2Zc@JngHtNtGep$ORH~pJ7^K<=w*}b7 zF;tF+T5gcoI%;BY1ugG}1l7{IRODNs(fJ`RFf4MZdg&3HHryG)2ZAXs*JBLUFe~wa zyTrL$cU5D0I(Yizvpj=~dF zg6C*MbgL_^`=&(B-@fhbYf@6AbDa3Kr5;jCmok;mS}FXV8v5Bodv%w7$>&*MlItG( zv$&eV?#Xj<@%N=X9yc;JzmA;0fNKXac?KYKNgWB2$odGlaqQ)^{9B8qX5V`R6nfj;qOBpp=w~w`V(pJ=2_oxUs4V`y><7?Z6Oj_TQRYW z5o#(eSV7&$3m+nAInT=5v#jcYjxRk96Zzv(2R0GOYknJ3q9bK3ENke zQFAT!vD!amqu+X`)L=uF!@ zdQ&3_Kp-Ym(iw|zMy?j1JJqWr;o*RJ8C!1Tjm_B3ds!1&SfH`0cx@Oz>GQqYR@x0u zMd_-iR_}Y{&AJG_>z@@9r3u%!0$-35ylC`^pw1`e8(`&*Fp>r}+rEmu67H?NFFw>IY{ME%=`}^FT z1ZjoEsO<;w(pM@_s{Wx}+x=!^u|CwR+1hn19A0wRp^Ki6eDE5+3xeh&9bgELzDuh3 zN^Zp5AYl5SD1@()bP4@>9uM-vKr-r?y=A(h=Z&%pAx9~xC3WZS5S)DMnPae6Xxx6w z%93CsuvAe|K`U%qNP_W>&gS^#Y%T*(4DHfr-m+$LkdL9ISmy#~M)QX|9vZU_C6h%W zbk0^lQlv12?lm86HMtV#$G6f`kzWo{cKV@ro^(78LoWdbUC3P?=Pu<>$K#@=-}F0R zpU7o?s0Q^2u=B#-?^Y$0%$!{7EBj5ilad&9x3~B$yPvENO*|2n)gzMUpH$IQ0d)W; zGfIW$4c~i#tx3LB6+MOEv?S?lwwNtUD#z)OQTqFe`^A&gRV1nRcq21V6m*rJW$0m0 z_Er_4A(FscG@0(JBh)hmh)Gs}JDQO?ZR8hq7dYxc0SxfnfPPcz`qIRD4>fvoz>R^OWa)MVR4(3} z3Jno1t?Zfa9Aa4;F3)Z5H_{u>sD|p1eCo(EeVB^wz+FeI$rX_f-iLxat;48d4@z74 z&t#cM=0rQxc5jo4`A;=F3SfCj(Fyn=GZ~i4`GkX7@CCSK7)q6mxFPdv19^lFnSGen$;kQ&Cr2@}u^fH_JaWc1fueRLS{ z3=q`Bh{x_h8#ct6wR}?`` zVocW3P|-%a`Oz7F0BfPKZ2U_Gw5ZW#!#!zFV!q7p?W`G`zdSye-@~BpnAMZMZ`A5# zA!_jLyX;A=qK{O>ICWt_wu+OrA@Gzlinq;0_P|O^JqB#?3RTe-nDa~3DZwsI} ztFDWjZtnUk>6)BtV+{k*5TrF^;w83!!yQq@14KT;!UpY6#v-pQ;b`@C{?wHPOd7h9UO zPwQkg%Mf@9cZOLt3QEfnfSFm%@`5kcH6?jufyI&Yl60rQ>`beKnpPbnInt!*EhEJkKnsA_Q z7gc)3mLJJSkU~$~u(C@V`84<@n_<(9+}aRp{R)WVFt4p-bqZa89|ysMa`jS0pYZbc z?t(meF>yxSd&17gsp@!RUs1j3?#es0MC4U%_zxCOy!rC%5DF=NR4{~xfV0LLEz1c1 zz-da%s6;ODDoB6>wl>$5)<5peN@o6wG3+uQhOK*|Q-K9Cm6n@cuBAk>NT8gq$kUYs zdpX~=* ztDtv$MvXJ@foAZ=v)#3>Tk}q!HLmr7bbU{*eg0KLS5&jEC~4U1qSQ?qruET@$EV4qQIi7+1jKzxx8-|GCn0arZ!weqh{=8-Rj^W>E4_(;0B|nFJ)lMprw-woNtSj~NBfBJXHvTo zLe_@k?yD&_)oLJp!Qj74qXLB}+xu5_jpinfGBdT%?HVtf37p>5S=J;o!z4XYnr722 z;Og=0xq3_ii$Z-BL;OVi%%q-O&*08FJSJSmP?M8aN5nm|`Aol}k=35H32krpt2iom zv^IG(M-wnReUF$NKWc1wO40v5$+{vDFepw&1{>W3U0Pf-PI3tKQ|{n6N_`xmh$iwC z)HoUHj)1k~OmYI+HJ=EUBv*OAP397R1@^gOwR6VG@IOB3g%Z;`i)sBGKv0QyVfi9n ztgEBc?h2^%HC8-T0@KdyU)3zIXU6L8lkFjXloY@brhKyQbzw_S6wT-LjxXU%1&TuwlpK~4s1)6BB zY+W!3A-3K2zrN+36ja#~aS80Sw@>R|4W0Hg^kL=KaOo;AORIffF>})Uf=X#$od>sVD!sBdM5&YvGN7203js0R&KA9N3V;D$bD(twK zwE_aoFVnPvq2xxvM@?uOS{b5cr{3=b^Ub5`>p4}Vsv+ibM}x^oJlbE z`<2H70sTO69+Y8w5QglwE!o-D?EmkrRkP;^Gc*ILu77J2m7I~nq+PH$2re} z9kBbq?9nId^h>9ECh7$#pUBRtWBSh+Ej{S4BD2mnzm7}Ooe`l?8FvBU$|bYqAlnhW z0woD=$$cT|<$B%9Oy|5vy8z=-^(+Y+to)ziO@S++Z{v zCC?N?hN-3kqAakKaA)Y(1;rxN69bg>$@10&f?hfA=zEJ83;tCuWJ?T0* zEL#-is#(lGB8N)Z72p5fjlys(P4Ymuwg9{lrjVehuzu!jI}%`2v1H4y@2!El!l^aG zhWwaaUPXwRHn@NtFL*Wm;U;ip$wV8AWtC%gT(%YT{)5FNWIqt<4_|0V7b}bs$ZGiJ zf6&-=K7oWrk$C4lm6E<7n?Nw1rBZ4&05Ao|S&2f1S;*UQb)RaxP>^REw}XJftv{a( z;I%b{3}`Q%h0*#|P&EMgE8n%TIuC93D27pS3n{KH`JaTa(7NMNN-5W&vu~SL6i;F8 zcz&6Jd#OvnFOeG|dnshJktD%zADH>3Cf`OGL4K47k8)z9Z7<9qA&{5z#G^LX?ag_p zy!0nuRExIhK9P<}J8eMzTP2Vc2~N3{K~N+NDyNYRLef?xnd?ePqDBGFkOgogd!9M)EJtav zzAIKe;4g-D@2o{DLmAVR!kkD>z0+Na}(iyPg3aF|VWtf=fselJCnvj{(=c1L<^ElAAM?<_a|d z^O049llY^7>CnOA@S84nhK6eF$hZnE5~TqxP$|n2Nq68;I{FXxR%18Fw(5+QYn4SvlSHY}C)+Dw(c@cN1JE2( zsF~kl&7b*-l6Xz1_OpS@gx7R+MyZLQF&&BWk*++<5b_2UBc$ZE&}l9VyNIYv1d%}& zqH9G`c6U&0xC>9kl1LGCcZWIQi9f44%6=b0wLAa~=~&();c!b=m+J@X2|fqpymjX_ zUA9-tZIe4bxz4T0Fg)rBZ(3_Pi7}bA&sWXOyebV`+L%jJ?n#^7WIWJ=@j+;)Y1eU% z+r9~RI}bg?jNyuEfONm7nbRX$*q~0^>piu){_5{gjhh5u|48+elGOr(%?i1>dYml1 zqg=PQ?4d$T0AyIRJ}P@v0U5FlMXuW~LmYwPfjSwL0Fuu4J|i2R%A2l<67%5dS8Yh@)=$6hMPfyWZ}}Zs|wy03E|zB=ssVIn+#f@4qKoM zFrHhU$L=xC`zP1n%^c4cIosKsE8wEbP?A1-!`x%p(K?~(7Kwx2Xc)h&>Oc`9`!TCy zumeS*_6MrVGh9NqWe)NUvmv04G*D5q>T@$KWf@{=T3?HnI?dQbX}3+DRHy1O9144&26bMv z>R)DZ&$|!YaPF)88Wj7=^oQf?Git;j9%HHiBRCG^W+5z=kq;iM#4-*Wy@v$9k2fb| z^ZX{AMMGk?HG44-BJ3?t$51%bREMXI*=H@2SKYv?y#qk8a2P9u8BMp zzz%^vGnrw-^Q)m=?{_(u7&C|l&re=%lH?x$=GtNvxsuvjq-_r0-WUN*&L?Px0-?{4 z#VUCb=k`jLfSI1F34vQIYt=s3WrD@bUcxkQG7Bn3)$c(_xEgIBO3jXQ=YnfvT<$aP zKNJ?LahXUP|GmDzMC4#GKcI0A9y{{}DbfPDEgvW6j>o?`bM0a9h0cq->@8hwnkLTO zZp(Q#lR@*ff`VvoPiFU+uIz3Op^;P_8z6cg2CF+VIMT^NYb2G~Jdwu~-86-^DOL#y zEJP|9^LvQ>xC@nBR!3a7MkE8T)4KvrZL!p*7Yh}%^B(n*zAW6doll(}uI+ZB;e*

+}wGcpuj>XqUASLAF4-;aN1nBK>=U4$I4?Lqlnbm7z8s= zY%VN-oLO-YU$kZIvRb8yc8Rp5rKPvA^=~1AKp?__vhHYr}jN7}M8aNEt2t$-B?C?I57V$)#ApP*>m7Q9$Lof`IE{Sjfmm_<-!&tj(TxTk>bn$NC4emu= zu`hzZ(_ku%?6yG7L@xE*SYIOSM6GC31Spw+M}Q`2Yb<<=kyr$PZ*|beekx~V4n(55 zAVWgw$M3Evd&9izKn)D#)Q5MVpbYTb;h++T5%HoOgBgSEo(?*N$1qt{V3LFTO5F9r zoj1PS*_{o2pK?>lAdk;1slNHEJwEttBUw2)AvhN#8$+UBEUmTJR&aIm$L#p$8HbR5 z1-LOJO@*}*zjS~1Hd@P>PPgWqF?Q1E0vb#Gcs3~@-=bofl_$olXS6onC9^0S^@2*kJlCyEPgq*Pl(ynPU|u2X4imn zW^zv5l&Z+_@7uOhCw5%%hzq~OQ={Kou1L77PW2<%+2CcMB-^XiW%$Btd)OIShWb0) z*_Rjvh?wnJA>cgszPQ*%GWVSF^~l!YH#>TsL^IP0J!W>GINy?>uDd`+@c#;(taQk> zKdcOEk!WG<<(lCtZw^$o$S0Z+se$6D%AX-kM5Iaqd*Hf$YBejr_uuXm5HOjn%=?Z2 zY_HlwPqJ>aLri1w7618_piM0lgLAJHAQ2vt&g?iyI*-DU;%ku@{RRDMZNL)`Dz{1N zu|S&jS)xz}@Gr^G?8JwgCGJ!AQ#sKy%Kr-DghV*zxB688P7f56S>pNl8QDk6qe?o> zxx+6Pd#qO?UZN)1SOjF>?Rjn(mW2v_+K60B(q_15wkeJxkp+lBi6dLDJ~Zh^vOK1q zN;LNW=eyEP6)YAzYzr-i*}R>-BpjA{R!?IS5r9NcVq`seN`;OseLJMTkcjrr1iyPG z%o?J@g6|-OvVx+ZXKVz`YjHBMEd}~l zEP@I&v@UBc{-&EOw;`Ik853|C%lLr6@*e(ono$+*T?#xzy5kVs5q=1%K1Got30@fkX=p z11{W>;=*K6*V?6$*GTQrF;n;I&I_(XOOs)4Vd^`vb#d~47CC>C-8qoLJ`8qu{d256 z6709JFfvqJJ9Y$#C4Owzc89u)D2Gkb2{NqH{?T&f%_m{prvpd-Isf#}epZ!_=PxHm zkPl|22qv*Tm7s{f{4q0A!F=D_JBgX%cTO|k`Te)wFaDnP!dOUD^m}2=G+D4Oec+Yn z^fb(ST7Y@JK(XOiXsLMD}@20yuilhT1#d`xle?Pv=_O`)Rtm;x*I63D%Djs1ftL(u(6IWUc z%lsIhX1LjHWx^j4EgU=Nrz!iSEiAv^B9HL=!1`s*>ko=(I^;ILKAWr|nrRGExp0tZ z2>0&)O8)+(Ne89&g%9%Y%v`%YQ^cMuw}q2nIMVX8BMaZk9Ww>_YwJ3-G-XVj$ElQc z-d?o-tU5SdtxB=;T5xMKa(gTj@t%?L3gQWRqV9!PS<|b2A4r4P=#I2@;FRj=6yJ&S zCFzg8K5Z(its>^N!!JZ+T3TA|j%{a5No8dto@cif55H?)yv|C7;Z*WhmUZOZT>@ z?f0EK5dSRx{ZNY-d1=|>yBgY1vkmiKSu%eoUYQ_SHS(L*&gUWw&in*j&`+-3uH+oJ zvEHK%`Op}JXyr{al`Q|f;M{DotHcfj@DcrLKAJA*FqD*$A@5E`r>LS5G&eu5ATNJW zP*Cu|!GlcKugd~G^v>VkKeEG0C007L0lWw6sZQ>pk&!CHOs311MbDi(2Y$LgkM;QA z=;>cuV8l1Ku{D1RFFxsT1~Ltc>Aj_Buqo=(m)Xc_7lwsI{~8K|jeu~a1P3eI=X9$o)v}>|*gf|_$@zmgGul(yD#Q~D zwqN^fy#wxOno1In#o#}R$!c-nP>w+*cttI(h%2WhLbFFl^+mGP697#zfQnmG*B(Ac z!VJc1*XoC7QZ6beDl%QWb{_(6GoTcIFD)%KfS9VfDRo{{LZWe^EuEZ_G7hregur1; zuw7B|wy?0sFzw>04&j!2`}S=Rzhf4p<^{cfwDU6I&*Fb6?bpl}6dDS`#cpYr!KSE#7~=4BY+S%-#)d2(6u zHfBo59Ka>b07*<>FEy_X#miuaIA>FRq&RyW?yFKRh$j|443Fm(}R^IR_3L2;wpe z<1}fH@)B4R{qp6D+wiYlDqU{q$60XM#8Ew-$xP+0Xa@V{v}|yVTh>9WI66@=A#F}# zu_SK8LwaKq?^RZm@=>WA<9D?b^qlCfnK9lOXtCc_>{!NiP!H4=$~x{fn;gqoqkQX7A89UD5u8ul!AZhx=dOC%t{fyROK} ztGX_d9&Kvo@2D#2s(z!gH;-UnggjE6RxRY*T@#d(6#0R|I`aGPb)Xh9GE5rw_VIvgY`;_O}C6!_IVGw=rq`bPK?V>_8<&#TWz-@VIW}zmdH$$b~F2G_Opz5{t#>x}4ZWdc0rC27@YD_jV z?BK5_x;b(qnr!+_4J{|D57UoMD6l{v1 zKpL+;cKC3;H@!rL!=jCokXK^^#ti2P!>ffPItR9?kM)EfBAPXSTB7m@_xh9mC(3uTygny;?**MgCi<}Gn z0=4R*zkdD7gJ(JIfewTY)4ZhmHn6epnhl!)nN=7Gd-`-gKZxhoAj6L;^k;mB-F)$Z zhH*^p(GA{h$+QQrzya*tF9uGO;HFal&*Pf=8uscgGYd;I)T++ZE;%^anko!Wrtsv+ z>>bBMMWe{;Rh5-i3#0eX^4d(KWx}&VDPKuQKhA^#-5*W6a@(4VnE(CfpU?WOT&%3p zu#&BFkd5qd z(1k#?l*!)L_|m8tYD))Lv(egX!Lo#1(pBpv1Y3EHCEJv=i(bCF*R{~_2qF2mg zGch`9Ghs2&dJR@&%WxQ=x%WePZL<=j<>h?=vyXtXeIIK00pM%_hawTq!FGiNZWfh{ z@55JJ;3FD#eFyRg`B0!)CH=7{oVkYT*(ymY8TxOx0Mu+(--DvTJFa*!XuA-SNMpfC*n~XyCcsAHK72T@oYWE& zT>3C>@zU4_=Pc9a@ycBDX)nR8kI<0F5FYdh85thn)wt)+e-lx^6nn#RSQ6O}78h_3 z&@lsEMN3Y1x}FR_=>6Q9pt$k7>c(hhW@b2+%_wCPxOMdOj7ndUb1q*|`+QG8K)?nM zi@Omrc#Wr4;mr5*@p)v+^3%pdv{7lU`QTv1`}?(Wqmar6c-VDL4rM}@U1CaFZj zamjs5r>9*d|&0yQ0eQJ5=>;qrkZ6( zw95w3i8)uvbe6|t!trC-;^fB!$4oAEBp`wdXL1Y^Zjd4QjC{tA_aoVn0f3ZbrYlzx ztw*yRijr>iF~t~Ooi;@$B#n^ zFvGbZjyaaZ4Hf$Aq10AR*xR@70eU~9(s+f=dEssKB1lcXH#RnYa?sGw2oiA4Rfj`; z?~;C>C@S8=LhsDvycwdCWbB}rLWn-$C6>K?Cn!^W+`;dOGkAIKkCb09C0v~no*MXY zdtuG@mW6G?=BE1YO@8$CjUMcM0J8(I?p9Q(2L&^jNpDuFw1Ru;&kD2H7f$t#)2P}v zD^omf;q(m&4^IKMMjZ-^HUkk85BB`-vqNO2_vp-N!(F#>su#t4E-_xcT2~hY&QmTl z*ja?4duQczH_sIG)2_ZiIo>Cw#$>N8A~r1|`sn|Ftw z=QqRQkIA{t=FdCNZ0*W?g1~C9!ZHyD>@pc`TBv5M&MB{&l)TO+-|;2|lxjRyqY*PR z=Bw-LRd{^%@Ni$>dpH3+Ou@BKaB#?d>EU6Nbid>97ymE;Cxae8KR=ah(@?Osv2a2f zL2ZI@@G|+84%R#zDD&jRGe`yLhNSQo(9U|}=>EA)S6V5r=)A!t3ifp0xM*-kWQ#W607tmz;Yk@~WVX>q%S z9>U;bCFz0z_Afr%-lX4Lka-ZRMQ5Koe~ZY>!=k-#4V!q14xH8b5du^e&J0^JG8$cO zc>fh1wzRB_iIYP`4)e$5p%RzC6v-jIkA2|6?b2$O;YT??Va8C4f`kj&%9F~@27^ohQKWSn!C zHNH(vMqIoBvJ+uHGRTcn_W@Uynq%6MnNXtvr4vI5(1b?@)9(;T(awUw$!UY~8gg%hz4(^`{`lh$ zkE-%gcimf8j3r z8C_LTMYY#hQ)2Du%8p{@CgBs}9J*k;*Q}1{?2$v}w>O$<4(RCWjzLp4JUof=jSa^! zb7S@81Hb*I54H|jxtcKk1b)Y*(PkyhW*~HRR%TLIrlzK#DOLoqaFGxmGxPGQ=GjiS zz`4y~-dh~xLU1%yOi+Mbu?EV>NZ_6Ifu^ipqNy_nKb#ZqevI;=;pXShH-ia|OB2^J z3;Chyzpt;aj-^*1KBdsewzqhnpTB>w;!jKv)BlvAE*QFD6jdX5gA)La?FX66%^4E` zpZ;t_H9XP94!bg`6N-;C=h>REXcnr$nZQxd04i~r`thuUK|85t{vaY=c3c@G~xluUqb8Ll}w&6_e3 z%F2P@?@1;6a>m$Oi~L0u$bUj7-qPW0^mcpw!OW*f9O-@ zu{1dg*QNCEG0=l1T)%#O0g`pcpm>ijU?CSe%szqtH3kV24X@AgW|;K|fcGK+_LCwM zyV5MMkPndsdidAIbpAJ;Rz6iPLI@M2QUvZDCmtlfB65U|$U-9uDCar8ol=mW-$ZQa z5wg1W^Q zKb+h{tn~myo)9{Xf*?XpT>RxbR`vLOBq}|z|65;K(T6nwT^ZdAx7Lh2&+=wH{@20p&dCff7o&l@Mhe2hVjjF_c5c{q7L<(MvI`ivL393!evh~p{lleMJ^ zr?f4aCC*0;yBW69E^zi#@1(X0kq!X!8S@AX$^#h9ix*?C+wQ|?kXx8#(!rCP^!S?1 z!~!GO8(Dd~5Xco;w2rH4# z3Dvw6EYDvJk+8AJs$PtU_!At7;Pz)JDJlE+?>C-`OOX+QwtvUZ@&t4XJ9C6Aw*O~Q z$SaDD<#|>erM@V&DrzyZ@E5cgKO)X-bw2OA?}R;mvEgIbq$IISD-2sp&}F@;67Eh& zEvIdSCPI;K-uzD_dw~5Q8EqoCZ7LAX3NAt{%A0#u?N0`V@?nR2_wJ=HoH%tV>gm&` zJa_`3@qS3(TC-A#ata`oyO&B_Vu|bquWXqHBjJsFke<-TJ4Yrjc?Qsv2D0WjQoT8h znOjGb`|&u$+>0A|Des*8r6S~Z3E{VOhw%!6!&vu;`);VYD7vm5N9F|LwWeqZ3X$x- z49GZ7f%VAD&)-#_)GG*9TFQIV9+|wzfF;W;XMik-wi`Gz4Jo%@6|1g6~{1Ua~rae8wMT=%#fv zcGVC$XN)F#j=xl zcHd~P&@n9X7FfmM(bK)>L$q<3=d44l|7oU7)|4o)*?H^mr#`)xte| z^oX2-f&tKKk!*LxsQCEG;oQ7D$Ml8!nxSyqJsyiph4q`+WJF}Zh<6(qQB;WeZrRZs zGx~hL_;ua-p(4k*#LKegV)5D>mK%;#?+#$aFZ$D8ZR7s^-L+(|7ue0;A&C71h$wVI zmE#30B4-+osrt?3p6TM`y7nep2V+34&=;STk*P&r%*V$k4>7=qgQZ&0JBP`ikKWtK z6CxvTJZ`b-ughVij%bd@A3s7nNa}FvJ~Ix1Q#+r;317ut9ZY|41z<)BXVNp(RaI5P z4wj@?2h|6^@#)6<`T6-Y0$ArCDe6$fjQr%uN5s7lpOLYUw%*m*dFsp={hjUbRYhjX z#?sQKNRX}yP?w4FU+YT$xQT@i`{-zbMdQ%+a6nvTfAZXG67tbLe4_P}YiJ*MN)Ic= zH8`v~{yx#1P!PVK#8XiDjQ%97q@5MY{vw!q+xZZd{Cb}jyZB<=^owW3xVPiHXR{I$ z6P4HW{}oR3MiXE+33dIFK#mZs5ewye#HFPRCtToVssq3fgLj{A%P{bnn`he=)hlFx zrFx(E1wkY!+!z+aT;tbm_rP$tPgBf-;OKMLt0=XN(El*M8>^#AY74z&5dJ=JlBB?T z*%Mz`63X=tiD&7r{dng1A#BD+fc?m`qN}PxLb&S1_N~bBV;NyoAz1n!;*WoVkVcB*h?p$UHBQEsGM+VKU5s|+|8|B%`ACe@7j11J~r}Z z$)Zslo+!8`zD4QrI{(*kjwR>gs?5tF2*_}#pe#F%xgT2BA68H&1z?DH^**3|Z3+NG zQIM-Fjj-y)wKc0#VDT24&0GGngc+=dwdPxnPM!A*W+M&g%!e_u0>aAF zR(ujCyjie-rz~kYS65DK7>e%y8kjzn{Glp;BS^VI$eG(Q$`4?44MC1GH`{lpo#j4= zj*OH2-@OCpSqb=)Yf0`C6UGoYv~><73MVeA7s%hhlYSFtcP26Y*%^~o1X51*yVbQpA=LG~WnXcO|5L-)n4+0wm4(?^(T2iau*XIII zHysASTQCpi1ippCGJBMa$j6ivH$E=MW~B>EOqC13k?me};-|uWDm{Kwx$1kI5@^kL z!f;i}IrC92>qBI2$5u2({qak6i<>2eg;Qq+ld|@8yS428W-oxPcN1hc4FaL?I#_TE zb1watI2@K~(xKSa)@D5gh~@q1?gA;oIif=aHDLy)r_EHH9sd#$=}=3V&Y^r?NCmAQ zISPK+pNv0p7^o|`p+0j-eVf`69ClVl`n-F!E`~KT zDW&HZr@jHOPrP~!iI3&H|EfwBaBOXAf>xt%;ugv11dJ^U3b$zD3cFD_5)wkwI3CXL zs7NH)$^%n=1qvaO8bPyx{0yRGrru7%ub>p(=R}UYMtKc`8b|*R9c#?R9VNcTyAM+1 z5q=~$0xHv}0`8EU^TN%ICzrnWys+D`dgyvWQ0qz8^NL$M36Wni87*IH)7sKMuU{+b z>wm01*8?GuKE#GGO({?f1!kQXta0w%7)avxotHu|8jkVU$UoQy&tA5E>BmFnlj~LB z1l|g-^VomCdFeP>ITotW9<0Ni8;Cr`pp3P-76DWW%l~`gOXQ zU$^(9!Iq4eyOv*Y7l01f{b|FIv%ISMDlU>Yf4a@g;5NSiw^>Zq&@di=NQ6e?6TyjY zIz~c9#s2+1%hx-=BUY4`i_p{4XC?#Hqz{GFa{FI0A4@3!d=3WKoHI2r5D9ykN&_zn zdaN{VEMK?kG!%?0x*oj*M2|_b7ZpdPZ|=`I(~qX&#b|!GtCL_sJ!F9+Qq|Kxg#f+Y z$SI%!Mx&`SQIT*b8`c0=1F@9+xtGw1@6uQiNeKl2@oJXY&Vc~61Qn@Xc^6camoq!r zCA+$^G770Ee0+YeMgxx!Kuk(OLK5zx6CPfp1iR7_HA*LR@?S`mwcj zS_0BQsX@$^A`UX?friS!(jk$cM%Xl*7lUtNH2ouSZ@W4I-|ZTSV*6|7#=ge8J4buC z|7}Elq;TO$GXZ*kr9hzh0hE5DAbfPqcvyPmEZ92b@N%eSYgo|J(^I6pj!PY#Hl6?_T-2PQ?g*TS$&0^fU!Z}Izh&KoROsufR2W~|u*2=! zPy0%S!PK-DxfWIPL$-nYdyeW}0K32eZXON;@!uH@Taf>8;?43VIqmK2&ir>aS3W7wga`VEJRpWHv^Fqf+lqqFOSlT(0GqNJn*6r3wc12#cRil(NS z%+IANlvG3GD{H&8pm%3hW|=(1zzMW_9=llOi&s>f868oGL@N^)T(;i&mD3BNQ2kMveGD!^qo-LajQp*7h0GL$a z!GnOVOtf|3=N+9l9+e%-Be45JS>!kX>^_v^JH!`MO_5P*a+A`aZ%BaIrIz+35kgl z9}1dF3KmKCX~w@7{sK0oJ;yS(e_+69YJP4`7Fv=T9(;P}IL*g^fHUyu%@f?#M5S;(ylIb%i$mO0IZL9&I1!S4*he`xj7l{7ZQ>Pgj2_GSdQgLyLCH6DZ7`- zdv892wu_AGA_LbcLDzC7F|9JbTN}OWVCQ$vm+JnDW|@zh6Y(!w)#MhQcN0kWF>*2 zPubXTijIxN^JQg8icvwAW_1}lmghj@LVvQu{E+KnJ!KC{2y1AuIS$pKjVwYzIKM-_ z0B9l7-Q6vfe18(!NsqT@CRFp!kJREp#%*Ss1PS7zYy}HQ@nNVAOe!AAmqo%ZtEj3< z5aSS+kgx`Bt(9++3v?`~m66ZfFJtpEDO`7ACdJ)ru%`wJ-eVU*#QV(c__nyLq}{#E z;N8jk%*Q3dg^l!$jl}`LW(0_#!+bRt!tFt)V+2j9t&g`Wl1(d;%_x$sYS<;1m-HkwX9HY+64%E)@M_>&&m!TJyIz&9ivRg>0vp!wa zGaSaMo;wPPZ++Rq3kbyoFr9OGqCHar%4dW_gh>^usjM6a<%Kml6J6sdH0*Be+qciN z=BF1V#Qe@tcCBx^?D0Vnacd_WD6^#AhN&hNIoWpBNwV2;S)0|aU*3JXCa-;3t%JkE zG2pDITWKyvB$Ym_2PTrkteX!3#DKebQqA~Lah-AkfpteT1E~_(f!cs;C5aMG9}ka= z#6p5^>2MglUQaqf4cBeQf$l$NVD}n8by83;eae{z)YUH~#Vj%{v=kcd#<#XU2zFFV zeDEH40s^FBk=8)))d*-&G7ze5om>D+^Mj&>v}Tv8088T`y7gn_M{iA;-hNE2J@&9c z?%<@D4WaFtP}o$y$?l;bw29=XI7h=K1sIK^*`N`uh1<*FR!CyFXcx z|A*t)Ju?%pJgeFl_CPi`K=-cTrROUDLKd+isI*L*9sxF_V_6UpA>;}|d#bJ~07{$T zW!@E>x()Pn3!BUAQK;+%EGU4PxzOT^1E@7vbe4$l2zB)F@yUdC@eb}v^kYEnwLk~Q z`l!OtzX42z>=hD7dKHv|<0f=nU~@sPw7i_~ff&H zJ^J8Jkpzq-L=dUKGnc$tGk z0XqIA+M1b~CZjj%4C_fMc^Nbw$WTbRfK}PORIVi`@Hl>3>D0heLt8|1WlDScN@i9r zzU7z6@7-W!6EFQxke~=#jn>@)iAEFHJEN(pii(_3-(Jwk5THVnb=Za~Y#0ehNUKK_ zJP=grs_rD#aO6Q!zbE94Ih^HpXv*M$Qp9zjXNU%45};Ue0#MpN#Yn04XO+XA<8a+_ zk~7*H85VJXH~gF*1yyhxqoN_c3g~#81aE-$##oVa$h-mfPYlh~t0_mNz&5gpPn)&khLFNRpZ!=8lv0BJ@BV>YK2|oInu*qWxRtB470MiI|cqhmiV>O_)X$ zdn`?LB@n3tuB%t?L6L;Ie@hQ>IwvRx9-Co4=Wf0 zRo#2bJVJ6FyTza=((S>z=eTGI%?efW?NVW>kyiW^>IgC0v=r~_<-Fg(VusY3{)aJK zl+H65%;oVzO?8UKdSdHD^fXD-Fts3B%#BmcHqC{i88lr-)H;zRwx82MWRO|@tQ&BM zt)s8Ng{ThWSH1E0#~WZF4y*ITe*Z3-q?~>ixG6LQ$lpwW0OGFh%G#PC3@eD&HW~J) zv25(mY16k(^J3q+wsm&P@oP$KcvEV4)2dzrIhlA^VcF6lOn(u8_I{a=#=<7Gv(-%Z zly#eR9kb}FIHOvMziVx-m7O8=IL-lG#)%h>faHcRfFg_m@d7pr(`6gb4em%KKOyn}opNKs@rXt*en{qtLJEgur^RkmIT z<-Y6}wmrQW_^)S`0p0^45$9wrU$PI?c35Xc{Fs?YaLB@c4tV`j!eg%f9})&eI{@P8 zyl%g&4MnEwy;h|*{FAldt@0%_$GZ!*npA=)52T9h^t(YFj_~k5EHUVfOAP%A0~jV< zYCr$T;(t}OAK(LZ#u48T`@$_xsZ%FU8~t&%3A45~FAD_&LrwVp(^2-7Ysl4<6R@NIic^VwMg^)HTvg65T z@R$&LCI`_`hRvjk$X-`b^j$2fx-UTHUU9_x6hBpeN2C;~E~<5M+i>&w%40Ar96oPb;?06TRu zRVX+1#tdJ3A!H?a*6ZIw@wu6;X-_a2LMLfN1yf35j~=U?tU6qbh6Yy%2C|(G4!w(C zZ}kE-M-24iH&UTl6>Huv*c`ySvt3Oq<$rmy z7lIC z)N#(5mO#mW_I(yOLRvcrJ-&9Xny)4Gq{V80_clOKyD(c$r)jf)CR$UX0T8!L`}xNx zCV~nHPz@ms#G02OTi>1EeeL3T|8ZeZ#u1=e!ZXyW zK40qR(ToX6$SYoqHueD=FIeyA7#1zTw)M zip$r^7JkFb4OZ!g#4A{@vo}_s@8Y@q^`{r1&vX!{{tfAx0BmIe*O{$w@zFKe-V-JvV0ohz1I5+W~vcGVO~0_U&6xH!ICr zQo^=G_yEEyz_C<-s(ja?^?nUi-#V+{l8IAyK;jgh%7+97DHu}8#W%ln?(O)giATg9 zy6DsFkl4ifZ5OtH;678o{(J%We&80QSpM&GmbQu*T4x}d&IB?)XdMaBAZWA(VjluF zj_gmLuEGlVP86j9b>Z#(2Y@m7PK2s2ELcHUfpl7NadCk8wLoSI0HVr9bj{8hAG73e z3DbGw@d+SLWix>G-!|$ZzlLwlD8fa_wL#qpeEVa`({Q}dgWi_i3|4?ferC~5|2Fuz z78%U&J;+-*&8qehXfQ@4LSbG*h>hLA%ldh-_Vq}3R*ehX%^kEY#IUAI*&ihx&MxjQE*8YMj|gs7AH{W*qxO4G9tc7jM{anMI59!f*REd1J*80!Vy;J>v` z#}V{N=D{zP()CmDO6iPD@sXhplJ*(x9@W;X_+qiChs|Mmi6VsjdPE_ z{yc8$(jYx1cw=*u1HjMffNR3QUamnm^*C5_vecZ$bs!&PZCAzL`^3*mv$8ldQwOI2 z$CLiQq(W}qhfv$C<<~pL)FOIcSuK6KrX1!X+bQ`7a`KWI-U%zC7?efu(v{YXJx=K= z31Z_x@i7Vwks3gYPftY00nc>=3n2k)W&^}{@*1Y=?la9KUrD(cZ(g|~`Q*uy-7EnV z79BV+D;Dx|ePeZ3q@DECTC9)K7u_3}gKw@0^BIw>TADML%U;@w8QOjOIH=Tr*9UnB zFjsZY$OJA!msRFQlor?j?QrPLC$||H8Bqeu+}xb}g9jf$1WtbXbUcWm!E1uJ(jUSh zm@W8O%uY4~GZT|I1j6^qU!Og@u~%&thE@C`+BjXXq*|D2-4&vq_V5FkezW(D+TeFx z36F4mU0ssIPSEH9Zon%jv9q_2gJnA2Q&beGiU7o!?Y6x6%e+-Q>aDh-#q`{ zAHQphVyZf)PW?u;(SG6pC5=j{;;B3L)>=gbpL|%vl`mNe{g!&-?}Jf+(I@}+59vAF z?|JA=-x)AJvCr$>vm7raQ|9Nuts zJug$Osvz1Ow&^(dR^l}qh-=`ANP;$@yT80Oo;l*3M4--oJg7YscmQW()-@dDwDAA1 z_1#fXCC%Fd2G)S=ief-yRS?Mv0wPgeB?%}|vVj~WhXH0>7cn79lsG6Ll98N2Sw!L> zQPK=blALpxuX<+O_xHzl&)GeD&JOqX?b}^l^;FgKL>}?y^IG$m$WcDZ;$w{mdx;0`jP-tvN~vE-G0i)AZ+7BatDl%F~*ZB4AKZ zG(*=z#l(Ovq*(!^84%+TVoIsXgON=@qJY`2A23-901Nzha zLN8&+3B5LMe*G|d!~mIoj-G3luURBhbPPMbR6VU{jJpz%m$kw;^AWqK4mCeCQC5sy z0OMJ~yA~BLxO==8lmHS6hLpxIWIOB&#UUf{NaOw{P9fl^_EH2L-M^TS9u;&5XJSbD zQuPeomA7VB<+QBnUvzKI?iHE^yIS|2lQS9RPv!#>`~CJDGXMJaYSDa?6nh5PpxY&v zX8@QL@!eSYn}>c_|HK28L7Od~kb^o8W?NP~d@<!`fp?3)uBn_`OolFwLPScrw93w;wH#J=6%2PKKX5J2g5pZY_u~jj$|!N4d=*HpFGlE z@Ft`kjzOxv8qh~s7v_V4!y}RVKIc}10n!#y-%aY8H?7f_0WWaAMsDjIO2)EhfPW>% z1e%;~Njo@!t8*0O18)}mhVBX0pj;Yf;i$(%xC!3DBz)bvA7W8+8$a^&%I)j-fzaoM zw%?@d%4>$z@Ya1_5@gm7hEW;Gnmc$gtv{fioG=h52b`ri@2WhYHyMU#p*Q2OG?Y%a zwNGvs$b*@7OFaPI{xF&+PvCoUhORmuB|fn)Rlv>kCr0V7OIrN=qVOpmUB15=52knr ziJLYyd3H_R@aq*KupiHPw#x+ZS{w@AAzv~#n94sNAZ0#OtNV-}h+45pvGI0s% z*>6u`S*9X3{g)fx#4}ASD^CsfJ@u@1TU=k^WbKaC4F>|Bbb*bwS@}F^TWexUHr-GzeQ{8+$^l|F&Y=NL z%8J_%c}--R>}8v}mD_K}DOK+^6skLyB)6G-b@~t5lj5#QyZSf|ksqvcaTcHGnhv=; zhq081jV$0ZDPJAUHVq`l7t9Hx-&Tr811+W|sMsPtcSJP?S~UI@u7FE9makLUSny%mkW3VGvSn3Yt{kkwL@`D1CGgV5T49E{78} zL^dhnKAYbLjO9iPD6dVw{cGAQ6+D))gPBPlI~U9}Y^q{sq?gUJZ`vTt5RD4Iq|ESI zd<6XR#tO=M1&`8|)n#xEn-HliVsY~CgzA+GP~y@ADsJKT0%gQa)>^`YxFBbSLrhN_ zQ|=Y@5FWBWtth#8g5G@_cSV0eD|?~nT{=ghy3^A1(-@DM>9ZpUrv zvnRFkmoQoBP{=S0WM3pVzuugti~LXuP@`5~;V{fG?V*53{u&5!a)hmgBuzcNuKSGl zgS51@hq9{nslc|?34oEM3<#x7=Ghr+ltEI%AqMWW*e_^E<+(=fx1H2G_S( zSZ8&R;$574T8Nm?&^wyPG)n<}*hWvqra>$y>Xc5}IoOvt?XdynWx?Qa1v5e>hOV&DiLB-D7sBKqbRW7;DycAqzDqVh9}u^Rbq9fX z42%Y{8xZd~L!-!{Viwxn<)gCP9JANj-=)i}JWm*@ygR}W*T**kwpz-?w2Rgl(apc( zcK7peV=pUz8z^Yh)mvJF&)suFNGMd9sxmTviT3kBJOj_7jB`P#I0EOSI0 zn;*Js!5G)qot1c6SkS;EY~tbaSSIa&&0^hMnR^64uDIZ)dege)DeI> z%PLg*L@tik&tIcsHS*6qr(O*D2M0@4ytXy$%6%T#8@bSv^Q{PDSrBWGE1sw^TeQA! zGA6Z2R-ms$>mVl;c4=pY&0FtVQ z4!oH1~>9k_Q}Yv9*Sd4NlveqnD!Q`SR1HM=Kq;Mj*@fz>(Sz5 zdDY?@pOQp_JXRcatXpg*1jQ&v5KEZ2Klv`oo^L!Baksk>Et;YupgJ<#m5yrQvpwcI zYu~ju)_)tHxogf4XS6yTLmY}6tqw&5w@qM^O*0?JxO<$TRhCU0M_>PD{57O^snl}+ zO%YHTZgb=?m6uzCo~&csLoex4BDtFM>GL_uC@_aFD^J9rqjlq!;T6e=1F zdZdXTSE-a+`N-k~8Z8O=`4JAcDn3Hmyu2z8QhW!B>4TN;YAj4yJrYa`)>=EvAa5aJ zFZ_fn2S6pIp@0JC}oh@pS9A z$%JzS8g^|&2bYIVINqLj##rjc3SMDY2~nzQO)pNNyPedzw}K*%2EY>vq(CSlfdusJ z8_+1+fD~=&c#{Uh4D4$mJLM*|4jJu+JN_JDNEOt-6$iGFcnlOis(b0Fb9u?eH6xLM zlwmWM@$k~|lG;B;4vDgY&-0ZBqpQVbQSPcmM}lIsU2Rw}B_ek|{UZ%6>XMVWt;j|v zLC4>lECaq!4e${l>X!h9NQYuz9jw|XC7{6Js)hV_Shwcj0V5v^GGxKfiZ}u=ClOjm zBaz1p{D?~V_25c>fkyF8>t6((&1cjNI~VfGmK9%={wewMp;G3h>c;KzB{%s(MQm<< z*wK%Zb-lZfLne!c2I8C0nQE6=wp0gL)I1_p?F7~5D|g&`e%J@ul1e3!*@yo{KA*X@ z*kj(te(vsHLggzzPS()Z(wRV2o1miB$o%{io4F#Mpp3GoF}v{M7MsJ74aV8xdvxrt zk21>{lvvs5IP~g&k$vdp+IW>m^$QaVIrSwiEP-{v1cI*-kdqUi21*wsFk}h^Em8*_ z1W(qNISdC>Bc*15#z(+tAoZ4K?8j*9EzU5k>}6Z~dAmttT++s#=8uAUIlSRyDJjbA zzZ(<73f6A*AvZU3Ix8!D%gsG1j(0f(%1ZiD-i-E?sW`GzcX=G<`uc3_aw!iaR-BLw z3lh53%d>8GGb2f`VciwrL_)6eK!C(>x`U6+s{uM*5<+b0QZ*?d_B@LM3ht3=Zku@$ z#lfq?*80bxtEEp=)cfT8UmU+h$26r%R-Se;a&>jxckyRjGz1;1 z|MJMb0;ZCZ9Z5TBb9&}W_MxbJdrF1+&PmM)0Zi@@3AuA}^E$QyDod{~m9>;a1x8Va zmV2P$RbpR{JK2Xyl?>8o*Mrgw3WOl*+6aZkIgpv>Qi8ON$n8q}b9MF9NoUu#ha^S-?bm; zjM*$nARezKZbRNdYX>Nwy|Z0qRXBs8dYHKhbsfj?OW(n%u%4v*zZk`!P+{)G?$7Cx zQ~a3(%wBo_MF>yK8r>PGJSFn=8W{5eDoHJm?CcXD-|IL|H^yUdKCgJvm1! zbQliDRqS#5!l`miygdoXm9Az0t0HTT9rC;S&F*TZZibsn3c_1c&Ynm=Zbk> zY_FTIMoFU8_G9ekGS|-WsWxX9uw`- zIrmkKjq_#2Tr(-_H#7~x1;t$bCPfp}3!*PL-V*X2S=l?*m!3uS@G))##*ppDI2k zCQT3urX^hb$G2f!8!L^C_H_j|s&~z)=eg!F{Wf4!E8l^X;Idgk;ZT*C&FZjz}81&249o(05|wWQ0Kw zCr51W%p23GZH>g9<$n{fIf#f*7QzK2u>xKUGtJ|JV2OQ?`Du3}E!*K*vg);pbf|OEZ`%lE&vA2B{a(cM zVnUZrA6N~J*H<;50`CR;Hwx{~K{4TY;4R-;B~T<$;JKSjL8ctV$?l~C9G*X(@EoAI z!4Szhd~R1Vy0jzn!M$J>^6Sze*6KlqW@~dnzO4oFt8HF`FJEoa-K4l%yDQJvLcMMT zaF_jwHeHZWIG#eJtjeu^tC8)vUnU7jrq_s7UUKl|6(?|VV5f?O;KrAQ?$R4Z@NC*8 zVxCh=!z0hJ7IU){ZW^0BVplp^XOw$Ij90yyJ4Ljp(p!A#~ zL}G*(Hb-zQf#OY-v|PSy1{F4{-4=lJ7eST`0WOBljbh2^>3vgeCe`#5ZJd$8If<^` zhQD>q!Us1iu3tMIrsXbZE`-rH0ynAR9_7vI;JNh!kyH#w-ct*LpIiqN>LNX6_p)&# zgz&KME>gkyJ*wdw1h0(gx9{&aIN0s|`Ih2VCxOYd*^i8 z26A|fjA9^om4j;ZT3~{IN0mH-xyco7!<=Txvt5S~Q?gSY~e08l!`c<1(Zao8WYc0o}UrA}F|Zp3Lifm!I$E zuZb%V+$^8_pZM=bB{tNKR>rb7g8|J4Py5R!Y4^}oM3(9JnzD|{L2c%drX7jyo z#a8}4tWDB^gv}Prg)TAbJ4c)rT zBFaDGsFpCHOFa zhPw`QyDU|h0wce!+XZL&hZtaiLh9r#KrG26#pX5stg^?rXUWUwjt9W{ zMR2x@+I62F`n8V-JeE2>XCBEmnRUk8a5JzOpZoN~)vTUy;jIH5d$II{6ht3*n2{j1 zd)L3!XS}{_G0>}r?QbYXC->g3Vn(R8+QrcXwiv2c0T@DBZ27s>*2Mr52@moQ3x>Ff zVF9CX!92LJ+}(+|Y%}V?(L8qm&l?5YA;XXmZvw_N5vccl#OmX2*7IW;*7+RxxdJ)n zjde_*coBA#elo?GHAIB%x`)a%X36QA$5k8zgd?WvG1M> zsL&E4>5#HGZvY{RSf^nyQci=wf&`I^or$JH&-fw^;IE!gzmdkM@c0)O`P}yq;iJaX$6Ek$kT&v>@c2|67{aGRNwP-ruFbCVjYK{nO`@+8cOWQj0*IG_crY8Or* z*)`;phLzCEwDC^gvSmFdiv}xjy$jDjvObMs!e4GQDi)%6_lQQwT6muDoQ}RAK)B#F zv9A;BmR<+wL2H?c_K9`sBsYswy)bnYJ@1p6$nu_f$k_lyp9TC=r*Sf0C2IF|GBFubyi$(MeLdZB@!wxB!o+6E+b*!M{^EkqD>c0 zAq`OoO}}R4%jRssr?*1`L^e#&v4lQ5jk-CKMYE?M$yc(Z_F_weI*91R@!c}31teeW z!fKB&Ee5GVVbt|lX-QaZo%@pJ%k^dpAa*dC_R@_7!DU0A#r7^3gL?!HX?DPor2;YH zQKz6u6(ss#vfkY}=O^s_=D9mPw|L{FUIEV@g23r<899|lssg9?;4k;BE`W!rz&sHl z3o3f_(`o$;xS3t~kJrts$!nczAiRLWAOKD?u1B7?Dp>O9=^=$NaeAMvdckSFVC-!?k~xIhdAJMG_gT(Nh`>z1vug#|tcc*eOxZ%e!fSTw zx58k~bn~}H5oSpyTvt9z$T8uwBl7O6evb%7sbVzgKPSKs3zA^NL2)1f`QOlC(gc2M zSK0)aa2^)9jr+j3n`^YI&^L2!{|wmL829q|7`?LM6^EPjz|1l%ojrIlQ%pEM#U^|D zNp-_EdA&4Jme?L0I|1qC!EOGBVrd@O`diHPcsqj)@ak-k)(n8~JjfSEQUjNl4$FFb zfI6bw;Nw#-JX-h9K$Jrj>4WMWKU(%1dTbxJ&qoo?Efpq|u>Q%=ovrumsodtW;JuyZ zgcH9&zc`4()U)B9?aQVXp8Qy#Bv6g zQX);GgcWzj4V7h?+6h&-yMb*!nJR88$dzN`YIb_>c}d%1FB^U^5| z?a^r(%599ouGMN`-&bh6m9TmkXh62y7c#jP(3rQ{QBdA~W6kH@E|0~rcFEC%;5l&C z#FJv&^ivytrS%h7@%|jIOD73I+sFhhor7|$n3Bmcf0H^hcbV|+VvRRNxPs+M!{rYZ z{4~lx{EOu5Jf=9G3)7|Z`so`b>FCW@A%-WIm@%EH4$cmp_I-IS;K%`LK&#X+ck2zqjAjg7ucYZ5TmOXk5ooPhE|*OU}vTr1Xs zyC1>dG$B)-|90SVl*DO$j#^JQytUTM*>6jn&R5b$3H=o^=E{B0Q ztN|Llq5-c?`>$T*V!Q@#(Q<0-aC?A(ZWs4xnS!S|Anw#E<)F@jzbqHRSo{<6;7;(0`R=hY5}Y#Z_=g&-}F{X`JHc$mCbq}pBo#7)RyfU zHUCY8Uj#ebokl9mgIaW)p3YA=O0Z<`(?!`C)f9m z#yDQVCSecJBjiZP2kirn&g?t|`j@+yQe14hm|FX^D3h|fMd@2e+rl0cXTwP8@`XCp z;-q5?VhwNH8Xhd$IaucZLO_5PS>z}FS20y$GyZNcP)_+BY zY&pFdB6CH6%l?K2t7Hl8xJ`fRHx72))4CP>dTZW}5eKzv3t6FjJ8cdQ~QKfE+tWw=y4T(_;;i^dX-NldW1|mm{wpN9p|-n{{+yYD zh7B{3+LXH?_ESX&C5Q4x3TV@;>x(r&~k} z>5J}ex>=}fvNev9p69GKFCXFzP7$g$XUtMTYg-`Iz|~CXqSa**?whe6P2Qn0gAQh6 zFqL78wXB`odkBigQK4`UnlDushW$L^cH zqCLUBJ^8)ICb3;R^oUfU?&--cVNN-(X{g4^c}c6`>vy2J7r>Z!yL|>FMyH8Zgfj&8foj%d+g4K(Jd;-hjxDA z2_{FsYP086_w6LrhBybs%Muoj>&MDqE=F{A*w-m!M!edQD$W*LMn3KnLPNwXS?LHK zI6cw%_R99sN#EwCJ(sycDf2qs1eu_6Fa%FcF;|N>V!I&kaT*o*)zfQj1OD3p@*@jl z3#RS-)k85ed8P}0R1Yy^0S}yw(+J^Es34B=oxT`znaj=T^&j}AQDKUZ-VHvY^4%U-UiFO)r;#^>Q&OG3Qx*_sBm9(~p15VZJ59QVbEp$^HL+xtMt{ zTx>P%M>ghLqTU`jHe%1Fse8Gn3eid<@CcP)zh)D3!K^;hM1UM!f<+>#MJB1h|DwruIb>K=c>y> z+C4_8?-iGhHjAz^PX|A#T7L&Q)0e>H0#}^ke@4YcR#lQ=rBo_dhDFeq4HLvgS?mq+ z{-GO~l%aLqm^{^9G&s0O($TE<$ z(a^5-|Ff`i%6WJ6pQt7>$OjE}j|y8_TQ1#~TGJ|jw3Q3nTWgy5>ezPvWI86?zK zFS|yu>Hoeyv6wpm>y!CrC}JDFL9bXSRl;8Ie>r|kxA6bD zH~8{Xi)BzeS_k#KVty8G$thp{msH1xz5Qi8FAF!+3jfw}~H8}NmYS0afN zc-1ko_McuxOIrofOD(90E1?(=@=X3#&17BTG8%*sZ7RMD0;g=T=tTJWdsu_=RLOa0 z2XP!DG&0mDg zJXis_cu84*Q=6QTA|OCJ2lO8@o}JXU;^CRL?aJmx?)hB3$(9JJ;c^DaS?Db#e@0%w z#Je5pT%8*}*{(hVof)yqYxi`a%5#t$?2mgHz0o&_$63z3219M1lCGqj*JEOk6E`ba z=6_I>MV@EA;qUgM*;!9eiMC@)C*@WVB|6)tOtl9VrgUOmPdo&OvbS?oROP8=)u%jHJQiV_gq);o0SP;D6IQt zv@D%-L837l%DcWk^m^xBFqTc@;E^|g`S#CCJvjrlwsWDG-rT@---yI>VNoQ~AMj5= zY7jThe$~gMG;@gh0L%Kd!7!YFy4$iZXxk3e?)-`OU0*59Hd8-FDzK$nz_2rz){OQ; zSocLmH>2&w*``Y6Gk(IRy@ihHo@k2Y4LmD~e9zJnmR^LG3=(jQtcq_SrIJO=CL4)_{@Z*2rG}aSxlonV#q9c2Xh^*TyGG z+#EIdxE)rIv)ZiaoD?ctQowk&a>@$|*4xTf6)r}a{rGjNU1WkXr$nn(x6R>AAX)(M zH}^WwYL_@oH|_oix5O|H%XM5_@32=BPgC?_wvO3kz(9U?)oC>whUC^mttrIy$8Od| z(mYZ-KiE?(kSAV$Cnp7QU=SBHnB9eTn@FfAA9}!a{0pQ3J7zAL-G-aTT{1Efv9KPW ztZ;jSEaLgjHM605()e^;ICJyI2K`&*j57u``x=_d`|9cRQ+7`vhUo_2D9UHKPlB*9 z$P>(k3dpaVSV5&bb)ozQo|n7TD<_&R8Pz@{tAt4hx3%Xk{e^QK@hjQV3pcKvc^GuBJi!Hi=3u@# zH#c~E;iGAD;hgCD0H=L$;O~MJK2o&AIzl#XJ2OVy!<_z$CUD?C>gIXlaQ{P}hiWQjfcAF}V20$3RLT>jPMfc+GYlmC)*8 zXV!I<@GUi`3k??ALA6KDE#tlwx)w4>~c1+DHHCAk3B|zB$de^WUAkwZZBbL{I{TMB*6er#oYntqnI&v zhK_o9#)fM#q+6k>WBRG>o>iIyA-yLya>t*1y))LstAB6pG~Wrnw00U&j6PDw4Z5$3 z$4N!zi#f0mT;9{nwuZKsuDm}0#J3uD?oRJ2KIKD~ZclpVA3 z>PijY!hoD_vQPEF&mx><-uN}1>cjPP*B&}d{`Y{MnMVm7glhv*0#=*Sqy803OMk); z@Y83co-xk!+a!_(8i|Y;-;|Wki3X&VI?Gjw^IwuuUiCs=RnI2u9eI& zr&0O*f~2$4{W{5|UwWv>a(R4O))1NX)onN>XYM`gm==qTh&^zRe(1xW;V%96ZEVQb zYPAO@d2MeidD@i9AfK*Zs%dQdZScgJ4a3Z=jHdn=C>pK(&yB}e?*8SptYmKFna>vo zglJ?pn8&8~QNjeq2btgwzrU~3zlGWNB;@j^$%q}8jpp(nyAOuzvJ?Lon_(i^CTPF| z{Jv-6oQJagXZ6GX5X(kIyH+a4Az_7BGRDZU^wf>>+7x zCoX;dRi22MIrK|r2cMs585mNabFtJYg*RNM;$)F^lSsn}vn{RS{yV%v>9gD;ecHN* zA&=DZ-9gP)Xy};Lf=`Q-CeaDE&AKj;#Xh{-_2t_284@ad!zbmg(58OBlpzuBNiu>;;ST2u2~#6tTfKS&dD|Ob?MHjm z6MR`|+wL}}u3cZ_1O1aCq*y&r<>b3yoa|?_bjE^wZip?c&P*>Uy;e$tH0E=$`k&FD z2TH~6-VUyhf3y1q*J3bRFBs3-0&V0w;6@4!3j+#XEy(w#WMt?dUZ0aEk(>zP5UH6z zG(nxAI6v7fzplAV(Ob&L?+OWXT~0Y867HT~z6sbd{9vVEE1UZ2 z_|7joXlYn2T{ACuq1N7BRV?Nm^ZP;N(O;Gf&jwah$GOO`yVx}qNn8MLDk6)lYiw+v z>ML;tciG$w$fn*yCHWYstOT+xZ-7_^s^3*03G@P}SZsZ1n0;I$ujHS0zC>H|k-fZJ zy@tkwT`g;?g6pyGn_6bK4V%AA=oM}lMk~DhU2YugU?te5Bojhr1gGr>ZmenM_QkQo zW^{}Ue)ZsQ;2BLrVlX;s&4|ND%%;N<1ULAEh2^XQ%L3AkaI&m+|cO>u~QuTX!i%GkLfr%lgEmc?8$f=eavA+O8xo}cz*AE{wAdEbF zfko(QgDh*qaN<^+*?7sm@SP_7fiyRKH~> zzvX2$qA@xnp<$*3^nq6diO{W!VX&X=TusTa>uT(a;y=Ns1xHE#FOo*g?}{s0oRM0v z#;!hN8x4>kHA9IbdtFgdm`mS5pD679`##q+^>~K8A?J;#_Km$pxw(OE0I=O+NI?OA zW3%}r?E`mTs1KU!jA(p5c_J}DEGi<1`>LC*?~(7(QHhT)SbbS+Dei1&%3ji5CMs|# z4)|&pNJtpKDT5cj=zD8zeN&@J!F=xIkH$fG`9-22lWqMJ;efM_L;%{T)Qe}J)%!vt zBywD*O>LwE>eL05P;-uRMM$(=z*Tc<$JxmVe2S!sQnqCe)kQlDZQjngf1NK-WzXp-eu^>}#6RP-JBt?@8P;VDUd0}} zM@OdNXAk~iJj>O7@ID#D1_O?YDUZas$0CX+Sb^76Di+6KqSXZ_#FxLe*-q{LxY+6J z`Vwv3)2qyb#PCsJJc>S-)p@@a6c1AqIK& zocS3??e=f(+p?aAEalTG6yTS?EB;+3gDFh~F`CTswUk)gmM7AI3sU3jihZB_HdCrm zW=ElHjghfW$CHSF&>%#+3Z=3?p~OgIb2PjX7ka6)`SChQ zQbI+}LmswNaAyeT#%1M_8*82M8YKPXcWOy8cL8)?ZhNND~NT)`utd~})LYK5bv zoEc7#gt0k_Y=uQ=u1%55yzgwO3(3e;6y2VrW6WjeRby*z`nSuYijnOYTv*QZYrC#j zZ!R6}$&9yKML$B<_Wipn8R~|dtRO*#r1(M!1e|_yzOiPfdfTnq&QX^Xh>?Ik0a@5j zRaNZAfdmj)l+l|vZp1-lNeZx|zv5{7x$9#Ri2scBLVgv|P9geLMCwOpbZMG#fCvSy zm1uBLaugEtGL>}f#H6=OZ#jx^Cjzl+(Cc}%5l|$AH zwU#e@eL%DwFCUSjBT{3p?#z;w>0~o9NCB9coAZf^YChb_jEI3XG&DkhB{MEAj*aLB zYH*W%CAzDttH{oSHWLW_r2~sya!SfrLXld`>c5>%Kawkha)Gcy(75y#G|!cxN5BzK z;6Y2l^k338Yl+lN$ULN|;6^=?H7ZmR8+e0SyVgo`4jwaq=iTdCIQW~j&xvAQtPUiQ zVDCG8F|d;r75NARMY$&=*C%-~ETbKlDx$xU!)&P&2>)XIV@E$G+r05;AH+q7;h^V- zgJzjYf=06d&4d4@*@El-1UWDd}aS#jWgnZM{j$*7`m{~HM ziRyBjxl}n(%Emkt2?SY~?4>@|viqx{)kkfO(G$)QMntjjAr&u5^Jm5xwc4Se^7X&E z*WTogkTn!d`;@F6W`>HKR=IRyX#z!5ZT!MP`|LysJFrk1q^6Z_zfl;qaw3L0HKQbR*5l661hX5j9KvH;Yg8B(S?kJY#xU3J{ zvM%k~x>k_w^I9DW2ck;#%rY8mIm1biG0)%NS2B7O(KvtbibIHwEKgBNqs5`gFjB0B zE=Kn29i<|I3cv3uqk>ycM>Y?@D<1ygq*RSfX!)CB+_Rj=RX-u?Xr&Q2-)PQ=XGu%>pZ`FDCN7F^3wYWLq5LE&qkPT! z>R*3(*bV2r3JZIOlzM@S6))~UN<&OCz@VrFW!7BFi6ao}UkAXWInx(NjT>oE5*LRY zm)&|)SHpWX4S#!cQJ<^VgIu;`T1JRn!8q&H<-Zi16AMl&N#IUib&HACADFE*OwALyYT!#LMh(s}e%0#Zx}KRxiueG5A9q ze96rlxRIm8$^SxT3??%Ua||y~uL1k`xaZ&>=-@#_w=jlMnJ`CK46U$T-Xn((Dm9Ku z*c)E?gO>PMi7U+;78T7DCyc5b+c&BptSGUeJtnKX`^mz@mL#WAsQ4j7dDTzY?GAyK zuy%N4{oW@pgLYDuzq)$#F*^&bm$}sN@h&nAFEL^`7divhwZ=u(BOV{0{p0EGJ>s;o zUi8%?{oQ|Vdu*nMn08?MWrBvM>Z@1Bx8&a+LiAAJhqgkGIhCCX>TCP|x{dw_i$ zo$>y5#v;3o)QP;H$$k;)>7MPU_J&}}jRag!j*QAK`Pvp=vSl6v98jmp!|p9@G@9&`JUX#%$6zP#t}Dm zds$XY_e;C=z$3&7GPISWw?-G~GQ&3_Qcgm|uu#2nfSrAO($V`f?C)ID+Wm+-)NAFt ze;GYz|DbUwC|@8*AUvXU@J&l15s-_>+WAAXGH^n0cJrls>#WUPP0oJ8a@0RB{Im2K z<_e?TKLnLv9`HIwCwwl}$4+EG(7rw6Z8qPeAfH66RJQKlv)5^30eda&-Q7gABbOTi zOYA(90og!*AOzxn^|Q?`r2k!{A4XGBq7B|2zu@ z$GhC*j;zE;e6hb&Xmv}HXyT{ognD0L$zuq@fN9AZKA3D7xZ0a_nD+x=)evKO%E|V^ zri9=*jVmRtXKCeKXh@O%U>f5$dZdBkg>)Q+Kp1@GcPFJH{zQokOQR+hoM6BPXI(<$ zL2`Xh%F_r)bJA)7SQW=dRFobjI=}P8B7nr>VXBV)JP$S-`#dQ6(vm5_RxfjiwhZ6C zzcg2y5N4YGRrQAH7yE^2^dG5VQL2v(>LA+q=y;@obx9}g;wry^2}@|tRMeBW*$bce zx4*zza<5O+HWk;#q8GUyij#+(OXXK9@zb(>i5QWSD5)x%7*ub{lKa`Oj54G zo!;T^=^%@SbIKuawPA(S(&o->@p9D`Gs6%y|7>yQhpkFXLA+9XG!;~zi%%^{F>IC^&h zUe|KPT(sl{#{NUx@4Wf`T7^|T!EKTsHu&2Q2D3N>he@AIC-C&GNF@6lnr?s(f|<8Y zP29+A81lQOa%wuPsl;ISGm-E;7+J1@IIT{iQT*F%>w&J3g~yua;rsrF+~6e-;J?}e zQ5fQiL)ne{P_Ja%ikKFwli{wg@YGY2gUWsDZOw1I4+*gn7ro(feL03POG?2_X-`Iw z{Z>+2Mp;1;EK+%!HXRjMJL~0PDfRj*jr&HsE25ohPgEx=aTGg`31ceE^}?nMvp$B+ zWpX9*RDb)AL<-aJ2J_t9`NFYmf$@Y)>UziYUVJI2eITN7LRMqKj##+{9da))wxoF2K0WO%lmzdya581b$6`zO?F|Q_)`$H#f9~H`uHLJLBpa zRArauQ;`AAmjxZ(<{jtfBObh+uGaYLZ!MkvNu@}OP4CeSY{Fc8%NsilyP;ZQjmxVa zSf@G2YU71@1w)J}uUsr`#&e1TEPX(m=O(8E$-%&_2g;m#9 z%)ADDgg&6#ARUiavV#UNG;rhag3q?boqvEE-DtiuD9dtmOk#ZZkqp=z&gKdg;m61O zeO2!lhIodapSsB_LOOL1W-@LUc;SE7n%7lKcB}02F(7Qi*tHFB-0jI;cYSg5WiXLe zLkG9-ACD%{yd}WF1aL7$X)i`w#2mom8y4AibNN+ENI~LKU#ZNKBVt1>k0cVpA1SX( zcw*ta$5-Z0C|Qwris~6DD5`B;WS764Euhk~?^uo??zZy(fkG;e0S<}JsZ{!g-lzGW zZBejf6MlFnUr@i8U$7W4S)zPuD&&!B_}^9f1g2!-c3#)?+|iig7Tb^RL8)sM#7-@E zrk6u`&dr-#W!M;(p544Bn|fN|X4_*o7F))`8;4xk?S=MWx?gWr9|R6g+4)a7E_&wK z|AS*Hj{zJrZ;ab?l>uKEvFia79Y{7L0-=2>^?+pdo%nl?(99B*@TK2i$^K>7hH~9z z>7ripy#&rJeW#tUo`Ev3K$bOW&#v&Mh>nH%%z)6PjOAYG(+4JB>1|l9umw!*kImH0o|Rdjgf!;6y!&Q0r(GHz&Fux?W#p zIP6=UEuiF@*bf!`UY{$rH;M*>1iicK)vov*^pl=xGP6bmT&pZC4Rh_=SzcQh0WyC7V+3E@I% zycu8edtjCkT7Eq1v*!AuLo-;Utwb|-_PhS(ee(VN7jI~64qoL2EnZ8UQ`_NU*~i25tzfBmbZ z$)@Zq9A;ftCZk$^V3NA4`g#4N5`EYk%=eXjgdln)j>BJhAqwXmFYJCGrL;I-TMr=y zuUocq$KQNZ1Hduyqmk6lmgihx+YRz)J~=#bMgR>o%uFl<{~+faFp3upnJ6JqX8(6o zYsQ&>?+L)LT&^;mw#W5_J+oZa54G@!CQQrDE}d`G%{3Ui*g(xzY=5*F)i4Yeb6dvw zs9hM@;XYUF`GJRmDXtMkCzf89Kk-`a7C5Dc-V$Av?%?Ig!>36HrLC5k$IqV4FDc^H zvjkM;hZ~(s%xC&PA{j3K(^No!Gk@*ie8d5~kLG3J(eCAhQ)CsU0%foqY1d@q;PfUm z&4F|QZ};RR%1ANRJZK!wKFOLm&Zcr=vcZfIAGqqI@WA}20Ej|(X*~ZRKpg`7t6%C2 zhA9q3%#a0DtLii=c9Bf}9ci2Zky86JRz}hX?^P%8((5OWs!^y*Ua9?{#?+x<=aTz( zQ`MiTq+<(NkMeF-P>7=Qh0Y5~f_a9)iTT_0p`jsWob0TaWQ>}_^M~Rog@w1C9TIjcF^A3eG$3HH`7d<4{;Ii- zNTT$J`RG67@vqnXt}1DgLx-=wR9?b5yf{fs>C8MH@J|?E(qEE^&`d~UpNwF_c=sM6 zA3RKa{%o&y((AMTO9D{`mbG>{v+DbWxXaPG~cKpbZ(GN$Omjn$9XA(p_@4ZteOuex}W2~$hVi&@=bDS{iGZkkg zwZ4gR={#yRD{T1v3| zo-Qd$$=a+gyEmPM!t2~W0QUi}_}y2cH+llP@cB^BdsJ{OR)4pwtLkPa#5FKwp!(hh zS#b8)z~|4U(+~7k;BW?8EmpuD6JQ+p;)Qtmp^Z++^!Le<;}uu{IO({8P6`Y@5RT+I z9Tf}jyh)Q^>$d>^x9;^s7m`}+ zP8sk|EXWAiXKU}nwgZv{DcSFIr1o)0#A1hD9{4}YTmo4h=x6AJeV^Lh-5s1k@EUWF zaW}hNpB=gBgSeMLZdxbPxbMCoP+~?zL@+1z!(!q)b?VB;kB#f<^GMnU#4&_mubfrc zv_Z|qIU;yqvnli;jk=5h2gY0jHD2uJ&1-iJd>3+1dCzGT{|c*3;{kJ(_-PxTeH$v> zhpj%bLa0@iLs4*7F=~2s7wds=4}5-H@#XGS;nA36^SN&K(32OE_sid2o9cILFKi%f zx2em@7(06C4!z_R=5J*m0Kt~f@(buL0?%@R@a&NS2+sp`i<-WH$&`%dt`)6D!5z>| zVF|VjB;Jjx@<1yb={UXlT^f)$5cT0defr&1rSBAyXr5cCakeF)~Vrq+PVu?xvgPw~Nw8`nrt zyYo|;O22U_ybO_U%fY^#yni9#c`br}OU1xNhU^MY=B_6%FEXEXAM1URzZr@QzWhBM z3Soih-!KAIeshr-6lQhV|?<)0|?S*u}v$II`YTK`w!(HMzy>8n^(G2ewRR{!z- zVpdLrTlYK2vYoi{2ni@K`zeIiCjw&4d+JpD*Znh3ObDZGh=CPxI?ytS6} zs_)Ir61{Q%{PWKvRxBuCsTtU$95Afd`gi0gKbO?8eMm>X(aYyITR`j)<#CS~LgWED zl{x>)9ppL`A=gxfB)bP{0#ozzb-sW9{`B$V8yXrx(Bzx~WW}CX>XH#OD?0B%JT@Id zjgCoOhqjWgNX+l(?^YhYGp3v0fHW0H3h3;N1*r&q zg%;Vt!4NKZW@Qq0n60+Q;>~I1W~k2EJK79PAfGs>(8gFO$E)&9f0-_h;+|zu4va_b zGZpu58c<-oFnHL&>DS!L_dq$wHAI~)D5we|NA`tb;8HA(cM`Prk}7Z%C9?ZFO`Q71 zNV1y14u3yClsJ0&{Q3D=r~Vp%;DNWiFGCWzl*B;1iMV%=8_Xm2SqCVNThZKrWOURb zQgP^_ECwYYP$si&4MFpzAK&^xmDKb9n7R(IsE)P0YK#fCn-U*i3V6T_&xgn5@&m>{b>(4sIdUbrS9um2}DUY#!o@Q%gkmFTk zPn}TQOW#0l#sy;f-&8|f`r(exLBsSd;40sK?Lj-a(uWmVA0);Tyv3~4>+?`50%`~9 zFe@AvUi=^pTW4#QQE6Y+!dfd%wF`t{;K1KQq)Ao+=cUD*$5dR$n?LlTz!G!$s)}dq znz(wU;WMS>ft`7wT$yQ-%(oqY%|X^J&+5GlF;^z>Zc$IrQH=3o^~?Rtp}O6nPu9 zZlUh0PjPwan6eFv)U@U0sit3fvQpY46(%pG&Dz4JaS&YlSVFCFMM%@U3?+BoPM1NH z%yul*gks&h_`m4^fm)*zlx%HUlU3`$f`V}r@cvX?jp`2EF+*5Q&9?{>0eNv$A7?sz zSjWI14VE6?rAxPgwXp-vcf+vXuUDB@2hmMbEbJA7v;HCX?iD9EDWj?zk~;#D&@7-B z@bX6G(qD(3=$_)qsEHjM?teCYQPub6Gv%eNfq9b{k))he&7`9oIRo=0o0K5`TVXr8 zN+jV*33&eOi&DSM=vxR1N$Z~R$rK&Cnrh_jOvDVGFPxFH#JbsBOZ@E`_11r5m`5)w z1?2PLoG8wEeF-K3@IP?b_Z8oUB4?rN;P|*T$WVJ;0T17<|Ij0gum3)Qjnci;5~eYG zWDV_3XcBNC+y{zGRC_6xQOn<22*fRa&Om~0%U&Qb5h`e8v$-=blav$?EzGqO1Rqa(|f2g_%xeOVOWRx4A%Xx(aO%KUrxy5 zm#X6=I_A=H1WIw*oN_=sJao5WeF?H=^Fmu?kMh5?;Upl50qb5M6iPCXEHv^Q4H;lR zc$p6f93F1^z*C8NEn6Q~9cF`497y&BL*+pf7C2G}ha#iRU`6@8d-p(vI|~@lk=oOs z?^+BJc7sFxyxiO=-QH!3b$n1}Y!M+#n+@|_8V33f0WbSxqM=}~n%>RcPdKQ?R|UUJ z^0p%h99C^ki#`61U$o+DWc^S4lF>AMjr0G+S(zHUePezmV3?iLGt55Nd%xYfs$m6Gi?>uI5}6DU+lxkFD>lApyaU1IaaZS)sG@ZDdQXaevy|aH8pi? ztjx}d&Sj_2+~x+15Q5wVYIin(_hI_+$NNt9w{HCnLl7JpnU;~k4=47n6AB=WA+yvV z;suLETT9EiMh1DY;22H-cc=L36_@}RQ4^Kxv0tRa&flWuo_{ZCk!JJf`2foUjknn& zar|{GTQ+Uvt!q!rgEzIP#_&7m?0S)s)K;qIvyQ?mw$}%5>YRLS zY08VS#;%5RhiwnD3%W8D3H>*_QGhmq?}9~Qc397z&0uvX{-Ds>MFuw$l6xI6vr|EH zMq4c_ zVxH!8^x#dqhkO2(_wn0;gw~`KBX`L^wOJzHCA^l=Io0O?VIL zXfAwz(7X7DXzcA?@*R+CQ~iJs~l8zjt7!-r2q$O&YBmJJ_1KN`lLU zyugv)P4EXWCbx$Py6g|E6&`6Fs!Oubo7#~R5^uXQLlb8s{M@6j^v|msu5LUPM(Ks< zG3dSN2Qj>yNmK3k}b^?dZ<%Exxc|KRkDj|M2_|{#q7yW3*X1CKBtJKg_geC3l4i z^tPYX(y)JG^LSkwd>U)1p9Af0+kDVWhKX#i(7sal`BGZ;%=dUEZD*NPr|# z+RK?na`OCP=ATG5?hUc~b1rZ`4Nesm{!-|Jv9|RHJTUK@>fL#UoH2eme2@d<@q!yS za524bnKG@!tbM0OxU~8^&;b7T4rF$J4_rgrLjStw0jrM_E?(YndLT@azg~Dvf(0{_ z0Lha!I6i&@cRy_n0T6(4DBw`aBFD`@b{(LC*4EHy9*KlN0wiuP$K$TD{cef}F%`Aa z*x1-ClrOydn@4X;lCqAbrc=)fY!@itK70ZW#)v1RX?tY_YPGftVZx=IvhsXa8lAS0AheRo5L<4C5fY1e08T+!} zL{}&954s;$Md03bA{$NEWXJV8#eaNJuYMkE9oR}Bu8u*~CS2R8$_{Gd->WBW9j+2; zFX0y$$mxV^kJF3)6%L0`qIKRIkik1!REJLF>w*@{LW8{DWCzw!W_Y3kT&ksJQMeaA zuD9}wkEM?g&*cUm!J(r(3NwxLBcMHmKW6}C_&)6Epo91cjL#>DLoX+)a+v^VtT+>} zr-q2Z(4ZiWAHR#9Y?Gv=}<=0j%_ z694wtT!dHzg5r^!5Bnczgu67BY8s{yArpJ9cQx!6@{yxXyaHdg1A_P59LyO7bh9Y> z6i-M<0CjCWPnhCvz*$-B>$mClG35x{2=izXfArwcKD|itcV(Ox@0{`T_oYgO-by## znKSE;OX?F!T>Ncw6^8mUHkqjk(h%-hgpxQbuHzUV4LVl&kgI+6t6ybf|63+A5bWwb zP-UzxOHG8*uY=Iy;d(a1CuDCAJvuJn@UddnCef3g1J@O;)MSz6sDFPIMOA6HggF&0vV=VEF(To4S6?|2d zz>V!bVDowlB#yRC(UN)m^}WOE!E91)el_bYdn|R>;#AG)lx(~W5IhpIXyP!aXTjQ7X^-*tW1I| zPA$^;wYH887q|`a@0-TH8#?5slrS5zVZ!A~db@S_*I)01T5NqcB$)fPgkOZjpyEd_ z?1!_UV~<&#V;~fOn4&D!Z{t1?T*)o2-ZFNbAG#_7S_oc{B!w+|c;=yLK0PY-tHSR) zBkNP_pS*yZ=`E5Qjs%9P<0>evy#8p?>Hb<}l0t7{%L#|XeDaWL#+9SNg4;1rE)+a5 z&v|Ypkwf~|qvf~jOt{(lcy+cYqABlQYS!-4Ec&UXuu_p@z`|6@{GUJk584i>emvPP_~{OOmeGFThaB)< z7W#E0(iem_v@kcfhP?sk(9=gATrQJ|tn~o|r5BLAA-zw4P>VIaWMN^ez{`T!1TiDl6w<^foFg&+X zs>1Yb=G=F9c%Dk-DfWPWl*KA3p=&5-y&%(Q1+!Z8X7^7M^@BxQn?G+vg0_l}yiR~} zH}(3)nEXG-LbPL7eRh6wmJp5&|Ds=6mRMO*bNv@Ec)RV9zq-fwKlpzUhTr6rf zB?IaiJQZDMQ-06DuwXrpUQp7fNKM|luPN@V!e7 zp^3>>FA+q7@N}!;Uolj4X{>Q(J2nyfu$=jH%}vL>F5_iTnRFEl(3Q+B0C1mS54D&8 zZywF9cF392rJq498ByXxC0GqIh{%p1g(YCe=>&?#0S%8VTw@Ak-a+NwIGn|81BeR_*Cd(9rTQMJSH=0E3mhh0ou9V5+J*EqQh|dcV)I_Y$f&5VW;8 z%iR-}$3j}%N=L4Ek{N2-w@0Rp;I!$4-#* zP?OqT{ge%rHQ2to^DIzE{quNkmW)AbnV)HAl`zztMUlEs@QDv z;D>)Unk(T~n0gh$O3x8@W55#LS;qs@O7qFF4h3n0$?9?jX8L z-T`M+t21wH8$#*|sg9wOYA81Wf^r?LOt}Hf<_LHUBR&Z{K{}977c3e74eYNP5dJ@E zX>BcE^}3J>!Yt^J03h2DT+$X~0|{z^Yq1_Jj%F5=SFirl4@5GNGTw!tUn{e@-?X%> zOd6PotRU4HC9bN*y(a(r48-Sdn?9i9=+A}r%%1o%F+v0G*Y_9S`Y)(d2~{UYk~30Y zz2taxkATbozG`KgX<|xZhNL!b3lLF{4-0i?d?THk3%8apFjc`7=&i~a%-AR3?JIaV ze4`v#C%u49(`DrI>l@E21DLJq>*|)lH=g`>d}{W$*jKOOFPYU?!*2mYq77XEJ!-p% z(vlJbcr86pBIw9A$!6x$y(lGBdbjX|a;0h`Zql}F{oC^u;Am3Y-dM@Eu=E%N@ZN}% zbID6cF+#{MefhR&SD}3r9POaEHG+he4Bew>{(dx5j9ve9%hix`Y%eJL{dg);WQaH2 z=%?>3Eh?={-0pE~=IyKc=(NhFrK8%40~YLwy;DK(Y<4&HUB-WR@Zbb^?d>qlSElpH zlaL?R00Hoz>q9kl1q7G%`Mc$y4&()v8Z=m@yKY0#KuJ|q2XqBLo(H|$+qZ8s9Y5~q z0hdXA`}P_tq6Gp@Vh^ZX>Yj}XfI&eC0C?5~+ZWJuTaNP28L5NCJ3UZ%Ljr3yAa$3y zvG&6tKv95p9Uc+ZT1ceL$5h#Uv%n`NI~)mglAjL*q1R!rU9rhJ86EKF`rR6leUs_CLUYf8PPnI$JcGfDkNY zxsERzWV+sd`7OuA>-2gXg>wQ3w>MxQUNm`5vU4}Jww2T<)k6smz4eRi-~XMY9L6gl z(aDH|EW5?XzQW-JZ+KCM3ulCK1-t>D0R}psLCA<6TAqOH+rSA9j%?tx zEP~S&VMyN*s;RMV`*S{iePyA~Eu-dJk?NZ1EBZb#k*hOiy$^_XR$$vzfbvPg7OOmL zP{XTK5Gq7@6!u82-%qlzpc5jhp{rBKs;4loqeZg?6=qFUVt2z&?vrx5(kKI>w4*VBOr@H!t#At zL=Y)z&x&!M`xG4&mEP8-U1WW z`ug?j4JsMuuqlm3FiOKnklBZic~o(OJXdCGELK|E%$oG0`mK7s@Wz8%MwCY_Bc3fc z-IYdfHkvya@w4@MZ>+>?@Z@H5>9@?z6Yy+`WVhk-N7Z#<%<>|_wc8*J4*_- z<7I&FNj;#o?Q6e13Bn&nyZloeufk)5)CEfQlHr$92t$b=B+&KOfN{AXX8gUwG}-Nb zhN)qtBbW-HA^slJ>|7_iaua6qt0V;O%{=ls~Rb)Sh+PS zWY4!h+Xy(EO?=;jdMCNq4Y>NB1qK#bAgdhTc-ilk!A?QJ*P|qz){V0G-&1$oE&R2f z&75;R^J_q{f)dHbSN1>eHdKQ(J8qds3(Xi9>*f9PcMw4A&O3yOm!J3DB!^mzW!~TN znx(Xq$kAxi{qEt$t}zljYr!g9<*(FkT|4^YkGJ&X4Xoe%^Zeu^ooAa`-R7dmmM9B3_yhk6*XLGes2UoC{!$ zJWQ5xxs&a)_V%%s9@c30j6)SG4`wM;4V0P?d-Z*5>(5BHAj+YH2eeb-TH4xzM`ql& z1oD2^Qlpm6me?Y?K_B36ssnR$7#mhN1qkY|EMyLs=Btvxr-!wUtSg0@fb-@|5v6?2 z*Aa0SM#I)K(er-l7zMN~L;>qzkGKI+a&s5h1}ni_Qh*(F`dBsqf9-p|rIL=Tsptv` za%ETCbgEuX>}gEaVCmoBHp}i__jF#GqGdFCWvs8T$VT-o>yeU%34Z6Fkq=>d0-umi z1!)b6Ovv$eZ+;q?59DN!OeOE}xvB}E8Q<&Un6cM4U$4&EA{;)Cjt*-KbcbnBZ z-a&FR{)411?UAFW5F><>m%NC{zYY)(5~2l$6Bm~u0JNyMv~Mbm=lk{ft3XLX{xBz1->v zIOZitS&hPBp!yL~5E2X!u(ad-!Ld>81Drr>IOl(sfHbE3&pO>gW8pG4;9D#7m)iso zmVaO&cXoDC0FY+==DtA+K-@=~q~;nRV;Ny?_5lZaBEVbiD-423%Tt{~;6bZ_zGG{1 z^D9o}Q1gXv)t+Dr5lv&#n>Tl(I;J2&Gh00Ta+*kq9W92^g0)oa#`QcGuiS{o$N9vM zcX^e&3z@9`$wPYKPk3`P*zqVPe#Yibv?zaHVfIAVd1{n5LDoCWiVM#~H1l$0H_+(& z_+`>2E&t}A;1duDMeXF(ec?0W0M&wI$Q9g@1TN^peLK5`!$M`RAf0Cg^#a%w^n`%} z8wjnXj~+dW=wi>DIfGUU6e3~I6Py6l2Gp$xP)D~MZ+>$clvg0Qj|34pK0q8~&oj5^ zA^`@u?Fsdw_1Ju}tP~JG+r9ax=P5L#8Rn^fVueY~H}|`6v~9GM zd#P}?f?&QvFdt~Gw$yFEP|9v-$Cb0?7{F-CJ2% zp;NO$Mv@nt{wl6~nx@a#->pGj5=qyp+gxsW&FWTcQGel&1Zw? zeMr&dp{@*a9gY(a%&)lF@*ell6O&m*a3w`13!lUvTDiD;RNwSwyRH`u{X;nInMfp3 z?a6w2dK6#)e{fh$+Y=H#buw#xK{Yis(jewTgv9nD?CMBguL1JnO!^7nB}jrg4Q$|) z5nw}91jR@u5YWWCS?L11=7}9g;pM;Yi9E9JbTk*9saPB(M~;)PV5aRXX`G&`64jQg zY_F&PIDYG(+c9U|Q?xY$BURTMN0v9$=rbaI1zh2t0z|^AXY6T_RNKV`^sCCL+Ps@r zK!${VV>tioC@T&kP|`s1?g=(R7|KhH91uV?K%AQoQt1%+BE=hci)aaKtj-hnEM>Wu^MP1Taf}~Suwq0dIP=;0xYEn%s;ux*3+@x{g z%EsC|*-E(&+~EHBvak5Chrik=mKF2v1!ay`Hh*sZo5((1J6(l^2<{itVGb*7&yF+v ziLR>04M`kco{_2b@`2*=Q#zFA>6aUP zPmhzskDRkhkc4^m7So_h?W4$s;izG_)Ma#xr+K5nmzPL02_gm&IEAd7_j%lO9dsR5 zi}N=QZFA+}I&txatE0>dos?Fu46LNVgP{&Ts?yD~$fqM>2%idJd658*nov}bgFl*p_FP*q9)I2 zTGGfH+O4}ugZVomr*m*EW}S&z+4qDWEsjh4Mx5^$!O4d3d+jt*N|#mDwsrFc^-0^b z&^}*_hql>9p?wPrBiVDewla=kdMbd4>QYKq1G@s@gFj2ukInl-MMcMmo_xZ#q)5>) z<89A+=X~+RyQ(^&8GK`d^03)bmdw@~BMy1wpo{>Fi5Cwhzuj;BBZnn~?uZJ$73%v+ zfoKyBS)n*`9yii6H1-!HjXMXOk;{4{ZZ`fCsg~nbYzb$?c9{8sGOPP&|H_bgTel)* zfOSysIBbZcK+>z2QesbLxCGXUvllI*`arHw61Kx7 z;Md}XjVf#TGW1pBbiE}PZVNV`Quf5H!}hmT{YR<}OZb(=Ts_34Bc_;|+VvhsqYA`j z&qW-O;+338OI(|+&N_-YX;mFs=g|8Vf1Jx7SJ0(`7xwbJtuTPwKA>OdHF?KP`&d*2_T{4nXR#F5_C^Ze{ReZyl4*SnZa*=mJ!J&9@ zwyT_<2p5GW@S#xHE(qXbz$66Jb2pwIB$Ee7)D#wQ8$lx|pYK_Mg28 z#30`MRaiBSvJuN1AxHWug++i)$I;sz8)sKtb^n)<(xJ%XyBJhF~i_eHYUMxj0JYQnOO~&SI*f?8(Qf;^HFOdfR`t z-t?ocXXIG~o^6xSar=XDV5R4GaD2Lxe||tH+ghxboP3uc?9f*X`+v#52%9K>IDFef z(}q`ksj5 zFp`jv^3MF|NcZ4{Z0T1GF~QQSk4KU#l^jYh=$F3D6WL$YWLZ6J?~Pl#3LJLvPgJp8 zuWF7qTGVq$?r~;X_nyRe^8yluVxqU9YHYIKxX?}?X##*URMtHaE)t^Nf>2TRqyKTT zy5C~ZGbC*zFD2%D@1ef$%?qdcV_hb747r-UTxY@zw@S^Ii6OBgGcrr*Bgy$eV}H6| zIfNM)D4fM)V2%`=&>9mI!n&!t>b&gASMS~hsTf?dPdXHDzrN8~84Io^T_uYUkc70w z;D0b5AvI|MT*#hC^pMrD>=M-Hjh{Ca0pQUPLPFxkWO_chF^$gX)xBX+S2Zq956^Hn z3Xa}rOw3Zg>3g!)Lq<4O`ye;ZJLF| z9Kg7JpVR`JG429nevH6$L^oeusBhnV#YAtW*?&6>%pKSnt+)+sa1Mi@5HG5#s_Lk} z-vQi4ND+m@N$t@Dj&1Ab4J*jEr>zIl!oihv90)XzqcpLb6;&*pAR+1+7k);6KyW01Sit7%Ct z>R?>`K1{DQ)}5w$6935UjW%yc5(uJKh|@g3e&{a675%%54={)=3W2u1JF_kt5{CrH!iyj3L8aCMl_&YCo$_8zDBW=VxA|sZJ4gRN1qco;v)DX zbPdOz6mcmW6B0abO-oA;f*p|hWrFnW6rWW6h)KoD!qbDKEmC%@-1Z=Wz4U#bp_IUJ zS-acpqQrJLePNy$-E7a+g{CPfP9eLlx|4%*ETffkEZRNA^>cZrNs&p4snnGey@r9+ z&$Fd0B4^|e-zl>(a_}(qij6FnZe_`;dzu_TW7SsTsn^XGvWw~Wa<5zXxH&qf-o;&B z3gXXT~rI?hP$(0riG(-FIW2Z@=0!5`a%hdUPLLIKrmq!B{}j8gR2 z*jQ2jir#6MO!%4A^gtl{&76I8L^{4$+LZFeUVbrmGf0l6y!aW%8NkOU^Ch&OnyRFZ z(Qam;4K|I0M(%g}%?*6Nzp)%q5!nNhoP3=QGY75~P8ak?I^7xUl>78nxijmu)L6L7 z#P}*i0?^{O7g+yO*o&Mxq`Cvr)O9fJmrKBcHfH01;oAZ>bt;&NSSSwKEnNYmdjnFw zz=3EQ8A*2(uA?WGGXHv*r0jkwN^%|#^Eo%7swqLiS9q+R^pF+MwuWL|XiIO=!r0yZ zSaOuwAP~eP0Q|S{nWgRY5d%5acUjAr0$<i)J4aB&1KCihob-Z*|VM>3@1nWYaZE$yfEwYer`>0kiXD9CGBqxDW=) zskYBKhagQT3jeu4@^dLv5`>K7oFVY10KJeYZ~|_GRu6X0ez(;#i~<#8EufYl06^pG zlT%amKIkC}SXEgG-GQf~y3KCob%uklRX9@M$X&{zHNk_yJ57qeYdL`_OL$0b5R!Jj zB~etw=!+Cb<+(S%LyUn`lAHjORblbay_KSstU^Lcrm0#f4m&-dGd}`|^ae-|hC#e& z_q-amI4NV$Tq#wJCS3w&mys&0t{%}Hu<3;hMzxaY|u&o$@cUsva3YBV2 zTR2jcJExdy2vCDvG;oJ_aV1LF%JXZ4LP_^F@}|IOP}?9*>j{J44@u3a19)Vy(b3P@ z`5$+!NA6k=-BAi)&U-KlP*~@XB8NlSLXD`HSh<5cbczpDj6C3JkT`?SO1eoSa5Ndr z{sw!IHO^ATz;56l6V)5IcyRbKZ|j7dU49e5!FndhLWH2Xlul7@B(3=CImlv6Yp3(9 zlDIKlZR;*FypK1%gQk=OkfcXqUPvQKc8y5pBt=^uRO<;azsaA`c-ZEVE3kSbXF$1>jh8Jjs$ zuIe?|k^wJqF~HI1Jdy~-&MU!Pt&7A(xz_vyBG%egtz6h%`3(7!Ub%C(i&Zy%uOYY@ z8~Q?4!gC{32~Hf^Jsbh?7)1u z@8;-<+PN6H?c2L0k}m2+jFuZ{lsp(%id`FlnvierzjL)&X(ZGP9u_=*q9@tP&&D)O2CjuW1>MHh!(te_F#%=BYstFDPTP=Ht|0 zoSK^DMG-=e3`6dZ-VoX`00Kw?`ir%ae%xS_t^1(?_=htju*Lv+t_Xh0VKoR3ST#szqgc& z+QwYb!XW$H&U%giL)cLwYm$BD$gPY0a;lAyE2~tHf{5j10_GZ+~v~mu9G77umB`m_wQ#>?hgvJ)9~Nu zS-_3pW2)DMm=Ux62mg~%hnjU=rsASEgh)KJX#Ti}jL5i84u%40b!(*-R6oane*#q@ zOX28uQ69>r&g19&9eiIox*uLT>UgPLOpzk1ShSB-?vS;au7ty9>Y(>!^+p3@kJZzg z$Lp9=ruU><<-I|M_Ab;Vdfeqt9kwuTUVJ8ZVncNJ23^Wh zu|@X17H2WmA+qjMT68LPzsFv|oV(kv3}Y{WXi%c>fx;@xKUj-#B*+sP>y7s>$Eq58 zZ)FZ>>F9(2273&NXny+V1a{p9^+3;fLqXFMz@3mmS(zd`>iI*i zLc2s?bUDal$S4Z~tlekiJO>F7Xajlcn?3jDYy*$~^81jz`;S>^X?5SKpQD5}%B~6c z>cc$>PKngdo2DL+z2n0L|CHxjPUp4^5h!&wQhmBQYY5Ok)bNFBkZDDc7Lsk21Z4K& z))LuKYr#Ft$cc1wNB}z>y8$*s?|f4qNgPc4mitu|33BQ-qQEe zaYtnG=*dmIuFbdQB#V0XOF7FK*F9>6OK`36;XpZO1GL7WjKg_b^@P`Arnk1DHZ z!kXoJ&B@@YQ9UT=D+fl|6;^JeF#r}-j?!>(xNrIrK zxkHR!jiplC(71CSi7LUZSayFfal%zgON*|3 z44)Brh~o4D*TzOtYthNDA~Fw&vr-xIqX>ZnV=itx5t(6F^u~^QbFOud=NL0{l^$GO zhH6bvSw%3YI7O8$tn;Kq6OaPTX)&8NmLX86Fn^QMkI3QHt5^)- zHz>G>IHj4&W#KkG|E$;s{Wz$`PIbu3!n4_^t*4j=ngv}wH0!~FdcnG=a@w8NpQLQ` zk}YdDADhDoUT#Py%R`BBzf9Fyi5RKz_{V666@g6bmTvaLPe0upQO9j)AsY??tu%Yk zw1lz|a3uvJDZ|v%RGzW@XhZGo$hwuhb%okEIOCyP%T5Xx;`TR;)ZTOl6dWeUIa0U? zR8??SoGV@4rS8%Bqb1xR?wRrpPT?pZhi?=ZxB9ZSK)>4xNK@znJAlWj%=)hEemT5J zB%lZ>{YE5Jy0Nh_Q~4`;?81X&F5J4(;9Yf-k>hp*=3Y0b5a+C|P#9bT8y+j)is6C?0|X zP1GxH)8Uody_Jn9uv(th@0-1a$~!0-5bf4;-xFwf1`5C1LRo1*3O7MbtQ8Iv{o4Ua zl=zS+nu^nu|8qWYdL8^(!sz{}Q;j6@#}P+KDn?xzw+0l?Z&Ko#`sP$?r=;2v-NV?t zU!fEl;N_a$m9!jaE-Wkj+ZzCyBT(I`F9ONiYxR{;%hTN=DCLE65a7eB8e{i^mQM;w z30VTC(-Sg$U!HHJ>OEq^34;6QI8%ecv)zW)f_i8c2LK_ z$CHIQ7zD2u0$o`+uhO6@(H{&6$WYgEsNsyF5*2h}vygKLEIIOYZ?b!uqt%<&1n#9g zUyhsSVng<`#*C@ZW!Bqvj1{*+?B%j}s9^Rc0+~_K}!PlTkn%rNfwicfQwBkk!@DKNzLmc@mD*!>eXe zHEDZw)7V(kWA^i-Jpj&ikaSCjqKe$-M8zN!;ylYRfjt22RY)UjFQZf8^&WhEIAtLtAQ+!!b5 zF&7~Qv2Oy1>BJT&mZ^X%LMRg4=Ll6$h;Z&#TcUocL`DU5<9GxetHwvR;<&(Lq%-pr z+|wEZIb2!O2Z8^JF#HHNxA!6Jn8I3AkY1i_=R;D$5Z{C`(wC6I)Xmkp1kZMmFNB~U z$f>>~s;^h2n$~}a`=-xtk|QmNg$}h#@Ow-TUMxU0qVR#vSE5ygt;Vj997YNp&z=mF ze*oR(Ij0VND~r*(kSOIU_)39Dy%lFA)m(Tbc82_muiD~lAUC9bv)?GD7*{u<6l3!Z zX*rxl;)157Y)6TCQi@7uhb&at<4oD>$< z1Ks(j4oF-`*hvGaXlOk-R+OxZqK=)hF-|jwj`Qyx1I7n{65SG-UZ~K_9qVxqQinPd z58)eKw?)_$YkV(7YX1ysI{(I-^C)*OeAQB8v~7JheaV}5^& z%aS%T-*B6{vxig71~Fx$E~wYiwRU0uY(Ol9jO!a~&8hl%skLm4v1%99XC2}c^V>qN zroa)rlr`znUrlKJ`4NTh-sJRc9BV%FZ-Ry0xX?iA_}oNBV1 z#V7Uu0#aMZB%(nHl+mpcybZr9$QaEhnE1RarWd~piuvJZc-_gVN^fzR%-7L>o!186 zTU9s@lroVS3wEPcgsj62G4DM zttRS}%G5 zb)_zfdMnp+vs|uw4lES?3l_-@`nL^WB|D>?r!8_1EsLqCoc7@n=9unS*4|Gk^gt{M+!_nQ|hpH`EyWh2X${qHTR zZAH=rK6A99gj1vs4wbcA4&#GlEc`@F^J6pdZ;0r zr0KNeiPYg&)xD1K2-0T}vq6QWZ^hyiiMkTx%tV@kM6sV!_g%*;##p0}59L=_na?G%_zMMW;TOUT9kC?v?s@7xwY+wCsD_U|J6 z4%)?Rs2HHX6qp5W$FDbha2!ZQ(<@$vIuMt_Yyd&g>&LsQO_-ja8F!IZN(zv|oU)f- z{BzsJL2%S6u<4>S)aKduYV#VfGs1;H0y`#Fl%HQbpYqCl{!KNVv%KIpb+U1+zH;Zu zSldIU@F|!mg+RLle_jmKKk=L_z3fPsjQmCq)(!q4IftH#?Ivb%DR{dJN;5(i{31i} zsLpIGp?d77oPZ~J5DJKJh2}byi2S$n4YwbAC6<(=?W&An>QV|@=+kvZJ~g<(^^3LmsiJnJT@512G~`QxNdd#i%P6Eyo~zUQoYmcCkdJ;mB}sDX!%D`gA1 z?h1urngI@g7HB6{Sb#`LC$()7-q#yA^!FdLC%#8t=QUT*a!wX9j;T)XD4*#2G@;Cd zwE`QzsBSeI29p}QXNUzD+>##ciE-SO)IVCF;IS7&>Bm5 zsNj5;=szaU!Reh+PthPNG!GK>Wy-Tv4y^T|EvP_8{}BmN!H+pG~aGlv~fK%R~W_ z#tquT!8R1W@OL9;N*Q$nS_ngQ?n3Kq`p`EW(q|FAVp;gHyk~}CsjRzdEVgj#^?_Xl z7EBKxeWL#wAxCtwopV-dalSQ*oK?)lAVrZdtC@|lywTp>j86PEur|Q22vjZJe22hu zq|-Fri1%oC>ZT(k>+2&O_a^)*L*&cNtx=Wqrxn((|ARj#&eyxeUcNpXb-j6ia)S{V zTi-)2%H$?c%BGJCCO*%G4_Q`>#$DwUZq|-qAzWBFVI!7RE_;fw%=-F>w`1PieMKD| zY6sf6-sSK(*Xdz)sy;m43nAs9v;!-ls>xwzWN`$PWr^cqisW;nByW(bOy0$0j zb%gSpae|VRSN(On(joFw@$^kas+6krtTBBi7?O@7U1WOtf!<+oP8=;Fm8&VM69!=% z#y-|wE|VHQ4A&f!$&f#rJ`x#4;C4_-?t9JeA%6eP`i67w+q5gxbedXP+JH}4?W;uc zfTHgjTij{r4Jc#gINAFxjYOkMkMW!2Q`g^y1U$)VO;u2p_2_!FwH;pGnvlh| z@mgp4q0B^<4R64egqJ}gFhNd3g%L*TfSAkRiR959Z{xZ&S5_uc+3Mp%$?9Px5^RI- z^-`ug(w!mLANZCIH-}~&NT1O0GT2gSBDK%_L-04@%|L!2R)f9;lzx;(0CGsuf^B=%9-xXo-IXw}!nk^m zAbqM^XOF4z$~t#GCfLZ)aXoIvT4Na(rSr3ruXwM`8F=h2Bl|EZH<;V;<&kUJ3lW=f zSVo?PRoKE|0iZ-TR+Yg`*vq+Em+lUxjX_)kF1f2=_Hoc_D`tk#t_e0fG_-V_P4mCc z8AZ3Z1vd}JDMy}pUO&~$NgO%_Gvk{uT1`FSnyK3B$ErA_0NzlpK6q`{f4AP;T^>0H zSjxkt{mg`MN_jpV>9wqS%tbY`wHM52k`oedi_!Dqb<>E%;M2;wR;zhpJR!z7hw7dc z{T7V|h0ZG-x|D>QbFbB7a@5axGR6jpK*QgfS;Qo`hbx1n7yA?2v{lCL(o9-%duzz) zX+Z|Is+0OpWdk$V6H##ze#wh}dZgZ`ir7o$xTV4=Ko|cWr z4y8e?yyv$zSI}AO)KA`Q+D!hrzB`HYk>4Z+dDRogR+Bjyhi?@#VWpI@jns4`vJb746 zIVK&yP9InCp~A`rUhL}s%Uk{T@}xdRMJ=-h;(=-U?WTQnGkag9SPBSXE9fsAy3ot8 zj6D!wvBc?P;~+BjK@(1%Z>_J7*`o1(C5LOcDbFaa8Z&*wz8rTW+^6?UPD!C%I z>dj}hNQC=}srQE$QrB3DZloBK7EF|m5i=N*P~6;C%Ncyey!pP8o=HRZ4_E098r_os z9~l_5!C1@NF7`PFmF|#h`u(2gP!<$xJNxW<%pSBjn&-`>veLsx%uHWidjOI8<+P{e z>a()4cjp?DGzkF*hia0?{_RLj&uju=WjcJyp`HCbC(r;`^ zaj89#pYNdH{3c@a*m!8qnIe7o476t9Elcz?y!P8Y=4!c8Es1GYPJ8_UsKXv6t?8nBR*^ge^8ik3ONyO6&n%_85Lc#8DzS z&4zHER>4Rli+>B@OmA)O()O5rXXJfyj|I(<;d}AgTRu8CG}$u}%}Rg>QjnfFIm%Nz zTdCmX-n8$r_g>lr%mApc!B7Qb%@h_PN%pvtYfA4_kmP!EqAe|vEK7QHinDZDUxl$wCCnBk zRbum{g@kNAKTU3lYEq9RX1sE>Nl#z=dj9DshuRs3H4`-QF!7=p*KOSp13x&f!6&h} z;W;kqh*VlJW>|OA!6$*+jkUZHhVNPRk}d>>cY>Y!Lef1E zcd5P9;p~Uh=P*r}0T-3JyC2K*F?Qxr;q9GoBK~D541=jVy;^G(Cg6Q*u4%$}5K`@^ zyAW8HGj`0gk>VHfIfTUXmjp@kTF)7=_$Yf^Zh;+mwLROrAyEfoDc9Zo5Nz(NkQ?ET zUkK=5_Q8GkV0(N|C4)N!@&A<_aCoRLx1@0 z)(@|I&uto{Dz#I$zrF|{Xoq^K#~8@QO|{fVQ!+O<1O7_XB>6(>X8MR~ z94{R82Ydb8+mc$7Hx}nJ@;MK&4nV8gp}W#}r#la<9_rWnUiR#)ywL8)isIE}L3JTM zlYJhG;a4M^hKBa+yZlWkxg*;<{!>p6LDLpQ5d;0WBWN6KWV>IYqjv(#>q@1NslhZK zl_|H=(syE=Oj~LfNeS5n3}T)!eB4dj&5enn zZfzW$qWdZGr;5CswPFoQE*;i&RMb+Q;xNIDSHFKkKGRnuNL$ytIr^^V9KzhACV!j$ zHcfH-Wl~hqLB-am_ZDAnXOk4;lsAs3*leB*qKB{5_6{~Axxwvg6>C-X_Z{r{dZV9~ zOrDjsF*U}0p7&W6;TID{S?Xtq?#Q{DKYr6JKturOIna=moLiOAew(UP;L40vh;)$fKcIwctN|B zkD}ubQS-=K|f#IV6wof8cBHx!o`&Arw^6Kdn%2a+D-}5i{;~*+v+78u)46a z{hWlR?D$)F`cR?%4V76RH&=a%XqygY{`LWpsiC{n@qbQ;_{hi6%NX!cyb{9*(kQQK zA$>ck-xe)>FG#NcwL1ylxniT7XWiMG>TQd_@D`F17PC1nkEt7jj1sTUG1PMm#s%tm z@W-nQLIVJjzMmTrkpHZa(GOYQ);_w!x>5XrsSHzO*q$Iy~i z=HQWC>N?Cww~qfAYfzYL*WFq}+_TsN42vCl(hw8tV$iZ)a*rOyl*Ef+-ORh6&REpr zHVZCUAYvhC_$+$16F-pYiOrjw__kQX5f{A@1B;m9NeWJ;CXJSEyWgrT*%}T0vX?Qy zXJr&J*6Hn|y2m|bpH8WnSK5NC7k{Ms`s*}iD##VmX@-n?P+zP&x-vXgvr zAX~Jvv4re_jrFM`@C9hg4m+RVulU%^BpxDFfs{`(RxytIK(b=tgz#*HaoHt3d%*$- z&mCi=uXIL>B;=sQ2yHwyjgOA{30B40IxR8kk>?zB>198!C)wMJR46JcI<*ylctQt1 zz__T>-?=<_WjYhLuKv2Fk(W^pIBY=7<#Cq-&Gf$eW_vj$Q-)+?v$M=b|2Gj<`j7Fk zbB|7SBxY*cS?cHrGxDL(msN&zxQte7&B*BH^Tv!U<(jibyGCt!gm4s$nzX6>_sgjQ zd!CHfZ;Vk*wg}|pS&xiVbX1=_!^q)}|2ZZoPyy`79~2JLO(_~8B@_eTWABp^s;$^J zKQKbSl5p5Mq)YE5b?u>00chHFg)5 zj{;S?<9z{_u}=p!D7_SRbcEm%Y1eKjH@%Z)4VKscuBdQB_GUqg<~<)iDBjXP@MMgt2~Qc@4`{X zXaadQrf~(cDh}aVhLAk1X;QJ7d`8!-9lyrz_0V2iVul~P^CjSaMzNeuI*aMA|C1J! z5stMRD<0mpy4ToE3f^Q;TWg8*2oWy*jBXC)*A~~0KO@^k>oBrCrxv>2t^iO*F2m%; zk#VhER1Ri5lkV<}%Yr9%y;49tzeMmf?dh(8`x{i$B1#K&ngTY9Lu%*nY~$5ow&WEt>wErYZ%)T|HH3iFLNsw-kdtNv2k8@4yGf3+k)T(~>~W zz>`sWokEgdzcFrkr8_w})MqO832_2mZ+;R{%Tia56V|-Qp<@%hJakV7=0FiW?2F&L zV_>?kxI{c+>9P580b_H&(*3Vq;fM@vL!-m4JD1{rSorQAG@q{pB+2_NpVjDl2i&!M%GH}bZEw<+UB=5CVl~LypXqsS+=*tVfF!Y`=q+Z~YQb(-_Pu$(5)9>C|%yQ&h zIY8JsPx$K3_1^aiz0R(2w^OG0V!gPXkmyqQs&Fw61*!TrRM_@ z?X7B;{*SFMkB4&a|Gpe|b)Qr6+`mpqg>&u}Wr-4!Wt`iuB%ux2l|9R39s5jm$2lz& z*}_o5DO=h1(SpV{maM~&ZD=qU+c0LH&ova!>-Bv9sOY+`@BZ08@6S0sJ&k3}HFs`l zY+>OQH(%S!UrQ8fgpYl%65NI3Uw$v4MzctX3T40X%E6Nc%TS&fMu%8@=CsG>-D(T_ z;OP)1Vfvk5yk)M_(nC5wM9boJ(eh7iD^ufWb7j=V0Zp@$FMex|WLbdi&h=fKmgFJ9 zok!PI1mC%l`TGvyD)yH`<}!Y0ZC$u^@oM&q!KPCwN$u__tnb7xddw&zNeUV7z6*WU zYc(M*`N{QL1)`^&PX&+W!F+>fzC7q%`aIZRRiNTrcnVk7JM(dQq)(y7r%r}HKE#^B zU%9_CI}*vcwLpvC=p3m?StEZZsl^qCMFN>m)hd0p(woFONE)5oP7~3tOP#OR$rhn+ zjcnyYnR3&@J@I~@UXzmr*A%*=DPpQ-tQXD_lV4`Bkjg^yG`BfU4D#K%w=2DEbdC2S z0c$tVPB!ROSNR_{kylAZYm6Xnb>c5OKUg3;ayGE+c6!5kZ$ra~S8t?5RbOFuimCi2 z^x& z3e23LN5Yid__C{?+X(ndByiKs->*C}!iTu1;yU-mmCu^zE_d5fd-^b)xw0jU*_-y_ z9ye#Lf-Tpq_af5+AABmauMmcIiW_wV@@Il1`|?lZMA?;NalHEBFv?-Z9-pZR_q;PW z&@>UvIQ6BQUeJMlr5a69={Ju7ldOF5rD1cBRQ}huI9dYi`_P8);=U%ElU_HaFN4INsqf z+gsO|c&6x$6uUWo=lB=Co&y6q!9PJ=%8R_K5v}49(hvU?Dj5`NWDfw0NLBFC|mr-cH@G(G#b}Ky-E3{5Q8yc2LskYtLPZ=r+nOM>|BDeFYjDOZ z#$nrziO7%Vgg(!?Yh5wEYB6SxJ_+>7lfUb47mYM5O1kgW91g9>@?fESaiK*vTuxez z)paj)bO@`G`CT7NcAkkw#r25_!`)Iy=NCx_t~2N=acf;WvO^~Qg4;(wc=q4^JpEyv z4HL5YhA~2g@n8E1D?$cMTuYDXpA#`_i@WO2m9`@Xef;zfI_|9LT?g3oYd%@w18j<*^RY*t&>$YO9e{ z#b{h~M`vZn<&>@S|B{q^fsafg2}0vy_}j*!(kUxpKT33IprzPGC&>Ov|foSM|g zTW-|d9fzmQY)j8hEB$vKx*%}ioA}~jRZ>r>lHUTI{Kk)*X56<_1~9n_%R6;S}V`yW6{5|LV@%ot>XL6XBb3|2XPb7P$ zHnLKSH&*~!{Ea_b(FJJED$lof=FWF+mp&QL@%|&KV;xytSvnZZ{|+)H%NhR-{)xZM ziy~X#t;}hJ%jD_5s`-Eg*P3A-51pi=d& zU2Q$twFt4Fh~~K(&P7TwvOKw+7)=x)0BuXV+z`-t#wLBH&J$P9&Xn+fL`t6)nE4C` z2$v^lTUo}ObuLOxEttem>aK%nLRlhM(}aH*QDVbCLdivD>T*tfmjko+^Zn&+gCZm= zqCx-Mii@+`6o~WaN;y8N@yzsk58E zbolnWt-ZG{0{G{3MB9!4ibCbg%i$-abq={Bcwsm^>%oLcG^ZJM+K$0|_)xaR?|}2?}7r$9f?KOp&2HBsD0w>+KDd znNPb|VYu>x4n#kDw62d%{7=ZrNNWEf-psh|eEH4UkOR-=MCaaM!wt^q>4O@3a^lHN zdvu*9(yN_|Mii8xD6&Oy;lEk^XS(;lUO$Rr;3M|h4knh}i99p~JI{fVJ+^b?t=D)f zKhFm0zQqHM>(qQL{CONj?02hVj|L9zO8V?aPmG}iFXV|rWlhndEyzN>E=eaFqu}Iv z{5UHJqkm4^#GKD`{)onQ5!*z2VNJBJ3U96INm$*0UNd-ZXUqg4t zpx)$5Pe5upUg6|cT}RTHz0)c2?8YiXT4^2ac?^o$3HZkW>f0z9?4GVM|JtQHH}!2V z;IaeO{Bg3VL&8(|-#y?9@~Z0HA1StlSE}ZJ>&jKLHK9Tvcz)uI+VqE>2aWiTzkl>> znfSQzaT89KE5ULY4Xyu6k{Ij98jW(TL8F_MD`y^;K>CWp%};;kHVPmMADDRaz|q*0 zHA$;WSNOPje5j>)yo0ez-6*DPeDS@A^i^&ah%EsQilezj5^HyT$y>58p~?055UY8nYRF* zSUoEVCg_PRxa}Y13S%ia-Wcnk8 zrlX8UP&PY8k<<%ya=&pV95Bv{aiISO&PFCRh>(`5cZi-GR-`|E{20ZQ0l+pQAWdYj zfxyKAtXEoJ1C;PP+-dHqr@@^G$2sCbERpehwbbzYw!8K0j*1K3loEI{@1Q~^>Ogm>P zT>kcmRq1@(gZ_y!Ng?lcc3oL|YFg==)(rj%fDQ-Zv8FJP#Bwwac~Zj@sxqKygS|{q z{Jb$f3ZU_hLaBmwwy-(pP=pMV_d z^RKVueC<)smtWjTf&O+eM|r3|l`w0M-HPy>RgD zB8oYFb-rZqf%Hk2SR8p9VJG$NX*QP{DVy=2UX5O3%V9j^+amn49#c(E;^#**yUT|R zEc{ds&mE*%~jPojBV`{ulQLWRGCNb@{9QjZ{x zmQ3;k&{}HHDB!AKzj`h{V?*k*E!5k+PuW7S903sWB$cURz6p+CITSatpH-x+_Ozq$ zN~&>pmQKpH(R2xQjmUGtZ|0=dzKjH)vEk|rb-tiI?v%fE+T;BRSJT7XS*Yj6#xklr@b%_oGgM4U$1VrCC6<-9W=s@dlT;Pb zFN$3qS6urt^2?BHn1Fw>wzw0|z6xb8cJV=+ncAWNE>PuYS0!Z5w_e-;TmY=t?GYO5 z`gCd5Xre2d!4PK{jr2p+J43$h7QX0z0L%?@@{Ns+z(pK-g6ttv*)ASG@vgQofD5@w z>8YuQVax5P0*HTR>K4+|nmY;+MS%d40WT-lgQ3!IIMti|_2WYYY;{^@&zHI9i~FeM zHV$^tRD)WB14KEJ=dIMv^|2oX|F)(ulz*VSLdhdtQBe^Rb3D374HC~Nwzs!CIXhGN zhZkTtV^YG-ym3)QG{XyqpAP1xHR|Y-q+UB8dDh$;I|V$K<3kaKnEx-GoiVP#K|w+L_V3SgY1b`gefb{yY=h88WkkBM) zpgw;MZhgxX3)Tx2O+8_+>=!1w(eyh7NGjCtDdbrCkEg=;)#sXXnYSUssL%|dwS^(g z&IJWW49t^ySy8t2Z*HF47N)artK>&vy)=qWn6LJgp`yDm=H~W-Lg4H5VG}L^t{Fww zq(=Jb*`GUk6qZw8wI6Pw0~}V}SHmxQ7nlXDt9P`<{^hNu6)4Qt%3PqCnHk8gC2ByD zPym3d78Z$D^;HgwSo+@3SDnniX6Vf%U7Ce_u%duq;ET~gp#W`M7=Wg-m0glLjNx5B zxu{)jN1PQVGvs6-0DMg8Ij#^jnSiNM1unJjA6cnaEW67ON-Hbbf#p-u?Q`~A=CYA; zdlN}+f~G51^vbW+89SKCY>SY@X^;#|xIbSb;)SHJ0lLoO!A`D3s}dF2tO|z2=a$D> z9wP}U-=n&bm>fBMVVnq7ndIQ~)q8&PNPK3ot(|#tRmxkh(`zmr(cj>c(}oJyM_i zCsNV6Y7FQQdJ#2zTk)B`Z;g5-^pbYi@zL^fALoV9yQIlRRTem0K?#uN-9_+oJwM&f zRq&g+uiyWVG0Qg@5%;v`D5!q3D6XubShw!eL(uX~+)t29MMPy_zB~o_K`8!Kl%-Qr zmPJ`%9}CJ|!TPB;cA?wL0P8BL0)h#9LTta}gQ=JB9~ldhY^QquQQ?Z>ibQ zh_|wf^Z0NhgdWgI74y^Ou62K7{IcNqJ=R)D#Rlo!FI?9S#!6uXK3@a+S1iS$UOZ=o z#0!9`0@ugA7syZnrAM9l=n9KyKjEZ}jCm7DvfY)HT@5F+B@5=!(Dt&qx!lKo9^?=; zl7}Z;*S<+l>T@&J!~UGHPtbX3$U_GSqCxq{+YR=HQq74P!0wBOI)L+hx!JDn*@c|E z&W;=`N$nNFG41D!Dzmb%K^YUC0QFp4-wB9q&&!yVWfQD%f4)f6xf)BLjZAOhMZ0ft zI4IL@KyhcBl`E2a;7Eq~|JB~0DuE)GKeCWB@rz=&lv-vT5 z-!^dnYxKkNG}8A^g!io$3nVXsH>9)xU=tt_Ka32J$R}NU@=qx#p~X~1A*TlL8uCCK z%d{v{$}rAp0^r7HXkv`8+O(z;JZa1Z%xf~R06wzE6Rn-cSc_?UAvXTjFmH>p<5U-qblSS?6$puB?L1Q{&#^xvgB!T@zSvAkEgidzJKe}X-uvJ7? z7yUghnRVaN-b{2=r&j6~UbFi;`liWh2ZWHsYPc+7@1A_6A=;MnZ2aQ|(Mv@NW`$mZ zH#Ktxoev!8p%9+7=`mOAW60ns?VrNG* zFP*!7MB~5YPkm0FtfmoIbp&#EZ_$|QeSu`0qmyp%yW%s8Ihl1$5qIT~sw7pLKxf*? z!fQYHo`3l_ux!0mMq#>8A=4z^@pACYL#tsl)zpTK!vS2R2OyE7N<2FqznuQ1y?t`V zh6u@@C|c->Von~+P;>F5EmilmzB{wEs36#uczR3=Fe){%t*z04^pbDAWiL&^?lM5x zku5i}x{L3gLYc^!hx>sL-vAhs`y$2}85y1}XGKPqhQcWcDxSH(7JQOO01Ds%d6u?l z{^Zo<{KCS8?f(n>&9483fr6=-S$(A-;wAF2ut`qF*+$Do{JF2r^KYTMqkl%!-=~cZ zr#2dzypwgh)fe<`k+_>C_b+6uB5kK@{d7oYrN-OrXDvaII$9TAv&R1i9S#U@=^%!d z-uIxHs>0Fgg$zi)ws_jJ>W3oCg%SW#8{KZT^dG2x9GyFP<-bsgGe19nVj&Q+^!eji z811k_#)LxLOrDUX-M-z{Kg)|HgJ{dI5n%Qv&-#l~9A-JuDPw^lgK#j7S!9d)43Ey) zZ~6Hp5b$DcTr)2>qNSa0@0fG}yG|^sGGKWRiDH5S(QeCU9%CCyGBM6|wWfx0pel*Q-dbT|_WBtU)14q` z={HFNK~~)&$ou5ql&O9s73+F37i(y#oTj9(^KX5<0%cu+QYEXQwX4p*6ZcjxTUc0( z??(OxUp#^54B`-~?#vOUw*b0{7}{ zYtEvaL$5nILE@12>Xm-n`JER%tY19*N&PR1@>pYKa4pMkFiJ$KVk>OC$}oY81}=>x zYD>hvk-Bf0>@cIa6G`q3tQ0_=#Z#2KBL0J7U*Xs<7x4wUIM;Q zwxb&WRNN@I`TeyofjqtLV+jaueHOG089V8tBuV0i4!_49Q7yu$VP{n%|Bxaf(+qab zaFbugY{TqhKfC%cjEWhgrdxU5vD9^N!#v|IS>e;9y2E*x)q`XEemyUpVc_b$FLa@P z&i$U}+|uu_o#|p+2)wZ$glHh&Dn$9aDRk~PFbL$Js15)H`?l{c6M*M)0rT?F0hQcc z%2X6Xs2;KeaRD^ZEd%O}dja&d8wVj3FS2CW?AnNQZdNhC*X)MO=)UG2S=HJ5Ntj3~ z(e(1Tq14ODv@@u=Z@H&0h7j=zYoWI3?g6~J>Jzw zVYA^(l|j-PSldr%i-0|<@1nEWF+A&IEo)krAyskVE5v)Aq!-tGnH=n>6c8#w&5r|DI=7b@vT<|CA=f5Hzx9_L~!3kPJd{wX$852~yDNVGoyVAOW~ z0*I7b_Yk>99MGvN#Pqf~t;X`V3s4woO5HuGGrTfafOw%sH0{x!Fa-FCc1|5s^ZX z1#f350kvOxVgjU4TZL=t1#BK}xwDf)E?W80KKv)dU{$!^*6{uCU%*+s^a3P{^)_}4 zm0oTDhn^&2sfAgQO5L~ssm|lq-zHC}PB@_{I29ivLLWA&uI?uj1R)}X@XN|bn>4GR zJ4ptkc-EX$z{o+o`+1FkZ%==y#IR(R$!Msb*I7Vhog^0J=Xv%%Ndo}WE&UyQC5=427{oBa(R$Z!cb65qRN?8N5Vy)36uQ(bL6r37jpcM0W_nTI1?YBnl^~M^46M?uDN*hprD}TMf7m> zh3nnFRH1*B(E+ODXuUZyc4c(6+(x1w=jg$8CI5Y_dO{F-jqs+<);sj@DsUx2xBhO# zo6n6t5^MGDA4WAKek0HzPT3k1gs=B~D1ekf)rp@-0-To@eLqb@3U@pJSG3v11yR%& z^8ytN;=e2$^N~Zw{>X6Q{guME6Q?Ry@R>?z{CeAy?`Io{mw?ai~@C&DTVk$^~@47&>YP7sK^FZ8N}BG?$>&V+*0^EtLhHyUOLOyJ- z!YsFh_o(9+%lZ?0Oi6P{vz9tff*ftQviRJ(1dmTFN!9MkS={=r zLswxQ?OUocWUjyc4K?DGQOcoWkv`NUl61}I(ExG~tQu`e+*9>2a&j)Th{L+GfNP(r zr7ECVq{Itb<#oB|J)i=D-B=RS@5M`2_yL8ZNrCk@cK7`_!~7WLX(<#Ot_{XNg(`I8 zuUyZd8Z%gndnf&Lb#=3g2OoSG4VrYes&4|>DL^Bbvy|Y~s&l_lkZ|0go4LTV*&iRHF(^ue%b0l>lL=TbYAEOifJmDyn4tJC+$kp4Eu6C2*w4}1DlFdn!USaiM=r)T zPbr}A7OYgcpx0WS5yL2w6yMs)=$KsIng%sd6F|rJ1O5Gql@-ZK0c;Xafl(FpQSqUG z5-1!rrnM3!jP!lTt&N;;7#|;7gh<2t*@DPfCnwkX!#pMBq9zN=cVd-6Qzzo&U-FJq zb{=Sba!1HJu^f;t*4r~H?^F?_D-i`XhZ2@IQTxA3Uul7i0+>JfGB|)68GyZ^j1mSF zSaU9Xupkoz1U=yL7Oga(U}@&J-){-vaG4jJot*)Iq#X53OlmBS$l+B4x9;cyyZD$= zG}n!%ksYk*(ZIf+{S$I_`HO*+88@iy#zBv|FD<~Rt1P(M-@UPLXweA4F+iKY{uIS( zMSTuvRRbtKL<24gS{N607qH5Qp~6cO zlo?w%g9DF=3Yf%LLlV5=K6==hZ-1k>P~8k5r%DhmmhN^TTm4`Ooy4@N0r604-^0G` z$Sl_EYXQe)|fh8-5J{#xMNX^(=}0=6QmY6KA%QCM^obG@bivA!ZyUqpfZ z*r+FD$`b`1+9G291T8}$ndo%|UGYbIPy8GFFsPOe80)B{&YahK-^qcRBYs{q+zt8) zcf0wv3`z#6<8K8tB`T{()4l9Du^kt_drx3{ zKlXjL$``nnTu`8hB2TfvTUOMfee4?w+8?2o@vrGifz$US8qhiy7eM3`@?4P&rNxr$ z$Apl*cZow4?BPY_(a3)MslM6(gOwG`YN29DV7F-cDnCY_r6CssR*r7QkH9 zP|IUV_?5o^?fN6ALWZ=NFx)V}$DO63C`Bk*j(Naj!PzoI-sM1V#DuAG{<->C+Xc2A z;1bSYKUK-+vbD9aGQ}?F%D*ZrI?#X<@9KNINE$EMKKo|-sM5shk2R3L zlCQXoAQV2J=zQlImYf)&SoeP(`jZ4V`T);1k`8F;s9W9K2`Xkv(wHP9L zklApIVt}%Zya*MqgBl^NeSL|Cz!7-`h-@^t$Rsn2vg#fJOEY(`-hFT1PQj`_4F|Ul zZ0|okw-wpZ+E1Iku0>Pz{t(OQ8PR2hiOB3z#Lu94@@s9!eYi}6C~OXD-vhmDf6%iu zSUw_nn2(^o<&^NBkdL~|nc?jHk)fo-iAuaeFI;F^y>Nl#Idu7AK$8 z(2Wcn^TCPLOXA<2SaeZ|)m!mzr5a;K0v6_@Vkla#r8-Y@3So`NUnd1tWIS4kLZAeD@X3=rhWG2#eOIPN0!izHe6dhtfd#LUylo zEGI@SVDKMP<2p_(%;c!nhLba!+~GDwRj!9;L67qMw{rc}RpdVjOmh^;`PC@tz&^k@WKJf& zI#)r;`G;VRP#T1);0=R({GUaNHR?JW&XzHIx znS*pk*ViK$^V2!GXisZxx?u+z07i7=rQ8c}YxwW5A5-6wW2Td3v~Ur5bf&B1a32mhi8Qk$;!4TY$IHz3o7TR zP7d{(%Cb`*j*bX+W;P5joJgPVTOT>B)$1Q)7hK`K-u@UbaMYgu!iK%F;`1xhveLzV zRL>PN!kTf-GV!SSWS;A28r_g^owLCiss?~FAc$Ja9RV7m=6YF?j#yt?{-#cC>$H-i zt$yqzCYdA-J;ePu6NFpEX^<;D(C^K>7&fuLOW~>zLEtF8P;cd-a!kVnknr!LBmAod zU6T0ZnyjNFk zgw1_6Ge#p$FjX#>uRQQ{5ZV0jE$2COQ2VA{;Ln3FQ0&kL>8g2O`mHD(g4(R+?5P7P z-MG4(ev|i;qWIoglGA#dzZ%5Zx{a@(SL*5SB7`|doX*$akN>B9`;EMhgD zWNiy07B1@Vr9Q{_Hu}L4PoGTuJ~u>DbZZr?|5!(Wn%_j|y#SxtI2~$NE?pq`HBjWh zfqKSloSAY`$0G5BlR1~Z|9HdM?PzvEwg%3bjKuf@T9B=y{pzAdoyB_$@SE zYCkVbqAg-vY)G8v-y0h(6Q^>5VsT0q>px}UBtbPL^YcykVTm$;3P z#!B4g<6uSkt8UqOkA6m`(2sXcMWcjIzVv|llfadahQ>szbP)tyNU-xX0Vig? z?V}iEqD!IGPaY045UyZ-3m4`6H2p}tr#*3~Vl`^M-)r0?iVwHLe}hoNy2?O%dCQI- zUV8CD@eEz^sz{WIFamBUSuGB(iQ?Xux;@wNoc89`o9Wqyt|g)EW@jnT(+c_5?IARQ zVMO)>SBm>inIC$kZJ2#aoTjE2HQt+jK<1+78nX16nRI)AG*Wy$H# z0zF$#q)fyid!M>>7t4i)FYaLyF?f%eBkQlgVe=?JB`APnQq9GTt7=TsxkC<-cE*wg zrfdZP`G05i(+ta1vTR&N4O};0?C+gBq>US-dN$2iW9?y~(X9hI5T86i7Vm0_@~<$*e*5nU_8j#%Io1fjUKj>C zN7PKrzK=o-DESF7@)EfnSlJCm^V7%@yP-<8;yl%r0R4nnM)-t^`Gkd>h5I=ge*S^X z^Onn*Xyn>jJ0&b=%^#%e{;ow_lg_PzTTMSzy#-=U>E}3J^tfTPWp-t0`T}3;Wy~hZ%Pt3U)WK;GClRrH{OR5!}WI07Nzi~(*4!hJle@(2jElZ?gtbe$jm3*ni{^a^8GnPlf|b} z&)W|6>-h93uRl4jS}Nrn?(9q+6cyV{($)u&9-x6)a*zb-`)Dhp$XFSv^r#kfa-QEP zf{j!SEFJq_bT_^*$SFLvVh6LHh_JY`;eu7uS93b0D+HFjMUqTR)+700IF7+vtH71X z>aNfj?^Z8%NSD$ zDwaH>rNwMFjWEm+^#@h=g=G$1VyZuiR2JkZ-rJox85$<^TG`#)%#@hR$ZEe8hbd66 zx7VwSKdvqJ$ay}idHTlEfV+s-pJKa|jE;~Z8_X=Sw`qR#l2DDaTBR1S zzlJaFcIGlxvd`0(PE`AEybj@3EokWJ-e;=Z+=->dv!uB40p+@R#4(mu$t`E(;dYDh zh$>lqOB?dkY1dwK-yf-|2SnmImr7{QaYu{;lg)(*A6WUDj*MnN& z`_rsqG%k3rA9o}il!OugnBGg-TQooR<@-3#jMk|{K2+YI7{o9>FU&pA^{kgm_NdVD zj1Z+iV+b@~vZ&P`EquK45NF)v4bt-Wc6*tB$`97#c)yKfOtOoXW?vaecM2xI5bwG? z9kL{O{e;7n!xrBkM+iyPeB!QBiaW9x^uooH-EJ3vocgjn8Tvq(5_{@6SU5yBQE@df zL2IDm!`FFHuV}{E%HB6}8<4%pahd%shUM&U4@Xl+3w?ilec;p@PYw$u8D_V)Mw_on z>gYO`96^Kt!?gEAp(3{2_K%hgI$Wi|R|3w3?9z_V!yIkfr+UJ#Q8FUW$~0|T)!W;^ zjfE%G%riT$=yE3>i=d?BrrwXv2o5P({2e@fwu0EZf+Me5>HE-PyddRx^`0}FvFH;z z)Fs=RZn84jFraP)!Am9n6-3u<;iGrN`nrS1#*UFHnbUtIjO`yL$q@&8{Sw(Z zIp$Hid-SB&P#gK(?fs{qHLQZ~cn>jf#yFz(m)?by2bhb;R}Hk7Nb_xB=C>woZm<@2 ztSko>umpqggEWO7p*@2{dPJM#8`eTfHue$ z+p&6uy{2inh59-##PM%crAf+ujJxwYYEaS`s)Ksk>q%`AH1|GO)7u8zdCTb|HKevZ zl5H{1oCKQXRdY41vkpIW@Y|{62MvNpRYZvbpySnJA_l+ z5aK%-6YfJhQ{>dOD9HK!cDF>dv%}P6LxZ(G$|oaVUwlG*2Q!CbFfsW{24V#Jw=Z7q zC(!krC}lZnWf5qO+*;H8IamtV*j{n}kkg1Iw{FJi z%q|6f%W^*H*;+j4`u$CWaAjS*J4F7fE{GpJ%+yUgeqq%7Ny58wP8{-gFL7#!O*Ip* zU!|7Kc2yGRK&FX^3|eIu@lF+=JJF2#0ZtH-j z<InZGqPjBbT#ha*ig_??LULu@wHq`c&&zQZPQPBVp11RvA4S`#i0*;?VnySgpP z%l@B})~vSvF;Up)mjd!t=jX&pA8hEi$UZ*tbu9lVcmTmQ zT-;HCoO?A-EqkyKJpR(JWU4jq!6xZ(U)CCVJ5M3r3F3Ww8r zi(h?aMZ&MV_%{>Ibi{tk{L{?Ro3E+(AMAvXW`kaYYZ;aXQ!D?;ozf*YtwdyJX<>a5 zPJpH6Y~tADn&`$U!!+GFDEZJ^gfjNIt|T!WuU=u}65Tk}@Gz#a0nD(~w2gxzpTJ-3 z_HkNN;J9(b<9=ysq9bf&!rTF7qa1!Py0@&LVY1S|Yt_zSB#UBot$h3XhJxUoz`yV9 zpomv4h1s?())#^36!I8|i50J`Oqwsol|)L9Z|DR&9M)_%&9B_pR_%}Qk*_`?d##I$ zo$KFohL$a&=3^*v*ER_{*2R1t^v0dn*j@m7ySz&;a9X=bh4g}SPfqM+I`NTD2QSe; zq*+kSVBi`uvxTY%y|ZJLbva)VFH1h_%quEgSR#|>@-i5L)0yfZX3zV3uhvIj%sKueCo$8eqWa$m&;;8v0^l|E?7NII8$=}b?eJbHX&yVdv4*s#GE1Y`Ks*D(z zMU>Ct4?VQHQnlcbD{YV}~*FG^O|FNv663jFd=S{~|mLD&2?X`Nf z2)6D~S&Er&9UY8^b}f&>9=SRno83?x2v3{%pUiRSud2lN3=YpO8iRJa)o$f|irexFXAXkASnwmf2=1s!i4ibh{#XoRFE^?nd-HKY3r#PF`VX0?6y-T?mSWNoqDQQ7#7*l;%gL{>Ha1xYC;;!nloYOd; z&15o3VlAk^j0!eDJS6>sIc@Tei_%nRQQ8Fzj1c0%8_4vddb1gesO&-x&0WuAdt zP%3`iq^_STE99Gv9Zza62ysLqyCK17-d`OxYc7$wSA!?B8@D~EpxB*qpj6#p7SN1t*uw2H=m1^PyBPi_>63;+GT%8aY&x|1f`w5Y?fPwXN z!aU|cSL_!Ch8;)`5@cMAz07q%)Ut~(?7^Dox@GB6K8;+T=`%h(*wK5h|9s^PmHfUo zg!T;-qrY22?iI|_r`AHYOp!`>*qn`xb#|RTgHB#{=WWb_EoAh zV}lq!GFqdK@^=sPCIpU$I2zkjAwM2#S-D-l&IRLpsz|L=4lH8&oh`Il z3@OOLs%7yaSXHgc0-b0xch8Dq(h3|meJP251Bi(g!ZBFOrL@wAnIT$#?X0@XP@-g{EUZG6->kn6>SpGF@Lh>9v^6Ci6YA z_q3ojbR`))jfuqK|2D^t=6c8?L|c?*HAZ>%aW@G9=J}^kiM>jGIwd?x4D2yb^C|#Q zb6X9Y6kdTvp^VR>3}Bvd(eR!Fm_m@%$C4Hu7Gl&1dUHyw{9U#!w3<5h&hT6)N^OY-AQ);D)xAhmIO1|M*WBqUO7IwIStciVpgU=Os%#~%-HUEvt|yZGS6`(QK6t*Spu5xar6cY?&gv2+ z#c~Bb2AKF$PXEa+zUkMph)!g!UE@Ou+(1F8M6BR5`u(~*7QopC-YYN{^8L~4PM{7Q-XVAF-tWe7is{bF()NLX5;zY z=(QrWym>&y%atF8>o99UI8w-*p5e5G^g%Ur?=RAuTx*veud@vTw{rNML=@w3QiS=; zo#DYEz^Ah&1TTHAoLewfZcS8vkCNQ=X8j7)9SALsiy_1RyI7SJ(1KO>8&D0taMIcC zwD#>KIb(W4Kx9%q-DHj!N67-OEchnSfs*GD{yBZUj zg*&7=rKf*D-=|moZB3UBIn%H`LD>3Nu&~Jl2utL=LIX99#~B**zq`N(E?DdA8eblG z-c1XQl;fq_GA6Yc4S4<5!96;JR;7ut>{qHz=4Kl69g5xlyvcDTScLCwFW=jeY~t-| zpy6)k!D((bbI`zz2@x(&_+qW5Xo2#mvtTMaiMABLEc}V2jj1-IH#Mzfn?BvrCTYu9 ztzJi;LO+INenHEIb(md<(k#ljB-sS7T^il6>e>9GU z=Q|T|QyqF|4{&cJUvCyTQ-PhB>Fj(?5R51 z;#scTZ%WGW#ifE^{Nvl_wg_5-a(iTT6&zAho%>Z!sL)47{E?JTAz~IPEmW)WvO1xv zACDs`e42SGvNrh1fv#)WxUc&oXKL&b!Gd6ISQ`(uBYHg3UvIWX?vRaY-5e~clp9jH zFsQKEiny1!W@t!$0!*W`^bV$Iz>i$4gJJiJN=F<9FlM6|3~-DV;27I*J|eD_UsW7N z*}CZ>n`ArrK$LoF=AC|f0vzVn6!WFD;dY6PQ8gsxOHGBk3XN)&$rsiS=4dE`-oBX( zer@E>t-5JtE4KlHm@wNkcY)%{ZW1hGRjU?_-bw81_8#jx*55|8lDJ)Dq-)A`9Wc|) zweI<^OuYIrtRL-zd1+VUhAkgSd5p58QxD(oAUGshaStGRZx~%<)JQvGCEjzje03g2 zl9wL!+Ox@YDSvWp27AYl;*RGD?_NI7Lr%qkZI{#IFx9XqK{G2yV4*!mjAJ2>euB^lQSpO4p-{Tj31qm^4%vbE~_ zW8nJX$CNz!H9-6VY9FV`fEM9kv%2tYYZcg&Hb0rbx7wY%D_bOquS_$~@w99`QDH6& zjNwJBv98bgF6$k};hd}N(MNVxwih^aGlCHenF7F`*_JpFqP$f2?bN++Z|E$6iJjr$IO}J-^~J z`cz&0Y&=|twA56i%@WZV-yZa_1uiCU;vrtOgtN-S1mMI|9W44E^VAjMbWW0Og~=EH zdFUTMi3j4uUFL#-(=k-YTQiPcKO8Fx5xjF z`O$~}{NMllPvIe#xPRozMFx#>S1;?fkNx*hr+0r|xg~w6ws&zc7_Tui+)(m4ZZYs7 zbxU$mDf>PB7eLzFfB8FLA39AzgP<%_8RZg2gqhv+8p`=FQgN3Bviw5KqR($&T=71= z$h?!(+i8jWYjiEX?Gkh@w*7F zZ`~HTB`-1*+q+7!%snltR0v`G%P-hsjO~;I%7M3c^4U8&Dzt66gvuW@Ycq%0A?XOK zAaxzPMGSu6HRKSN-T0adXsDIre-@rn`XaJkZxDT{s)}DIqQL0&p`yS;e#5E(pvz7V zE`UpDkBs!f)`1{x;l?dFaX(5Dpf3r=I6Hyn-yyyP5-;zFPR392Ra4iSFPjVaCPlwz zF9+D$_fEh6UX=-bL;fuvEA!Skn@!FVnG6a8US^qJ>S^Y-+@5FB{7%ClhXyqSXH}WT zQslbFW{bDZSy<%qVn@qorVGuNo;!&ubz$D2Us`LI4qy@?5~tv;oyBY$Nq1^>mgb;X za402xDrl!BW*WPwo=91(O)(+aX}>7Jd)NKp$GE&wxisJPRnN(7mLm22I|%aZqrsb> z5Y2+gu4oRG8sWf{J%Sy)p%WAYprS!tMfiCaZs(%-vBN8d+a5IzpJ+_A-MFp5;&+03cbMiS09sf$T+x+}hbc=5Fbi}Dm;~zAtLDBnB zfw@1FF~z5-Wm2iO2Ky9G9gN?vyIx2H9VG$tzo>ie%{ZAFDHi{*-Z|iG>nPY{BpS?& zOnn04H;AL!-m z-H{&E`>C51KTSQzmW1;#p(C)=S9GM&=0X3KWZ~D>q}X2%*0V@hyjnPhv`zUnkGNW^ zL?^g^^zje+)Le5hsX1bo@V=yv3t}amp6DpnnzaGsO|5;-w?UwqDbO71g)^Rgx?iF$ zOIS`?hIKbG&8|awQCeohyoWq6vSNTK(7Nh+f#YJ6@VW@o?PNLb?9m5DB=k%@maYc~WtI+aRS+w1SgsA=un|3C-^ zwcZGK`CXcHsK*3OLbbS7^%YL+Yjihjdn+6bzs60v9{gn;Mj3sD@Uor1lVdT3ZWk;4 z7Kkx$UtmEd1)I0YUM~d1`URsc*6SaKzx**M^r_~*O3NUnF-nH*H_JIlp7jez0<@GJ z)^aXg5xe&n?jZ&=2-ti_YervQTZt-~fAAkCS3cNw_ull}O}HcA!Y6;?#gyst!2YNA z=^NI2%@*_qSYutxpK_>Xk@LC_8(keQoVy6s7m|fdid}-f#!0A74nY3+?oCt^Ih&C) z44Sp^5%(Pt;_^MSe1 z?|>~=5j~?-ME}8Boz#qki3N1v2@+4Qg@*1Eg=Fcc+Sedpu%4$3=`dEbZ8S4%Lmq9G& z18vWC#;Bk?!@F`O?R*b58WQTyD$tu6Q?Rqki4&dK#Ckc7n!`SlzT{aV5$NP9pe!i} zRfs^+yJq%XUEm2gX**o^oLx%X!ongL+LLdUS)GC^Um?^oHY6m(bgdkVO6kbpY0tU| zj7Mv80}}+reUiQm44(?#nJH97)QcaQpSOEA_|wYEW}2{KZWkOJ91u}Pb+8aOO1?+U zO>OP%7nXvdu>Cd^hH64b-@xOVzEo%v>^faIG&DpbT0q5fs9OIJRRYdTqFn`4y-G={XOoli_XvYeOR^77sNGw#-;N~!@n&> z(Y!}7pW2Gkvw%{{+~TF>u>XhGtECiLuZXa9O1*)F!6*>vTQ_opN`B5D^&`zb9Hpd^=&N_~G zq1au*Px)##fFnMSqU7-U2z}@8Eidj%!1RqMb6_Rmv?gDJ@~bP zjWsNL5)%J;Fe+p+S0^*&e0FPxv7>jFrCP1qp!?p2VHV!+69#rl2CTJP%fZKNzUj5% zys?q)&fa1}uTF`Il4gY9WvVoamzz=D3nB;L$Lk}eIz%T_w%2%9s&xt~{0az>vFa;T znO$dU1P*43G3><`l=lNoLA_fZD^;`9x}86$N%saU=nX30 zUyYuLSS;Z7pb$MGKrgMcWe6P|A*ia0W2LR!8c}HgsRC)*6$}Ytm0Zure7ouWRhK;b z6x$vrVzcvlT+!=%38$NXrp-*hwK1IG2pZP}Z}PtT=>1p?Vv1!*sD(rxV^vta_?r)O z2;lHDU{8|%3XEdaoIyIisCHjqB!-~77gz+6L9N2>ef-0Tu+kHhoGjz63VeB0Gl)Sg za&6pr(U~7}tL~SPpIo{PyO2wyaM_j;S*ql8y1nmHgP;Zw@-T<~_iecfe32imF+6b#}F-eyEXE1 z{b)dgzV8Ms^CgyHj(tz_CDWn)ipTsn*&4~^2LnWC?CvxbT#*4SI)5Kt&#ql`ush(E z5W)7GHkXeHzsN51?Qhre0T={fkC2ffYyi%Z>Gl&HJQfVH>gqfdJ}DRPhN+w19jo#a zr7Eb9QdwcOj%(}R>Dd8WHK|s*fZo3vPT0`wybjlMyDP_PWO#Tfngm23xt^Wam7FA2 z-}5%UyM4IBc`3wsefM`unwCpCCua-Z{&QHgPBdwY2vw zli(k_@k@@Bxb~JZoP3-5`i0{6cZQi8%h-XrS3!xBv#ZCK7YEfle#f1$bKop4;3ty_ z+@aS3CC26>FYB%SV{MH2->F(icAZG(BsYXB8#QJnf3$uqEIiQAxXo#LEauO7v3rq$ z;4N}~+PFged18SrS-5{>?iCd=Z+iija^BGhsYlANhARiEK#n#Fu>Nf~hVCZo z0WDajShKtBwS7oFP{+A4k*yz)6_*TEe+Lx;k6)6LlS8#<$;ru^_lutbTWexrQ8Q5C zCj@j8S}A`_HP||E`?!h*&&J)JXdJ8+Uooq=Y02lXK{mj=vp(FTa3!u`rn3_{CEu^! zcPiM1i>SgZ^ln~Uxe%09y8=Z(LdI2c(M&+f0JjYJ(qt|%!q(Pyd}bBwpY^~?xuG@# zpBh9?s!=$qzBWqT78QB@6gRmdpkn56Riv=3Vgn@>j<(8M;#4(U8VEI%Zw>_t#(C8jt?b3pYx} zMn@~TrKg{=;}Po<5KhK5TyQ%J^9m%o%7#FAlnb@RY4#RQ4|m{XOy_+EBuL6d&MJ0Q z#WnrD{n9G%4D}B;+Ls&BV!b#54|;9+^%;OhY$Fc5P%oW;oXuVPOam&zkC_3U4OLwFYlR6 zC9$=yuKY4}AaW(R1t2seHYf;8Oe+FW24aKNFo`ZQgFf_P{m+GFMwC7BS`x6e_N>|g zV~Ehgj{>xB0!!qNZ;KF=t@HngK4H7k#nUXs7NiqjfGEZ zZlgYFd>rx3$VV!Z8ry-IUVqV{&!O3lba8A(;^cg=rQuYTuzF;%`Ns;U@u=d94sNP5 zy-b%P-Y;*(47GCN6Eem{IZhu{#;+Jg@LT*QHC?a{e12nK2QrTk#c*j(J&<@acSSVvOkVx=Mw86zS?7(K4W33Q2Kl%;-~wwsR!>&|YgLEa41mjW}- zNnoP+0%Qg0;LRlJ6^biMPM-rJ=*U5$4AqJG`1L7Ygvr;cgNui+z7$3WsxDacQ2=9j!Izu zuT?Jb6wlB1^N#tR+9e*%A5ajJ>FZZ!QSoTYU^jnt#Q)a-BWxWUTAkNprqCs7&kJ`b zC>{`sBrEzD1G&^pW{Mk(j!(TKUJ?jBJZhy^#>0UAQta#BObu;qOLBM-V0J5gvIE5i zs5%@m9bEDSF1EoCv*Zdd(H=xpHEumbpso>!@1wmdI|-D9j}*3&l9NXL22Sk_tU^YO z97R(37rRZqct1LL$yZ+2O+0j=BIM>qqxz-BG^eSh1|oynSq%s4MMk^e{CMdq5zcUl z(FLBA*U4#(X7iWIwp?DYNFK!{!hnD-4802#~b0_N`9Vh5i zFXq4W3UHknPCk?N^WAXa;P5e2dhX`6ZqYP01pXVT2pV}Zm5kRgNw7vdY!KrtSIKan#MO64IYhNT_M1JkJ!BqM$7rsHf!j2_qT&lKNh5Guc=3w2@1;E zR+ru6V5zJ-SbXTNm zQ5`TzE6%L^1bDG1=oD3g`(V+T6$UKLxul{MXGu{AL%Xc2_}XDP5;8Oi_K4o`>qqFy z6BFtzxk$!)NQ-veI~$PI;nrX7qYQQ0BR0%@TKUK!>@s#D&00ZyZH*q9I;)k`yS8r2CS+S-I8sI5tWxkv0 zVkqBwNkQT4*W6u}2c#?kW9<(Ha==jHmY;UxhB8p0(ljbD8EBRrYWB$r)Pb4POgEZH zd)v|0_6iZ)0$ca{2BWo4Ph{y^| z)d`u+3<(f)9Vf#%TrS6Wv$o;w-9F=xZ8NPD0`^7`JS!&KE(rrMoGth#VrrI%Evavp zExs0~HgkWQ>y4m6!t(O6Ydu#J5b3Ju+dfa>q${Yd0+)Ym{VYsRAQY6a!?DHAhY#j91t z16?-wq>mTY8bQ^Ht2*6))u9&r%DH`^tw*xmGV+8TD_`tcD)!sf6PiK2q@tnGO~wkV zSG|#!tjHd)>`c)A>2^c`C%bI19gv$4IjGYd4o;ICl&>7t5Nd1OjHZ|^O?}NTkRk*1 zYFvYeY)a}>%Ud%uJ0pO|Qwk-?U(Qz4lN9#tOAum#!1&6UbxSoVuhi&IIi{c``F-~h zo5&R%Y3M;fn&|>{2nUvooK39r9w|;WX3nnE)N=NO+C#FW=~ADn$g6}`Y&L(+XxRAq z@m~sYF7jf#abRRLd7ysqGc#^+ztkyXwid1LeU{K9eMm<@a?~B9@-`#yf*>eDk(n|y z6i{!wbK^8P04}Z`z>((!gF^lpkHzmzU6tIGH8OKa6%|3;1~GvW8>4)*($av;(t#zg z^`zsKB1%LsIx65qPxyApwy!qv*QMw{oQ+5s?42ghax7m-&K(NjF+X(=SWFCqjP)G9 z0;sU(D4>na&#EeD!U3 zDFDuOEPbUv>cBjJ*tpJ;W@5n?gKq4gzD0|L0*GQKAZy?03*KzGRYHKg#DCUQke?oU_qk})$)IzvCJo^gzBKgQ=&JP^19sRjL_$7wgS%CGA&uA~18}Q5LU%4D|DsEFKu);;` z!pY24-5$S>0NxdBj=@aSqAJ{{=!%xRODKKlKgSFz8EFf|WCMxmwUsapE|Lzw#!U>= zzFPsrKj_|e1h>WcB}$G}KV;1@RK#=JlU4@|e5W@C0lqIIXgQKMespY^Km&@u&xo@h zf?Gf2v%60H6Xw1=(w<{w083jN7TkF^pAXQaga#vqP9XDX>0f!w;qDk9vd;AGO5p8@ z^!&x()Q#xmKqf89z%35CJ$=6?xTh{?nkx}D+NdPK2Y}?*bXS!=Wd?N+sC=?Resl8& zpx8j(fmDRpLYqNC#+EBKW`RfAYgl;zqqR5rCk>oyIg*SxIZu&t1ZzBe0)EX zBC$3%G_g}ns>*}@s!A2WJWuG)eXv#hC?Y=tZbJQcH95eri}058av^YFDgi6ic;|%+ z0SNABSKx%MX2vapW9{5*r}&L|0fYX2$)*6s^PKbk{riFDR&@sK^SmP>??X6gLq~_! zyPE635JMTqQ;tJVqjDQ!xPu<}jPV(}uh``4V$g0Fx#LpM{7jM(0Q2h)14UXD~xbSOtOHi$n4!6H7yM~Gbuh-}`G80HQoFi-T5 zp~GX@>%sBg>dIF~yW=z(7i;gd0A${X!bPE-VfdZ>;)dST#>#evsBP_8(Gncg$xo1^uK@VmY`tF^ zwe6-vVb7J6DaP;5hZYmzAUwPlT{(irVOAH0YQsDGbAgb3aG}!@51<-yjqd$ROjP>^ zci4-?V(J>=?H6)gnkuZ-O*gt+wDehE2s!v!;9ynFB9%aVTa)uTQ7rLlzFq=H5?DBO zi|5yFl()RK`8;XpCH0}L8(V%Q|IW9{7!L<*60TEGihCuF&sP@xe6c!iFtCLU;AmTe zijU89Ax9rXMoM7BdSLI7A02`ljsYOyAuf{lS3a|9wz;Ilz0OKaOgjBsgaZ_m}9MPC7* z&KTl*!&NJs)<_57J$fgpE}w^Zz|HS+*u)P=sLR-s@6F24yx~T#Lb^XrTtZ?Ns49p4 z*~oER(ghHsU?~@SCAj~`^!xkJ(K$K_Ow?z_HtXni2Xsvj&!UtFnCu^OFRM>G5FM65 zhcn0`RTkHAB)M^s2kkx+MNV->FYrpUMEP7#vo-)^kY6&p(C+rv;2&SdWaq)weP~78 z{)nY5mr7X?vIq&4e68=?tM4~C@tNo?b|B93D7wijLMj|azV_N8cIV^NFHRjA&9EF0 zk-VgGS8qc#ZgsDVI|#?jBfQ4D^Hd?awW`7Qe70nSvFxLtY}r73i44Zx8F&BA*Q5#uyn=mvw0ixRjNhqKEqA45pNhBKtreDW zJ(W(h-xcEW@z4H~ZfB~V>1TVh`99#zLI<#W8``c6AOCr~D0>70ZV0gm^`$O3nrcy` zC@Fr2jhfNj&`E61>R^8Q%_{GY=`wR2472eJWz6&^$aDN?H)g0wq3Wkma!2t=3CbN% z7&)n0;ol!G!x6Qq#iA!-kutXS&L7mHtn?S06DxcMo`LSEK*(I>KezhAn$ z=1kod$oah3BBkBkE<`yZHrzB?`}^?uq7_*u(Zp<&0sV6dHf%yON*M@V@wJQyH}AX> zN`4%!8k&n0mcXVPoNcRXLY_#X_c~5o0Zqi_SQI!e-gUG|D@+%eU3Aj4{=#Y|#2Uro zXik1)t5I3yKvzJHZDyNC2`9L}y2!yD0Un``xQ*Qo#w|Mju~~;P5RM4*<6cXbLsJwj z>7OrFmw)FDV9OhM*_9&-3PsZ8CV~oPhi=bQcT{g2=47_@*TCF$SN?u(dY6Zf&(RNaQ7IX52~|FmydVGvqQ zeT}#ycuLw*mqvjCnWcBpyesdpC}k#CGR;;uFmb%vds5!_Z9=|pt%dHxns$e|x-fBr zGn7&P2Pd7ctKQ80ISyGu6eJ$kwStLkUvhEXay z&B)_{>QCAZ&TjB#C_mu#hM#w-6Gb+7&R)BPQ-MRVMH&`3V|Im?nOSDmU-`(VGUiCe zI=QvERF;{q)WsX_HeW3d>PcCcFYNEu(K$eO8(Kr}rjO&>j4qTnjJFlJ#b$317U420 z4tVRE=y*y~S|H9=!!o;(A_B+R^NAhO))rwP9Bn zw-NkXCc~?W1)N_yCmgY>c)#YmrWe5GaP{Qt!jMnvoC`T53y!m9O&&dE)3J0DsV{x_ zS?7Tyaq}srt(R*fXJzzTg^z4uXIw{l#UYuN2-zqtJ02R-*~_)ZF&nWGS)swD+jYHK zmg~U3O|ymM5Fz@r037?bbftLn8D6u(b+VDuA0P2)=31G3&3$}%pC)~P{r&NNK5_FK zFt@UghOC?LY=o1iQ^Le!=#wp?s3@&(&qb{c-c4d><$!p_^9zWeBmi^65J|(ylZ2e=+}Scv|L)l?dmvV1hFQu$hvqHgyd~KRN?=)O8Ac|a*o3B^0!<7G>yCDiX==V-n3|A zbDKceyJp6`UB7yBr`u>jlEedg1{mt2=m>GWINQ z`Sv;OH2iZY9QCazKXUn#eQiR*N@2>F-#_wquwqhNKzQ!go>+zd*I^6|JI9(nKIZr$ zWixaeLNbZM=7t7eKV^FZ0olEGA&u&P=BZ#CyuW4AV9nO}Hv#Vq@ptyWTwc!8<@i~J zh_wMS0aL%>Z#YY1=Ib~e4;^RF+`ujoI;40JBwvqXvm`7|G$_f`mM43<0$xZJf%~Px+ zCUq7_k#ZSwV%Mc_`NN(JNKGCP!ssp z_1&#w#!h>te|;4rJ{+*TAEJ*nJ)wpCZXHS69Ny-um=7%l{LZ;eju8yUcy`k;J1FnpL;Was8mxfYp@1I*-WauRNhQPNa z8(RgRBzG=KG`21wj21>5qDU-${mm3>Iq|W$c zT=71yRLORTXTJ@b|AXp0!5EuErwv=1q-x{yC3~ZN((J2iETY2HwzCgyf5@DDFmb)- z#m0s++v-GKKYlBgX`-|^``AbE?WJwxwaFEw8E0LMlxJN8{hml=k3mzCjz$j|NzWxX z%7%Qg1BqrANh8J2jGlW5c_&?>w*Uu#O&UJ9>+ih%BfD_1&CfjneQ1n+f7DN&&i#^Y zke{Im)+Yry4dtfh>{7-pNvRI{t!63IjO2s$V&{XOEQX66mR?xMy(*M1+oP|x#l=G#lTt@6d;zO<1J}-Hut%LTGKdvu; zPr@(OeF-v72LqE_kEIs)#dtq8Be?3^qF3~XZ;lcW>~Lakt8AvD6+@D#W6Ajb2zDanT;6GT&F5wKTXeRB9uIwEp|GC!S`LFE$Hlhwj85 z=R4-vU*@AENw*h8ZKo;Ii}<|dz)~UN<;3T{xAYt6e2%kzq(E4Y1L`KbaCjN_Gkw9| zZw@~no}t;8rrYW5*Rv0kf15Ily?mLjiU9lm_8}IRSEA=-9o__Up zgs2vtA#68aA-(2M(Js^%Z5bN=%ST=xtDtc=ZdQUdxt2)SyDi1y35%Y^vzUciQJuz) zdf{F%)pBo7CN7Q7j|t)uN)gwjdL@6pEA9*gn;2HIqqDtZhldqjps!f3EBww~E~e>f z{bH#L0nEhw!Aox}8wuiB@j>Agh^fQeGt_ZiToO(ffTa!NejpMXkRB&Q4RnAn^Y@m?JC}q#{<%$C`0wvZ`(>-PuIKvRKLQK|U#A_|K4m2zEc|UMUpbg9Sdr_0exjkfk#&q!OSOWZkKdEG_Em&DUA{-j4S+{s4sW(+ zedj;#s`|-_X_80Z7bE_a6dSyoz9o%oW@Y=QvL^1biv%bzO&JxTcd4P z1ua$73oIyq?-6_BSVDLBfIZqtn}$P&Zs|hO>LN$PlNRsEb2IYKp7oKErTH%GV&U|q z+q6&UEb$|qzva+*KW9N-gZmoA>&Yvj)HC#mR`1azCG?@beC4}d`)l?;HRAs-1-+3& zGv9lL(%Q|tR;sf~ZT?F~Pw(4Q0(bb-_|D3sFL(AACGCArTiMMvb`n}D74(%6 z*lF>9znZr^z*xeq6z3@zec=dw1b>3<-!Gd;u3MUEjNzi+k51@(zw;k5>l}MZD|1}y zGtSZPY>$}Gl;LhBW=8Ys-R%mxt~c@O<@Ch1!pkjSss0uwjd?z9 z6)9bQ)Y6vfKxM7f-e${r(%78*#E}pz)Q9g8=e+=}PhiCVUYnngDmOs+#9wHFGDib) z$Y1B{GX#QtNhxkai_E3R8WZ$a98KrnpN>g8ell3`%`a=pOMAhC!}=aYoPpBUgX9{1fx|d;HKZN1OFP*7m4}>X`<3p%MpK%@<5*_m(&ld(toa3gJuvPy~@8<$X3{H zn?`KCcAm@c5;xoTJHc!``L>`c&d%x6(Zo^JD*Y?k0rbf`7%ljNxiD{UWKY_dr&<-6 zLhqlwfFwz{&%w8Ms|B35-skCm1&!((A(^8s00Lkh1OE2XJZD+YRC!Xhg zD0HpaLv(WNd3e&sosp@IH!WPJ(;f=GX~VyuTcUuG~42kIL`y^8Y|bC)QMoja>m z2_z}8+Hfi9R61jfZAkvM@!fMQTJ4{I8i=fA>ov|0I`u3mq3yw&e;XUs?$f5G9;>g0 z_lP#KHF-n71#O0dPW04!mLHWtf3KftZ~V#a1SrbOZ~y&a=3)3#M4LE(DB$<{Vz>9ktIm65-TR9r8*= zif3AfZelhlpK9BdUA;xGb{8L`X_I9iH<8#Lbe!r` z(3K-FJ+7b>zEh*f#QB$vZ{U%f47}aIb!AHt>80>k)nnkrRHr2Uvi0G*Xgc*JHL^HE zBBGfv%z6y1!Rz)}|o`24EHH;op!$xQe_9azadmns4 z|G)Gymlh_yI9s!le@nZO(lo6>&DNW>@cxG^KMGzu)_{-7#jI zPo&yjZl%3`zdZc=?Li_{EB0Rvds>{k^!KkLNb+?RfXAH(YkD{JdvAm9o25QZ#{O~5 z{+)Db`PhL)+M4eStT8h9yc|9~*AnAsWvtCMJn1%J?snFCeXjveRbQB9e;*S|?K2bM z!KZ_CiuyvIHjF>CGzdE*m%j=a)Ks}JRpc*Mk4zgE3yp0_(eMu_ZL5FxwEFwN;b+tb z+Eg4F2q<&2s*zc97&jp)9=EA~o*FSpck*?jdez|Nt=bgJ@;H4ucC7( za9_(De8H zC&h^UAm%Y!S`i3e?uqVzc48RjI7KdOvpNzlDQq}XB=Cjsqqq@jE9M`X?s7f zd_Ro3i4MTQ_N>xI?Orw88A{X8-T%FNZJ-6fIKqeGbZ(JJ^UHixP!AQlx*hDsoo|oX zVmDt?A9|TP|0t8yNStcpA9UNpjW7RxrnsvmOl!f{#@p+X!G)MWy3nbl?usw1OTf(Q z=mc&NFyO2ZFSK|kx9U+B^;=?3k|r3r%Jc>FUeG(a*jaR}ft^U4TQKS`67K9z*jBuK z3*Y`Ye5jr(yT|lG?(_<`viF-eilei1bNg-FxSNBFGFmLu)uo}*8KrQ&{i3?3Nn28U zjvn)DFIS@}WeuGs-*BW2;*l4)BVl*QqKEp%gZul!+WVR4O7?(KmA8@>`{dSj!q)0B z{tosjuuZ?H$|sszapHJlN5dWg(Mbi##dByae_T6h+tg;p1W{402u)q-Lowd_f7OB? zcW^Sa>L9y5Xc)*^H(kNZmVkoNe4;cy+gPwe-m zx{Gnoa$O7fd`UH-KbnYt`cSoe;5HZCyMOYdE&I{#+|j|N%3?HrlFmv@t2F;HeoxPn z`qFfY`GU3R!G3UQZJk}xr<15{{#uj~p|T5hPA0!Na&?j4bn@O?*z$I1FODnlQJY4Z zr0|$n_6O;(#$Rdm1TrnjiW2{`*8z# zOG}XmrBuw7GR<_zui`DeCSZ?MzG=d8V^h!G{En>!3)8$_D{nHRB{H2fBE_UK&FN<1 zG#h%R>^~+wt-Gr{7H)N|%q_I7u?`Y43Q5%?R-+lCVf1?e?g7oe-Bekoq1|6;DYe(7 zL&8RUv7s@hw1FUV5IlM%x>{GPB^EZTn247jjJ$9pBC`3d}=8P(!J;~XuFWwU)jH?9O2tY@AAI*9Vx>BVJh*Z*R+?M z=#c9q08lw=KKSQX-+dN~gfQ*L#Xv)9-}V)YPERbFx-i`MAw_f@nmB>ThK3F*MJ{40ygB5V6qBw(uK2xCp@~x zJjf4-D&Z~*$I(!KT#snn0=-X!PdSu|vUhJMxR`3s%^BH4mpWC`t`fR0<+YmnsNyFDyry3{>#H}n!1@iyt^=UK>ylc(&|c9KX)l-tkQpd zayNRT-VbZNBNnN4_@aVpy@C%SfrX?DC_t32%I)IY|= zQ*~?M@5-Fjxnow#&qLIVVD#TF+1E5(+FAwLiBOEbTwutPDw^8J_=`2f{R18UFzkuB z2y1a$3!9n4sq%%Gwfa!EeqjP7<#JrLd*?KhY6Tt4{_i&)# z$;2v5%1o!0UO{CKA|D%f(|kU#Y^g*h#dD!HqM+J?5Zq`m@T9Mxdc*gZg^=Wox<7td4Hp#>NT;`BFOZ0roUmJA(l!9VrJ$N!H1E`8!DRKTD`F=F zeldA30%-Bhfkgxuq%Q}A;lrXqj(385^JUns8Z^ zb5JIkr8EQH3%f~NP2yhNeKJdR?I|u6I_EW??-f3jNv}&M)R6ft+3sIs)E{e?QZ`er z=Sj?(@ai$YOY|6aFe-PT@jqN{3!5r-F%s^ zrGuqN(L6_}N~o^ZOj#s{n&!2g>0D~155Wx*Hm-T{^023BDBU)SeR_!Y#9cWcXEKh? z+OBJ{theNBzr%g~!i2kjaIEA$Ln>5av_Xe9XklLlZHM0! z6iD*$@*0db#R)U*8dz3_nM85uFN07(r8QVpp*^H~D<@~Q$Nz#V$JwtT1pyVDZ ztodWH%SPE1>eHVZM>q|Akco|r<%W#r>EQRzcagR!~p>dAEkn%f6V0hMid! z)1L+01@GohWZki}lo`jHnVUa{+*E-{NatFD%-VfWt@jiqp$S4Y_^#~rdz|-$Nc5S> zxE;J^arZf&%fg^bcx!d&^}QS}D_xGnrx8nZj13qW@;Ww~jNpJsSV3}M88jK(2g!a4H$HuA>g;6Ir!KelqmMzi`YlHj3JawI1@zfb-t2MRyi<1z zrpu1<@W|g$#l0T8Z=78o>#^jTv42>4?(?zS!Fbife&k3WxuAg3aRZ)P^7HSH@>I^P zJ*8VUSvcgl|K<0H=ddTzdIbDA23?Y$aVi9E&M8^$L}l&QGwxjNa$lLSs^APd5~BMb zXx7>vpOEYcCI3h3yCBJH3A*;NLtg9?=sA8EO8xxqNS9ohsj{eViY*WA@G6PQFmF%GS)Hk35};Bb4O1Hx7NtUpxZ2FDVQaFk6=cgD(W9(g zM$L))AYap~JKrHzgyF`CF>q8^C-wYVXDq>sC?L+oIsKx6b9m5#KZ#kLcb_4ifwXqp zXR09E(lal8&YeGh9+gun+g;;_)JZ7Ap7ws9kf7k!0(F=D9~lLn2k>e*?>uoL@f2*A z@qAvX)8J=M3`-9SFG{B;;nQ`V zHs6d!Q3~}ItN{T5NXMXhz%!D%O0VE&rTD21aB)-cu+M0X0ZV^*-*q90+a>Fq*~Cbf_Cx zik4Z9&VkY--(@~*SE5^Zw^fxVOMfRdQw(g(Y@t#yWuT_~GsFPFBw@NS;M@_4f%^pc z4?8tnVf&#P(+ABmBpyC> zgx0MF(8_vk$j;ur40LM;6zE-|*jtZ=5>|~+{^y#WU&ZadGFHpyP^MEpGg#HX=uTR^ zh0K!mz?VJ3rfN`Q$;V%`)RzNUuLhtHR?yy-!+H`WOXooCg72~gw(IR=M9)$>Nt(%n z+NQ8xn^JT85Q-ZKdTB?c3mx475^znSJGRE=J|ThVN2$foZZnr)#t+4|&>7o(yFuA= zvBYY~)I5Q5xO0HN!CI6})JFEUmN2~W8;+YR_D+^0avC_>XVaVXLg5I*_ zQ1oJbJ=mb!+so2@Hq;784nCvOGs|Nus*%fTNSXy9Km2e9>x~af4QI#tjalsn?H>1Y ztC!UTMY`6d1JLzKFj?|~_tDzvYjg`yQV-tthKJBw^Lm!KW-%P+FSJhs|G_yYC-M$M z4GoQQ$N}C%jP!6%)XI#_w*tm}-zl@$ngwWgaNn zVL+!4O@MTYiJ93mR3JB*)9-z_cH@`qh#vD*I8E)NKuKy{AQeM z8=O3{5N7nPK6T^EDp~A5gOe9MA-g!{zWXmTyp$6CxfAwi52RA}T6AO_n}mk*?kVJt zEJfQP?Ul7IY_E_}X~R1Oxcdr$>JC!iBx_?m0!iE6<|3U$GStQPL51=vj<`BOpjZH< zN+y05c5tXJnZ*&Y0eMvyW1Tf0>VClY$$IbfV=t$8D;F5(6}8eW9JccsiWs*V0t-cb zV`C$cjI>9YI;YGOJpXl@$7x`Pu`Go;|E5hbueM`nhIjrUHW2zsjHQO;tp#dJgR!X0yx zf?6Y z^Vu_|U=0& zb#x^1j`QIfX*=E9-J8qUfcq=!)@RT6DJi5`SC|Z|8sXL>;x-k&oL8@1Yax=o_e=DF zJyozZ+J~gq9WMhU9Z=?bcxR}FmKNHj_tq(4CU<%WyEWX$D*jZb@WBy&r0aM=&QRjs zl$H62^NoF_#|-@GPdsisX=KATb%0*Ak;r|YpGBvoovaTAY-?INeB19#FX?rGST9RUl8Sp9-KE2#@Jpe>z|StQc_$X zh|-Pm#?(=CD!&H3f8~~?^r57c$A(2fk8PXelx!ps+88UV28a5~ak!lVGapHWTz?;w z**%?$tUsE3=-BOEH`~+Gb3OIec^!B1;8XmDN7*2(ogoY5qp)Q;E2v6lz7qtTuxe3D zE-@qLXtIoleF1fRFIkT+yurR426eg7+}c{6XE(N7IP@1I|3$+ER2|`thYgr@%a$#I zCJk@ZhPE|D`$%_?oU|4vTH6svLnP5hat0ErPTY_xY`+eWy0V4I^JZ-i^(D8=LD{0# zQH|y=4~pmc`72A|pgT1xizhJ5#=KfG=1_SkU4Vlt6$*l&x@txo z;Cx)w)@GfbpLf$kErN5F`ktu<%UpS!=KysLcTLmrkWKH-SOVLvl7+|#+X>S6Q)B)1 z6|Jv}!AY0v!D_CA4tY5f?KYfLPzzV%a*x1)f+?E2-mdk3|^ zS4KOnlb((a8`Ohew4glYj@SckN_}UiOWiC~K7)Vq3>7Y9?#F#hPnehODmHSFq%=(4 zxik4B!o9L!f49`Md_RTlZjkqRp|Uc9j_aA@Vd7kb1iClC9>784l@H+T*O8D_QVEv< z_re`73Y;3FtI>AvS42SCAuPCT;cjALf;M4PVn-Ba6}_v5JvtZ#r)Z}#=Jbaw%t_BZ zmhm;y9IW=|jq(3@oG7`G3F})MAv|f9vfJ>G(R0@Qvt|i>86(XvD{jwZ0Oa@MI`Iku z+Vu&=znPpX1@bD@aF6$^;0MHtQ}66IP01j2rWnsH5;fj0Zhe%$7A{ra-tBQIJ3m{L z-O*mIi#opGcvsuTTZC6qzsUTij#b&5YYM$EZN3WCW`COAx$|UgWf3+PU!rZMGl)vUKI88n44R4vCO+Hmfx3_FNBkd z)Z`-0(NS%{6U@vBom4{pImLv%yCYp&S99*%v?$V`fAAwz!E<1uEw%qet76EhW6k@w za(e)4*Ln?1x~WiMrD%Wc^H1d2hp#99N?ALu)hYfaJ9}x1@%i)n1xH5$*4*6}wv+R< zx1Dn_#$zIEdbN_tTyU^E?JZ7Y_D_e#zv^?~KkDW!(|{Ak66S!bH`) z{3jJd%}cBOzUQr4s;z#t4!y#(=`=SVUo41^C&ixPii7Bo@Y~euh3dy=avUCqTz#^* zWsjccvy)a||9WcGzuv|G4kukx=)y5<3X(BkO;B_v8MM9^7#HT8^q!n=f$u*^!U`Y) zxL)MyG-{*gJo4@VEJF_pC@#85KjaLp8FG1eGuGagYeb%-$6W>D1wqXUZ9g`#l|NlyjogX3Tn7z(yp@Y03TBD_HN@eK?~c`>Ui_& z#OgAufcE!$rde5R&u7>VT1a7EBuIa*!|6;#Fklx$7ol9eqk!=3HP%KZCTbQpVFSUS zb}yiiYDG%mSVfJ#{^Jmv_foU3w@-H8D6lN)6-ist;3NbGw7=2}@EVCeEdOk_klt36 z)T8ZM<)HudZN^FmnKc=|_G~Fz*|3?v`5jetAzU-qt7GQLp>1ma;!6|`7YB~phE6@( zRy$a31a+_1`OmrAEZdLp%x|gR>6`KNvqlNm{Zm|?OL|8tewVm>w&4%Yk&MeBWlDP! zW5lmk_x|U|(lw@pH>n+32XWB_PZ<7l@Qm8_>#{xe*&cJoevx_jcHLT=+H_-?$h}mt z#Tqx=l~p^JaB>6 zfs3JI4;}4wr*qdm)aZ;Be$aW! z36q%f@4p$=S7#;)tCc!!38)|YP--eWq`Rsdddl|rlzJ{uMcBUyK*5Rz{G|o z1V!txw>54LYLCLr>>06L!PtoxmvVcyyFiKmUvu@%elOf*1g~} zC+g-eFhsV3Cyi*-oZZsit;UtV$<57dvtUb4OMAk!v8l8vo%Ky>kwfT;^R>Y8Ki1;= z2Yg!2JLUEYV7n@T0qsp(+z3Nt{)68z@<1)^HIRU=Amv!xB7XKX8@BGo0Y6hSGp1IV zaS!)~4-TZB(s>;>=CeQm29afc&HNe3{N$yssC-`DXM1{zxs>*HaVxQ_u?QFXraYD6 zsqBk(OX%-{oTO}V@?$y#3fQdnpnC&@2~#WMZmd?FTO;!G6@7gUKv>Ld3b%g~gp5nE z+q^}yNK191MvKGshc|55x64pW&p$Ln=h`*qd10ykxA!vzt#4SUUGvY*&4$B*u+vc@ z@h;ag(p`S6Ec~V62)6mQ3YD_P)auuBFH{-W5HIQAn~eo;e{CO(fBBiX;h}ve3;sFS z`}3-eueT*OH_tzxt(8dlk1o9df3e=8c+=LXCmS~Jd6DA|1@KJ|5+xiapMQG1jeD}< z)(hd*^iHV!9F;OB6iHc0J;T$V7GMW>f5+WdG&MJ`&Lu)Mtwp?4261&^PV-K#v;0bK zW^7sA>$9pP`sZO$2|Gc~GyoW6Gh1nF(ZS>w&DBFC+yCWtK& z``{gv3xAnmT(Ug2=S!l_!FtFKNmL`in2`a>$T)aG* z5Z6KgE~7r@WQr%JhQ4L-n*BH!zszOyH{i68crnO7rOQAY+~ zJe4GZCe%wj0}hT-DHG{@9ek1pl~P|<_d<(4-oS9lO0>6K*V~++A!lP_!;=ZRy-%QU zPNgp*aRctK_2NQ;{u)naM{aHHj1B$ffqnT6WGNl^URc%D)h&|IE}nT{49G0@Y~0Fr z$EGkoo(IwXsF@N!L5X@r={&%FT&QEonk@{n=a;F-lR)=^9juQja_L-O1XM~M3g}Rl zCg1K`js*&=(tFmamtUPYXtf4znitGEv2gOA2OIl=0ZgF_F<}x5>0w(;_82l%d>Ys1 zjAd3ddF+CK5j4mBpY<$nRYdj6yjWQv%7s@3E5YuuI$hA}HlAAE*X=;Cuqm`86j=ch zIrP77XaP{j(=nLk=NkHM!YRV7iJD9T#jDnR5yw%aT-d0*;SQ)nM5$~x+TJ`I(|8neh%tsh(scSv_P|;0o&t|NkmLEqrz(eUe*&J zHxz00VH4X)o!Ulyk?l-Ck>PNCv_-P0h)9{S^lWfJ^Dk?CRQ=Q7j3y=)v4tQh!8JVliG6z)mQ4>$e<{oeuEUP}`{8kf+M>GlwrorNz9J6F)Z?qVy4|nS(|ZvZ*QhKbWrhFv zkP#gaq{41sADM5Ak62nI%5b2#w6930_Vi(d{}pu8AA4b#tphAu5W>WlW`c^ta^PE1 zRzM089%!O-1L`+}O9ZTv3)EN=3BTH6-P7C|X{ zk&)WG2oQA{8WM0ZSpk#P=cVa>1K4{}XbA@%sete~f?D^#3(_;ys6hc1!V_HA{y1;7 zJQ7r^sXn~bw~(mn~h6x>lof-W(xNJK<)^`y#w^mmL!=KOLO4SCX?A4JnGD^Szq7-fg3>IZTSxiHW2Lm*QazB~xJ9+!! zam}~`HHG46HqZe z4;C^m0~&=sL=6F4SSP_oFcp()EWyh2^oJ%m{FL!i%d zJq7KN5LNuuTxD4OO3(_JLp~#h90cvIg2p`8&~xHMXK+9&r3A!`=g*x3W*%VaDhI~N zTS)NBJyy#RxNOIBdNbWZVX~dzcK8aJHoZqtUux&DH5`{209~^n(EZ-ZrpIZqx}*S> z{9il}IF5Jt9gcwMuLEcQ?_Yk-$N$a7&$)n8!vB*Ey6O18*`S+@|DUo^iOzVRb^ngp zZUomj6`bI0u07yu?GgNc+WYcwtn;_+FKyE_ZD^6Lou(-%CCiQWsAw@E#6(ewl#=z< zv`UszQ^^)0lM)iyZk44{wuEGhLfInw`kvSArsnq?$9p_~yvO^;^UQtxjv2pu_%5I2 z`drs}p4WBlSvy%Fu&BMMTmp2VL}wzj3P6l5+!+k02P0YE$l+K$ z;@&;CkdTns)+1GKjb%oto`g5ySUd2eZBw;x{qlApd`O-86^xW~%bp+cczTmwcLth` zA3rAN{~O%pQ2vruYn zDxx8)ij3HMY)_PW-xB zsk7o#Gl+8~a*9!v{ZQk*J9o|la3Xbt0J}SsJ)hg)1Oav7jEsf7y{9_SCt6;|Y&HSKVm3a>M(J;Y7%HX9ZFV9|MRDJm${mlhKlL5N3p+%PU`h+A z<}ya6YoOy%Qf!%B-SzC(+nFK^#D%;0jUv@jjOTc8iY_$i7jAF5mY(ISIBus61wDlZ zHfg%1zP~^4o=ju#%Wa3jG1#%2tepC53furZggJx>PA13T`qI7XBs~lBnTYjbLQ&{+ zFXWHF5-ulcTHdgEy?<0zG!1$ zPbpTABRe*|`i<5e(Aw zR~Gvs%+xA?bt%@riF)$-;OD{$IOq_t2h|3{3K&MY_=e@3(1c_ycd1rv0*GJZ7MRRYuzeMbTfq=(?SCdaU3c2t#sXEz6Jl z+5&q`#SS4IkAo6QHy&zypJ;oOz=`H(68#U>utqSq|DffFrZ`g)#xpbL;PpsvV}%-z z8PVCwdiBSZuV71AA2RrmoICZX5F?cgGnIydo>MT9u7JUu4XCALV;2c1C$d_% zCUEj?H91awT%{cfQ_5MD14tr3L`;ETmD+CL4^s_0pH8cUerq>@JIz^&O{w^H58#+I zi-t8fU;zr>ylupGSm6f9rxAF5Cy-M?l52!MUCD_E37OyDW;n2%q)~V7+}T)?K$5ny zj%1t7ZBG7OqZyMO3rexB%c{nwFieISE^Gy-b46iYU0v15G2-X3l5D>8VpWrYp;G%? zpSScVeu>0-RsB6pOlup91qKU+oQ>;koGc32eO+9@L3U^b}y?G);E* zn^YG2n;csZLX`|HQ}8zOY&CXsWg207#($5%qnKnCqLB9qNNx6jkdFkErvsR=7vpe@ zn&lWQzGzJAR7)Lh`AkKkp-5tjNu9r#)7zr;bY;_HXws^1Ky5CG2ETz<&y^`$is`JE zdJCJ9(gaMISvmS!O|}P6+7*SG3ZH}HKAaV4*=`QIVO8lO`RH+3Nr@<3cJ~3oTizW; zBcb$QHLpE60jtt1K3%7&TX8jyhQ%G*T7ks9cf!Me+nB`ZN#JC5rI(^d*4OKGFxRTb zuYAGpRdkRgv)&Fig+!Gu_7?GO7&)8*)UC#*jhPibeLgJ#y;Nt`|kkFtk&%|*8pM- z8P414ZV}7G$=OQZHt#m4gIshWwg{&C5Gwbo>z6~*4L<+&o0^+2K>JDaRHlh`%>iEG zkUFKdxd=+4HK@UEbDXMj)J-Fm^|+fZgEDV}mtnVVU|%_!4RlVyF&PWevz^|xk3cDf z&oCdG_5D{`?fLcCQQscuu!6Tw!ygAk!{Ct7hKy+guxG&z;xGTpGYEpJ5J#!xO(j&2 zT&PFjP_48Ba}}BeUxg|2DxlYS1|*oVe){t2 zLP0wEy$`#0)$q><#@a|(`Pq@vBDt{#ZF1v@TImkE4hD#?N+;f$R`(BCE)~tFs|tPQ~Qz`zs+3_f{#FW#wkPZi<>G?p?K~+ zjUmKn)@HY9H$zgKktxj)JvTv2y~Gew$e{IZ7cffcu=kZ1e|K<0Q}5`(i(QI!9rY9^ zr@A(p4*a(3p_ElNF@fORoASG0H&lx|+}dfoHm;*FJ9WIiXfmYH7L|VB_CkxFQ6b_u zCpf<+VA03#X97eB&_355`|x2Zthh0{Uo?C9_s)HpnOPO+y7&UgNU?PTu|02V@Hsa= z$Gx8m&`DuHhCFLhJ?Mnu@2@RJuU)z+US$zKv-Qt1lnwT=r<%qg#cS-dEH(WZ29QTH znhK@i?`Dve7`m{iqD6enJaTZP=8;>q1&*~0dIF`gpcTC+?eJlouR=M_mW@5h+cx4Q zb7Ht_DhK|7U|~<|XTc=9Huacum@M!_TS~m{YGM)VJwCG62dkd+l&LV~uB8*0t^8Q> z&f96hz2gefVTCWpnRd5+-ezc69)=;o#%dBt+k=;Q$2AYDz~-pyH$jxRs{1){`wVla ztJ#As3NPQ)O+;>L!W1UJbs45boni)|LQoGx$(@C=V0AG^9l?!s&Q z6t#&vF#x!IQ;!*fzP@clL;(0o0y!e}_?Y-57~cTJB^&shD`C@I?%t386{nCu2SNwZ z)48}Nj<-sCV+QB^<@;n@R#wsNj(McR>+ z<$?||D(5lq)!~n^ddP9^MJYIKU|^r>G%fTts0H5~i>6X8_HcYEk=R1C zh4J6qC)zQqiR-2?T&zGF?~!vPl-ydvwr+B&pywE`8hN`v})hL)@|l z?1mL8*slYnf298=82${ZC$0f%H(rkJoI`hRy$7Etx%Ia6I&9L)Wa{>41?ElSD2tqG zr=K0mPpEL6JF>81SIh%;Y}>Yt#6SBjEEaE+U{t$7md!xOVa{##rx*=@5Qz>`P|aJP zx`Ea7h^n^x>R@I|85pQ;>r$jGaWk-Mm`UP1Di_olgc8i1G^TiDmHWj zuKCu%_awqS0gqU)1EVnqjZOtnBRbpM5to&6OiQ*DI)$UzdOUZowDk0D#+BvgYk4ZS zH7j5OlXU8gQmFVTi|hwAk_ zwGe7zk%zNC^QmKy&MP^1k=%EgFY;WO&!~c3l<;ll!pw#2iqKmp z&z{{kWmM!S-H}?}Z&MeoT{V0ChDD-cLF@k%T)5mKH8)pAVdr|WW$VS#%-+rovr4(* zeqo01^mVKFwEwd3-ZC|9{1mIb`xE$1_V-<2|eQ(v*f%M+aS++j8rL&RQuLgi_)k9{KLCL+6Eak zu9W{*uq?R<|1G`Z$*Cah0^Mw4FmLT=oI|q2M=@qu^$6G4+_=CZsjXmrb{{Bz53;Zk z(M6bzZ&yOHMb4OT_?XZ0u}L1B!$By*ibhnFnDs!hqbbXWVa8J{&Vp``y4POKWK_LO z@z}C9cmq#+@cb^wZMvU(v{3)(mfklieLKo(BC+|ZB@g+_{ruW#1d~Vh-)LeC!v5TH z?`{MUHOJ1TH^OS$U-|2=>SLpsfUYlqQwqA#OvL*?ZlFgz?4Fj7FWmeRkVaC4UIUs& zvuSWF@;YsUa%gapxP!CWU)eFLpd4&^V!LI1e>#!|pNGI=>ej`?#EjkYk1>BtRqxX& z*AH0;*>)Cr!D?1bNgeZL-}-aM#It&6Oy<#;OmkmZc|N@D_q#hk#SBmp{sNJk6M>o( z+|x6?$HpQ0pO@#J_Z0KeDO130PJx4w;}RGcczS-1AU%F}UO#Vc2Ot0G*ALI43(#He zN?|`dO5Hjb-b`~g6JUGy?%m8?meAm=_F|aVCs{u;IX>@#n3QCDc!pKI-?Ba6;hL~) za3G~W-2Vn*_KyRF+H{X%@253xtD`U*t;HPWt0+gb(b%wFOIuqmUaDB{eXOMi_;FJf zodiaP4lOSvb?XoqXqpKy0rC%U!h0{X7h;O!mhF3W{%DqbXm03BH{_;~voE!Hv4&aH zfIsB8vIbi|eOo{49oCW^1ugYwF3s7nUQJCc-3~`GNtSMR0R9Pr6wWv)ICw7U>#vnD zDg7TBV#~93sQ||k^d8BWO~68Ru6~6z+g=8*xC)J0E}(jVabP_E1jTon=VhF)+Xy`X&rr{9jS$8Fl$*V;;&GbAKPVD@C7rxeTA+b^WuHfZbjU6_YJ#V4j8 zj={&a_w3&Ug-~jq;CDy?@@YxuIzXwN52R_)9Xu^vU*<#)20JMg8t8h zB?nHQ9EiY&4`pw?h>FGxg#?8;l}U}nv~83FE##bJjph%g_q1^gLqc+-_$VQl)}Qmj zO@V28zVXA|sHLNB-Mw8g7Z7XD`;YrQh9WWz&209-Z_~~GT}vw!r#X4Gw_eOJ#ctoS zW=DVGwx8PJO<9now-3YqY;Le*E7sj0^+qTwbn}hNF;3_%vJN}zNUHF>-OGlRIbEJ%$6GfyBE>zKS-Ow^C!WF@^am zmUFpQfg%MX2~yLW_YwGjuBD%X3vt>N)mrYli7-$D_1=3zap)_-r@z$p3I^0GM;13U zrW;Dq4NcLJA&I)dhNB&A-Q)hgo(#0rta2VPVWU|Ti+jVj`pTAbUyvCZydi-Cxe#<* zY=gFiL^wzC>Wa-H+|a?&BwPZWKdb=aRR>RF9t=>gnLS8*)y=+g^=cYKOE(4Wk@G9dlT|nxs8v>3xbXf9=^cmfX?nDs0thyVn zi{qt`naa`b-~b4rbf9okIs^Lt9Lt#PA|VY>BscO&fQ0&96DKj?3oprxR2Mx>?8^VrC zAYQNR_90xP;GmNry$v=h1cfCvIZA^tj`B;uSrZ71$KG0w@pMAC?@F-J1o@Aiok&xo zwDPQXrBH&qQ@=#gnUyN2Kyg%?AGRZ_dj!)XIXq+rxLzgt7P(=F!)uTpHIqCRo*o<%d%;y!D*3lemf*q)lycHQVnG8`ugLvzA4T>sVAHA;2AKgdk z^7gHIH4uZgz|DVY;Xj5sVh)fl63`5*`v#7mG;jx(BFkdT3(-i&DKaCPjD`DWgxeN1(PwcSIQue*@M-tBQ$MV z)7$b9Op%SCq{hXt9idb0E}lP+wKay~q#g$kSkd53I|dTT-h6(OVAFJBps!;bD}6EY zJ;X5QSuYH*zPIYUZuoW<2Sd)Jf%T)A=a&FRaS52yf*R*1Dt89teuH0n0r_AJ$2cu5 zE!Sm?&q^O-j8t|)!VVPfiG^c(kq9>=z{!-H&&M1gKWd{lZtrPM8z>Kp!f4=4U=H9% zS;Nx#yQj6TP?|O#(1~nw3H(+*wEA%kkKR{u`s+A>n87pRV;Hj#?opRQ zN1Y{I@u(4*3UW0(36CJHZ7TJpODti(To9Uy)AL*Zr^(C%_6+F2e$$Uz0z5i?HHM*n z3|%RN4$boq5a)QW7(PFgYD*p;RYCyCWhcnu`INlFKd+-%suIg|?Hs^*TrB_vKF|#M zl#FG93qfpDK6o}^Q+PSt5o63g)smPF@PCgZA4B(Y+>6@^d1HJZM9}6qOTffORDUoK zB7Iv464fb^O^P=Li@?>w(XvtL{V?&U(k#YvCkYJ+d{xHa(xZ_5NAn*6oMJC^JqU}3 zVIo22HeFpx<~k3T$)|K8^FWgBog~!{JRqV+bbc! zi2OB(16*NL4EjqPzP&ypF5OfHf(7Bj{;y4J;7vkyN`n^+P$fr+`;od%tPR>~C1%!* z5wqT^f9&n=qpnNoLUM0Lyy^G?qGxnCPL59nd4IBhCagL4qq>SZy^A|_ei&`8f)2|; z@cBQu{9HvzCDvc^_g^bSitcnG@A=@=aX&wAfp5(HIHw*$Lek=d`l!+7WM+t3#UF=4 zCN6v`nOsOXWvmap!Y|INiL2s%W?FH&-$syV9S=t(Z}8Jo!70>4To@R0$)`4?^^j

$*Gc?=kCYIcRPM)F2qEvBK+uR!RH(P&t&Get;^d$wFEMIBGwln=u3m;miGVlO zOeFC50!qCBuBCBe_TV)FJcmc{=Wv)$C@HQ+DnpYpGV}$9O3EaoWW{LnfliNs>tAI* zQyH4I*Pww9FSUNNB@(X1Y004hA#9)f2}qfWOnS8Sey(Gw!B+v$R;dwnZAP1)6FaVh zmiO{wHLr-1$AaoY51$kx*}Ia6Faf`x2LJwtH{=J-^l}$ng_?C@cJX3p9PR=@d%n`P zczvt1DY^Fz5=NU-15)r_^S%!=r0=}TJvhi$u{+6b9Y7fYpZRPc0@FIm+3Zs>7NzlN zaFM;lq|T6YNhNM(ggYWm;8sK$t2uJ;0z!WdsSs69?j6U-g@z7LOe5@XqzI8WmZjQ> zKm@IyZmi7AGXIjEh8%!_nq6iGyn_F9KU8OQA0OVw+*#7wxecyqBIk zyiEd}qeeO3eD($fv#HNrWIMUJ>gwtOJ|Um4FZpA2dNHy;gi&1M``?Dek^jd1)JG6$ zgt`(hbSx+ERe*Wu#NYczIw1m=T={yS368xB=v_rPzjrAs;UHRIl1l(I14V_Vf!1<` zqyb02$B2naOW*|y_*$04S>@hZbFK(9|Kb?T2Wf9Mqg`h%ug;pY$@j^74z4f=dJsscb)kZg*)6-@afJrzAflw^p05nZ_?xv#-8 zBNqL5DPiEDWx2BDw@3Tm%qI$jD))$lYu;QjJZRowfv^GHt0(eIR*sJWD%z0GHm~>_ zid9{JH#V<0dKMMQK)>wBC&lEdYa*Yn%v1+lQwaziF3^QI@91$$R00FSFrRQvDgqXW zNtI9N$qv!<7iaesvP+Gi8ifvt$aSLOq)vsoe&f5o z+>O|ifD^x7AAUEvo<3!Lrjowa+l8h~ zS*~+8BEo}&Thee}>Erx#*tdEfgqPQeGEoa;QM_iB8~D|5jLJaoH-y*j7u%YgIudN_ zk`T{N2lz=zI;1T~Z0m}~!mRmJw%8y(6*{`51^y`Bli13uy7BYfujQRQqa|xh9x)2h z$mjaK;}24MIaQ+p_CeGtb+YYeBt12ygPWX$(ikr@`_vRscw|`t$+$4N-&g6XA-gxz z19s2nL^k=E&3^1KVCKZsL@I-ILjjkUw&ie4k+$SB89{MoSLvC{ix_=v?P<`_s2%2I ztIZsnc1D~x*a7n37Bmt~XZSIRK$SW_dTA~#Kp0k(*qVfRWes@zZaDL6QhjDBej!&H_vKr z{BHEb-LPf=H`v(r;b?Nf#rO3-es9TPDcCe7YO^-Di$2y?xwgqNv3Y%go$~6Js8(?i z!Oz0F8#DoJg@zI!gEa|9t9y)Z)~-#(GaElWJ$7J+9(Z0-2{j|iUkBZU#o6pYVDq^M z6+1htJVe5?Z^}tG4OLut@x#I(bt7mX8(T+|iV|jr05!Xhy-(v@V`duz#iEqQXYTLjGdImok&DwqcGTw(v<*|*0S=og;bX3t&T?zeZGKF{)QA(oW;QGE*M zA*$eJx1e)5OhkAaHNmZ6QSp)(D(djfPwhZG%N_wgVa43f4~yt2tUrjyDvW~WVegWK zYneFg4|5oX2KlBN!5I7Xu2XMtDlO|-yfOBkIy@q$aqLb6LSmj1y}+z~|HH1I7@N;| z^URZAjA~e3TBzDWL$A{@(rEC;X1l%HW77wJX13%2Z(mwKpmxRFu4XjSHMvLm?lr9U z5BCdV)d|;;Kfu+!IeJl%f{QT#QGNybB;do_4$mcrA7&&GsRZU-Y=cx!5(grkHRefp z72D7Dh-gj20mVq)e_ZXI*t$g>g3=-)7_w&A;H<(T6y_d4t4@uchbKYe;=X$|3mFH< z@Ycf0MEl)9el8TJsn{!A{TO*;($ODJ4b5u3%J+qG1@;KZpnzF7ANKB*$`^FDN9YV) zQSrTK92IVAUh~sdjS&+ftqnC_CQxPlv&=L3MLmC2zvDd~YdF8bGXRbkcZk&bAwipC z&hnpCLw+2gVee~faG+zD50Exc2B$lP>y#%+dAuY&G=>7f_U19oDbuEXXK=Wq`0?h@ z)2ps7h%oeDzEuI~81PvA)BUs(0IDapH3Chfv)BsQRO8!h7)2H;Z&u-Kb0cXVNMYd( z;{WzZnM*^1c8gtlqRet)P;XMZ+2Ov2q z9pV~|dcZPBDr<$u&VYL@PO4WrRU~biT++*8VQJ^d^4hI=e)r18qL#}`9dm>TzlbZX ze6qhKG;-#F!UVg22llc3ZI_efSqypF zo9H+K^AMG7BaOsQLR`W>H0r--Po_tRKi=ToAXje+x+>Jpw0WlwuDE1CDl<-5<5TWhd z5V1R{Wl5XAiG4Yt&t|z#o0vh{;#|FYcn|Tt^XnJMP4r_*V8O%NCaUxno?ifI zMD93dHmpr0%`Z;d=DbbPX{1BJiS2^3ys^N5;BBJK`=KJO-dg}%cq!J=(gKlj215qa z)o@@OZxo%eA>dwQY}+7qwL-S*YPBR|N@O4%MTFOr2p!jVh175fsW(fzyG;EZSM0_r zO?*{QWM80D%kvY=b`8xEBjCA+aY&uKf%ZGBI|quXYca`Ka;N9NlY=Pu{J6z&Gpn=lQKx!B{- z5hRS%=2tp;Sksho^<@8%Ae`Uu=E~Q>*IMeQi!hypb2Uj+&>_aJ0caxk<1Ie?gi27u z=pseeG+bLtYwpS|OQTo|Y#=Y)(y{;>XvFAW&Qmsd-3{Wb5-lGwUvHfgp8=DSX{$MS zt$@SBL)dZ<>EF6_kaugCUH&NBzP1?B`T4SHjg$wVTL+z@tws+;`KSnRDbjDzL0(dq z?3UpO%eEb~w`usXhT`Q4$G%*tkbSWdlu=Mz+)87JiS|R9@P)Sao)#w*bA2;kEigBnY&W$h{Eyu=^5ho2h+PD)~i$POVb#9}JD<1Hmm!ey_>c1ZI-CYHk)oJ^zw zm2bGu>F=fhN~6&L0v89YOt))>PV#k+X|qfA_5b$X-Wsz*#aE9G4cW$X{~4^I66adf z@QYTKUoo3_7&_)wB29usAh~#zi>9uwu9PhJiUgVvWmar- z2&WCV9s*URqm=-%v!Oi+)oe*8)Y%rn7Q=3MVb>1A`y!T(l}EM3D{`_S!yaEi2WlK% zY*yjrr8fE7Hl)GfIC9)j8CFsGf_@ zNN1Zuvdz#SM#9PUDSZbX{sdr(BQyHlI^WoPy@1z$n&-d=2%B%K37}6LlkYBI@pYn5!$pw3(#CyMndr|qAG1imKnED7`!45YS1IjF z5K6K-<}k!?gpT1;$e?q>30GaF`q4iosR82n3`0L{u+|f!DEcS8R-dvK!8eCR8j;;K_oo~v4zAs0^bxvrKW>lYer8L7sWZCd7{|S23i$j z`bEN7;E}B0kbVr#223YNo+K#G1-sdOZP!)UPEcFazww-m+iT=veV-G%Cz}I1mvN09D-82a0EFT<)tRxle+P6G96G)Un zDF?)Aaf^ijF6ADyz>z4g2RM!y_9=GNI{bFfj!+Gm!xbq26^aIW7obXerUQFFRYwNg zH`?6P_t;J)KmjhVc#BEsd)~5(u>27d9Gxq4NEV176NsEY%$EX!%p9Xbh`K2Uc^EUj zT)<^0xi9iyfGR65EucyrF!~Clt2OSlL74oMGx(+t{J##xH;h1=Z+Z*(p!}2}=CvZo~YGaEXED50m#HaCZ=Gnx#uLXxN^Nsm{kcunn0M(v1>~Fa? zR?|xyn|1tI#F;40%>RLBw2M5x_fm2Z!C^z3WkO;Zga;>}@PnTuKI;1452y+hX%=m4 zlW^!#23RdXGQJSrO8)uD_ZycO*pyBIpIH2?N zx#kca959oZfZBJ_HH#xCE+A9SzgcTKiHlEtC_k^lTA^N8A2hW%^RCrW@vt^2xvvmV+%$3*0ns;X*Mo<{ zH($K~a$X^-H|~RaHVOGz@T&PY^MdE#lic$R{mVr1+(6!#{IB8Fw*Ow2!7%)< z)Yh)jV*amhT`>@2nZey~r+V*&Mg}SIHlNYjq2)g`c9VZ>9YkNQA2u$$Uzt96$WZXU k`1c~rzhmCCXOWGD=z5GP7l5CyC4=WbeJ6 z8d=lLGTalDW7^0<0gde;ux9V8?qyJRj&Dw2@w!IuzLmmG1jqsaNpGOzQOIoR(H%T3`|XUIe9owpE|5>Y572yi|c=1=QK6H$93H6jVuYt zVGh_vq+JfL?vR35kRfB%sYWbN7fe}4mCZyYBfR^@;HJaXOs zi1dH|iLVYH*`)pde1qhYI|*AuiLwmCI?$%jZ_l(3dwC zMth1SdX8>7n`m*XXxo2o;^#(Ua^{STO5XMNT?o$kD`ZZlIa z&{r?e$p! zB-qopnS@V9N=hmqFi`5ojT@s~`2y@GPrl8_I1Ryo`oMvU&vr9J8?~lf)6k%=sHiae z<#uqu{`Y~twS^wP2odXx#P77FAN8dd+7}oYcuh%(YOEv2udJ*r_xDS===k^(o?c#W zZ|0a>yL$EcMEWZqi#?ySKRw%1HIiD)Xj(XTyLlM%)QK37pK~?j8t)h6?CQrl>Pnv*KXW6)Y8(@l%knW ztO>CWb_?SSxV@$i_ZkHU!-HnltnQ8E3EXQ4&z)~KlCZpqPmm8ieLRR$Gpyqc$?HHW zlK&_t$L`LL{z%9AT+C?<;W^6r@lQ1UWwK1=UAuNo1sAU#|DJsFAYSz;UY|?F$NqSy z>o}|w<;mr|RLf&C`IF|f-X(`|izuT315%Q(Mx)fi11D8eyuW_^+E!p|0nJ9KJ@xhL z!&`UK?8Tz_U3+`6qU7=B526OOO1Ew?p1hvqjvuv|syNv9r|E56foU+OX77mBhTTpk zaZ!`pUrz-$R%bp48dwP~Ji6bWt}C5%t5Eos-B3(hu9@y=M^0*W75j-3?s8m(e0H;c zDA$(fyk5S1d4i42qsVck(spoZyYSH8UsFqGj+2sh7rk+v+da&moc2XDDgPfsg#FGPEBdg^?7S~1tE#niJpAn+F3b|aim zM7=D}x}LwaeDc?)x0#u<7jh()e)~^7VOlMj*hcdE>bU{sR7O&gOl>OG%ic>fgHc~~ zMJ)g9U0IkQ!sCuD`(Y`H1E<`{saV2id2+h#j83Vg9hRm#SDR%q*sxf4Pu${bm4?$& ze>(n2uMnU~>_HWibHNW^)vH(c4n|nt$~5jc)1GNCQ+kDnaQqn4s^!qv;~(+A`y*vT zlLfNxg{?+u@S^aLZnxt?m)>}}LhVeW^E&VH>=0E}Ru0^~xlHt8VX0Y7Rvwq-;_>$i0 z`a-ealWlwM-ti&U94SmM&}FG)Ir5$3q!G!Is-oh))S~5K8Kw`&c6!2d3W9*793Oz%&KIP|Jj!(Z`{qp!VO-;wjs*$fT za-CKk#%3#HIjqhRm3ghx;Wb9DV^PZ7XBs6Wuo_fM8;ezMmEtZp(LXSY(P6SQx6fB3!+i8Ut+<0tl6n?ilT z{dGHY&8E`*9Fq>Q+|QdI>o`axPhU>)nlZh&!=ksJHEK{LM^5KH>u%e@8)lm6F%kBu z#p`yn6FtREkMgvNoziV*?g~61c|V)ZubhWgM)X*@IlfO-Gy(7lI7_cjhaf_$znOH_={j$lGjUg8|m1uq|_Yaj_i;##_IA>;$oG) z40O$LSNy~sm-QSqNgnO_@NndNh@jc+B(3728-Dpn6C%MJhUBz75%N`!NH>SgEpnVg zIj;*B;vJ}eb#QKOuHLG1^S0gP=qq%^OZBF`2a6Y_^DO#)J!A4kIm^D`*R$_iYikt|i34?^*Hlzm?pKMK|GrfBN`Q;e z_V&^_+PkmFmQX#g`Np)1(*ZXpWuvC<|WA8JGRUPbj!Hu4z z%_Ou7gAyA;s84iV;tzh7{%D1iyS z0m*acN@biY{g|RAct~GMRqLI;cK!MRKe2f=??b#S!q(&TJ?ry1x=Yjj*Hl%5C#FbV zOBw3xyXQ|7t-SLK#a>fWQ~%bFR{Egd6z$+Q`8eS2W95M0;Hu=DZrTgacGs^w3+4@# zCz2Gvp|5lslXqX0-{3<=62bi_wrigk654Z2@!1BF3JMAigCad1L|{*?uT0!?EPVR( zX$X(*MQ=tiVW5N$MYo2r{s*3H-Q|e|9Mmh!GHR{duc|?bifVZIyU3wI#=O}H=M51A zCRL%`oF`JY0?{-hrs)69Qj<02#(L|oPtSB`|1_D^a^#fbCSFaL9X9o4l3=v%dZ_9! zVc%2x!=mTH9x-aIr5e@Maj9~E2_gW5^1E}fp1IRCCy8eGx!R7kS-qhUh@%qyV(nrM zlaTqbyY*p#A5dHP2{e)1j{2%wAI7iHZvCswtzL8&$=Q#%i@rV1ix-Hs{b)VG_~CB7 zCswK7{uGJ+wV+cs_I2c#np)alyLQc+mY@9@RYcg_NGq$^+sx(VWt-uII3kYkpshE> zU5R4pBI9`lY==rb?mm)|->{8^^ih(K)uu|s=ATK)AOCoQi>q;|JwdI|?jZqK z1~;}n+r#8bdGw;Bfq}v0RcxFxii$w|%&GrD1^d(RW#rog|rt z6bCuIp^5O!YeW?QIlaxnF>nmKZm`=ex--kWbch~i>Ns*!XlcIno9NnXGmq2iB1`c>=U9B`ZIttL zL_v7!Sm)6#`Br0|iK#`xc$=V!YnNXc$@_HRc6QS8{dp&_*Y*4DukU1R3x9Q?>gnPa zffhq^4o%jHlJm`DUJWRpDNWyRP{ zJz1W`;-V=%@EzCn)LUKNRHP)~nudmkx5qp4n)0nD)Cz3Oy2b0ZkZ_c~^%JMXcT6np zb4W zA>n8wN_C^?Or614bFuSAh?u=q(v1%+-Kbmf2?-uyVPQ7FDZ2F=>DEy?*EBTgOExHy zl%?Kz?Dcug%>Mm#bTspPN?Y0jtv#RNZLe!oHsN9ya|}>x&e=|oSd9DqUQ1A$2QZy$zS^Wzqxv1a=c5#_1QDsk?+Zq^Yc&Nyg6d= z%EQA0cq#EWh1%D2X-g?9t24{Ms*fI#7zao1qt&g^GB-bs%H`MArWUA`2$plvhgPR9 zglBSQ=2MJZ@Z{vL3k42K``FmnKG)Yv+1Uwq7ur8VI`pE)f(!7nD1?!5ad8Elx}oUG zNEuzE@al{XiUoUNta*P87VpgEaKXoTbBD!AQgAYxm3fX7jXW2L^~KE!VSLvNNE<-H zbkP6b2WiC@I<3)mcXxmO{8`({Cp7fX)?Ku&xKvS_NfO-0)f3d0AlmN+k1Zdk%||OvndX{;>)HW z5UE~(7}~7#ha=ZBjao0i_S}91FYSoS%@qVTq(M5Aq2lS>xf3(?5-&YJfBfjt&0YsM z6lr;l+xb5Cn|rV;c6lA-da%A~Yh!C`aNHRb6nFV1u+#NV7?`k5%X<~};)aHX-4~wj zECp@;_4~K7cDM%TvllNYlaiCKB`6*T%0B=KK~`m!Yc)oT?(AMtayHO}tnTyYvw$^} z)YPuXw?qvQ;@Un3Uyc&@0UYG5YE9K*stw|J^6Z&(QDeuCAEo$|$jC@^m#yc|pP&4+ zN8%?MtNa+3RuMh6;R48Js1bV-@adySG5cQhEcvMe2M!P$1F-pQ-*MU1L0iOx{54?Wd=^K1DgNCzxw}J6FY6eFb1fIjkTu zIQUsW0QIrs$BzgJ9l8=JdhYJsSoOS_>1po!ZQRQ5mC1L}ol#EQmC!_^wEh&ublV=r z_}MTZ76O|80bILpY#dk_77|iYUQQMi6cn$XHC!B7TVG!RGEb~Dy^uNCn>TORIi}CL zKWAoU<~Hk<9I&}}@7}2!8D#jGh6P*T!?yPJXtTb`5I%!_*u!T-&2hZWyP;Yzp&phl z^f)(aDCq>gdPTv+#B}V~G42XFIy&9qZwUm}E21D*Q&TG`E8E1$$@!->l?hn+2{PdJ zkBmF=eV#-f0S$3#emquf%3871X7TW$6zajgdGQV?2?(32niKJ z?_FDa#vQLpf+5g=1{{1%i*LH_Jp+S5P3Tr>A$AhlkR%yP))~v>#B_meKA) zIzXq2pQTTJ4Ge5mQd06U60sQAIs84@Yos-m;){|ZJsMN^0!?>;?T75zW3GFfk~Q-W z0MKzvE`d!Q^o$_O%oCA4dzPfRzQ>jNA()ej?R08j;Qs5$>TZLLQMzd5vaB2INBygR zj*t7I8T>+4ECQ~md|cw><)za6Xj$q;aqwHs72lVy zv9Y}fShYO!m>Q9Dn>R+uIulj7P*l#jc6&Uj3|Tiu%UOhY6Vk`PzyRgRNu$__p~rbc zY~r_;I8aBtYAR!_!mFoP*CU*qyRnSY&9Mq9?dgj5@hz1h0p)b2EeZighl!X2!wES^ zdk6`D)}-{4tZwyN{I$(heoW7zqL^lus`p5&KKk=Ve}LYtr6%yC8R&Uz8@}j6JgcQ? zlg@DV-o1M_M8a9zq`QC|F&f*dk#DsN)LX~1g^a;|!&~I!2V7!jp}p!$b)v@fy0iQz zT-0P`Wy`RHd?u_SB6Osrq??o_i49=h9V)+7S63Gy`Wlq+ftA%oP>WxEeNUL27D)k+ zKYWyn)ZgbXUTyN3s5(g7mGskvqb8>?Okn1KC=Mvs>&B z)=G0)vx{AHbtMCRknR_Cld-W8M8T_~?ts2TwryMAE7PKDCsjct9`x7j7Zeoau0W~L zoUQh=9HmT05zfua)9EeuSOm#2TbjPZXWXtFbLO_LE{|!qsM!wX%|1NowG9oG0H`5- z(mu3qC^#h@9XB(>PH}Jmx17)@u%T>fYFeDCV$v}-=1>D`PZn*#bslP=cxv8~P8YF?+==&*RNq&5|w+OlFT9JcoV8?Q1m}v5S1-#oN zur|}JB8LRNyT3ob*r)PV0~w{Gt$p?9%%MYvw(r~-kQVLS`SBqIB_*Y-?$$kwrxbWx z^=0(+Pk=2o(wpk*Z+CWfCL<#&>Fm_V{P-m*JkmnxNzY^fBV8oTMUWxoB7?%=;cG+CEGdnw55M?zfDT%MRZ0>3Jw0!Otl2L8oGpjWYcf z|Dye5KSllb?*~wcRcJru$a&JN!Z;_c6(hT!&+yx&u-n_4T*}KOZS3ujiio^oE7Gfe zDd@B+2!wRZ{LTh9AD=5q6NJTs1FfC;)_c%N4y3dHO++bRm8a+5{PaN&JT%Y{aZ;@t z4g3&?dgf0bqS*CTcx|aol;gZr;EqZ-Rf(X{=_zvLMn)e?_41Lf{zeFTmmnlUQ5 zVe)Q8%cbSz(~f>3A|js}8?U4lpz`QNE*5K-ZYrG~ei;%%GuoczC2*O=|H$FPj|{$Y zQlPElTNI~5y#?lh-X#I+4%-%Atm@v_1-N!xHsHkM(&*@Yfb@(1Ev8TZTTI)a;_Y5v zUoq{@MFvL$nxtq1t&5w~SoAhbX+@L(5NAFQ)(Hu#KJFbfx3sJYX2s0Yq7I)=KUXvUpj#=<)aF1ZEd4ZiJz_NE(VN$ zW4|yitNT4w%g@_;XOj_D^SmeBKUr}P0JVVU%$YM7jd1MTx${eosaE%*nEm`=US1{l zX(Bt$TfX%0AitiX;Q^{#Qd8r(^pKpKd~#~)+~v!@?k&VRxix$4KN%oyYGUFGYA2(- z>lL)KsqP2N{ku8NojV66aB9+4OiT=!el^2x`-^rImvr5#-LY!;CQ;40x-@^k-*E;Y zguqHdP5^3`s4 z!5tudvN8~A4e#B$y)jS0Tb>wL3x4mD+>bmkzKL#Mv@}2$+ZN2FMF13L)$*s6A&U{> zj$v#jV9O_NW+#1a*&8heLQ;Z_vFU>pb*d)XngHRv_jW6dPWRVtX-ri>*(%6?yZI3) z0+^=2HAApr9(j3rn?9@YPLIV!n{yV;=?hv8Uf+wHH*S5MFeO4M_w|1p$#vvln*D-F zcP_N*vXT-Kl8zmb)z#I44}LzXoFkUg_0LDZpI(rIc*U3C*?*f0nRcQi zcztv6ND^2C!HqPSekzO#?smqweX_Ems)|?P`dz6i#-=UE?-F2y&^|7W+{3r|NAz>sEsE6qs$^y7O$F zdB0@B8=xn73U0l7_jIAEy9~tYP85gn8&&52A$p5c>Jy?bo9J)i{u|SQ5VhDe(`Wp- zSl7P4SE0xYyzLg;X`OX{S zrt-u{24frY_eUf}qTjwXTU&nEEhr!$Ky;u?VImr>#kY{Soqr6n+BE!}cEq;%os7R^ z@{=sbBaJhE+G?XBBN;zF9Es%{!1iw6v*%zT0S4a*@_ex(CE&vmMbIG%Q}4vYlZLG+ zYpKq3eENGKrA5y^#JW@gGG2Rgev6Ocx7hG-dQqoU8r;Yye0OS~p6*>-+)*^<9d4Td zu1~1Er=QL*Lv_3Q1N5!Czg^74Q}2`V)?-7ohpCgun~|Nex8giBYh zJcAp#vv8lQ`?dj8} zwe|GK@X-P6Dm(By4<0-?3x+>6meXUHZ+YI`b98LXZ2Gqh7HKOiB_P8;d6U=>8=cX`_R2Yu--a`eK_ zmzS3x22VkZegf}!5g51yWi15!xUG$bg@uKihv#ub1OvNr{G%QF*Flhf-rc)p_!WHC38mPb_@M35($avdWk9VRcc>IcC&%_GV?i=a zy40f$m6cL&iQ!cc?C262z`{)Zrt{x~i4xS=*|{kSu`pOjDb-qDQ9-PdyRYv>bMxuJ zk%7!iK1}>+4jn4RhXGd+i{!Rr|Igv!_ZA{jR8wr!J5FijK4-hGrNy+qzRu14B_ir+ zL_`Du*JHbQu*j1@^12nC`}ZkdED8z;aD}S=3nd-R@Q|XS;`0|T9-~g+s`ujV)6&vP za(bM+&>^5&gmLrpw^;p<+FE7i?&Bk+r*{le$5WKd0_P3J(9qD&H8n1eAD0dq2~$x~ zg@lEbb$74NWJUP+?D9z*&IOMXwVfuz-XO2$oGXvZD=1t`(GU_87LJC5h5Y_%UJE^B6Egw*h34LkS zuKd8heJ)UfCo8i|dl>K31W;xLL2NAp)U-ZQgE3bh{zD`*3$ilUOR5r!*wqzbkdc%z zMNbGOrPMpNG!Gi}*8~n}cu*UBoY%~UIM|&F-J3w^(XB_bA+UjjPgb^ItdH2F$~pkn z`3+i;fJx_7TI;^bU5M*9iZQaZgYR@xwZ-gaOOU1kmC$H6*9LR_H%)WDL}=L((CED6 z0XjM_;MA!~$GnvZR?KcHW`~+z`1>pU91-;Wlx^I>jg3>N38036W!AUV#l>YWZW6%n z$kC%0`mLaH{Td$LfsTQ=qQy8dhKXjopzj4qNivrwPs~8+I*Xl|fQ&ykG+fW);N|80 zhATI2&pZc7CB&+qrI$daaBNW0(|bREzE{*?aW8gA)|sBe-OX(aV)0A1@lDG=Ur1Hn zD^tF?J?8G^^~r;ZbrKp+A4IDt(;#TRZt^To5)#->ojP?DWI;JWam)DlxPEs*o~%fs zp%NG;A*(@}AoN8rx^qOf^YTh?(Ss50I(YD)a^m$}0F7?>`69D(b6J|glxNWZ(hOVJ z2UHq!OnZE9e7O4tG17Y=mQW?r2-N|!5*poxgA&KdZQHil*x0-VRD!(ul=O^wBJK5_4K#y4S?&^W6D> zwaCL^YF|b%PfS*SVc`Yz3F-MTd%gBo122X=bnUV44mAAGTW_wGvM5#^ynOG}+I z_$un)4;}%5XN84g>?-fyO_}gQK&Ze1n2mP|X%yP+mywY%%(;Woj#S~(|3U&V?uwlb zkBE5aq&NxX;=%OqYG z>OKMfBWxtl-VgNCD(RySoQ0`_xPIhVUrVAYdtni59QxnlDb;gKd;n`9-(G$vE2CqD z{?Sc?W|nEtd~sGCyRzlv$&&^43zrQ#6O`gg%)%R-S!RUHddZYDptwq={Eq7SY&SRT zh6QHxsjaJ%eDHu9wvc$U%fj>SoCe(mLd|49Q5Amo_Yc*HG4NFe6faEl@UD%U7#Ogf z<9F5HQ=3;AXF-ylmz(<qSvzJDQ62qAoJJ3DkiODoELWhpL z%@ZRhmE%iba+2xfZGp}owlWkKC5RO17EhQ-%gp=@FHwnRfz69N7Ps?9WI2XKA?9pJ zyaCauOTu5hAzbLwP5dn6YqwLPTdvf0_tWYL?4Kzlj&M&w_Ociigd@#Pgwjw)& z7UG)2!OF_&VaFjJ)Oe7j(`5@qrsl9S_SduC}c$ z1Wp?Y>-o_e-5RF`GeEfZ&8pJ~2?=##l2}$BA)-3e2a7~IXJDV8uZZ)ysA)2AL~HfT zvFlI)`@|~Omq)m&hoSduZ{Bz-0SniR5vKcsn>TNcnYx*MpE7v>mp${Hj+S;=NSvA3 zCBYAZ!v5sDZs$uGB%H$O;Qdq0GE_Mykzec(z^3%{)#*Ds4uVOmYl;6z*WIS10G+lI zGJ$03pd8+wSIHPiuM_zFc(THFly3PoULKxby?uRInkJ9c{Em=x0yHTb+G8^ddRSo% zp-#B>o?zFe$>?4EfZfN`cL6mFU`HzgIW^V4G`@rMYyklB(q{_LaO%4rKnJcm5U?6_s3ZTAWQwPyYoi@snomgU9GhDv8~xNM}ER3Bdip zY@o9WU-|7x``J@>P8vk9DrF1J1m4-J_?cswxHUIDFgcH_yZJv@yvUeU0Z@fN0nK?fwU zK%IyUgOBl8qRc5!u7Wi_ZtkBzNXHTeza=QiPZaL$`vz(nWO4ZHN3(Ji+kuHNmvOHq zY9Ai*1xLpH`zr#Z>sBNz-5}paT-dKfK-Q=|Bm~T_HVhN8U}>JR`B_3*ZMaVk;5&4= z#=7U(Rpz5dLx+bt^FCDO{b}nX!oFJ_#E?biKf{i*RR2*_PNCeGVO0N{!IH2=J~k%X zy7ly~=x`y6i)E1s1MmQJVjPwSZpl3-i%=*u3cM(USVIrzw0W>%YVP}V<8#b_)9cY*goOl3ySccyIBmqlc7D=Da9)j9XN)B`M8LXU<=f4@Kg@5$%*y)gCi>ew=*?<9 z80I8ep7V=7LmJX2n1XRffus4uhb>m2^i^gW5yB5`jEtLOeX?tnZ(hE<`yQr|na<{U z8eb>&KQw9hE$BP)Ey4e*&7M7bnhY6v?|Ogj1Q1$MEy%`A4Gfqc+Acn zb2e^>?5Df?_7wCc!v&=X@)A(HLBsD!Y(v)Nancy4<$)RNPX}4h$NeDti3ykqyaed2 z5!!3-)zYI6wy_^j8t)Z+Okey#^)+tdewY0eCzMl6L^}Ccct%>YsnE@h5 zeq!Y5F1llh28a`R{xwXnUbY;23aK=9V+1whWlO+|7p1dwPrbanh~Pc?@eJuA)V{hN zevBz8W46-j?i*hTpKC8h7o_cH+o`|l!PI_g>hjr~C?ShjJ$}p_oAs1X4Lxuc-lZ;$|x=D;fb4dT2X4efy5pGaWkQfwg^u zx!@%Qg+RWX_qT7~{t_)k0YQu&6JqM5F3^(KU|N5g5;%mf`4xivI3)1k|sYd_YGakeXP6mJDcuHFM=KT%fWZ|0;N8$1Gjj;b#O zpbSR9Y?yN8dXm~>xU6;~CZ8YcX+^1;?5&_k{{8)F;7QdoFn9a;(HE-@gK~hg#BCR? zjEg`(m7R4U(B#{TKE$Z^1oe)lnSNFlmaW)Rs2Y6x_U$7x5;%2gCy;Ih?Cvi@L)p~w zKi&tUDd54R17r0tvKH!5xD$yPk!>G(!0~hZy~Ma3xe&(}3j+a&V_-b<+?3;nR-XA5 zjDuVT>uYMt@OofnTI4JDWT^3zv$N#@c2nzX_A(YHsdp?cFGu6OFgWnmw}m!N0iw{I ztD1UC2OAWvrCM24_11Y~{c~+?pAQ41Z>UPFhGMt18Jq*E^Q z5XuSq>9TlpgCA1}bMJSXUvG(-$o4k=bw zJt)qEcG%e3c-uJzOs1^9eixK#|5Y zxu8$s?5~X!A8&6x+C~%1HpyDzgSa5|wB94Lf7J!_m<(hKKcX_*oN^lw*IL zA5shoBrM>wm(okjl{69*W4-`hK*oS6AIgethY-3)rNn_9LugHt)6->s66@}$^!oYq zisi^fiZhf~sqQsKN}(P<7;IoL4p#h)as8ii?NLY!KL-Y$BE60B101$&+x7{IfZU1h zZ^JkaxZzk79|=kE+B{uBLBS+a_*y&qMinBJ=XUw_2*GZ5JJ=mbL**-}>8PoX8FKu` z)v*l?MzVe;3wc@6+)M>j8{Lmk`h*!2p`S)9?&cg8cUpCa8&wo6vTPc8wltC0;z42iyCTfzmZ%3aHvXnuSBDirk zfv7KCRValMv!>5ld*91Z*PErAM?vKzsZo2YGlb0AoJJg=qYplFuK!v?k8IJegFO)%z3kEI8Bt&drVeK{aLTr z^gZ2qh*_-xZXK9!bU;KF7pLB8k7W?cPRpnN2s~LXOf?jwjCdX0=4FIYTwEMM%+vrr z(+h8GKu;z}FMLSM>b|JR(Y7-Kmo8sEz#;9VsHD^c5xg#pU+ydUXC?`!a_Aly+HoxL z-$zfp=uPt&JoM=C<5C#~P#V>;?;ldn)IUejv`Ov5-CcU84^5z8(YAA{Tm?lh;6Z~p z4^VkLet-$Rkx<}F>E*^gdS|U8l|3}7i(%TfmNz>^@to}f)NcOw;i|xZ-;+P_RnBS+ z3=GJdfo57pN%FvEaxHd76qLa@nEk}}iA2aZo*LB~hiGX}M_iFW7+>88y4lt^!zb4I zM%OPYFHZ=*mbZK?u;ZXM?faa&4xfv*nIRT0(z@Y9a&_n=+>8ehCv`Z&XCDjE^5!=Eu9dAcxDHHiO@M z=U97||L9h6-#+d;HPrBiE6p;9kZ3~y040uH3;_1UCEK5_7qrFUnNUBz`FV2Nr%C6Nse|{4!yz-F2WnXeh z!2JMY;4?i62FKM!N_4fBVH>GSm$pMlo17g|N^Uuuc@({HNZ<)Z0=!&;%+x{EB$(x> z-CFMyAH$vM^UQdZj=yiy!TDB9OZ*!`JTRoR7kU&RLO#dy;FLI!j#%k_VyFO-V zZGBJuP4Jy6opgu+l(%l(x^(H%7b`Z`ODxBaZy`)cXiu4%J1DE+y!e8XL)F$}Cq7U0 zRq<$-kl@p*&0&f1H<e)1!sB^xI>nCv3@TU5k4S*H@RK$E<{5vX~w3 zdL?lA&DGb|6WuP(Ic`s%-i9n9pAK=%H8C;q^-@e(hI;qOd*N5%zJH8mQPup>XBIcp&6mo_*1+n&#-0ZjXnqA7wg z#HBE6d<^@QyIit38sLu8AToAEOtiF~Saq*RR#?}77QTACDwu#72q4-++&3&V)B{dA z!qX8wpfd%yhdF|a6Vr*igujO6iGglw9}pvN#r^?Jx*LW9{QOc-{!t}2-q}nH0i(xr zUm@A5@69FwTzuQ}W}zKFga*l!r+W?3Ij^7V$?DZk)*N1l;*VmP5M!_({m;0LIif6I zQk;O_+m8lS=c3^1e|<-;WKSGR!TttTy1Ka?5f!BeG`(%8q%UCFEs1RjVG(z(Z)&21 zAL1-(_tiY}I}R}TLI#69iX3Qra;i_7n0Ejo*ep&SLE7%c%|q3d$q+fl7Ct&U`sMYx z&4fV=#zBI5)&y}-z*0%*_!w8fIEUVXG0ACSDuIedjET4J+NEL;{25IQS-cqq+707q z_d;f^_gCL+BDxq>hZt(@-n|c_}7B52roI0jDj;J8!gbu1TYYvB-zK{%Qo#s|jTuCNF9P1kq7-bagjVQTaC} zR>r-1cNoh-O!zKcDuG^Z2D_l7q$HZ#w$F8S-*V^6^l?db5*O8P-u#4>0CIK1Q~*2s z93wJZ`A-BgyJM9j2Lx}OjyVcf3|KEQVZ!v6TRe`|oV~j-mno{H5dwdSaRc*nz=$NnPE}A3uIvg24}joRW^N zwqpPch})zym$|Su8*(BX^p9}?Y(5=nI-3zCtk+aFa?JWJcH^X0`|I;=JN79b^(71m zj9$BF`5vJ@OYS#FLBEKHK^-XnrnYx+aj|wj?F7a;Kqp)Nx+m~D`Aa!=jLirSBv8Q< zsAj}y3uYL%@bof+LdEoWIPVDSC?%L=C_R z<{4KVsD-m*9l_SmhM{L^<2=su+J5=59sSrZkko!3OoX3T=D~Wg9n+&g*3Io59dFUF z2*8Hp29HgPmbSt>f%)e-E35gz^n$cB?r;fbMik|HjKP;LT{;WD+JmuneoSj+BTNk5 zf&9uA7Z>T7n(l!-tA=cV!x$D8e3+EH{7x|904D**p^4&+%9qFGl;1aZcG9EmJg~Nw zMig8HXK2iS92ypO{>|0H{QPq>bDFSwqX>v=bs(E$g@0TRMJp<+s(LoGw!Ex9f>8mI zFVsq7wH^JSDM5*~w34|f2n-G*@uQ-m8ZoUUVwQhb%&lfh;jvJ{>wb!()Zu z1^L~9+fg-O?ZeH%@zn=p5$zKQVxrM6)eV?}`G6Z{aM1wi@yZGNAVk6M_XsmsQFIVc zqEB!F5Qq^RizjDo^apPy29Fp^-RtJ@qc(xwC2y8Q74KS}5zjYyg$V>jGUcKTgkYQX zRUy-GOsvUTR_R81Ud=5w{mz1z$c8&TU4ca?L-YJ?s4T53ztKN1P-*ED8X4&e0lW`R zz!TS^F$ke#E{dMkys4J{?bdr`Hnp2K<*wFmguZ(92__%w^xMLX{sV0@lar57@4ikn zWB69!wD$3;j|yRy7WOzw6mPaN#Bwd^Pe+`}3C^oWN}0j@l~a!+eD1A0k;|}(hc2%T z9SN?@gOlL_?n_l<0upH+=7og70wA~KY)-^(*E}%`SRp*~)f^&&Y`DL8Xn5*G5FAUtJEVcc zQ&6`%u?@Mn0;7PV;^L7jIDIaJC<|P#gpX^}+;k5xSlz1?tWLq)89>sRnVCMAXaff9 zp;8m6oq~4CKG#!P`dIGDm4p3axlU`s_q4TND~j!BSN?f`Q{yuS5>yM z9*F6{Uvd5xKImHaW@GIo2htJ_wY0MxG3+XEZ^Sxb>bN}!{>)HzhE&LczgAaQbI~{g zEh12>u=v^yDwz0>BZX-f;9RJ#6T)p)jQ(Dt=%+YK zorg#c>$m>YT*8m?hfRgta>XZI3dHrmVchVdq{2!4W_^`oX_Cp z?}rRR=B`6)8#qBcI;+c~I z(r6G4EcGH0`8;#a6+$%_Vg&%NOuq(tTPIPQgoDR^e2A-bTs_9Y;Uf@*CPs{RVt6nS z)xc3E!VqAA0oAoIUNNx<;#m4%U*9L>-bo+h))a=B6&&QE8pnZrTIXAFF)?OHnL(Tn z{fuI`#@dLI!Dk48AO&;4f;Az>Wy_-0AT4odISquXb3y$iMrnk6jh@)UQyfK-i#0We zy@GZ@Ktd^2{#rs1X3A!O=L7qws6s7{v9OpEsZv*0r(83K5uE4O!InhTL}kK-BY?LL ztn_bgZvHFi17@)I4>!m8y>`5_cE9Niax``!4hsMx&5aW~cZX+Q9F;znI)({{`kDlL zHo!~lI%X(FG2%fyEO3Zsb;RlVJ)rLp+IzT5kh#`0oFtc^sMp~GU)wlRPSXtV6=Lpa zM?j0@o+3+z5h33%eRdyR=Qe^k!~J&v6mZBp9_U?=RUv9!%Xf^ntBt76gY(CwrZ#pI z<6;bA#4)9hU66pqA$fkNP00sM&QuJpzMv#Vl&^R3(f_sMePy{E{+aI&T%yT}`Osnt zjDe@jvChnMr<`}Vxd2Nj4Q+db3CfPsZ2fX*y2Sos8v3l!R)13(U#1voF1Dc)w~+Vl z-LX=02LpIhG%#unb#B|+SEZ~e##k{uN2U!)iSTtr%ZsXVY*2eAp6auiudlHpxWmELa8Ty3(9r%($W(7=^quC+Sq33 z;b|g#HGvS^5p^>IFRJxA;gZjT#P72b9EG-MffG@`Fp3d+{pT`Cc3Rqr$-Dy`>JI?L zl}}ouug<(1g&jWdfP_I$QDLQ5$^-f;kfLxS0zzDdyytUZZ_O3laOg@Bc10mVI8aVT z=9*9=vNdp>MiYLxSc`@-;lCpl7=sGd=tOPO-tq5(0W^mNwX2Ecl&o9->Rn={)EYBX zABv@4;@mplPn?;fZH1arb5r-6f9pe?O+ZKd0x*w`14p_HEFQxHIfgcJo;&-y5X3)W zD-2D(|pv&18-Efcwu}y zJ3DJLLOg*Tqu6= ze7_t}*k~6PjJ9w@t9^Nk@k{|#Z6Gl(ZN;IB0SBDUPbOchf&Jsp%pyrGAw&?v*OrFh z@bJ31(H}}N3qpqvpG{l;N~Yb_0()?*IK@;~?0aH5+43F7agZ=&*on~PI3KALL0{eV zdX280e9TjF5GQ9b;3 z?85%vvCB0y6g)H+o_8=ndIkm+LwihE3wU4)mBs^KWXB8*afCS6c7{dizQ?}fX$H+K z#6g7~rs8Ip9sPt(ZJ8Bl-F@YVeGLJp_tNhq8MP z{Jm&n-Tu$WNMZotBnS7ZLbQE>3gMtjNJomVBn4ov3T7L}OH1ooic+_4Gei8Sr@r~& zu0m&_J@M3lYfCoujjzu=A)s^YMk<~QP>ROf((tgioc!IpcaxQ90;IqckL6jEM1oIa znq2{SOHg~Dw1X(%(Z8Fr@q@SxObUs!bC@pv!pU@{L`|Hs0~zM2;8aT^!IBi1p<$_k z)1&@9MH6|i(i%)0mcW>d@Us=9Bc5rnu!6qLf?Oo4IPxNhUZ#`;!yfYF8A|mVc)8dI z@gSEnKt76s6#J>(EtuUZo8)loEYWSl(AjZ*`w=wBAq#Vuuw5LU8p$D&Ac>UIsp6i= z-%|!5y`go*@m2QpX!VIY7{f+-(8eS|;qv9nZ8+C@tH6dhXk1!RAr&A>2KD()r(B}g-LV6=w)Fr3}RE79tLi=p-#1Q0fQLBjDfibG63TzM#XK+i_p-W^E(wk!Vcj-2M2gjlMou0Nm4AvK>%~bC z7$J1*>Y+|-$@e8)U*hn5cz+WK5q{yKw)?O%DkAq_vnC{3j3>R>Fe|`A4`_F|ogWL= zBH$r$R^&E1CUIy=IYr~fm;+R9%(RFn!h~q?0wg)4PRTS)uP#}{3M#BOCV26)8ZlY= za27AT|Lr){>!v<7V!q+EoGv|0U?0qAcq{B|Y}_?`mN7i)LBn$+q>R}xVz7xPt`G)a zr;RmhumMkHh9kXS`zO?KK!dQ@2&AMrwGL0)r^?=X*yF4@Ud+j8f2z+tY2m{@qM2*+ zk%oYb9Fe*X4_9}wb0b|`gAX5M7VVF0chN1_bCOfw(?I(3YUP8xDXGXPyyqKKJ+l0lf3d>IaKUjnyyh>0Fyc!TNic>Mc6<~SjRXLqDo z3|_8gVTKF07q%q0yWxt%u}8A~Q*ghO!VNYFmSNO+9ZJYvdipv({S6R2job(4`og2& z0o0uvZjn#NloW=z?>1$j@V_Bzwt-Chv>*9+A<$zh=H5*wS^=dX169$%F7Omozx1G3 z!nL{2$E)Lv5hj9|3ldU= zOc8$S7Yt&9K0tLBw6zc8bQzbv6Poto(h_mNyC5C&+)^#)wHUJoH2Hz*o6vEHGv;4l zCi5|;#Zg?Cu0up^GcJx%Ux$!07$F(~+bLS1XC!E8Z{L^%l2u0f?+ZAwZkT`H9AC-vWDQGtv zub*|lBYPKqbI`|r_RkCTo)1v#;F}a^-qpY$Y!t!Qg(KA9j{)< z0!Spz-O~t}zpFG>Nxj8@@#8)9OzzXC_Z>NMgm!RM52Os<2|Z5+|~xYIt(h+2;k4 z*6F9Z-=wCd2D**b1h9Rw9F@x>@p!H_@_o+Z$Z*jH)B(+DD5Q7*jW^qOXeW5S9CaRZ z{TG_%;x(K{H`I)iLQrB%5)WyUI14OfF>n}48)j?NZ)DHAs!})bqtmed*`%z4RPiOoQ;0#w6^?mkY7Nc3X;7o>m`ib`#@0l zsi^P;a%tVl>`DkQd+?wHaaysWI{*>&0W7f|?`xva)?jlcD-`;GDnoc2l}2%nj!mr_ zH^ki~IssP%2(y7D)pRf~@Jy7{MLtn+CV0H2{wB&$s+2pvmz4Vua{_z4l zgS$Pxt4Iwq15#*t)idijgel*n6}GCdh||g1FpbHt;ryUTb6!_4XssKR(QZLtZw!qY z05N0cA5xAiS>SNMvCs#cnPB3ltBP>kE+(4;J^&N*gST1P4uE;z3F8*T`8JSOgA^T!&DP3I?y)gK7HM$S+1UwF(S#6ez`zpVGR`Y z&r4!P2+i@1=NSCg4O(1Zkq9mE*Dk!3vVe0QqH#KoI>HQHhFn3Z{uF=hEdf7~dE21C zZMrV+&h1&2cM&YCIoCVozZt>!y5s*a_1)oE_wD~El(v-;DO(as!>H`Ni4++rGbJ;k z6xr$`$;i40$qE%AmDv!HQbuM7MHyMY*SqKYJjd@io469k=c4N*4-pbCAj)I1&+)4BkUx;#rCB zoNI%}Mjjc#$3{&f`upMa#6r)87*lW)FV^uh&!kR%wR)0wnx1#$n?gA)s zGv6sECsDc;E4=%FJ`x!y-t;QU3=8@}1gqS%zt5ib1r{&MvuEpAA2cWkqfnG5)+Y|E ztZhg9w!tjnFl0r{uM#%3|7uD3htuil=`grvYHg8si5FNVRlL67XTLGL5~6B%`3ixG zQZfgKkL!f43JE5v9w_NLyj?F|EOZ^v$TS5`Kr&LsPSSrabKjL?l)cldyex7+R`WyE zo-krYK+|^M9H^PJk2~mN>A8vvXCw9S4N#Cj*mnlY-63DP>40!PS|QxCCJ)Ba)C8h| z$gO*}=Fv9j6>uA*wKYR;HkdR+p3k#uy?AbS^XQRxQ%E?=gzhyfKC0&j{#jN)*%N2e z_B7V=bG0x?Cfs%UPo0emwf3QYm&ImD^@xNXJF`X>X)8^#SM|-YxuJvWuh_2%-h$9J z5BZOP%2NWEr2O_)Vq!QnY#9#n0I}G zgA>Vj8b7xNkAs`&jo8$8@N^ADMoOwgZ#<}GreZpzw9EhFv)skmt;C*^3qu-YDO!cD zPoL?D3TOZdE;-%6oH=!p9nvq{%*b%$h4wH6v{DLO$^g=d>V;S{l~h#N8_hNEYbP+k zaK*AAR(UkoRkXVq7dcU4rNl2Y&!1FG2%Y!l=JLtGDQuZD3_6zCNRdeC%>R1@Q1GQE zu5Y~J%QOYrR^MN&7~^wDr?R#(i+Gj9Vgb)_9Y;w_fhSEp8&jhd2T%7 zGo7o{wqOD@MFJ89{f>|A?Pty2&f)F=_WiVW4tM6=W1hf-r9Uv;8zJEO)Vn&R$02gG z@B?i{SKk`})pDptd9b}T9{jThgQv>eR->ZA%dSjlKpT_qnsEITPPaHuDQ2eEuLu(; zYF4Zk;IQ<$Il;F5P^@{u8fNGVi|6y9%?eu2mE*x}3xZ2(MA6C^XBEKPpS2+sYs6po zuIl!kT8Ab@(1FXK=fr#3*&&sX7vZRN0EwaW%XKXWhVu$0=Y5Ul+b)B&d}ebB?*Ie{ zb4esro44$Tn$VPz<^)BNMjx8ND1hkV1NUS+^MqL56bJrUcv_&tQ(RJF+m(I1jq3_+ z3iv0juoWQ{DK=-$2z;PB36!$cZpZ;Ut*g@w%4J&ole$MeHgqj2Nbf%C;XRI!C_osq z;}UnQx7f+an~C%F~#_;^Na5&#wGAplC1)^{!-u{T)y_0S>KAZ!c{7FmpZ6DoHQpA;{l+ zX%=20=;VRa4FP1UO1{eAsgMCK#Cg*f3(bRn(4)L__ysx_*ZTwVi=aUPH>9TNKe*!)0l89CnTCr4p zvBN9^TEteT^j7{=UD-tww2o$Ds3Y%sUcC+9cBtPozXtI9!uM#aruh(pa&VpYLUNnm@9pt0H#>+h@o+00id58m_CjQeHA>;&o0D&b<5Ke ziW86|njz5s4nz95anmg!1KcNY@L=5V;-=6~LwA#ZYS%J^HkEYZQ7I+4jRPESt<3DR zzjf;tL4sTo;jO|c|3F`i9qh-TxhM+_%7D!2m4pmJxpw^k2m~X_L=P&+RD9@X7xFDC zm=}F-*r^hjDv?+XZ?lHGThln6atq0;TDGp7DeLk~vD@y`pG;pMCo5Y3-`?Pb&uHsx zkess9L|_}BuzYmWeRu_0L%s@x9ESQ=0(KE%Yi(;|BVs6?HHIuN0tRG4D;;Z6M~9@X zt7hDOWJeA>-W}UrPt;rn|67|wxV^Q?M}CjC>-KR5A3vA2@(O?phZxnnz|^9LGwVRs zrGxuTYm*NyEzs(}zxsI~=j-l+qM}*>8cPom%-}x zH{)-9{1~5;Z8|*j^jG=Bp}kW@h}yf4P)wyw^9~ej=v>a)q0RayXc z8e6#(SECf;Srzad`s>=(yhgebOW5ivUfknwIpL(M7G}4&u*-YA#P5fJQ$pX@M=HQG zh{;aW;u!}RpBuQY0VHWIRX%#O7seH%-J-&b&+2}=5Gev~vQPolUGm@yGj)wKfj;tGqcOk&(x$SyY6J zFGYaK$PMMvc<})MO+?Wz2>C)Bp!hS^tQN1By*!MiTbYaf@r{~SiX`a>cI>cN z4Ka(5S?4r*4$7%g;FZIRGX(!Y?MkUV{Tso7{%xne8k8-2OmuNUdL!aB<%v>dM-I$W z!TlFDY&&>#(e7h?Ev9RQk@T&CH;|6R}Q~JcrN!wsMyk3BSA2daH&x z66WE`Oa6+6u=?;P5sd)x4?U2`)XdDV0nYSSEA``)5x^Nz*ibwGxWEj(_{IMVI)D3a z-TNP`P*_qUUk)<3FXpPG-8Il#@o=3sO&$O;Sn+q~q`NgqU57Za2M(PyX^pg^!$OX) zA?K<_BDs)EP)ch@%f?nw$(_?D8EK%g7JvQjs6hdBai2z78LS&QQ%=a|q>k6cbf?b9 zYrnfMu=BM%aVoC4PaCv-Z@P1qk5lH_clXEp^rA(JuYYW+q6}G#)~z?4{<>Echi(`O zV9F6(qpCPvMv~1A_^S)H&o8HM|HD83XRCmzz)d zT2Z?1BEJZ&PAb&AKWAoCkrOj=SUgr2os>O7bW0jj{***ghVBjBvpUacNtTR0w+_u2 zvT|zEuvFH88WYQTaQsoG)1HGuA+Nx?0tkL2I=!TULudW=!=gE$$=OMlQGPk7nGV$N z#&u3or3ou+%s>n)OF5jfNzx(0>1^vT*Q!gC{UQ4Mg|3$1%*$~br|I$#g|Ih4q?E%} zPtq>AWp^>I5yTk8^cM~s&E4yTax2@h^HeHd{+oMpCtBjd{m^e2m&_pfAo1{JGo!Pi zuRLg=2F=bI#2HVi%lPUKRH(Vk-Lb)jQv;Dt#*Z@CNEz0#V=qco0Qk4s&H+$>+(60Q zL12SW1D>wBw5A#jIh+XeZK62rr``svU=xgG{uVjmP+2!#tm^#MWPY6!3EQ=3l*&2 z;vW;pV|k^e;}=9{bpgGRJO^UM9pp7&?6PT0@SU5qLb(r0NFKXRP1!Q02Vab6k^pSk z{Hh7(a8K<@p0#+e*6h@%koUOv_!fqY6+cl%yph~-kDN}$bpJW9*4pSJk2a(@TU2$X z+jAv7{f<+WzG>19XRU>S;a+unR=YA>BK%|Xuv=P^LWFkYX{|LG*RFN6KLM1ILqDO< zbdZB3HyMgNw2Hwat!qQ+uYmT;a)`RM+2MWV4*6X%mLGukYI2*15v_2}t*vjm5Yeaq z79d6e`ZV=E$%#7nPunbQX-Fv1_ccvBl|xeyTPfoG+Y@MvKv|b0pE?orq{Tzu7c3B5 zuMTm67Q3je2vG{H7^aykr$KU%f{`Jb&PVI?76c*Z792i#@+9lD64$G;3_QzdW^oWQ zh^=N%carG1lvz|#QiH=$y~&X5SLks`pac5T9m2xuzh%(mK5swezx&36cqP#bzquT` zWCnt^%HByzaxRDfI2d;L5xhuNXet=K)UVMv`wdbmNckEpIU%v8UZyKap6dSA+ZzBN zZMY3t7=g0g>oTBV&*}CQZt}n#Q;Q!k{;6`ATsaV>KCsptUMvRZeT&Y%O~Y$xSB%^( zw81AUeUG<1K{Hnk>|WX3OzsR#aB#5RCl(cFp`@oYala2Gmx-lwhsD1CJ7+Ta)p79? z?dy9!;RmIY)Eb=Yz|+`(Qv2RZj`S*w^U6t%2rsbhO3a@B6_OpAvd z;#yr)XlMY>s|l0mm!3$LJij--(CwMml6HUr)x8RY>osm2PV) zp5`SMS$cUM{%TlgxzOP>Om(AbY|cM*K=HKJ9|XBuV*^v?$8au?G>8`NIOs9< zyL36VjIYs99Q%=Q>sD%kV59tQ=F@K`G7vd~N>eB&eL+Y48_>2{NK)`s*Vp__$=!|G zTy1`x#*XQ)F|o0kURHD(l6hbC?v0_6X?}R(07AC7;FA^c%HWPIPF4}lWPHx2oS1bn z;nG@zKe29a!lzR`DkU?|2N&wisAt!u@#CPmEjwd&#N&C<5O?$eED&g<6_9>`$Se}| zU|4>7-?KWUbSP#_pStpcCm^AW2!%a1DRa=~DMYZm-;b?~6=$&-G z;;CxqgOcJ3v47VW%j@98f0a)V?fE|=#)&eXI!5h~t$se`rYFPnx|2SRc>!rm@{jUI z8ci9{3kHXVlI+c2Z6>Eup(P;lXk;U-#0MhXMs+oCo zfqcfp%L^AV{b3yp@d{9Fl3-Ez6_x?*fYy%Qd0Svhda8z;tu6 zYCAi*!0Abla#idk2Wp#RZ34X8HR#8>pIo>WbJVu6zhcAT*`r2NplQ@?{C+p93Ryfm zs6LO}`|2-WI03&4Y!0(p(g7xG{8)YXp5qABsPHKYj@{YUK4Pn=(+i>KuD59n6n2V_ zhuayA!e|>w{o&(NV)ub3T*=k72%`KXE|Pp0Cb!$tdG&K#JZUxU=-vhY$`DkbV!12F zc$e?&w;KkXA4Cz9PzTuQ7iL}%(*&LK7p&iHO@8&?B ziV*RDES-%jff~l_8^kf%GcaJA>lh!za%K6|r*2IRinEasD>9WLil$6n`F)@v`T=sA z>wAb=Ij>gpKSx3O(<0Cp{;`Y58X%JzgwQ=B8)@g$;Fx2D)Wu?0{`9p`Bx$J-vb@@%7K9!i-SDAcDGX3(ni;1^%2gDfOvN1lBUv|+Gc?nE~S z+({L_VgwKeqx!i`YHA^z%4tFt*%rq`Jz2*ikG;dt#Fw0ZSz!tO&l!zCT(!=^KUNWrnu_8zW!)b>7`9Z5;*XLH zJD8^QFo^+vFBU-b^$iXB@6_qZf(72KuZ{jyyQuWy`SUz-s%Y|cTb{(&c(}P;hbNDE zVIY8FDfTCB%b4OiyP+Om+y7mx8K3soJ*`_vz&j;=MtpNVHuHT4yrLS!k#}_+6^;#l zG4iKsAp#{_8&RQvoY%{py$F*Rkf>LVdur{n=!>-i`MVuU{?|FW=f|3f-XTjd&j00I z9$d3)Uz!ph`B6$x=9;n=`@JBwCd+vcHnlI|?Iz49jex;2o39e~0^Z9J@T_=lCH)-r< zlU7yXiwTo6Kl=IrODg0akZkOhjIh-4yD@n1WRSotNL~_GP7I_YX?ZKLz)BxIdI_FHpQ^Sg zy*3-(1nfSZXp@fGhK3NTVR`zaM7_&EJf1;fr+of=LDo4iE=4PUFOoFZKO?s-B6RM* z#EJ_qRX%=P@Fr&vI{2%IN?}IUNi`0WpD^KXJM7Cr=rru2Ahcz# zt;wc<@?!s&UghxpDPLXY{;wyvjGjRK#?~1tF&|U1=+c${cOqIsv5#E1&269q!=9=0 zvpJmqh_z!|sH)A1^PDO=%@IU0p?gM0!vMqLiZL=|3(~%u=%9|>pN6uFM6AL|qdoR+ zS#SQYnSray$&-m$wMLyr+MjD~ORR5vM%Tq)tajC4;ng;As!$M6H$=J-GHL@Qa*H=Xhk8)fkiaO!BCj`1~bp>$bY<&fgyAx ze2h+OuJZBY1CS`$#&A89AAWHz^6F9RV0YcmIOFdHDnbhRV5S^6S?Jg=AtH?-!CnOT zgd9#_v$p;UL%F>^-rieEOa{TDLmc!dVNH;NwyE#m-`Owj2`Rz~gF;vDL=L(tkBrZV&v1gydGi~^q?HK`R33)|3LgZxZ|sUp_nk2 z10T@}WCI*nHAuIy{cUBlSU}FRc}v!j~Ryzlc9(Z~iWB11@-h;TSQI9XFh_ z=c#5#M~6-|T+IJtbI1D2wju8HWFS?kXyQrKK(_fUwk{h32Dq1I=jZz%IwvIr@mb;4 zhLVB?_mD~i`VZms8OoN?AlIq^pNEommmjA8emeA2kZa^}OoAsV`oq7SrxX8I{ac#=(ei^_Hq&5kP$Un~&T%Y=@knY4`4 zr!V$n&wTGF*#%smB&ZvfPwi=~tORkB(_zT0Vd;fl+xVxFjK`L~)I4|8415uec_C|; zU%fx-0a}D4dZJ7!n%%LA4#wX|kS12RG=$9Mb6x2Fs|6_A2ONwHJ0nHnF`tQjr3r~f zqP7+*S_b!b`xiF=gjbS6wk(qMO62cz#VTN*%lSIYBThRJdxmI%pg2SiN5FHrXLWnXy%s0N2m6cp3Dyo^R(_-KvjBV>?h z^ngIu0=poX*tPBilKxvRC&{4rRQ2rX({Z`=c@)QWhBj|UWk+Vb#uvF9tn-Cu`u;&& zUkh_rZ6$4kRW1cE-%YwK+}q)Kdcq9+)d#_#L1ePGgI$WI5q*N)iM8obXb@5X0-daA z3wR28gt!t>p5Ew*ZnEVOZh zqfv5sKT9&5DzFTv*|)f_jf{xoNDN3PS|_-!HM>6YIQ!j^w!GA#WE>u>Bo6>9 z4E@)2fD@$NC+RNG1e5wPy1fV}oFWvUyU+M1&%|k6i;CI+H&8H2s_<=x3=DQk|J*-k z9yu#iD_uBU5+qzWebHsC&Sh2WS!c1s|BjEKm#d%ut8U`tu)f&VrO;gg1h;Ek6WSd0 ztG!hVlVQ!JS)77qtIk-9-oZm4=hnj9RHjFuelWU%R9KwZjd#S)$;4by)~J)_7r$*@ zdyre!>!`+$6*MFR$wqUXPKgn@6k*4xVX=T~D@@oh^ZD!7Ym$8@S3^OYnkDxz#iL!{ zF{$0Ga+&7i;x;MxnDyUc>#W_HV6ZO>8eu$yC-QxccVS)#byz81P%rk}y1^YXVWi1- zEid_7aGjurXY&I*y0N@4bR^S5aSA0%3RJkKFT@WnK7zb)&A}7TJzpa3RLpvV1p&V9IW(RwBKj6T`jY(Mq0`1B^v1wpNd9-fr z&j~8Of-pDYw9in+PeTk$9sfM|iEVw#{30NkKskwbd6cAYUgHw3y#oV*E>(-{@G&R? z(o*k!itt^W(rUl<4PGgkkhsf?dzCa4sCr`-zF2*?kbG(S!VGCw$6aPzA6l;-;@0y> z60F(qw7K_ddTn82;c^4HIzEObWpi2n!;2)?H6$PE+*hpfTV$QdKnOb-E-*dOoo_<2 zKnZz(9!K&M`yc*@5|2FV804L8CcP))*}*`a``1uS;l@XcAB4B^;y>=;f=7>d-+n`n z=Gqfa2dp*)_AO+L>~+`%6$$bfkXgzFU~0Ln)>{5f0MB__%fO8*$;h8HX+!#n;}<7y zA7bI+(*AhK$47JP7v|`+wKez&$QDUr5y{XdA@4YQLO)>;-b=gyB5)&4Y>vaePj-6b zvSAU$^zC>5`J^Oo4?=TE=sx_71KDV9s&Pj53=OGrAAk}P+Rij-&BcgR1}WeG$G>jP z0-QutD7fys=O+SqECCx~;)^s5;pHw3C8L`c@sV{UD~T9>RigU(`w1q(y4#EuF#%-O z2D76ioT+S8wE2D86*}2Xh-;a!~zkV z@|oi>I<47*APsrY8?cY(m^=pT0BN+@p>Z!hMBzQPVtlF5>oxY3c+5fd`lI-_79?QB>a>+vSsyXV`ttB}0} zj}XH-T*KKt&B=N!bhzSy&u+=`g9t{;O1CSjg&agSBIq8jK`O~3B(w@4KO5UH0d6H3 zwLq+DKXs1hdPk}6f_*p7_j&;YZU8Ji{|m2TF)wE&F`Y(=Nvn z-*H;^kKU}fe^&oV68S%#?tf*?8Este;1&6Ec9|CREbpJYEdb{v6(0W*{ngKbuJ8;$ zi9eLix;)q9zmc0;Y*+>+cub>GM4Az)fbq>=eEIU_`}jGiaf&)tuH)Z=1q2iIj$s)x z2N3_+dnmSWI;Y{gBh*JSr|2|nT!J*au48HI+-Dgxv(9;bP%~TYoHN0SsgE8%CQ)?! z5zdipl-srK?VBMTBQQ=^ z!k>IvL@gBV^v8{}>x5)^N#5?=S3$Os&rU39sQALwfz`I_!Q1GK^D6ALMQ z3QzvG>3Vbq%@&_IQW=ClX=o$hGXNLJ*2IJI+BBKx3dF-%iF6xE=%Pw8J{JoNWE{eY za#PNRpF9c0*OA5FEXTXaRMfx2_rGJ%G^76AEm){&H9NJ~p4BCVy@^J5aLWz$+go41 z-7H!nF(mNNp~zkh^8qtfDM=+EEZUbEh&Lg4(3T~+|!AcJS$q=7hwtj zoS0E?U_}1-o;byyPckGi!3F_%WHbsaHoW`~pkj{pOSrL)lOah*b^1eM3Ii)Fi;X*1 zY+zism3rXd-u?U8@kdC;6%dO*ky7V-j^3>>48l9S6;{LsY!+Ml1w8m9`Z`eV13QjM zOy**s*CfFb7((*`H&*7AvmHwJKcoW4hcV@P)-i|X{e~>tw?_eqi!OE*qyaa!6++rq z*gJnlhzAHi6f1iU)aLNg0R*&6##!sN$3l0hh(5sf(d&9u#C}M4j-Mp28{trl^*GE<4A67AM%^L}e9l`ezH>^m=tTy)wjZCfs)7njJa#jipqe-)N1 zR5d9k2?$Ul<)Vm49tyPbV=ZSLL6XKf0z>|ND8w0b$49^TO13_uB>_N;YKwGO)V0;5j18@N7&9tnFe2uzmNo%43*^jK!M%Uz-t2xbz2R2H~&3pf%SNp5sS(+=fO zR(a5W10K2_5QK!G$%!t;@_J6N6oBnQu?r6d&gS3{x5V0K@b|~tGA%kC63%VE-C^br z?xeW3#c)dN!g^t@@4{FNuo0LVJ@#9?WN;(GlPH29hirWS>a<9J=EP`6i$ON@n}_H6 zS%}L6Ay!1?MZ%@ma){I5V7pyYi--y$$39+LBp?)MehL+9fFLS63pIxeW|{}j9Q}J? zZ^wO10p{z(>Blr9T>TSv1lc@@Uh_)BW*<16}AGw*?1&I<67I3H2lZZU{l3MQh zL(zhlmlsb zgx1Ib-ufJ)K*S;TsVVo$$jlUxt}G#N1bq1VNvQ8gXgKNvk&z9jPT7(UENc+evWQn2 zS9$n1Lf|f+L4>l9_W~}T5C>7I3ymC@w?GoN$qZc*{121_>XryhC|wIHlBCyHGF1qQ z=9p%~(d&}=w67Dspy)rpDdREeSd0|M*dIf*t*?!;x53=??IyGk29_)M)n1(3G@4Tc zBV_Ys3VdrQ?(4tbmed=RrSY9?5QH%ztk-y=hSlfX=MQdy(S|9S?+9ty2Pc)3VeP}9;fs!lkf-v`~2O|b&%eIk9McwjlO7tYvg zV`;U4o1gh&-c)PYUj^6fsryG zee<3i`41sr@-pja}X6eUlLjgL?!V> z>8`emgjD%~&e_ZqGXELrd?1srquC;qJWMf_@*%9q$x?>&lFq_x12i&6Q9CQSljJ|9 zt}I5NLb}-2$}Fzf2j>UhY^jJxsmdcFqS4xgj6=S;v*$1sFcrFS)bKj>BamQqrQ8Ko z0~yrO368<{{L+|&HK;`0hENX+3C%%6&)sSJ zuTLbvXsLBz2aEiOkOhL-i`fyp_ABVeNXXm3ONg>;^HNgXqxn4!Dqn}sLTxQW}) zL8y+$*u}o?O&nuaR~L1sP0WzN)6`FHuC4)5QBh1?LW%(O)XI>TAo8Q3JJrGkpxZU) zpI9WXAcfEt`FJZXE_ln{GeQ$LUzon;jy`mBw*dlXn7uT5OmFG`Est7UT>pUr_z_i72aC4$Sdb{k2l}`o31%)X z=by9TenOoIfWM4}8|T++SmzZIklDx(2mV6$@?vstB~2_BkBf*<`xA7Dh<1L+)b&&9 z*jA06gzQlDEc4y55|QAd42ss!K*(B`lA;L&Rv%W{^^A`+UtxJexBMK>>;lZhuFn~M zPS*%{((YgHKncol@9&+Dnr^tWXFJJt%wZX&(;8+5Ly@lWi^ov$Y1DC7MoYBA$U3d= znJ~#axdqPS+s(YTPtJd%gCd7F=S0!z)lN>W-rDzT&gK9mr%86rZ+e9`%1o={R4-7=j%lt5)+FoUT;9h zA9+_|yHNEQSuAJ?jDHU9#-5`RYSAHU`ee#VGwrn@;o*G4SxZCoO>!!`pypf!p^AXL zKQ5?f_OY8Q96#GgG77DBozP2mV;e!q4enRc0Z`V8fM%>Q8)t9!_kX|%iQjc=$9Z=9)@$nihaFI0g zaH3`69Y%p+|9E@Lm`zrKtJbY7rd%`AK=0mtaQx&% zXM5(&dEE^&1&p2a=O6$fBX;!7(SvM4A{)R)%13?_Gy8Jh-#Y|;L8}F)f;CR{Mrqy^ zXo~oWL@AtUlARYP1scuw4=@hxIfyFdx->VYaSWkFQb5C!eroRS^t814CYSKJ)DOcX zWDv@V^>7&M^moC+VY*~{oLHBQqHo^h>G0NB4Xj#GE$>ypcKS(AyB*=ORre`!$e$7# z6#*QhuH4+k*d%AKXKg4vQU4DSYWQCX@dK5Dikez*cIV9qEC-C^Zc3RjIPd@pN2m9* z;RjI$Y;McCOM|ossTyZJx*Hj8>-Vv1xGM(f7#J|)cFZw>-V`UVSyun1Q#KjdW+gdU zgFplX)SpZHFFhOCzvU&uwQ8WTQ8&YfL08PF`0L;!7_b4A*6UzK zn5Zyq{nufn+8(O+0CkS>*2bTBU&6-4gj@oZmT5?>_Q|(%5Y7niG5~q)nJK~_P@~jeA{91WA!A&d3 zLoger9J>PoG;pFkmhao!3tM`qLu<$Pm0jm@MbOBEe*cAvjf{%ZKeE(_6t%qg-HumU zZl~es5Hc-DVd|p66$wLMut;exo5tA`=jrf}#7BTp2pd82tkW;9UAHrFbntOyoJf1Bhj!I~E~=xt zFM#J}*(*~PAX%(!NNAa?SiX$5F|B(HbOd5f`Q~jS^~SAm9t*lV?KL5(jfiP&=w7pG z)lt-otUuNKgqnf&`-j+xV zxKyLn!hvSkwIwi>j{_sDc_bwb=v}^7kzzu!gB>@CBVq`z8F@(%Q`Fg}W7WI^1wnEG z7kQ9|LB#-4Mcjt}`VX)_02TOifceEam}j<~bd1~D=;wsO%|X3DHF6u7#F(WMiBcl! z9jNVM`7yvS8)!!_-{?Y)q484;{N%8Oh9G-gt=l+0z)`Nsax*3wn2^d6|4oQ zf@5SWkD&o#Ym3W?R!2FdB!v#yxSEB`^`Yu0)*c-`^J8#OMMLY(HIN(zs%$~)2ext= zXn)p2W~i}t+G7>ap$sJREGe~fWSuQe;+zhfwL?%c$4NP|A3x&p!!-Rz2_$qz(ed%2 zkSlZA-tc~ndre(h=hJ~m5C{Z8|JN_FJ=15z$z(8azGUJEmf?Z#pWjfxb*+Pr`;P-6 z0hexzGqbS~>vHoi)o>2082>>fJa;P>mwXf6RdkRT8Bf;l<7oNSl31qXICgggrG@d^ zSPtmbJ|^s&BLs9VCYZY{zr~q=3YvNmb52OB^v3eY+d%YuVN03Mh>C$Kw$|a|!t4dt zZv-96p*(3rr2=O`NiFVH@OHclS ze@tzByLamaukowJOBkzVygT+LIgLcwDx)Pym1=Vg!>?jkX%Jzd({zuW*VSD%>7gEy&t8d~+3WzpxU7Auh2p?CqgoB zPGq%*u?R#ET_h%xq1Z0>c+1xr6Y~OzF-GL2ktwnCE?qBXlKtUxR@7)&Jp1?*KwmPE z537k`{>(X?jW^2*OfTI^C-aFldUxTxhB%3uqB@zDaW)5y69Q!w*iKkOuRwT-G_*G| z5Qwh^RJ{E6F(f6te0(cWt+^$_(AnHuo&f$Ndc_^2CxoNB+%K1%L@3_8Vmvn2M zW#EG0>%>xGn_fw^=Aqfh!I4!UI07jRV@r2EDlInMm@4oF!&~ZsvO^ept44qvSrCzs zKvJ}P-|3u&NwEX;MBSv+>3ATDoh`dN9X)@1lE1X)oG>)CM~)DoW?C7L40sq-^iQE4 zP!C+$+1dH4S#^7Zb@UMTx<;AZ8rL{Uk8Jh(e>^A~*07?7M`;!bZUmiWSj~F@D3$U^ zt(6_+1iXA|WdQZ!omCkjjM0y1;SBMX&yM$mB7jX+Ur?VSd8dtu8F^#Xm=cf`y4z7f zvz^2~_cPrKzn~Yegk$48JVI>GXh}pAk}Zv$B!X~QptZh%tDj`B6o#nq(z9c%qNW>R>|}03$(qv>VXJ7~{^0gP8bi#y?wK>04k5yL7u5cJj;HHy z?ntYC2HbM)RFOP^uY0a`*nXv?tUP3TiB6p7;TH{Lv#3}1o5^c78G-RKsfpx3yxJ?2 zK588(KQVN9Pm{k3qDPTYr?%A*Ej)-;Zgs~zT-bp|2RG1=h920p@aWBz0=oCK*0Y{# zP78Fp>cc8jr4NIppNm!OGwBt}w{a8VWPVB0^c|QkNUFZ;QoF7)7p(dDD2WwHMzxm9 zkhzJ0&V|e$Fm3mVDlvd$KaSRFjH!Uwq zOis@H7sGli@*Q$64O{j$UW{V+KmJPkzp|V&^itLOnw<8Sy#yibM$&?}rMwcs=oe%i zpER23Z(t#6lF3=K=WpL?8%-gchfQ|wK+MQfLZD&urTGzME#Z_}8EBxp4s*aXP~+8S zz?VySQuSyWrI6}W*lXNDYYC8O+w~k~WQkJ6%pBZ}5C@sG7`3@a%0=&#Xs#-cUv%N zpu6#Yl_%S_31gD$;lOkKQ7$P$y7s~%1hoq{41{si5^PktyPf~3pIF-#_kO<9 zF>I)Dr7RWE51f!AZ*J>Egc(7CzHYDe?KvwW4aqR|)d+~X9>{$|=P&;3k;fx2Ffu{Y z43z`t>2&ych}%4C9Gf#o_Ax;Gq}DM>2zH2Fsd>71Aup5`P;N5<{Pa8VQCP^uf>?+?vEKpW19GXFwCf?Q8^K4!vc^$_^OV?!*IQ-z)Zme|95os61J%(1i z#<(&5x}18l7h$K1JzR$Rnu(gpV*&;;nM608psYYn17LnD?=(Clb2ojHuD(P@78 zL!8L*&~FVY=^Y*x#_gqHAZs@U@HNM+AD&fwxWS#il&{}gDHE5yI8&l!FJ z&iypp1~{p=*LPp=^t>ZwhxnT=A+zGFERse!iwq>&M~)GAZVd2uY--aFu-vjpF6s6^ zNDCqk9JXmSZ}bAftL6b|hkDY2i?7A#4z?1jalOGIK=;ejRevGYdBwQh*RuH3pb92H zI63{Uihqiv>EXxiiF2qwe?kF>$-!ZMu>RQmXQdkay?cD)N-_h9$PGGD#r+n%462I& zbi*`o-6#(I@p{Zf3Bbgtto=K8(t*Dem~+S@Qd6)7{PtituEQCH)Ny62{K-K`6=0Fu zxtSf%!#3ncuuYG2>(RYLE%N8_xorGPR_%irUM&tIyhE`+>*1wY8_GG@#-8}j6}{*Z z&m6=Z!j~kK*R;0g<41PTP5kyaDe~>)Yf#3)wtAI1)}EjI{gTo4)}4p(S&l9E?L|Xt zaK#&Eh~AU)R_SB*bLMPQ><-ODmcMiNZf%cw=ue2mL0txw!RN6A3fiZauU~5#c>;km zsAg4+lkpVGj=l`SP7j9eA$Zz$07weG^(>Q6W`H1HZ>wOpNuWyL>-N}C!Z_Q*nPXC_IUwHjD zcTNyG=*Q?kvu>fv|A^SD@vBtUJ<*HC;!OozomPhR%K5t`AB!jJ*u(fNF<#yk(2WaL zEVMF%qh;^Z!l>&5>dZ=@A@m6<-%0-FnxAtBVk1%V%C&ymaWQOe6FS~W!V1VXL?36p zKX(g;b{M22Q`!&0HGnw_UuloolEk*02F#j;!RadERwzmg`3A>ou+{BbNwB?pHbCJW)$ za5t$nSP;4wdTG`v8-P_XAjDetouC62r~nrFU&BGfCnUqo?HRHq>j&bGV|=cNnVJZ? zIMB8t-mmJ{4cx^*$CnTao4mOJZPqQB0-**F1HX_47dC=@0!B|S*HmKi6YvsDx?xi< z2eSooIa#*!sXojL3%@_;Qs;$f$RuFg?}!>O`1Hshnw$tixl1doAOq6HZEDxrCN*9| z-5BbjpslN`YG?Nyt?v;Tx~eE#!u?Ij-KH~Yh_YDo4}h-tveys6DNGg;nE{hdCSX4S z5TJk=5Jx)(vwGMFn7#*gj}csaHo9vQfa|93S9(x&-<*y@&HSro^C=En&Fy$LwVftS|tL zZw#(=fq9uq^z3Bp1RpuAY)jS=R9zjZ7xqyI(A*3p52QiuM%-gzQHTGof>l`VPY&B`7+dZrY7)U-03>m5CkavWGNVn~2}h5l zGvix@Tl&a228>&{f-9XzKtQF%6FEIWc=(OuA8;$e>%g1CvXT}=FD0fpm(0s%p!ejG z_1XxUkjK4PpH8Di2Mg$++DQTQKT6{Y2nIP0ApI>>{W(q}5V@<-Hm~C*o;T|Am(a0N z%Cpr5aC&}Syt67}%}?^`atLEfVn=Rho>^`C&M-iL!&$-mo(3jo0aarytimO%y^z_7 z;n7GE-eC_Fqh_%~n?_LtYHlkM^dv36kyI?8{nSgX#K`yw)R2dc`;+KJ)Mstin~;)~ zj_#~qhXY7w9j+p>IRfQ;j$j+_bRW5V=eG}z5rfC05Cd!--ok}+X(IHZR$Lrf53NqR z-32-cP$h)ZMkvUu(}#r`P(`p!&?Ijrs=u_=F+Lnqo-h$NBL#rsL2lOEUnukICvM=; zUdPd~)ixh&|19>SdIu0QZWK%h8oTBRrE%yMiP$YY=Z|q-&>4@&waMTWK-3}lm*A}G zi$=^2?-wzTg4fZc289WwyZtgYQGf4l1Mxq9wj;9;SeKGJDt^8(F1-c}2F9|_F0ey+ z#5zjj@b=;c@x=w3r3lP@c)A96W5R{SzwUu@)@ui_Q|vH1mKeiB(yn3!D&Qxd(p1Jb zRmW-}V|Li{Bb-*Pc_IuYYeryqSUOhl)|5y-5o8$ zFOQ@A93CTO`T^i3wZgj~Sug66p+un$PiWTtlSQofuP>S%W(ErLu|+`rX#Ch@DLR;G ztgbrdwxEl4A{bkWQjDz%9egUze=sl+ny9O>n-CoaqlXKH1c?}Wk)&X4Bvm+1k$+jfHbgs-JkWLU-R@oOivN|+4 z>a?1mA#nv5iF%uF2fCz+){?Ln$RhB!$W*tvw9C&J5v~Wnx*#Q=? z*Ll_lX(GulWBaYOO`|;=ij5vDG3s~~Rx@AzRR2yM9vU<=d}A=lkXSV$j%4!r<4JsG z@V|mp*@CM56^b0Al6-cQHwt7vU6tQu2sk2&&rrg256@k1WxJU?ww5F`6MQ*K416$< z8D%A<>rSP3`x-ix1O*qQ4f)j|n0&MR$vQ4+R+7XH>yo>=ID9DkIW#_;CeF0;1h(-d_?77tNtf zfAE$0*tl7Fak1cRRKU2>tdD4Hr!Qv^sekiMbZ7E77nR(<(tnaAL+X&?778=IHExpn z#zuoq0uJnR{1|@n>uXeK(c0TMrl_Fn(K~HcM~J^(qMXl1y97vEl%SpYg>qK^A$aLr zWu0Q^8F@F~1sR^~l;kC-9k0}-c&fmX*2yVGJ?z`l89%f&5g;E&+n^P?`LX^V1swc8 zIE22HYU)6FC`?AX3G?*A@DE96p8S3?uM?2~H;c*A1tdk1+pal<{6b^vJ2!9#qugpi z%wXQ8eXCc@xE}tiI^=JpUJ^fx^mjdU1^Q(87*@y`H|C$^&q=`OT|Rv>k)CQfh!2~N zfAX6CakqItApwAIQe>{~t%Y+@O(RR@;^11;$)O;V)15(d(xSgJp`IEJgg8crNV7)*!}4TiM!!_hh{TPWjEzli`M-bBLf-M z&P`0*MpPws-Ia2}KRf{ZU@kmv>2`n$AyKf;F)Z40en?H z2RCr&Uu$QWGp%7+qyAy1AkEEwJ#H}P7JcsDeWh7@}i}G&_2iM zT8Q+8<3DO^YDhrI6aVE((Z1s=0IGjSb+2!O!YcVI|67A>3>^8s^cqLvvYeky5;EU z1!&>}L0$xpXtn*Z!=d%_=T9DcKuCeOENoC_g)&A%u*C_Jl{~~X;xH9HP)CC?z70w8 zv@R|#B+#U}#10}{lJo*XF4TdGiwmYfYTTY!E%GDKQc$Mxu7UmB7F8B&e|X{sIu?w% z3Zy0j+@E`VbS)5ve|W&#`ud|#kQAa|P9Nhwc%BB!iGMRU7iPke^o8P1&wUQ9YWq@T zQ97fUGVZTzd{6YXnA9jddqhlZJtb&z)M|PnARlJaZ zX-IMV?3pq6MRd60Ir>#X8bCH$QV1tZ%VA4kb~w5eMcfiMBd=Qt;8?@N>CK|1M4LFhZv6%bEf2Zh+9Kt^p{}Y!ehW|R!p}g$j+E&K z6xDyw`L|X7Ho5rLAuK#Pn&v1(qio#1-NnK4k0iR>mO@n4HI|$>1ewt>G`uU<#VJIv z%Jir`=o?9hF}X=VGcCF7=RWLf*ZK)Z>dx&ZINGiwqL>UpQ`ydP8!Lv=G=q7FLQY-J zKJ&;xcEk#U(9NMwn1P)(eWKXT>h~`{9Pj;on5&jm0J!bi4-o!lahR#BmvZ!~Y~9S{ zBr_luJ_V_#s)oVXc%dLi?B*fCuF=1#H>MG_x z)gM0|E46WH&AOFUfs};$GrE{xC2Aby4{d3`BbMAAqU2WqnN>Y~EbpW+*9gUOoDRtTp8d(^MQw0K4T*r_RCZc7VHG4My-A&pG1dYnuHNr?iSVhRY z{&e^be&WtrLkje_Q8=Zn@CRSOtGe>+*`b*ZXMCXk3xD2*;q+rdcw@wQRFa<~c|p=a zfW2<+Wa+ui4j~_hZWBz-5O&bble$)jU8-Tx4&B-bB6R~O#-FeqI+snr{&-Q)DmKse z;sE%aH@7sm1x|>Y@$n7?73kkqLt7<2GNUuvl&pc^YnxW@(eA3M><#iPdee;P1&yZ8 zVw+G$A4A~P=1WO{N2f*NUGkA`yA!CQb}Va?FNh_p01o%G3^>{s*l~fVUq(w1rt_fj z!kPe{Z3oX^@m-d5%kQ}iH$c$o4|wctLx&8BY&jKlAH_czR%9WPtraWf>gDz1JrLXm z$1OB3P#hTh#HNrrp!&(nPdCK3fAs;X*$~->lMw9xHL4@&C_s`mW=XXld5TFD1rYmI zG@Y;QT1GU8+LXETWZ4X02jW3{fi58scX;EO2{5DzaA?=J&m+HMf1?F1C}n5Flv`w` zv#5@Fljldo1TEdBa2AvB?}k#uUhW}z(Uje&Zg$AXoG9(PtcnNDKi3R%>Ngbcl(A=s zuK>#%V+kIo)EM>WH&k9l+b^PVSDOa45QzTub=i#4x2omEJq=X=l(RNMm9G7(Y=4r&jb=c21crba|ebx1<^q4Kay1?;X3AGziFg9R`{N0+Zlj~{oZ!S z34>+Oe6p(+SKUfLzC}qWXoTI0U78#JRN+p7rCj0g9#EYu#8J^ui>DBXX7?r;kFW;8 z=g0oOkc&nMt3od5gVeh0?swCZ3L68402?Fy)K0%1HFJXE?Zgw zyHx3ZA}x=v!jyr>=%JahX{GN|JDwA0?F;;u{YXl^0;IjaBkgT$cp-v)5dX$z_rLk| zceZ7X4h;#C==6PhygPQte*%xX5rdoKXNSLk7b5s)D=a3jJr|I$gKOuu+Zd+d36i;n zln9)!%~!~*vfz%=+Le|NWV9^)=)8|!9X-}fa^R*SLL>k&a6MyV&PKiN7Re~UR$;*( zTl`w#J7x$; zM{SqnRJ$%n`s-+S$dij$qb8QPSLd00`^B;0DIC zOLMn&=^-#Gma?=zlvQ{qDZP-s^nSh^v-5ZXTCE09QDWD-hsFv>EcN=uLyx()%R(;zT=F9D=A4v&qS1fni;-qf+8WDiURl67X*(tYa1gx9$+$!E^<~!q5DkNGlPfS@YtH z+(lvevgcpuY{7T1;Ml!?K-r9RH)eg zy=jbPm92aC<_#+Wnuxr5qWu2MWhPc39+F{o%O-RD!@`tjYg3ah$x$Q9)fT@l0Bma~ zo6J~#cER-%q=!*)>g_r3NWB0gaUFQf;GuDHmZ0?15Thc8RqQ^&3enhTBA!dCUARkk;Rjg&4Yh>eOO!>HlNz&BJoc`}gt77-NR9 z6d{DM7u8fMv@uc%p;c0uQcb(0P3z1&MtjnxMWK>*E!vbkw9q=Gw5d#~(59kA%l$oH zw=o|*$MZXm??1mke#h_A@f@Bex$o<~uJ`-3oagyE-?`hqZ4Pra(Odl8L+l1R%;)Jb z$SwYYeo(HdgF>0fR)+PVv%7mM#bs(^$-?8%h#)o=nUaxF*-cD%Ui7l>oebQ5;-}{u zPb#&js2>JhTXCFIU7&1-zf1N2tpbaUv^S!UG>x5vkm%m=y-BJ#ezUk5he z>8Z>xqF9o6BnZU&{_!u@&^~~uzmkbn0oj@)B*?O;{^{Ha4LZ{vD)gmjNxo^C=GJ*RT*bF+VlCAEihn-u-v#w~s)AbC3C^mglGVXo@mu5^=Nj5Euu+Zo*0*;yY%>E3#fq&Ac;emi~!z!=9d{I;p*3u2nCL2F5lA1cdGxGa3j`N*H#;nI7xG%=pP} zV2C)(N7I0G#0#AB0npS1umB{>Oz1XDfY7|SkK%vJ+{1gjf&823AQowrQB zZr8Ra1vPWd$G3@zQ;|?Ilwwn2#0Hti3*3q<+N)?Z!D$eBAx1l3pnC(nhStZ%#;P@U z!@i0~=3|XtmdW}%C!quCjIgfqa2&{uD;o^`@#mjVjzCm_Q97Rced&jH;qXUKFE5h8 zlJ8Y92q!&A0o7*uayoq_Zo%k6>)sNx0x73%pPrpyb-KGltBzXnXkY$F z6(Evmc*R+OpeshJRqoe`)@)a>fc9!&u6N>FoA|K8eG$WVt#f`~Gu!~+loRc*Hxjli zL{~WTNxZDAOb;tG4Hy}4Br7n}f;h7=N6mTW%`sO`#9oaCfxF*@=v*|0w0&a=+=lrt z($JzF;)W1J*Y56(#&Oqgp~pf4UA}$$c6TgYh(Zn^6AF-ZBntCG)KL%Nn5Kpz3)QAe zD|JW)<=YeKn4;Lf5;L@M*KJRoh8(8`^~3J>e;$ZN6sv)lYdaqwpG+y*c-tdkyLff% z|GG5ZP&lLZmxBVj4Lt}QYA_!8wmJFKn~=gOgM1u2pf&XXQcPJW985RVjK)DdQ-j$! z`@w=Su@*z{;c4gq@v4eH3n!HG*uCJuaFIJ92=UXMu@aC;Y!&Jc zN+3|sL*;E%ucm=$qYm3QF__n^!I9u6pa{Vlr_Vvlo*ozGmjcYI2zeLsl<5 zTkSfmTGq3-z*|)uXpk%Vo3itYaEU(4vhSqea#%Byn>KFrSC9qy z5{>L!gZ)Fx0E%q(GQi{uUXBY0f;XB%IZe%`6=NX^n>%h^UgwE9LA9}zzH_#14n3>( zoIktP;gvt8x|{h5jPRaAFb*n(H{e?I9%(HW_lpJY_i^GL_$zEi@a4i>)^Bi(PztK% zol(J_lf-?XRm1OMsfG$)5HHR(f1UlApa-Sy$^+R1GkElN( zBn3ssc3$45jw7hghrkNUp@GX9FHjT0Avoi$gD%+zS(Cvy{l%p{KLHXjPTa3o!6ltC z&{>pVEJd%~c`SLD6$6Z<7>w0g;9XYq)NJu{faX7M4tUCbTw$U+q(8on=C7*7mB5ol z7UtOILyp-RA*atD%Ae>CA1YdQOf`O*;L|FJL2rq{d=VtYmAD&TSVgk8W{Z#A@bDW&e+ zJ^DZtg9VC%b8&K>%=z&Sn5&k{Wp@|o-Mh%nm% z+NFOTy7BvB#TFrq!9E<0a|@r7V+hT#aPH*5{kVQRr%KTVJkq*qH`8xkT2@{Y+SCO1 z`pl^T5H(Q|Li%#&QE>!iwQ?9SRhhA<_Mc+YZ*7%%a2CG#E{G6XlJ|e&3ki#uv%9|B zq35~=f1!v7qfx2L`q+>hmdvkq*k(p|3NCC{0bCy~ciGJ80bYGmz|*s}-#-jGiNY+% zXkx0m%U5DR!S21ca**Z&l@ISPW@Jn`#;0(*1w4IUrBsVlG#sj~EHw8Wt}P)j5pp;h ziBK=~vkPcL0y+yCI4FIpOVBkwZEYx7Wj@WQ+PlNN^k=nT@_bv5lyQM|hwlQ`u=z7- zFx)?G$w*PFS2-pXRDr^Aa?r)P+*f+;xr7jG&g4_0)!#p4jbe>i4DBosO+)b5R_e{I zvT1VMwP2)5!uY=5c+_D83R*&<4+;UPrw%zcHCt!!*nCsvNtv(-Ya){;1VHQIrXJnf z(=&kiLL@ufH`RX3eb>@HBerESk5{5LE#!z{+fWE!OZoQ?pPm)ogDk{n04c1Z5;Ah) zq?O;B_QQFGj8ac6D8X0gND}{wn`*CMA~Z!F8hRoK-Tq)10|@CUGLXQQ$uQ$W7J_$X zyEUXt`_eHhxMgzEwO^sMtvkZ5%^|2eLfAm@l*m{6%mcU>hP&^6+zX9vn1lM^COtnF z_SWice4M)RRxcn_dr`3@n!oM69d6+X9ANO?+xQ1#ZH|_irVRqELSm*!SwoN4&-`dG zO^0KncQpvKNZfxU2L9!&XYKK20{QPA z?Pg7lsI*xEz|=?T6@cUE^G~JtRcQH$sWnLL zfn(Rd!=Xc+@o|x!n|ya~v$EvW+c9u_mJ6F@)6)u2dd^&abKZ zun$X7s-85ykF{Hj1(=;%s5{lMa;RjDWlXF>##Rs=n{^zzf?k8c$%{5q#?8Q!Tv!AB z#p*#*6l$I@)hhaKTg35BXY(q%LO-m6*re*if(5%GQRTtg@sMVeM0%@j3%`!@hx))p zZ7483QB;*`+qDK=ow?Jve?HH0=(jvTb;raM4z4q~lJIX2GaLb&{~Fv6y&1^T_q%(O zG9bkeZ%vyyj7sE%D{Gq47Ql-`d7V>~PvRsViSeS&z&J$-x`j7CtTjIO%3r<&d%gpO z`(e947IeQV{Y$(W5n(%h#M>0!Jl>F!)8UyjT((2yxvu#++*FI2m!1JidwC6dmbb8T z5LObO*$CE35eQh7K=-h74cd0as9CS2&wwcA2KA`aynG2GP#kWn_ zN5p==%j+&~pBXQext&y9+2rqAkf5V+@0Xfee+1m!gF)r^;pu9MW)$gHE6J*@wSW05 z_n6cRmKxXz>ge?G7`dl^bTx?swowXPp!4qI#fPzQ2J@|{j31I=jmYr!iY&u%Y{if- ztw&{^@_v6@eNzvWxPFqu3S}Q(MDR>Bu92`cBZm#HtUZJIBg%o_Ft%$KxXp3%{_y94 zCBfQ!?jvgC}i_r7~Lm;O$TZ)>VCMru5%yF0Y)x@z<^^}6dE z`_fiP+MjEV?8u33*7uXr>nQTDdVTZq^Iv4B;KYE?9)W`QwX6Ft^FIT8XOCm{OsD?6 zklGCNSiG@wKimn!W2UVjIrZ)_S$&nFRP4AD?W<^)q&VGYBtssSMFt_-!Our7K{W!a z*E292+e$ft--U%M-~i})Wb(!oN@qzF0V`zSl=Cc1Umlv!XZE;P6pe8(ZAhl!8xYtp zY+KC1JYH=yO)W@po@~Fazs|ZssQy7eEAaYt9wa~`x$hUWw&CAy^+oNh_axVPzdy8@)2ipXUCEUn4w$@;Jc4?f7AE}Xasn%-)^Jd^DZ!Y+4)biP;qhC_ zS6*x398g#4V1u&4(IYPwSrw0tTF7bq9hxA$wYZDMdkS~*@p+aD+}{aOawY2Hr?xh( zMy6iZfbWgPqPNBmZt8)bz@S%T!C4>9>M(_ml&MW}c50A5l%nQ0i$3(bZnV6fYw z2hdAJ*ftvv;Wz=al?@+S?jtCPwz*99=lu1@8s+o48-f2@em05{Nrk zf&*1nLrxU`eDGgl+t5GIBeci+>0=uv4b9A`Ao))9Te^CIAG&SRt)GyBes~D=TS=X$A$*gc>(8%P}+LZ`26+&O`~Cqh(vg8K%om2Oh=%Kk_W{Y7uICE zJkW?*9uJ;6C5is!NDRK=7J2a{rA3QY{kQ?$*7Zim!2;9FsQ#z1Av&vpVk8d@ZH6+( zo6=D9y6*eY>l}f6B%gCeb`c)_)t$Lp(BkqyZ60I0dx_+`eL>CF&zJGG)SpRnw_K>4 zApBAv+a3pt1e&}NLD+VgY-uk6Lf;Vv%Sig9<+kE+XpWE+HHwg0=osgE>BeXX1}$Li zbrMk5i*t_`84J3N7d~*zL$H)#V>9>6vw`vrWfxBKgBcD#0ZSq;ugDFofdvxxK$oI1Vcx8Sjx{af5Pcj|QJmpVyB_P{M*6PzeNXDjzQ#Nx-4& zN+4@rIyK$bEHn z_4Iuc;6&8@&}B9}v1-R*ZxmEi_KFypkCf}qq$~ELPF;b&)m;?VB>e#+>a|fv4Swfs zl&0zyuw&hBR6B{zEm&B;9Ep_NV^KIgN}$p`OIK_9o=@uKX4GTra4!ft*`Hu3idKLC zCB8*>am126PR~v1K49REoHm)`4i7 zk&OhhLw3Rq3&&M`SybSG(e4b=(D4AG7i;!S5N%C?oR`1Rry=u0_C1E$N4eH+?-YeW zNSRCUq&v_Axl_$$up|+NlRhd+d$!=Dpw&yH$ItA740_A-aKG6v4LXkIP#H*60c?I! zU7b2A4Fl#il&wL)Z%fI0o3NT+Akh=BB|@1F!7A*Zv!FY z)>a?h0u--y4?o!?;_}A>9&L27ooH`;;J{WQRJv9rd5J8AMyg403)WCQD#!JUfhSOQ zQmJ>+)<6-Y+M8vEvM&dfu->D8eMfkeNvo~Ro&M4`uq279jMJa{=f}R++1efw9}9}uEumXhuR6O!QK6t&-AbehM-I>K^?Z7pajS&`T3WO!IfTN291`Nk;W)36P8E*N&BMNy-%_RKL zv3JP{DBVht1PEdc%7X8m+P%?MB$rjYemOohnqBBaO&P>B9C%GVID20V&k9F1@7RA& zW35#Y2mU8tw8VA%ap3p6jOo+iFRc3SHBg438qXc=mLP2Fd7x+X1eh!dNW2$@j^@~p zKcEyfk$mR5cOa*;<8`#3FZ!aLIA3u!0oG@Qa}TyCZ04kDe!N)Fg#$XXiYJk4Jb>Y)iCZJrLOeq{ZDRX3AKX&3cXA zBGxZMP&Sx)A19N1J8()D2$g?G$e8Y7a6_b1?K%v-@-2W2H4tI}+&du0ifTGVFfYV{ z#rGO?)=;@k=vPLy^cr+yiNXCnU0nxJ>vW*(@m@%z6G0!$kJYl-VB>TKzsZ1T#Z!4&H9Powi2LX%CK<^kxdB259)3?beXj1bm=cI(B>sx8^-Xg4WU5MoEYza)YybvDT#Q+_~c zws_C0E4zCltZ(TSy0jF}eQesBHU>-hQgmuN%*8QUzC7lpFxn>D7xtY#RMReKaTZ_r zZrL$O|66BO4+8I+xEA5=PQ9Cs>+}cv-sEhmz~N3oW0uNvqHZS4*qz`h`V1P~Vs zw4J)s^-U1n>1wQyjY@%1@DN#rT#Frzf--J*_ci^F-xdnEqX>@+3wSOKt6-})u^}Zy zc3>LRUJ`wS5XSbB^HKwGsvc~CT_dbYxUI@~5?tsykJRnr+L!gIVMb#Wo zu7l{_^w78~j-{N92bnFg)&vGe_pY>kH92b%-H0aV~oil~{S!YC6u ziPoCzGThr0xO?ZROt^h4Y8^YsN>A>@vb+VI!GeVgqk&do)@S+sfjrYbL=_y4lTC8i z{l+aGsN{;v1q;{0^UoG%L5N_7E{7n~0A!i$M*r}hX2uHr@L;nZiOrigk1EV@v-o|Wjr$M+XzJNKt8!0I z#41JFMYqFT|k(}qaNe7!R3 zIivt(MrW^!Te6EJ;-0{#+e}NhfPGA z?V6;+dG-Q;t0XNUDjz7aVG*8yvo}go58N5dSGmxgfgzcWi$xP2&Fi*;Nn1x(k$Mq zw0LXSu?uts)$gni4r@5NqV5r&0s846mV+KDUoTYYGFwD)G_oN{4PKe=sqVOj3#0ImAMMY1f*0_1i*rY6=3!GxDO91 zXkqXQ?XCO;Xql*l!sLv6Sb!z#0gyz@haI8Pp8g4puYFKaP;4V+x~nGwjD-qqDRe)M zl(5%aUVC04`I=^u*jh&l-myz`J|fPqr48!I`ETET=-+&aIEVFqdEw+oV(&0y>yFt6 zKDyg@7})ZVrHcc(j0TR^)&8rq-MZ)4fUlwB=mX-I!rz!uNqHSsyCsNOx-OQT_Xm&R z#A;e2XvLzjr)kp=T)6h!!#ThS1&aq-e!+ejD%+7-M17NpVTC&sSEaeEs&A}ybccH$vni`2>CEcwgY!~b2@QIBKlhA^j*?Hx_;`qCj0PLeNna0LwR{*1> zuZJt(;dW####4ZWplkwYE6uBr>8yodMZ1?4c4b!Xhv!;s{B3~>y_;DZ%IIj+cPEsU z)0@P=@L!Mw+Rl4q9<$Fzg6dnqhpl}du>_=X)Osl0D}A9Z`lk$Y_h5o>;viys{CKt} z_B(YVxVR{|r^C0?*^`rgP1Ov|2-gahoGdlwyoz&~eMd1cdQlP~BwRZR+Z`Od;?EnI z#-Z)ZH|*C<=mTfqheA`Wc>opf(fwh~o%l4q2x*qK)3{TeD1PXlFpOIz>h=b{)9nai zghZ$SxN{48hg&Fg_310ah9y8Lh{<3-;}h&>j7w@N7;Dpdb0ia}55(=P9hWhmUTc*I$qim@!~jM(I0EAKG3LyioB5HN}jxt>CaCzixk-zU-P#&1;PVD!j%vQ7y z%ZP8njnjct=F^Qka}bR?T@MDl9Q0Sah>^pepPr3p0@MHTi5_0OVzI&=isVeZ?kk^BK)*CoQ;bM8Kxz7M@o(!`xDu<+Jw+2`r-2@3KvDswEOLyXg!#! z1!XyRcx>zV*D@uA{Rz#M2oUTLjMXHT`vA*b2w4Wj=YG!sy2TRd5dOFXEO8^`08qz4 zTvF|o1&rHUxQylOetqM2vHK6uIudxWeCt=t=f&5a0RVj*Ea!^sR$DC`3!haxilpUD zN+YnQ`}24nQ~y>9*@|IuSM0BQ(EJwYA?1ai);N87E!N1-RJ0YxGiOR~ zGoNml?T-+ZdjQM)=$MLqCk;KrI{e~ahDMRCsK7Yb0D!#A#}hUsw7%)fjYnN6@6+aB z;y+L^LW{<{MFNNu7wfA}zr^elEmO4n^!=I1dQ9AoBMe3ie0o>>{CMK$5Rpaf8qt)f zGC_m<{qMj0g_HCPK-nk-T#)}1uy7rxU&s{?svDrI z8*l3+x`vc?i#!;Gd$L#^w9t=GZ9p$6FEuFV@;)p0g9GDN$h)Q%lH(3L&A@-1`6 zJi?M;;$KG0W$qYPi6h;1JAL}LaW$k{Ew9E$kQHNoSj4=!f%T{ygWd>SulHa9>4JgP zE~&lZe!&s$1~iu1?pT1DZL!q*KX+~ZiZNN!vxeEnx4Q?uYS_pk=Em(k?VrBQl0!2i zzGo&MuV$<;ci-N#v48Kse?IOz%m3XY|J)4rH~)7F;Qv=~wK zriJJ4W`JH|UywPlYWgK~OGoUMBl;~!#uy|FU1{s#xpNL z8{kIXCWg5eG2&CfmYd?7U?PE$HEVh1Gkk$TUp|p;<*9`XQ@540siE`?$Yh%;_zc>Ld1X!#qi|=FmL-0(2@!0Us-BB4+^kxyU3{PysLkBc=&HrE^BQ= z-Z+JUSP$7-k8G)FM+tOGl{qf@MW}W=kNyWUuq6vxAh)fqz%zSjdlQHwsnQp;K!ZgG zL@Eb<%OuEs`F<9-bwOFixb+LJ;=NQ!g{#qgo3G&~=8EF1*9S_Kdd?Z#ItkSe8snF< zv;pD*dQ)$_oo@OAqaga_zR4~7reGxuF7fbBpx<+Q3vKD~zb@ie&aVFQ_heeP|V&aa2WZu%ICX)?|33p0&)r zt}mB32Z!3~zDV5t-!|iF>l67JgoC7(;*KBs;tnk3z}8H!71PxGV;vrIOH{(?a@DS| zZyDuc?SCp&=0+J%M%salnNWi;V`ll~`{1X{zHh!mBXZY1=ptc(D$ByFq08$ngliuMCz(xFssoFW`&373}$qqSob$F>ixbK$sl5#LHB`;yMSVA5&E+x*FKK zfsr8`C|3G{JsAf)8G+aBeK>cCw`of5Rv@Q&Qt3FeqjXEiX->%g;{T|`6>rL(eZ{dT zHKDinKQAQ##RdXj)jK&x^jWIQheT2b9Ihm?RTgTj^!yVawV^S=*lvrIjvy~DoA!j{ zA@S!Oj9bO=zkw?Dg_|T5Li-_iucJ{eGg) zfeH$LlzjN$3_wU?dXzIDR~3jhvTVuX$E1wEunYi)+KX*8KtNn&d=t*RSxZ?a>1g_Ml@nA8W=OKl@{D#wa}xC>`;?5i9h832tJnb<;hRsuR$GrozSWhiq0>#IlmNw3CTN%+$d=Kyp2NsXTTL+ql5Gi}D#JqM#)(Inq6B(Ved!%h80UomIHzxvd=vv0%kO-C_(l{h%Ju>}~1 z*g9}p${D!BrO>yFJUE~{2PdqIQk9Y!)r3EZsXS>iN|G5%OipD+eaBoeU+|FqQtUtW z`4DbG!(_2-1kT$7SFFv)jj#rp8<*d23%t(i;hgzroi4|Gb#AK#Yq|{gH$s?%gLE=Z zpBdw3HhW=2q+1M0y@?4(c<$&;ik<6GY6>{H9^M!b$DE7r7$Kdgs)A3mVE3 zBS;}(q|EZ&-Qn&%_zq;`R+rSuvvYRe>eIsOjT+AW$inE$0%Nn>-GK;6VDM|D(RCa3 zG9#*DFh>+6oVIS?y&YKnNY1ep0iJ1ZGBK}FB>8OK%Ry+OYA{};oIye_lIVIzE@7@5 z`j6KK)l}q!Q4!W~VbJxtce6hdE=9v3qNZ5#>^)Gn?$ErKG_?VP1Cfg^e@|rbV!rdO z2Dj9DW<$X2JE4!X&lYkSP(MkdQnIon#-ov)!0H*q4<9fCG0yUCZ()BK6WGLU6u~in z?YVvGqY8WsJVo16p|aS+n;|px*OD~g{Yiaum@5{uFPz}m#sWvXGD*o4L3%H zhiT4)H;Nx8Zy?mf(K}?~-xJDMHU*%%vWzxI8b-bX9kLcYY@evIy9HP;mUN(AAU6yR zmN0G?$`c1b#s2g4Kp1aT1Pt#l)^IhE!6dft8X;m8Je(L$Vr(nTR$-g?5E4my4P$m} zkq%ZAn4=$wXobU{CsaQ2lcW97V0=iG`5IgaDacNsc6~du^v=Ja@jMCJJe>C_Nm507 z0H>YUo^%9JDK-vi=n$_u+~zKJrx79STAE5^s}aENb^^A1(%hdi`5Vm=VKZx*1c!vI zq`4sVu~6_0L@LJ`5?_sJv)G*(E(U-U(om)GCLh zJ0ZI8hK4P_&IytPq4TevB=vp8Tv3|+MBYJYPs~h+@F2XlaF4rmbtDky2rehpdEm!L z$k4WRS6yF&mp|H@5(K8hlI%_Nv871Uw^dpTGeRiFiSA~9dT<-lQAv=#5Pe?sCN64S z`()eLEr9nP8A^NK#6Y*Pk}tCts%*aZQ!>3!FCeJLRrCy zBELbXY}rx>exo4tgga96IUz3b1&%9C*9F(>?IX^RoqE$Prx89ts3vU6)!lWuB!X~V z4%j<=K)@{PO=7X(SXeZVYJj7}dP>20gav66c0}WN%5CSR!88e%14n1enESwadl4Rg zv9y+O&vj74EGV?Zx^kTQ^N-<+a4Df75y7z$Vxh{udIt`ogC4)7Q|FqX=6OgA;{l&5 z1FX*Dn`pXKXg$PA@u?wdKkhKK5UT)t{>|dGtJ*(4&+Y)O%AYZ%6-+Z&;2k;%@TE~T z(i2h`y%@ZOe+A5@HMDKih!aC~zLMxg$T#kv?rPr*sgIw`^qXU(>!m5V4%~mGXC;%j z)5}=Ek;==~5iJ4@P+(U(X}z$`$|5rGY>I?g2;-;U@Th3QX1CdBYdi?vONX1u_Jo;{15oV3T>aEAV5xvReV;|&Tsz;@pWJMSm&O4oP z)iVi8)ena3>h^`3;UMS&TqDNDQ1hy1{vjxlt_VYQtpr2Kg7h787}bTdYPn`g(Ch^i zG@RZY*FsucqQKA~8hkiCs!N?H=1Gc3o#+^}Iu@aVlxKkxBrL%$sd&AZ#_yc4_<2Y0 z7t|t`N2uUa*az6dHi@3Kvc&CS@N#iBIu0Oul9dM!^D)peOOfQNEahwFIR9{h*<^d zvXK}>Rac(RlYvX8N#5HLYB+a?C=t}|_i7!3ONr=&8fm-6L^jsy5KWeol=d}Bh1_nO zJuF63O!gSc?hG}G^Z;uZ((4RmiVbG=Smma~jRX0OajJ$mfxOhZ!dN!Ah4FQhqXyJ) z(3l`e1Zjnm@UY8e5UFo$IKtD>xi7%t^S2300S`RTXFOrLbr}V+NEV1EiVJGs{ zmIs60B2|r@_b{8Wd4*f`?oRLBs37?=*RvAP9Z+&4sR5*xsvk{LX*eJwYI>)f-#Q+O z5}kjnv2e$Yz3nuEX>uR1l&Oz&bte(4W)(to|yr=LN9953|zW`G}P~$EyNie zMUucG)z(4Lm8*5Fwom>2zr-jW0xG4Fq2@ zK$tp6fJ;*~C**n5VjW_RLEO_pvyiY^*-n){=|oSJUBNuJ6+Q#)pJ?y`yiuqHv?W0? zs7YJuk^s8MwO!asqz^H_11z*sDALScn#)*Fd4!M22CoThO7o_JS{lmQKuuI6iLp~_ z{7?Ue%F;1ZX6GE{#?}+F(#O$Sp8^gJu-k%TaQKVBvpD8th~B3wQiDUV;JvaWDkYC< z7{&7G094$KDePw#ZLuUGpywmWU!09VkR2L|(&X&6)d;QCPo_5cNeYwD7!UL4L_ z{4>Vn&=PrK>_^OC26D9$z7ofgBXP>}gw6GZuNI2_=ZwvLV9|AfJJL0VB4cLXOloo+R~yPg*XEr3HQooX=6 zr|_Um3`4SfI=la^otW3`f{eRphy)cwp`Od#Hqp`49Ck0PX=yD2+);xr3)q2RJ zkCbat$e;q)pbf%RVb_!YZlIChH25zBPW*6rtuj3;C~z9#PE?i;`LkwAS8v%z$<0A` z<}fC!zX)(QN={}OT31YNC=h=)N3;RAas}=c?+8L&F)FE3H$&yuTFI`(2O-v7c?7Ym z6#7mM61`vQ-a0Ya&RT~;`lwU4k<6qf?DqxDjee3Xq9GTU4tYTxo?7Pw=d=Y6S%vA+ zOHi;J)|x{K$YYw%D*^9AQh?F&^L)ETFo1ESq6OB-f3LHm{JoZpK<~(1V6QvPzhaKt z;AdTBZAbPB!D?$3CNE-@ejr*|_Ud&Hm zPZDQ9m?Z^rB0cA5Wj&6ZhJ_Yt6R6_Ur1jC4u-k$PQvTEGi8Tzdu{J--%Z%aJiZr)y zV`3d){1KSD22*zh|8Z3i)*q{=-rJk>3vza>;d<1z5WO00mWBgZkz(ac9+lXzybEI| z^$3g~8}C`D_>8KFCT#u}_8*T?LKUX?kdJ4l7Uqf%wspl3OPI_20wA@^OJA z_f@|*0|h(h2#5joi?#>JF@(_nmM zI4IPdFwWD&^1h(PP$H9|-#H?}KG;@NX8FD_+Nyuc}p%IR$aGfaEl>>UlCn~X# z({i<+J5IjPi8azF!gX+tgq@pvPBY3YT{;A-?$WGPr-p7?G(U;>fZr+auFPfLw&6H93aU z)D!Uzu;g}#cQCMIT+n5(JB-jJ5Z_aChhowvE`JCF=86#^HXX^n(PRzq-X+j zQ+HevVN#tm5d+!u*-Xqbaz_enEchsPuy( zS?FT6bz}P{yf+)=Ax{hdP;5Og{3X($But9bt@)|aSI?YAlvEb2Qw;E*Y2Nf^MA5e`t7k*}_|)>grY(T%S==aKfhSiu?ees~AJsp~5m~ zylCFED>5V|Ny{9kH2DWxUnP?qLS6$M@?7i>s0G>d+5kUF&-{+rS3e8p)MTqj0i>vO zqi6sIAN5>h1Siypi+|7!*Fm?s6Xv1H8QJD7!Pj;$gN4#i&r$X!-CTXa0$rN1rCGMJ z{EhQo0w?DintTX3=CbMp_jJWXgCLz}H8#n%D~OGsy(!=7=qhnV+lvBl9R56e)Vp~ z7&sDzy&~*}1V=8#6DVh3-mHNkhaIuqUHps;ZX-#C11Dgmw1Tj_SlgXPHDl||ma~_* za3Veeppz|~5`mW~&N_d&50C4=kjyc)Nqy*Ih;&A)0u=#LS&0vq!!u(<@F65c>7h^p zS*ae+jB3TkE}9|~a;m{~TBF(G?UW*lol`w&cB`Z=UO;fUd%7Bj!tVe8#6{XtstRa| zSq_*K{_P5qOp)RZ?llKNM=t9bKb3e5cQAG*lM0s{Idgk2X5P&zr-@HSFJT%I8erNOu0ky-=bxI!-IGH~U zf~nOBwQee;DCmM7KV;$s790}Glloy(sQZyEU#pVpdCpepw7{MZ^xiD z`rl3fVM*^T;xE9?RtU!RHqF&jM)*0MK7jy%MeH4^%YiE*Ile^--y-I&-McuDm!H2j zL`!2@oZOIXQvJy(ghl{VUrQmXD^_s1nWg|l%&aD7ck1{KId$W&z1dYjZ>~jHN)D23 z$T=8Y$bWE3n9)u=s7Zk){gLq8PL_|=~=t4k_yctJaDv5vZ7s0VWZ-~+k z)xA)2Pzc5ZnNjz#qB5&rtbgC%B5oiCL`1o8hTXXKrIji_NX5K91%%+~2Pt`$j1nKy zfO-csNN~+ad16xaf&X?{*HAChY?@8#2>~?BNq>$IPJ*5?ra}g^4Gq(9WjAMcb#=v7 zAjt%$S&N(qb4F(89D#0fZ@-b8EDZ^Bhu%*`#Mdn|qaquX{!FAvO0zEK`%b-tBBUXyMTsOamJ!+50ifSeu6v;O zss)IdYdG$qaB2hq$to%oC#GmD2|G}!+#=Q(cnEd21`jax;(eWmgY+ALnpw)i#;<+6TIJD8{yRlU?1P`O`;h7nMN;UD1ff zq3Y;lMa(TnI5NU!Qe(N>4zgzR&~;^$TE$2&lXns08As z^WEKPoChIXSlCe)qqu8me7kHaYT-kgE!O*C8gqzVh_P`tg|&qH@Ma+CdbfT>HcoQ5 zOJ(^q(z7R9`09d(D7z}k2A47WW|Ml{leSQpjoYVwO&A?`^XGYtgtj$oj(2IDzPSfOG9m`* z>P>m+gfU~3yX;Bd^nO%7Du#qr5nTrd#VC6bdqQ;q+gBD{bll!M+6?q})25zawUX*r ziyFAdfevQ|91GpXMa|pBFPb-I!=|f>)*Kvw1}sRjakypb05#F5>piLi?~TbM0!(rm zbZkHD)Qtg_@-p*0t{~OZz6uX&#I*4N0ON_%0a8 zZ|YI6!@yJM$s!rt=!~32s5WL%w8nrI(y>=`Iz&+UV*%-EVQruM*>kyhb;xA z$MWylg23c%|BD8oX~NrJ20Tto|L6?prGp#-U9GVE?E)~j?*c;Ph0uSO!ur*>V z7d3bQrh^?ODcPvKbw)4jOsq#`OCWzda~gl=ujPiZoU6iGNXto(;q@D-*FjOxiN5Yg z=>6%HOyio_i|7LlBNISBenfNLiz7&PBXBbMpc{w%=+}ud8tdlsT+Vm}0jHqoXqGhC z(ZYc=iG*F}fCbwz)kZU@23de|#=(zj2i2DuV8GjB0$n=09E$Cs86+BqU(ovYG&lKZ z>PdrMSS91)6jVhrL?;+=_>ykScroi3_WF*gNI+G)fIMFR)x7LE#tdmruT1jIiWg-j zw3c0PYvZOXJWqk6!LYQD0rGO3k<}W;?fop4yw(J5frkTfdnYj;!CAc8D07!tM*3`@ z>>STS>5y8nX1@%KN@#lcG$t(40QD`XWaUvH!v`P&kdTm4&<5&%amPiRSJZQXx|j%~ zgnZMhVkInxyu?vb1a#eaeX5IE%5>Qd3tXC-8$husS1B@{CurrmFb{3k&xG%8kaoBtGT5lsDyD0((0NFy^jJMFMv5ZU$zG@a*q{?&Jth& z>xcjW1|*NCLS*CfRNeKYG9{89(%BvFg@R)-RANPI660#&<1Y{i^$`JukciJ$_G2^T zE_}$r$}t`2S=;X1*^&yFi?M9DTeQ^if5Y&MAMQcP@P52LG!wFFp3s^PT<5_e-`jQwt0z6AL z5(Rw(tQ4sA6^s!UduV-m}c{amet_r=yY1NUFOdSe!)DeRB}%%{F7(}($hKB z4NDyfe(Q}_Em{3E1&c*Q>aPvq|G~1f-vwWTJ1@=|^|ZRWx>l@9<+(Ht$8ZP1l<~;= z^7q`FWa>t?Q|XBYM^OvYpgX~jCas;2-`IwVb7&Ov#zk=ADM5x_(H3ok^-CxH5HG23 zM8noVx^gv~ockAHg=%z*&{|z%nJ=`kCGZ&0<@oP9Gn`i#^zlJZ48jO`J;-6>)e5Jg zr8W*-#^KS`Pjgkq67!i2EwgI=OiC(xE|5|cAp-}*nwJ>?0kFal<5p=A=!JmG>9TrV ziz%FUN_W>1_DJ?L@;)>Ep3e}F^pNN$wlbpp!1-kM>Ulq1O&%V zkc$cwKqW~09mw9Pb>71fWJFYi<&wB74mXWtL-v41$Qi}BIi-WFE3S!}s;>pzr4|Xv zPvSKgmav^|u--MCa~F(*$XkO4ub@>!luRXvZ3dK9!lmthLgVT|U}d(Sgxn zcXxuV3`U=9@+*SCv(}~C?!m})G7~-x3yYu!zvdyy8BeYof!|$hh0FWs_4PTdZZJo( z!+xmG|M}W}nUGKcoQGIs^v#lW5wYfc-Sk)xowiAjpej*&^Sm5xK%z>Jv)IGKLm&B_ zVmyrm$M)QVLIm$SSOoZhn+$r&aUWBqhq(KIk>VI*=-e~oCn21?Av8*>uj;!YHxCK`&75MK3Mr7pcbV7 z6S=ARy<|jQsseehZ_(H)C!y9KLSwF485|Cq^up_xQf((p@Yml=PI`{o1kI9?S))D5 zjj<;bv9X0J6|8arZoneOt_a~`onZdEpYj1*(F3L1OTis8{&Wf(Z=w7JoQ?s(mTs36 zTE}&yhm6;Rjl^l7ziQHRnHzh%P`L%Fj&U+~Wr$|qiQ?I>;XVct$*4utOx6acnb<;w z(KmDv%eaF!w5S<|#!ROi<}y#dam6DOu8b0A(#fZn%9kP|ny#XnC0OjYiWaoM@$+KA z(vkmzs9DjB9_lun81;xEc|IsSGPNs0Z@V15hcAN2L3CbZZBK3-V6}arjMz-`?Wj7) z*ijx$Uc%&oCt*ND>```6Vd_KYU6N7_MhsM~VdR#~+lq-?*Ur1(fd;1pdN8uxNcO)} zNs*phV#%|gpnNQ)l>}PRn*$so=%@xP%WLpZK!7*V6Ck$(pQ)3hTEb$wJGW1dB*e2qahVgw;-v4%9?33CG@yPIFnXC%`Y`UIk8!471CSJp=Y=@sJ0ao#W9>U{CW z2%ZCltQiuUl}-H(3>aBOmrYQK6xc*_$;C(0dqAIik@ZH{btH2fusFEW@@wXb%a?c% z^U$S>TpK9!7_=dPlRr{M&WWx?Yj^*s1VeY_3|^JnWLBDyf1*2(RMOFknm#>+_oc-fV z@`t(GPGOGJ;ReKc28zFZu1bmZ`?b68)|o-KL;(Lz%fLN_u+vg>ENpf ziMyE5g+yCT!J$kkbUm~;LNLJCX%Q%mipCOWxI6kaEL^yd*yz+hd};^bXyt{+84{*# zQ?F+A!6+Nr!|Jq9gILgTQ%wff)`AT|_ra z!MXnKiH}6*k~61r1~?h~t%IG|SD&@m+3=*#Lv1V9Vw zb-Ge<_L2ISXWh~V>I&K9Cxj}J)nj@GUKuqg)rkP3R90W06H9hoWDlmy;^79&W0N|c zncO_@%$GMqAplWVe*gY|uS?B_%424_omKGvI8Sw^eU^>{P$oJI!6E>9IwrQ5J&_|K z8)Hap15^+a14AG2C;8yU|KY=&X%C(qQ6?XNl-W&mPb@cBL!yRR6ZI&vP;?w5%?YU? z$kv6N+(?rZ-achWPD{qk>zFciVDYFXA>05Ast3)uX503H#qgRVNk&edo>b+3kEc zzfO)V&dmJ9*tn*qxuo_@^uhx*w`^}Gh}^DIHc3n|(cpVtw9Yj7=JTCr{a;DCUbxWQ z9nrq$P}SA0={$jk4;6zmk&}~$ro4?(%CAqN9yF}ZyMI3s0Jlk7el85YQh@Lz005}+ zT)=Gq7i4wG(CURJ7XU^a#^HG9H%_h*KI;xRDHhZN>#tlKgn{bpo>BF>-23oPgeKR= ztH=W$iFqu73&gpq7KW~<_8tq^Er<6hE=OFerO>qyHajLEj(GXG55HVP^!8gcLfZn&%RGAWtp1Dk^V0{ofu?rBk|o&}1w=$t@SBQ<4%MI^xqw4ZL7%=s7rYlI zuGQAoraRl|>D?j`mN6)}Q#t2udae|V3=qUse~aHV2A5@M8mkzj3{Pe2_jW3_+>4m` z^XDh3#w*(vq~g!F&*J=uc8Ikd>NrTe2l|Dy-s=prTQM^~dA8fx{-d_!gc{#s8bxeDm@gu$uIo{w(wg z!$U(>6R^t8X01WX00rP}f{ZHN&zd6kIJ1?}cSpVaz@88d!sQ`X>4vski6eRKB z@M%>6u4p!3HT>$(K{>g%P~|N?g5B}$KwCi~G+~-aW4#U4ynArBF1&wz!plZ}5z~;U zaSVEOAuV*<5eO<>S0MD=zH`-=T3GgbAKx%BK2E)5bBg#)~<z0>sLF0*8HLM2ahPTb2@Kc<5e^hd-~A&ESURW z)~h`S2S;<3c{u9%o2ac$Nv&VACK2WJ-XFM`4Ki42VM6+U6zA2PNh$y^+J1N7$()x6 z3cMROJT&VEtW%5jajmU5b~n#|*>3ZIR4>9QqiD5HgbEu#3zepK2@Gt{zs@plQ{AYZ zkDHk#HHASWFf$xdxSQXrhB;hIZ@zQR{Ku1F zE-50l+`|FqK?2&%Z<~PFvYuf%U5BC5l_)xRV1+5g3@0b2h~VO1m`48=*TG(#L0a4l z#1&Qjt9RdH&B;cl{HIqC!&Iq9%Pqp)RszVRiqlPttr7fd!G7$r?mn{Zb~y{+YaD=z zH|VPs6%>v;IpyO(i!L0Bi}OLT-}rEhE6yTT2Azk~WV+uzVa{Y=76n!jC3*#56_m=a z`upERseCF)LZ2D;*cN%Eu&@xDIHQi15KI?;!jiYO$CWKu{a+rQB34ojaIOy!r>u&c z1Yh{xl{MyyyBDEy9*3%$VDB}j>0ibv*%!JixV3Z6?MF|NXWio~DJl61Cj=|UD#jz+ zCcw%Hr;*kHDGu7HSw2U7_>FY8i*A|q3v5;+7-K^+n{7nTy()Ps0Wh?mrH7O5)qV082?`h5)?x2`=< z={MLA1$o0^2sH~ZxDm5S-uE>|!RT(DIu!x!dwG zpo4N^-QK-Zi$ZVEo0u&gIDlmcl|pb8G=BT-w~DR-KspgH|6EL9l&?xRR=N)N^0C_9 zX6p^1t`Lq*z16yWk6#gflYoKcnceEJ7I>@^nAD4z5F+K{pMC8a>W|04GeKV0e_ItOVAhhXeb$wau`rqiIiTHC&KpypHnmn zbZD9HG5#5>L^1F!WlWRjZblv$d)&@u%pTBhtmfF+*`aLXq*CY%aDA7OlHHDTG&>ot zO$FxoF}-oa?j>z)ZT-miOOmaP&YnAG0%P6B(Jz&gljDf$!<+>R!l}-Zotbg#en<$D z_6I$MdP(_7(Oi6dF(?lSEM2;lyv6`K@A}{ummyk1w7e*TPuhl@JKiDnvvXKj7$Fw0 zBOz$FS|KD?1eNJkEp zu3SB52y=#Gw()^S;%`vWxOwf`;ka5DlGM7R>wQjqtlyN%7Wss%Ah)KbFOE84QR*(# z8vg47bhh|Kf~v;31kC8};p55Gg#$)y93?Fq3P;y!9l>@ z%F$XCdP4}Vr`44Wf!WrM%NM5>C~EHeG%bzC_xb$Y%WkBP3_E$S01`qFDZdNTSI~1E zA_BlTzt8B>L^r@L3HVL*)}I(bMLj3}<(7%Ky1H)Ly44uIm8;NC(qc3Vc@;0in`_7&@6N*~#O7%zg*RNmy86wgYBH^HyBC?O_lQ{V$7M3Lv zjx=<~wO=J(%VNMdv}9kkOW+3~Cf-Fs4FIl#;Bef;v|w0`8yGkatHp`?_~nZ|won6; zbxVLdJ+|xCfiGJuU-60LnuahRZy#=Fmhg0$&sRY$y+>8vb?f$GlJu_KyI}!ZIeBG61EXiz<>g^q1Ie~Gi3Y{3US}qNYXiqS!*pCyX0@iqQL&IG%g)mN)>CUNCVC=K@ zUaPAD+$;gjOj<^^2{=TEi3`kDW8gD}Zd1^?rArpCh+bsVxY|T>O=1u(wv(#D(^BZ{ z!NNaruU^Q*(|I+0`|(HP-c^dWqv=zJuFz2k(M;y~=QY^4A1t$}lic`^BKyGAcJ}PY zNO~rSfw7W)FmGXKH&&sf0aH)~po;g$RE5jQ`=|wm;?gh_xe&ePS|%VRaYh)ek!l+Sv+mvL=a2)2eg3q< z{(%8g6cZiM6m~F5LnMZIOsB@V`%sg!jDIvDE6fz#509mFsVw6 zYA7p30HGKltqxw}&733sTgl$h_Eunh??`3Av4s5QttQ)DM62668R6DPKOC?K%0Do_CD@3r?@ z%VXmmP#yGq1n^DmpE(rck-2pvg52X97=FktslhMBi5=aLOeJjem8&3VGwafhP+5(K z*aAwdG6E^8uXz|@P?Kvr)#7le^N0A`;EGj|2W2@ToT1sy%2*st=MljT8xG#Rd)E=Y zFprS}EBZ?+!@K1uE2)0PjeR7|d>0oCDxYO9R~z_>I6(VU3Y*z%CL5aV(Et+`2K4mw z5KvMAed9ZhD2VAo#6txKp)^>2I`XTbyRvAE=Wfkk6=|+>`Qk-NwmV(A@nMf`m?|DD z9K3McC)`E9`V9b;t#uqHS!Y60ZBaA863xxE}G*~@dLh4ZO8CEAwJbv@` zZF5_W_-qI{S^bOmeKiGB7ED=ri0-UQoY0m-;X+mlZYpM&MZ%;Qn2PtZ@sq1>1J{D``vxCC6tC9YS>VAbKz#c!JS$frx15U> z-X~wB4uww5NIaMVrEMx19aeoC{g1?vk=(>Z9{e5HO>av=enuL>I zkKT~>uOmZwwGHcUY`!AOj(essp#^tLFb)=JoRsCnGc;fDst&QEN1 z64O80%hxv?0ElL!l*vHMH3S`MkzfH9UD!Fie8Yy4*mRu1<^1Cqi$?T+kk0xewi=GW ztlo1hzo`reVppj!W1fE6l{ldBzNO_MUJOt3?!6C!mv_}`krV)2=VFraQ%V2*A^shu zhnfAYIJ)UD($1g>oulG)B&>%~DmxI)P7%eNe4D_h%YOa!_gIS!uL8BnOvyT@WI3Yd zQ5tWglv?9G*AE#zmNs53iOqGw6k|f8V1zXzF*4%Wg`>mSmF(xn=b;!jcr7GiER>Ev zYpD`@u*zM_|EII(Ew`r}S%1LlM$@%SSCfH_+F?Tj$rmQfrHttC5JLQlcFaPN9YQ?9 z#az62@dETxBsx~!101nH$~F=#6oYsc%oU}&561}wUyi(vzk0xJASeja&Wv3hI-y}G z#S&sua4Z|1z75b-fWP11)MqvX?tv|{%>)MR91DP5W@mnd5KtG7%-F83F1XBFTSRqI z-=Gj{rWUjJ?kVe2gXQQ7=3quwGR!&$te`dje{4__kLt9Yt&oDbvR;gTL=G-P;*+9wUqB|y`@5XHqLe5P3VRo+7~`M)gL79z8y5Tr}qGv zsuV6=zPzer)#}xXh{@yCVlwXno!CLrd|-baiL==7jO_$Xh;!JB4`$6PcY}M< z7+X7`dFc9myb>Z^Z7wFxrpVJ(At=}dp*Z#~Ehd6btgahcsR)DT&Bgv#TTz!Nvh05rUY}!#l%@pc+wWPuJ`ljk|}GS*2fNy zJ~T>t^DTT`pjeK)G_b~A)B#K}o;T&nzh`EyE`#XwU7!ff;UmzWnmS1w#23oUo7<qO~NPvL5H4941(%mG)aQ7M{x#=Mbsm_1SMhu5z1`j2D|~Z~?1vpzbVfK~7RNPb&Vy@9 zZ2F_ zsCu3N!pg%nWqd$BHXc^B8qPTQhq3zef3F^tlpKsO!e^Pc8*DHJ01*Ntqrz`h2y!Wo zq+`6YC*M7kMN}yosRZu}E?C@A55vO^A2|Fbv<+SK^c0O0gT2*EeiRH!Ipv|5{Ze;| zCms^88~+SYDe=|PlSkuIUQ=eUsk5ONOUK*ZwCDzvSQN>D__q#*>VIYB= zgZ$Do22tN3h7yAe-Kk3gf$e(vH2<7xMr@R;3ZfW90xgW#SfLSZC~%t(28c}w+IZGgetWvMtss?l0P+!If{w6ZWZ4uz~*!$&7Serahf zL9=?D>dP$g0~_ehay{4Br~{zL|I^cw9Y}%G**e zu`eyQxmyDT+JC?{@D2zR&avR5U%!3ZFPE8a)o|*tGXx1LvEYf1Bu*tPep5%Dm_QF; zHI*l1mn_)=L7^gWxjv)KAqU7WLOFoqs=xzE!14hAwkD*w_bCRNNk!Uia?C&*$y6r1 z_hVIV@7jjl2scQ15-$R>vso9^WH`a#d;L9C)=RXOtir+kjM&l0!Gbxl9z}`F6k&IZ z%M;yrlAWtn%7z1;+I0uqfcWOsjO0|wKM(!)Uo_1rJ2!LH!O%ko0?$N0r-y`>Rv) zWR8WRUP(zwS&p_7-O%l9_{E7p{mj%)*8wFMIP`&fr_R%nR#;hNV(SvL+2Zzqq{~{l zsf>aCeo28}P@h@&PxN|G8}JO3q-&LujE=}nvDE;>D~5OD(ZNo>3wSIXv>V&pz*U;Af{S18n ze}+R)bj0kSt2+yKc<1GZB<~F1l^6_3e4720=EOt>fE?+mm<9~gyGq=_7v>9mkNe2o zndtFO0t+(;IbZ5$WJ8IB^MMFsgnR3Q`c=o9q(uTdx>b?a9j?jE&25t;m5Q>hOQ5*&)wc@LX!ncI?b2^gLF$l{>Sfz9q5&kzac&h8ebMSeHw z?@PU?+ju0MULpC;)kC&l@@i_*o|&IHV}nZ=>-Z34W>MCszPU3e7i^1aH zM9~m9>MrESZ@{CEvan5Pfk2cAdN^^DjeFT?u`B3o$M6G|YnTrpf!oDB{;a$E!ZP@; zD70y+MHV8vgR_lS?sNC@GK4IBdeIi7(5FN~2(E;3cg$A32-Z)H2t zmnY|gQv;e0k!eW^ap2_4{rl^{BOV1GNTu+dq*gPNX*vqcP$GUHX7JZP@wpCCgPm+6r^cex1KpH zgXS>&QcKGZQ&&xU;{Ql@{I!~MFCz#Mkd)K_#8Hk&9T7(iIIiKSymL)bn9eP}=thoL zvjZ*)8m7$DGBAB1KkaxsBxxjFho5FS>U=%?%l0}CFpv=c)m(t4@2iY|fgwK-kVz0j zgU{8gGwvjDX-L`ib*SHoZI;41|2 zFB9Ef$Bs0ed;qsV0iVr8H|vK8aKm-dQji3gCjv+{=!r*FU_ihrqeps!YauBBcoDtA^W9tl56X%x!Mbx*B zIrR*|G2FreoE!q%C{;y%y&n%{-aiO&%?K>Lq`1NGzN@t{&{dgVwpKU2O68aaNN7SDk}@uL*Y3a}c=ZxAF{fda z%j;LKzC?lNnl9KHFC}t{wBv~%za;1RB$*P;^umIi%aAV$&o>+1innQW0`ublLbj5vAJv(_$QpnJ<-t&3#>45Duatx=2q(RJ2SWQ}630TpF_5h?C|ARK*@X zePdR$GXg=BgZCkUSzV^DuYdFU_4h?nC)hCFRk|9X>t?7yuFzkq+^RkW3vKc)_OA9L z_1UP+;HsD+SC#03xRD-^_??*DDwHZAo;v;+UBiZ#?P%IEl+w5LsXB5pFy6&7QsQ{i z`NJ|XP5(np_0Yd;2vGC8kmSm4PevVKo`rx&2yW{+7VO(f&7sMU;Hk+jBR_g%PvMN@ zF^sx7&}@$9Uth`a$3F%}CDG9Z=*+#(?g6bE&OH}1gO8Dp1ftfNt?gm-Eeo)_Fa{*v4O2s+sJMgzqX*0Hq>SewbJL_^_6#KEGyiECCr9DU+5lFaGeT+w zbgRycZSnTu<-^W^LMyt|ua-utAHX=qCk;O6BwYR=XJGQ10R!^`op@~?TQ*e~P_m63 zj&ADeibmjBqBq1I|I9M|>qCpWbn~7LR73I50;w&+K-Z<(0kc)eF|S>_CJC(%3~-x* z`=JO>;wFLx6c;&X&ANxRYe)X;2tgm0f!!!NLWlA81J&f?%?A_BD$H7iD-Q--yVg*& z`kDK5zFUw5SDVhkVe_u0;xN)*D8h$4l}G)U^Pe&Q3NNzh=%nCNDMS%mTz{aX6zllYo_j>o5v?DpQ+*t)vE}e_e*V7|^ zft24Ae0#1!beF4w!(z4dsUQ?}MB=+U>xTQpFqL2v?%amKlb|M1=@0SWaFP+AMD>E^ z6PnQpoe7@R%XnZg)gUpKnAw%6?C40M)P_j8H^P}c()*XgX^njbp1l*5q;suM?Fgo! zJ@R({n>ca!@Xwuvs5a2Fa&Fd|&`1sq&4HnnyRl`ZknKl+Q!rYRB>z^^t+;!4p6Z?J z*1sDwz99ZU(jSPWHh!XR3mOP9fqJAIG+OrT9?#e~ zoc)i?z-==>W@RHfev8UsWB_48b7suA+L%g5Tn$4i{DHa#HV#j?oWPNR6wPk`^})MA zPjvz3IN~yL6gHihQ3t{7MjXf^>~x15G^m+~Ka~RL(^(Opt(S&e*`(spgYnmgim`7Z z_8;p73!%eyAAAghR9zU-5_Fs3%2+Vg=sbPWu$Kh`YK^zq?rKC-hQn+_5|8CzZkKxu zk8~vKU*2FbNIDqaw-?D4U~)s&$v|1>5&+m*H8c}50-@76qZGUDXyi35?E$BLuk6c% zQm{0T*x(oQl@75P)O+izWOGP2{#BmbF?0x&xXm?S+r^m2pbc?i$7haWDzyKy+k- zqDpGDkq49)_5-34_16Y6g+W=9CM~~?)eME@e61$~`o(nFFF~2sO=4e%hEifs=AbCA z!3PUd@i@847tSgT$?`5m#eAEX!9^$@$_HYLyjH428n)=?=F2x&&T+o4mZySLeYrMAzaJ98VbkFCO3w+!T+D<3Wnwh`kOW z^^Le7<$wyzxN%c01wd+wDNOlbFl0k+59mme^0s8szbF zczFDSWx)sEkF#;`!LB(tW4l1BNK#0jGIvcVa5}2vH6$b2tZGg_6}srD?wgp*JP<}6 zH~1h84@U{TA27zF8aXU5EOC65ZTH}>%f~+hJbeRxV*HyUEOdV!apG4w4>$qSRaebJ))|!$b0l-FVG_N3+gfx|Tbs$QpKLtgBD9~H}SQNS8zl|zm zxaHz0@*n0u0%d?$cZ!Ooh#$YR?oj3?)?LFyb<+UQE?^4lEbh3v79tx0Xr>HUVyf6u z!y`wGL7}J10*%%QGSFn8WC(G*VXro-x21UF`*7-Q2)Tl)zi5S+SoLzVc(gQflCsB>Z*izX$+AI`q)j7 z{K>KDhS~IS4yfXIcKtJSN7|t`wqZ2a1T`UQT8AOs8iF!2Gg_e)JwD$@SRUu47~dAT z-r#j85N57ICr8I{Bzd+uNynRac_i@4IL1EbVYqSETPl5z?Z5wjP12#~Kdn}aea3G$ zX#(OYcAYBvIk_Ey8QMI?s{&8nL*bqDom;p1s@N|82I0z-(2oO`0qO|?FbMPK&nKQF z{0MgJX5G1<#`o{J`)vkm(NRf)L9{M#8{rxW;U?wLQAi`gfZ3vS4Z#RXPjcn|s=LV{kes7ofqs;ot1s7~}9)e2jRCGJfD)3k>7W|$u=IaMA;W}FJ`7zBgi=1 z*!2%|hEcyeJw1JaxK+@e0O>HWo21OYu+x!+97P5}_wzt^z9sJHLn8YT(IXHkKA4;ZHYzGcI>W*U!EI}3z(c* zW#sh`JUHMbqME=@ZcpQrHS>0IiP?O1GPwwBu%5R|-@9{yIaW^wapB@}L3ZWb{x8w% zM`;-u7A&4AbS6{md+rgn8#qFWpc3vdA-zPxf}^~BpnJ{!`{x6|;R5z6&Z_MIx!>pB zy?fwjFISb%@t*wq0N9TY5!9=Z4tS?m#}&Y;GM9N}Di^2qlFmL=VFI9Ze|>Oh$lq%R zkv6cExU?D4zK=sIT6-P4GgLMG2y*_7ff zBg){DwlC_4O;}0+43f6wbfmz)U;HOeXM!j03c5v!>2(xbla%Al7ZL8oAfQ~iZe3An z&(a}DuR$otv?1_Wuaj< z27|C`M8-#x&vh^^s}eMvNWdPg{lp+$)yP-(cm6%Y;SBsciYTrF&A8Wa2NBIkC9~SyCsJEc8H-%e*9)vesMV^{6I651_ zvS2K>*Q6#nvb&-H@KSSLm~D#d zPB0a5u6d;G_afSSi!j0K_U%x_vnzy!-*&WOC;4@C>$D80#)t*ZFC(-Al4x42N#HI1 zv&in2IW*W?80~qrmB>v99NwUTpmE^Ok6-o>y}G+ z^N08E->>`B|BaE1Tt@Z6EPnbN0YSlzBwf#Udo&R@0hUQ+r*#kSJ>hbVuXgPc;Bi!@ zC-h*o)|0((P!9+}LFL&au!qG`M&b&j;XZr;k@^h_B{0}0fx-nahPar(-N{P&-~OOV z{&V0d&P#IF5Rj);x$(blyC{An9(>x&{Amn@42x`=&xQurIk4zgBLBV1z8w!f1kw7< zqJUmCQp8Y z)^!n#20&U!S6ULY<^fuG-MY050x@$?IEJ%Q#p(4=FBOg1si5!{Ebs4?WBb+#k2V1i zkCt^E>bIdmf4MY>ld!4ecJn<5Jxh@7g0-_&!5n2`I6s1vI$bPv))^IWdn6!V&b_dc z!B}zopV2@jZM`y0AmlOtt%B8kaE*{q`UyE`Ij~SZ1iA2iWP45 zEu=jJ%W!%kfINu{74zYw`8uZ~dg5kFgVC0CxT<>U9L=}U+ENrgn3=;^(xJ-ivc1W! zbFJ&J#itKO`1;6tbQNrby$Dy2e+U7zajNqF`yQtK@&CQAo&x-&lDk@8?MT^@W(byjsv256qckPP0cn~f?ABgF4JT@PSHX%GO zL&o3!;=V&Jwmt!orZY;fWZV!+8Q9B$X$MfP1nMziMgb1n`FD9)?ce{m_hFnZ2J$o7 z@1r*as`}$6ab@ZkxmJfG>N*Otm#e)CpbTnQLRenWE_U*Z6=rv3n&p23pCt-RNY5?; zkJ?YPvJ#Atyaz3~;Aeu~6xLU?Zo9}?jFarQ5X0Ml%A;c-UWf1~8jUmI$Qt`GGnP2I znGL#a<$;p)%QT25Qd~k&jWbvZdv^JWX+5>yM?^!!p{3xXQ6F;q$C#xM{i6n$H(*ZR zt9P5?_xw8-p#D%Alx-{V_!*%2ikbh!Dpxci+p7+YsJ`zj!3Agp7$W3YQFF zZgH!Pc&zoBn4@(YrlY-SD?%JCgg9qk!M>M*oNNOIL$1=!*U`8=VQ@=8Ll2@6#eY@{ zG1dAB3IZ|+;%GZSM2Rk&)&ibti;D}jf3?)v%9M!#6D6?|T!Yl7b`IP8? zseLs-TWANPbkab4?!5?Z7DPi15Z^CfZqsWn_?QK+OAuUjDo?$m=Q~ys0{>-hmOXZ78{?R%pP; zve2$CDS>wQ34z38vx=m)6+{CVb$k4S%(r#{FHjjFU9io)ws|U$TjJ1q^2)S-Oa)Ex z9(9i(p&q+G%Thn&NnsK03BT5Qk$Qz zh(?_-5CxbYLMv22fnKefu7yau1TT2JBpCZhoec$na+Zni!r&l>K^hYyZ4ZEFy;ML% zgq7s_*0r-zB*ZYz8`wq|oOC;?M7Ju5^h5(nIZxugO?Zb|61bLfch0$HW@fSw0u#Q5K9X&O9{xYWPI^G zs^H~e1so1F&QdQR_C8H~{D$>3@ZA zv?7dYU)6{|3debQyF-j(L+a}fQD0E05S+ z{D5oTyil^nfFwzKf|3v-%%T@K@!eVgQbgUrjY0~4e8}d>?;s>4AmPpwh9y~mhFi!4 zM$O{ibtFtRQf(iowFeQdihx^>>J zW8+x&dTBLQd2&!4G_k(MIM63ctJx8IFGTa*|kRVk3GeuY+fh0wLeFJHeNMZ8bsPaLu!bX}oA zN*UX9000=W-G^|`5kNQ%YDy?w=-WRe02aI(>f$L)B@zyH z7Rl2Cgg%qu*q2~CyT-tRfnMT>X)S^QJ9q7RgAkgU z4b0d{Ng%_t1IaNo#T`>dtm)_Xckpn<$-eHoz|O)a$;n5-(f36kGkhZV)z@*L4wis& zA_5les8!b*jRfD-$qn~RN4TUJNthQvq{6kckbp9J-b`UAgcczI zx3;+=O#KAQZsh2t0geSIpq^;O@?+lpr zU8nv|Biz_<<68%&ZxprLBKMul!GW%*G~)D9za;q-w1E3z$~5RVFB$9hKEpH0Bhv!K z9JPghcDJQ>D%Id%ZSwVGz#YRrCFE**+BUxASgro(#m793Rbwhjtf{QNfs*S}3UgXe+#dZF1o?NcLJI7gCQ@4c)s5 zgAih?oFPtK0?naAaRIk(J;d6->y*``7M=Hf4YxLle*@N83KkUtRz;P}m)T7*;- zS>nE|Rmca%irT;p04xWDM^Dhlk&YUNOE;Sb;dd+t` zv+Vi?4Py~y(}X7n^|w~tU-oc9W#vQD@c%7QtPEc|BRI--=c;|7+K)L_?%))hF~wrX zDvxzjb0h2cbSt|f3Z5Dnig)|CXWH=hPHJ^&N$z$y{(?QV)$T8`DDefqFt*Icpct1M z>VZ&H+8`>*mCy=m@%!rvYjU&>7)L)(#HN2?>W=s(lVsZp$GXiCGc!gQ@?y-8GBUNt2A1g|(Q6iLGnWfMWA4_dl_}#g_(9;WPJs=%D!? zn%$7lS{|=+(OMI2z>p)mmtBdv3oi`@>JlFFs2^SNxw}crHy#-AXRU!in=*AD7QpzH zO4p#u%1S-lYai23(y5zU`#$Bam3MM-vKYeXiqZK=R}$b%vq;0R+Hp*?K#}mcLn~&( zd+8ZE1Ds3l3&cDnLzz;>N0@ox@rlaH$|Qqd-5-dlr~A|^26VH`&CTQRY1RF8wpHeU z**tkoNu&Hd%5Hg4@OM9a$57Lj&@<=?HRL!!q>d`>u0&H24{|sCHO^zK=Bs6lsRr+%sFfS3DI)O!?Bs2nvZ>NPJ%b{!YRugp5?e#_n8xRTA6}Nh_$Q1L*=(ca*J+Xcdp+972}6b3!~P`Ty(a;k@o~mpQW}C!ju?snGrfP<|97v zVL!$LRm+PM6A{T0%I3booN8lZQ(RPZHThwY-|4$WyWuYLoX>5Rx#(cg+1V)sEa^jg zdwX0uydzByEbbq(T1BouJ=;4G=-5qlOB0ioIoxOaIeo3y-M6xRAf43h!cOf$F_)z_ zkY^-2J8-aRxkuTLvuGG@zlHI3jC0FOf(OfU6d3;u2@f+NK#w7QHhz^d!ya4M6J_Zf zk&O%`^F4Hh1$G54DF)8bNMh+}h3NULY;44C#G%eyJ#ZrcS4W4B?Z;qTe9oH4*gH8| zg5mZwxt6ga3Y85!{|8qY6>pv{U5vd0u%ZJ4t-YmPeduZE;)0{tETRaJs zrzc3qorc`KEnNqyX#NS0ZQznp(to5;(~pO>wY7`iyjgENwDU?UB*VnY7cw>qJZS;f zs>N~qB0gM;eVUqgk{?DyM3ghedo3)qVJxzY7TXmP67SNjkJs&<^2>CtLJr2tNluLV zj|mA024xWu3O875OG2=Vi?MiF$?%0shtVU?RvUOFFFOkZDBm7tk2wxO;<)uw@6XWd zRNxy|{~JrZ+8XPxSq*kcTAvQot`Dm8*NxfkjVqU?2TeU;V}qX;9=>b6{9Rcr6TeTe z+1o)k)FG;zo-2{gP)r@KGrUsj=1o` z)7o+MJ8t-&9PjzFh=_;}YySkds;Vks=GhkRsq_cd-tRj;NhV=BqL@V*t4xOppXdo- zc3h{n1!)D|h8R$nGtE{+6L--7Z%kz5rI#;X{&ALgySM77tG8t+F@jcTSuz+8>U|+i zd56j2_9h}SFFk38s;cU95v!$bZ5oYr(&gja^sLgZoeTIqty^Zq%cZUeE9I; ztUVLHBKWtA;S+zKJdMG5nt6G{ zEj#(A*BiHN*6Pvo42)(bVmza`r>&_6%`d}o=cz8pB3KMx}fkq zpB}lkl;am1vx{Lxrap_eoLf43c!Jx{*y|}^6BI^zuViS2D&3Wsv}Ll9YKJwkcdD&2 zIf_Aj)u-laPvCdSx=!DnwbkbpoD2(d^G;Tp06sLVGQ-u?Fs;aRF=K@YogbPwVK{`+ z?CKnDr@oGy$hqIH;aSJe>}n93=HVcA#fd_+^$CE?fdszq7eL;7v!!GAhY#n`yXR$$ zPB*tqI|#|2vSV;DCN2^otA_scYwB{qu)8*uA%Wm}I&Y5h{1-Ml&6{^zN;!~RVu??6fMe>d>6Ipyyz4A}O$Ghqh9>pJH= zuip@3oH89olj}e1IarV7AhgLE}@gzB2>}X=>7EC)w|>;kgFpd!M$pf3hL$ zSDfp}@GM1uxa+K7yD1pT6S;ZwCh48iA3HCB-3kK1r(Ro67vk<(Mk^kVAoIB~xWNxV zol#k@Y*PB?+ZbdL*ryKCfHWu#GG)GZ?&zcTJQM(a$>^6`uo8B9gNVo+EjB84+cY&b ze_4hNn|C`pI{F<9$O&BZXj3z@OR%}K6elp8Zw$?Jem0Zjb4gZIhlx$`^jMR!B54@E zDu`r@ywET?+p_Yr^_(qn1s2E{)5;LQ%m>4#yIjki36@U5)Q4iCqAwA?==}a?s`()T zr~H)Nt9EQ7a`@HA%{%v~ql4+Vq@<)COc|}mDbs}u7b>iq$@qK)SMdVi&d-kQ^7H3G z9zbjZ%83sPf7XOBXL3GNZ9LzBBsP^#R@!?Q<=pcKkd2}RURD6DdD=9t9wuBkUe=;o zeB7b$i?Ow|v~(NDtdAc*J`z1(_w$pmFab<#c@i2CVOxZha58@cW=qKrMdf)Cs^ zQCqj^eyFBt8Q;Rc?*@8NE)sb?B;B}6+Ezfrob+)da5i{w1os^{FdOEOeuo3G`T5eQ zv@{v`y;`=tfq?-Wq45lC;p@xH%Y)cGd6>1w2??~b_^TBfnwkTjC0puH5Nj5h!q_m4|NFafy}#L#>N;p-%Fg6JxGWt??E?e8@}opAMSY^Z_^Z{!RE+%`ZO%f%`YQ0 z-lf988*^IEpw=-L zhM9k0*K6M$u)MQ7@zW>;%(XQ@pN^qi~p`r6Sjs=C{paeg7(Cn;>5aqPY0><8D zT9)^N@7`SuD#wg$i~u@xLXceU1s7QuhPh%i95W|A;|P4=Q8@WD+~^dX1J1aGJN)PURd3r!tjU)8m|Y%+;oi{c{~A4&g-vwJ9soKB*`x z&p}$As}+yX`yI-LhuMgNw^Tz2+sD)bt>dBL;gX~?_U-GcH?H$MjMCkWtmP$ALJ$kj z!#;*aMO}Wq%TftmVHaYyl^`K5fVNwQt4_oQF)^C@&K&y6;J$XUgV)OknI2Tzs%S7r zyG{NUh>=6&`KXp{g~9l)Uea3!eG%a!ZXXINmg!mZxa=`-|)~K|r!k zRdp^r+lWJCYN`}oY`AxVfD>?>;DiL0^A$8WX3sbB6Z#o|SMy8O_VksjRs}zLwExvy zw@2jTXwn`{(y$+5l{;xe61e;YO1TIE<`315ASTzO;VV9-@NA7xqGqydPlw@}Vx zb$R0ZdHLk3?;K(6+sO|fJm4QyYzJmk6_e(Q>7ZFC zM{=W@ovXzThUv@NvAoHUu^ue+3$gT`%co51oY^&_b2o5@7FuOMwfx0gD0`1{ zmHTl47|p@QV<#~_mBKIsNxTG*qNUOZ)kjKMjV&w+5|ji$_gI$>P@uKe2;?sz%=N1t z81orcM*t=TKcgW>B#;ibEABnCHo57#8svMr7B@a0ouq+TVAjbI$8a_=Gi6EKq35UW zb$@rbqaXL|ngU~<=PZbuYhe!0?4D=ir@uh_=kcf&|80c!^(FKuvPrjjjzJ-(b6zoJIYzUNAl>jD9c33VXrXBx#r%JL z$)~iF|4&2uM$vpD$%~`hF*=_Xz04QLw`p3Y%~`#AHAQ{|SHOvq1J;A=8bvH$UM!cL zNi%eE40&L-5$bqH>Mo}Ei^g;*VGa@L(+~DsalHhQCkfQ=I7uP=)~#FT&l@A4ZOC-b zhL*zu^nzcw;@qK6nc4Ie;(p;MW*U{DT=H&~;&<;q`rLbUXl3jmMDP;-PV${T_c5R; zdbkNfc;e^021SBMZe!*DdP)3hg~H9#GGqP(cs&rhF^8A2Xz@?a{`jV!$F0NPebWW_ z0{DrrVjH(Zc@Y*T&8NFOT-$!}fJ%4wbI!WQs4&%GtLF)A+h9ML~*TNW8{}brXPQkcns@M2|_tfLxeR4TbYhDhcqw9yS z*Vh^AxJf{pi%8Q{P>IPnfC4g6{iyha0mCC(q0~f!Olf!ox0qrs*6uypc`rlcT^?#g zI4 zT?~jY-7oMPE;Nj~&_vZ83m+bZ;0~4PwxUHs4@JWP&fy_T5P5{4MgIXU)Y9nki$epz zuNM8vXfQiUzc0q1C7LizMctl(x)GO{-!snQ^EPyWYa@=jUn2^@g0FpkSV0EkXGZ2G zV!RwHkZ65DMZ9|f185_9Ni1o|WE|XAsF+1XJo>z9=qSX2h7(t8|IQfZ@m>qiZ}QOAB4P2g=VkTjAmUkOa)`aa%&S{W zKN=yXK(nxkMo?{}jFXCnc58>(R{Hj6oz;8hHm(QsRI$F5V^&dd|2F-#jHcG8q}q$7 zF=@6~`Jn;!l~vJCensO7AKv%M>({S|Ga(3`4Y5wCto{^iVIL!~k+MNMUzp~|x`>*1 zh??B?;8E5A$afP4(7nTllBC1bg`$FJ1>=E|$`Se(AkynY7@`Lp<(IRSr1!0>PQ?WD zFKtS$3!rErSau~=$rIIJaWqFXLR{oZczAdyD6U}LyugLg!_^~B80xyObuzX&LQO}= zxG2cJ@v_)^OgAfVps|jBez|>uZ7^s@_4z#7!LramxPAcone#ISYP$8%2&Ef_Uctra z1e}dh>jfHhOhk%#!iKwB?r58WQ3b(C8XXQ3R5Nab`*H(_eV)*^m5gt_x@Fo06!ay! zo-}$I*QF1swi5{&44ApvC-zmtV2lo>M`!c;!jmYb>VZml3=hd$H0;y}U4_eNgIq^! zoh-1j={?te@yB9kgOfr`aSxQ5?;aX~(#v02IiVQ%JTYH6zq~mUM+ne=xS+7Qr#X<0C)k~*MdMaK1zdOcC5yxyi@s$ z*sl(8tw-wvUfYU4K~; z6_}6V=XSrXK(G82;#2hZb>68E1G@?qVtQX&2j``QVrxLITM)^2{MBM1bQ^<>_d+(% zIfvi-1q7%9D&pyKLpWJB(EkA*C_25rUG0h0;ipgnA>)W+BpoD-2{QADlL0c*+zuK} zs*g^QNgMv8Nzs$mAEI;f0i>df*c36fZZu=i0P4!eN8@!{p~x&sEW5m%8aKK{ zW$T4UpegMC9wf>OmM0q*`Z$yKbLVvo4UHeO=dgn7ynN6yl?_JSdZ#WN7NS)JNuUkX zBeg4KRlE_l4wLjQj`uyV3jz$TxO8{}uu}&6%QIx_CD6U8bOOYn=Z?67M^#ytu*uL%LZdu@rzO*UV zR`pWHk-C5_Nq_E$zW~20Y(@O1M9=`qco-I<9WWSfb&_-h9Pfnn7Z+uG=K^HD#n`Yw zeOSc-8GSV19K*PfZpe6N5jzbZn$z(WjBa9W@mGv7!$D!xTeBZN6w8?3k=%Ss^Bz3( zHXl_iwpiUsYr{eie|%ru(G7vu1xJX3rW?#616ABYL+Fdq%RiBczaZAdz5LuNSVWE3 zR&bp1T*o+XxAlu~HjWTs3(GT+32hb6i0G8?P+>Gc^FaB)BsLx549jK?p2UnaVP?6O zwIb#K+%xWlYW93|)W`<;?|*|vCGo~f*g&}Sv{~k3_z6XiiE!x9;$yU)Nx=vV@Vx@* z!H=1ZsdYmZhDvwS7E~dk8EyILNbY!)dr>y2$cLCNW*7tW!MgW2TGKp*Bhwi3rfmL9Vke1_V7CIze zKq%{?tk_!c$_pYbF;Z>ooiQK1!JJsAxW%*ipt@yP2(xDGBLm88o+F4dk=m)E-W6Hv z(42$bF?OPu(cH;4A@{LYJ}i6CQpMES#T7u4xu)8SJ5D{i#b%t=YYm64grzN{wM^{PPxHQV8943)y| z*nv>2^{__>D(tjJs`K%`9VDMG2(Q;Op$niF-8;oU1C~LnwL50BQ?s+Blkk$#)Bz<3 zgr3Layml@?TgYHSAocy>o*fTVawJDLSlx}bnW+KP zHuEu$+GctuqWP*2%~!S3ma%dR`qReM*N^sgLB}gEG6}7POPxr0EndgC@a5ItYece~ zG~*2wwT@-Y*{7=;SRsZfHa4|CnM1T-99e@tf2dYd=iyD`Rb!U>6Fv5# zvon~rc{^9XT5#=UjYxviLPTDJVBO_)97WP6-TxuDIMT<}@W+41=(~A@%j-8-q$6cW z<8-deOwJFBh`@dg{CYOkbQil1(ZWmWIymL*3clw(SY`fqV=~5|!JlDYSA3pW0q5?0 z~w#LC1W z|NQl4;T;iEF7!Ag7cQ4UqNF>}3V9>LVl>Nd$8)a``#&}#R?b(Xw^rWmv_H(oZ<{U8 zgTlT#hgWg&tNyzEPf|;|J0UoFW#*FYoKHQbta-8sT-3^?BR7tLVVsS>2^{dF%oy!I zpKcZ+cU?GF%W6|s@6JM;Kg!W{zm6V0!T?p9he$_Ooj@Z2Z@*(-f({-Ur zf@Y_H%ZtyZDtxVlFj&nzQ8P6poJaatomFBKPryU2EFQb1%^-Qc-iU4!VdjI$jJduC zz8&5Nj+P+tdmtixNo`^S)D=zX{q=E{Kb{D;hdb!z&XniAre24Pd}klVd@6i@j8z+g zg}TiDNE6hc9c!qIL#&VO*?BH?%(nWjr2Z^QQw*IUvXwkZoyf*SCzcVI=r*OMhI(D< z4x{r8O?!1!xZnCnA&3;4myRxyEL^Kbq#$el_HvUZ(Z`ZkeI8IKJ0Muj)7LVXRuNw^ zxzmfC)|r0^|F$_jGXo}N4dh}t(L+?&A=PqQpUAt^r*bd<$G2rnLSjh&p!71FU!4- zto`xB-A+@>?uE^Zi@!OZvjuCF&)evV^wD$fudbnd8Z+xJ0i!VLqtuDgCCci%q{b{I zcO-Jv-F}YkVLmMIR9hrnk)8UmHV=s0+Uyjin<0xH$=g+fM1Q57b^4S}d3hGK%wkw` zK}Q41-pSM!YR>ixMG>wmp zL#_5*C#m=6m)rv{Jn1X(tEqvDGT6Lypi3_xEW8l$LcaN*O(~-*F+AFIwRs#-u(u(2 zT@#PMg9mCQ2)x3_)t~=8H4Rx*a{ihVwgGHv>K|u{jo0|pWey3{9kL$`9 zq^{#-1+oJj#)#8Tv+%afTt`R_Odl{4M;U^B9>kqF2DU;c2de4{BIizi#e05~qdTQD zk?7rX2;yj@(L9E_NMH2O8i46>^;&&neolP^Ej-E6QfO3xgxXKb@LMa>w_c#?cazVe zBfRYax-3@rS3@0pJ!aZ9=LMkgk<-}%FRbOze6t4xd6D=S1kj^t7CMiL?Z*6^pu>2d z?UT=L!w>Mut)}^yJ~UCXWqpzw68yO^XB=gwCMJ{91?*g9dPx4+@kl?>?RRQA(mI~Q@53U#I>J#8$@r8MNs62E z0!p^rhdb{<|G|oQBPh>r3zR}$nAd-P<`Sf&_d#LoPUdFX!r>+{f&NsL6-A4A-CdF-m=s%+4UkIRw8ZLxL zm7OUBv7xD`-9Tx~yY~4r=K0=69GYFKs;k}VOSmpfG21kddQG56#nhsN93f(=R^ZX0(|2fRY=+p0GB*)JiB{&;SoKMua-LWTjGKeI9k^#6HX#T z)cl*O&Gyh8{FQ(>$BMD3%g_?Wxn;(fGO-U5jIF-#zc0}J&u$x9oA!A>0h~6`(A2Cp zKkp|B30i6%lPn(vC;;=mLk_Bwkr5dwNKIn!eG%3*(0*AWC+8Ydr&|Nr8c0|1c_$jMbUluM9AMHU)b7T{2Lq>9toiP$+T?0chfXUA_ z5q2TZNe2TWT6X@XSS@`*jewzc_Be?FgC{_VP>2E>bkGurBI9CdJ`5n?r=Qy`>)W=JgI{3+xCuJgdw2NegT)t%Ty;Kyd;RMnUYST&k zjtf*_{%pa_(VGlU^+?IuNORAgJ$Zf-!h6v9F?xcu#gINy4z=4)T!@;H$d+DalB@}& zWrPsgt`HCiv+jnb5n)WPy`GJQVM2~ zBnk>58I&N=vQ!KhFp|WG3IdAccq~B#6-sxECIp^x_9ivZ&7~vk2gdd7Bgp!+3Wro6tUo~DW2}ZL$9NSSoH%GtB z&p$^PWjYSfY+%~XDPA~zAH%uGvpgD}dekL(k)K~t=W-{D+*PQtQR?_|QHpUNBuCG& zcSyh8ms){gyy91lor~3m)P8)pjE>f6>+#IehjcS>P)tF;!RC!8q36_Qz`u?tySJDu zW*`zYQRr5KG1@uc+DhH*j}f0Hz}%7E%#&|DWJ=13Q#jKm562Ie}RtFAsT^D<(9X0{C-ywK%)+ zy$Zp{e-)>)&@&yr{xhr>zfOit+1Vk4yu~O=X=63GzzB}Q9ZB-&+O?2&iSB0mdkP+0 z^hA|;(~Y@3rr1U#&UA(2a}|^~r%2xeL|O)wh?2?-X^RE|(`~>e7zUaD1u~#u z*xoq6dP3>bL)7FaCACFuGRhG0H`2}_aPS&xBszdeD8|(qK~;MOGd>{?!bino{9m$5 z%M9o%tv$L@D*S-(Hf~i;P0&0mE&}A)y4CZCo5C>rr}6LJUrX;myvXmIHZmBSZQ9cP zo5qSRl`gr>dhMIc*ca^V1kmr$C|*&}S^*C0ZOr-E{JYuzvQCJ-&Kc&8FRu`2iw3U{ zX#Q+oA<$$YULnw_|6I;rx7z1FcjvEL!7%?>JO92H|Jhmpz8C+AJO92H|KE?w>t0%q ze=`}0&s?ID5a|Pi5K{J%v&n_4SA_xAo`ex5W>lR%I$lk=bnnPRA;Q%b13~S1_k=zg?y^-X z6+OD#L;u5Ot)`;>e?JcToA@;W&UTC=Rh!}Y{VnA^W>9CR2xP=%r3Y*u zv2^#t6YaB94!G+TbfsbheOp|T| z`tGO6cn-<8*yk4ZgInpW5Wy&G`@4R=pjBm9(YqrU?bb`Ld3-&e3m#3aEjV>bRdm=d-r?1p3Rh_k%0N5bKx{CO6lZ6qeT02 zw<^Y@{N&cKyx7IAT(3kWVo*2h36d;oxDzILmH=3+yTTjZYuFztszqz`Jb+*k>eW(Z z1B2h8yQ30T+jK>Q*9%mF_@Hq@aQZEj%d})+OM5vKAN3rifJ+Z`Kz{k<7XoY*nm4~6 z{Zt|A+4fMNFIi~onF8db3XJ@b0AZLZdBe->$3O4Fb4GCB0ep&BC+Jc+FI$_i+W4(q z$HxSG8`UjT7E*-*eY*&OH`Ek%bad=I91k}lO?ZUUV#8EmKUXN>t5Jaap-1u@HeoIS z5n)@8M5sq3DxsMLXKr0`93htvw0z1NihsNe%#V$lC(Oth#7aZY9!eNb!&q;t(_Zoc z8}Q|8VRL^Q>UamxD2SBRaOnB3zy2yME$s_Rjw~2kJKd;c-sL^e;R?eITJmiG9I{aZ z8T6#aw`^7rkd=`+jUi$)34f-iOx`yaf`SaA+gUIW^Ts}K1Je)uKNASK1lnTvSIl>D z`NJ+N4QTxHWp%-ms2)a+tbx%N)q*CnQc_Z|jG`&Mm_H(>?Vm||m>e6qeg+uflpA-* zGeJ_Dyqz47**}LDLG^g=?log)tVndo;4$UyyR$Zavn*B?{d;RBJ`4> z&`2U45HbMS{!T1tDej7fZ)?odp+d=vIho-1NRUA!5evv+2(3xGTL677SKKx=&T@(H z8lWEkaABhfRBe%YW{?T1?qz&b-$?RT!p~(nBIY)c!5!!J%(=DXnksRyh?W9F+nKP* zolzI;q$_^#&8lK??{m`+eb`JykSx$eOfj>Dsu&{7T-99>HD6$`PJKuOZ`-Yy&Hk$0 zwW&>0)+2`qZfA9&lDXHsdEaib=<-P7=k2o&nJC- zz}Y^;wi;!`cLr`_jJEqrZr-$M0{jEFQs0@J=|EA+?cCWBg_aaJBfdM)?^ywYk;5m; zd)tq5*o#rzHPDC&medw^{L`kYS7=i^fj|(f?y%?4`N zXkmXpQQfjY9DYJ=upr4q>t+f7nPM^!`r!{A-;$DHA5OsVbuDHB#%HgKBnT)ER0BXG zIi1o!ycU0L)V!$7x3fRRLQuWG)%qO!KXPpGe8_9+hd+U1{?9AK?(B;nxqkr#SYj<% zm&7lE9o`IW|D~VGj~zSa7teDzja$#8UIpXA6y$(5;uF%2#uNkUW@aIze7gVE?%0NT zlc?2oyM@KjV^%(!z_i>Xm>Ou%blRoXn3M6%OYxS;4>u8i4V2|;wWXyEyfc|7N*W); z`^}dGJf9&mJ2RX8TAd3_;#6v1G(@GylA(;Y|F-AxhqBWBL_V9#@QjwYv1hc8)g!cl zmErwV1?%4Xi~A3KWA`GMacdc)*El}7?JIb$_;#Cg8*csHFnJgIo4*DziGcv_pQFQa zK(#I5@b`wLyLn!6kx4v7wkXumHrO~2={0oYsNg9~x6neCaU0nT^)Z1qol8w!ac>xV zn>^ZxY=xMsm(`07ezo(LypXfE3X%I9HEIZ%b8~a^Q<`{=Zm`$gCl>xI1+s7LG`3wIbVqJ-ioD8y__Kd9 zf2AY!-D>i;uc=%kxJ;6|K-OniXcMziUXqbb0PtrVC8Ik8ucF;o$e{3tKR1?5WUjt^ z{W`ME3mK-U3#KRk_$N?-&prulq5{_;KxQ_dwSWANz-{sbI5lM0qvbDYl1#2>3o-Qe z$3H8b<}$K+u!X7~K=1GV1u6E=xUp;!bF~5UKK;6iqD?AZkTv8Ff8GR-_Ic^q;$Crj z!@R9-Avt?zYx@)OH1!_OuSgQY$AAkL?3g?Mf@F?t7hD0W$$sZb*xz5Nw-{EcqAf#k zx3T`)FN(tA2}b*o67Adu>`0uxIMOI8>j$$BR_MI0cmPpbv>4p^-Th$}cWNbUH%0sFVn*X5X1Nnb>mn1>5zq#wnFPS}%aO zzYv*>F3h=Io8pRMR?K35gU)5_XLK~e7xR1Jztj0l&^57iVph!Md95FlD2UfmTX8Mm zbKKPzdzT0a5rMuNmdw);!4`XTw^CR95{3-B8L;0U`0JJ888e%_T8~O-Y~H;2%na4# znEZJxcNB7C^1YlaEUblj^BNkI*Aa?|c@=bY(sFO@!MuS|aB#+@k7s`>8V#u<(FzdC zSM4$~LMwu(t{U?$7S9!k!Z4nRL;$<}db`7d$2{l9je5k#Bbdp(lxUCSvW@v1xnB|v zj54};U;_J@G4AUbqZ8;isi4z2iGXEax$LxpXsa>5iur$JpG!CDg_xo$a6Yt%b`7*N z`Q^!sLu(TdAr;N{vp;ubHC|hZnRTbo-dU@!udmTB7hh&vDU&;#^(%LKkM@bsf3$lQ z2p~&v9(*0^ot4gd1+!Fu&wdKF1gQm{Bg`G}^Nu*4Q4orNu;5#J`y4sBjWgL_&QTL$ z^td?%G6KIgyAF3Q@QRs-=ip+V347~F0Mq@hEE-tGUSuEDPZcPNg;0K@a@=!sy z5^`GdEu4nN=hS)ZAaP@v<%K4`ccx$ln@(Cya~6Ubf>G{PZ<#?q zU-0DCo{>;jGc;p=?VDGlFx3_khpP>z-g_f!&Q$(`%DJD>WR5cWPf^~JOU@3SKPpeHSv#u(WUWmcA@JK znrH|97KkXcqT9ZydH_y|asPOE$Qa+>0@w92PL+9xKA3?=(7_XBo`UQ(GGZg-dS+-? zaiil)BqFHd^aEKIb&OA~CS#OEzQ!+davr2cDGzrgt6B={y6kjvrPC}X>K4vn3Z-%( z{6^TH88`=?{OvB|s{_&ZCf&w@Xc=9;bh1@My^vqEmwm^Uj^wXAfB-Rt>KsavFLy1N zT?wX1Ht0TAv+CKe-v3pAqd?*g@?gYNYH@B*)#AX!)d9MM=O|x@)31M>{alFDV{{tN zB^$GpsxkGTY%ag9zvN(NLdIH>41JA=K8q}OpBuZO!UXzL#M41`({-omH)Epb8ie7ljo_*Xug#OS?6 zTLvE$rxp$Hqo9GRU9$Bl0r)Uk+RGa$#`4)KOxfJhT(~WGgposW^~>Cb4Jpq26nnoZZ|Y=WqZ@orMdr>skh#cw!O6uVo@ko}Of%D*Q=OS} z#%!sq{H&l^2e!-)c{@6>YTBag#iEz)EEJyl_?WZgLw;N7UnYo(1@#Rsw(DAI<1*~s z>og;^(C~X--19J%S7oE#=7IbKcBZ#!HLnHSjlVl_{N3>C@7m+oZY2 zR^R;Cbm`)|C7AC##t}a2DP3na_ zfR^~qK#){fe@afojA4|9?=l>5M0nxO^MtlxFyISxx3A+K2q(SFdyjz;P|nq%Qh0%; ztP?WzT8#1@;;{5WFu(5GJe9A~7;dY#OKc5C?3P)u0ACn`{Er|2pg(yqXLLm3W1Wz| zUsO;~gJ}^uC_CVe?=hG7rg-)8v4c~`9BTw)cG_xqKj z6B_g@=h*65AcVRCMG68QD`nDOCF}&d&bt^5y??;&EQq$m%c6+`u)_@$vrU|3m)5Z( z=xIfmlhQybQs4~`hS8jq$Di1na<_bkwDYi#n*d@1AmSh|*xFmCWpmNySD)Z(BQrAv zux%++8%d}yx9IB!5G$01v(T&oq6e*2+2~J}*8!M>a^1D+(ir5ilRBYaw5Lwws#LA(8t~#7H z8~q!Rr*mJ53=_oBJ7Hn-K=pFD`aR8SpcnIHYEad_0E{LNNa#ahp<-9zlJ6zEh9dJ_ z0p`?zvSCTwNZES!(drYmc?VymWIasAscRn$R&oGfQQO2nj$=4Ya@kCK!#$rQ_2H@t zxX2&=>Pycx!4DXd-*RXbDe&=u6~@wh4pS7+`*+ zT!iK!0QHZkm{>{U?Fac+J|z!Nv}`n!=-U~U*7-@?rPRT&gD0X&pN;v6QK|>xO2Q?| zWRpN4aRgDx0z4O+5l1eLKYqk8Un&P~ve%I}KHS=8ZG3y5dQ+s8OzaBB&o2mKS_V~? zN}M`t)iLprwpq3}B2aDY>dD#Y<&X5E7L2BihYod&v}L01-(Pog)5kBCsuktQk)EF- zF5W3Sw5Seg_eEk*;b;>cWaq}x!}duqwlPD4eRX704ZPL~4U$?aJe7V6+I#x*t6oMR=!?z<#_Z4g<-Oo^#&!#wl0gXH zho6E;BQD<{DODS<-fxfjnHN&wx-1rHBR4r!!C-`!`}Z#wkO|d+7?_W?&UH-l(T!x^ zyp<4-*zN;3^a3oa5U@~Hw7(%(e#Xo5NYVv{Ay&5(VrGl|xiFvB+S19TnDs}TAyiHW z0ft`2H&`T;IhXVvWnb+h>r!96k|%5d?iUq83}LHjDj@cQqK- zpD>SH9uDp~NaaqIu@hBh-+jZ!V(j-YM6qT6(|_*)`8Q+N|J^6{e=g|92m4Ps&Hs^i z=-us)<1QUV6=@EtDzF$GG6tvr3+X6r7t~A?BXIULBF1LfvMX4hiBe2z0N8!!!S6JO zIx_(6FmT@d|Jsp#U?N(b3vvE5pRyLnznwUIBR>O3&4tUgJcyx<2x7(_Y=Df3AIZ;Y zaz&$Z2~I)^oLt2q4p<02?P9|=Nn5|Yj_prpHH_lBk0e35UrQS4Y*5LAK>`$6y8q3N z4mP;M>C|Qtk3oc18}3!|Q{Rql+pHZz;yVu{>vV%ZspBv1(fV{5 zr19-IR48s~qj?>l$df6SgicpuQh^4LC^`v!;&!NHm!5DkJaJHEOs{RT4oAm5HbL*D zCyjn0H*uP@fIeQRN84$WS64wT7e|9BXgeEf_i1`B=pKpWRxOBT5fo#%&9}H{&qb6( z(Vbp>lm3U^oZofH*G`e4uM5h%f;#sbKe23vzW)WFy7MUJms8lv2S=Q8fc53DX$@2&mOaSj{}0z)K2Ng|Q;NHU<@&-y|H`?cx;LdALD(Lg~_7NQKc!y@y_9 z5`@1r1wq!GedICL?kXBgBE0)C0^-%Gk<%~H0RX##59Y_bf~*(3D0%xj-7v<)-95fv z_kAfeCQgv50TmIi=ROdGC=YQjm{{iRr1wA%f&Z=`anJAZfK4G#t#oZM?O9bMoAj95FcW$V_9xV9RY zLTo^${0u;xjN}iI~Vf6kZ62c(p zwB?9q;RwvY93)Z0Ql3*KYr8XFCEA+vNPmw$Z^53{gtRwyXp%uHdj-1e#iW2#>wSC9 z9NBy0hZz`EwiT*R=pH`DzSp&yVP|a(&ZN^fXz}Y#N?m_J5;DqrU$-}f+}<}K@$uuu zICBk2?@wUXQ1`hZIy7~gBz_Eej8D{7MZQW*K>6%m(YK4HUepFTDoyFP5p6(br`GXc zV+|U3ucXx4PQp#ZuB3J-11N_D03Q)3r6@O@Jmwg&Eyk;U-$W}9$XB|Xjh2PXeL6T)xSLn9axATTpO>-^GGCqNibDZwWmi%)}ao0iF=?pW+*;=e!_h5 zQuOs{bbwpsk&)cO2IDtE`%3FhO&zpZkNZVaq`Z6YdFO(weU(Z`lc5e1C*qif-nKM; zUu@vL3)30ZhI;brfXlo_bLf;C%P)js6xZkr_yFIn!T_-FW!)vq#|GV5_H$p6_dpRT zv%kU4<8#GeQ^mIj8$B05%D2$GFUSUBDiSk)!|nNu=1x8hoajh9S1#Lgx^CN~;V#lKq4n z)z0KeWlBPk#S4!)2C}}CIGO!(HQ4S)n2g*Q>!Wf!BC}6S~OrPKq62@8@{= zeUlj3$zzHEr#aziQ%vlEIwJ_ji)q64$u#efwgiL@ODjgPpFOAZ=0biBhCVrgY7vS~ zBzF};A#&9;VcSG{vV^`54O9$;U`tL(na*0fcy8xt6V3)ZZ!IeznWklxBI5}P;sFtkg z465j#XEM}VbowLDWvh(gtK5MZH>lMWd)YUTDWT1?=@kB}08b}R8t+n!P32=_Z%q7L zzTNB}^UvT;!XyeGn2>xOK}C*e8bri@XqXW7(T07O-sB*l^C{-{wPb{%@K41gs-7^4amJ09ND_fz#TC$ttGuxRZzGWDRZSj1S^KhlwF_@c8!Jp_M?M5h>ou;|MmLTf@ z%Wwhh^2?q~BIH~>bzwi-UnCVatRVuR#YwU9|BOambMgqKtpLf|^B3iRfR55Mmi^;a z3eWHRzW?T?{em6HVLU1=1MQ~wFPc2&bvy2=cPQpt1OwRUNy+F-As7Wpop*|=*&yG) zt#!rhLB%Ha$N5BU?^I%xEE~)#!Y0_eTLr3NztgBg=x8L`kzGA@ONZ!?rUxQ_a{^Is z9|or{gMow6rzcNn8p-Q6;1Di{7qOqvse6sXI5x)|3`e*p>^)c5K;v3gpptb%B^#8D z$R-cESMADH`p`@vtvi4qBsxbuh>p&Oz^%}HXHs%%LB)FMu|`<@eeP5NVuE@Im<`Ep)+lbtAj(O)o22u=1K;1yu1y;xJ`gD&u_*%G zEtkK<$EEA@fIN>prSU~Tm9|1>jx$RQys`scxV7)zym|EYQ%BJnKH)Kpu#aKa-}0qXta(J^y}D*a(CY>CRIeO z^YOVFxceM#uLH`4AiWy@>l|p@*@vJUI>8msU<5~{?^UCw{z<_CnC*qYH z@`@%n9pzw{{H8{hHx$Es{Ec1+t=uw{J&>g(+}R{OIVHq@35HA&S6M{$@IjjI)acB9 z3f%WeaI$U@! z+}o1iVg)&K|7@3HH&Id1C156!V42%@L7kEcG*-fuof|XO>bbL-Q~>+72TN>TGS-M4 z_`)3zcV0lJcQ5AmVaIKt?r2lzj!F!zBYkQ;Vgn8P{k+k;cPn0f;%NnTDA2~pQDy81 z{Aex}o_VdbW%|3@=ugxu@5b*K|E++;e5zT4;0_&aHG&X1p`aQtd_d>Dl zhKA|I{t7pLYpNNKH=}0cqP#$5OX4l#Wr&Ck()Lw~LNLYC2N@F$i_17asm>Nz;c5>> zo_?d^`gcgMui%iYAqN43^q^r~$m5rxTk!<9MmQyF(T=kgtRL`k7y4$2|Iipwk{Oly z-`f>AyCy@&OebMR3yR7lNMD^$u!e<)A1ImO)AT!?w8-kz2|R`^V-RLQIu|*^*oa&w z)KD$dz7HKdNXMDYM@vh>nwP+Rupf1k9#JxgWj{Tt0s-9#-VLA6$mhMFp{p3;WhQng zxhJ=618Y^5MEq}Py96|qpnGG=zp297pV}p%sVFMaq}mY zMT;PFeo1~L)TqaVvEs&-NC-5^F9pMu)BBq$25s_GyGr|?srRpeC1J&}GTZBpD_Ejy zPG=N)i8({%TMoku?lX47OBnAt0y)`>CDSzGNXeM@^Kzgwrn?F5{#`d~+?4@oASL1M-NRa8fzo==@d6O)SmRLpJD2N4;R`zt7cETHCu-ONk4q$no4#ogxE zHS`o(^nT1%yMpzn2qIMJjx?>@_vGOD`PZLhUqIg;e>j?sD(W*7M0;H(8Vapjse?NM z391SmXte0TJm&L2Xj~#X4FE6NCfA42l)$8~;SsPtxOxWwPRNJ)TA6HlR^+;L`hQ%@ zD3?p$z}j+&cy>LK7~dk8%}D@;2gd3(eMnpX6tqi63T(*#nm>3_dP+zL8LnZ@UkuJ@ zm#>4<=ks3U#h8p+4#?+nX<8kTUdeO~vqvdba0Alsnj0H>Ity)@-tP*LY>Kj4rUV8# z`JDx*c_z2YH6AqQ(Bh^9j()rSQo?;SFwmL0|@m({N-zA^&_P##Dc zU!&<;*#f)c^ieY)@gh#y(kCLV%I>DD9UhH?Bn6-P#B0UuocD;86cU2yI z8MGH`A(v09l$)LmHq1BJx!x-)2~$~rbJL5p!p4_ijhME+!CD6N;9N*{0}(-GqZJ@h zCw8Mg%)_o0{_Squo<5H$y#o&@ay_Kvu@>5j9Q3>{0!$Ko#?e{c*I7}xr=l><@WfF# zXnd=d7*bw;Wnm8d=mG&&S*Hjij{t~F{T(HleigJyDff7Veol;IO)d#CkRQE5E9o0~ z6wnacd0op^T?)_1!Sh=+XK93%#5c4V8 z6+f|{P(nRuH1rK#>18^92_5PQeS&WmEW*Q^hk%q1*TYzS_v=_q0gKHv$p}HP2!4#x z>X_fIm{8zP-DVH42V3lQXvxx9(P*LmlBS>Lr~=?@rxgIqcq9D$?ggdn*1{Vn)^bEw$Ive-yKjg1TWTR0(Mu7g6p;?}_FrkIzqFVT|x6cT;^ z{tHCY3&e6WOzk2NdiBjW{X^>w$ySP7PXd-&zMI-o!Fw941XcNeb{DkfOL#<7E{^hw z=KkyM%>gJotWH16&_N;Nh@;B_C#?iv@Kfyl6?$Z`u$+9K`3&oR7D1rM=7U}Vs^w*XAeJwT9Q;Zt#$IiPu5Mb2#>all4q(!32{T5FrBDRctfH9Lxu z(8+c}x)DH2(sQ#@mgf{}lqRzxijC9r$am6si_6wN zHF)J2Z%KFp6C!W0Irh5@&XMS$)$y+W5GGb%2hkx;B?Fi*=#L$1nv8kxz-HWm021+0 z`^7mC2k>I!Eq#dR&Gue!191a)B>9fB1)N(3-~8dBmzMCl*nR8G=FUqz2Z8fsGP;5_ zNwHwvNLWxoD|b-4X_%n$OdLJ+_Jn$;;B!8HNa_2crT%GO9PIhZ{^&p9X;~z@(l|=Mi4=H;CO*>>c05|7D%0s12`S|n_!goZ}8dKn1 z6ur&!f{Rxa;tU|lEI~+Tmw&x~X4>M}bg*Gjoc=h!<^Wt}r{|Hqv9SROX};PIqC4qy zwQ%T>Vn;coj@N*fIqMG)uLgTuA6_^qR@67OTe7=s%Rl{E?LT2|BF$x&Bk>_>3GUTv zJMX@d+BU!rHj_uGeZ7A>2J+jlf`xO?=i9R#A54_`a7srH#r& zzDnJ9OFow@8CAMNI~u4 zrr`?Xv*e)to}(GC;*_nk6J%~g^tcaWz8n}VXPD$qh5c!7cfM5}+20;4TmKUy4KLh~ zO6oHcPYp%Qt3U-Ac(L_!#sx%V>Im(OihlkyJ;5k-(&t;UHFlaWQ@Y-(hQ> z-o1O5%z#K9RPY1^m?jp}fek;+K&l3bjzZy-97pi}*C%=5IV)&OkOyKeWAEu{zFILg zrT2h%qx;J&Hn_4>il1Zo?eRI!h5s_Rd3cyS{AilG-|kk_eB>HeC=Wj#(aB@VF}j{Q zU@Z4%sw?G!#$keRbTW=;NMZ zqtva*sZh_(Mr|w-pynqOcuHZ_F9n>|xS^4#8B`%c&s$2^(xUYxTA>5p%dGnZ1 zZ$C|GRted5*Bpj;DDciX_*Y$O=;#O-UEJC%+Lu;S74ohL_5vrljMNTrT}{zB5{dW$ zMcOOpU6kk+ZdEyxd9CFYCbqws7|7)Ef8aN7nP;gTp5YO}Q;i0;mgtkc7s&Gp_0zR8 zz%aPfaO{}Q#g6D`-G4oh=U#S6u2Mgi4L-G*0+nMQ+`sROqcjV9We)UB@M4hECKf*F zh^Ha5gj8CYgaa@_BHa_sBIt+q$&bjvNNSQ?kv>+_uka1rdPF9_#CuEY;LSabT8aW{ zVq2ud)`a56@-!mv>oUq~K;@WBbP)}W?cH4{)qMfNNMd}4BWDmU0BgyO9lg(!M9|y&tU$+2Y0T4nN2IQKr!O z4=b=I!1l&6SUKwx5}`S>3xVhih(U#-gE}=h(fml9PSZsak&nS$EaL#bedf^kKgNkH zk%SEuWNz2^gKvKgitj}kuBa{1QD6yu&HvLE&SNY%pK~r+{dSNvHspyQXtml778upY zO3n~$0spb+toD3$30yjKVnXC(iSEdva$peMsLLjzsb>2y;{054pmt1qz|VmWe|^#} z1cWyryXTiIGB55(~HLrnpP06V4detTOKt-5e6tsXbG70JJef68* z^yQfVM;nanPW|i03MB16lyc#*MHg7T_my`qLclTrc620)@i9VPGlQaYYlMQnm}HThX$<;I>0f}Ip!W(to>IoNG{&7Muxe|V%D4ON$rDcbxZWz>hAM6K0#oy$J^0{V~$}CLasR;|;6?VfXMnpOy)knnx;F8X%f= z=x!^EwcKjpe!rz3HV;M1`BdIhjen`(&(B7#_<#4=u$o zJi$?>;02i!3WtFB!+SM7kK{s=rV!cDprUR#EHr>F+2K)(>_1$u1qbYX5opT?jCSps zK{(I59d=M!ja*TZ=wSBg>je=c@Y+e_bR1jgjbv*J7Pd(kxQ3)8$1!XfL9*hHa7W2i z9og6H*rxmAJ!T+nvmZfhoYUCnnwb^%7`dH~X4k^lqQpg|&>NLBae0NYXG|5U%NDO-+rTfgO5%BUe}CfX<|=Iu~%_;&===fF9) zH0KmD_8J3e@bq426W5^9x2eKVwww)_Bu!xQ&U^P<^*#yC^^6JpUSL#Jfxh(6{=S|M*01h(K=4L+G{NZVSHL}COO-J3LII(Ah z>N|Sk>MSGDz?Pvi+xdQmi{w9jKfF*#{wog5XM6sFH5_1tC(&n6C4))wEfP$k&o_ku z3>gj$E5s}w&lh$6AqWf8(dOEiREKZVUf)zP(Cjk52wvqEmIMb|Qr(-|L7uiS&Mf?L zsH?Gf5?9{R-1GgOy5~BJx~dS?^9}rouX5~iu;XaVfGqFL%;>^ut7A`!q zUN%Xx<~sTTiigWc|S-|%qEE=b>FB$EK0HfX@)FimKwaK zQ?#ZRI;h*YfqpyWjH42(PPw8({ncm)Es80W$%316ck@?j*SCRCkX(LUP>Xl{FZ-EK z86(o(&m&71@)43XP8Od~6{$8QF@0l4#e++d+EAruLS-oein8UmzPAU{zu%R+Yvc_! zVKo5l1D6cQl?z?SJEcwlAC!KHJg5S^vKlh2`%a!X*V~Rt^xt^IL9ES)YfwT8TM(B1tkk$6*%1}`N({c(+6%_dy zN7ffmRzeymy{4|Q-FJ|ua;@G}#xt73O|Bu|+Kb8wz_Uo9r-_FA3h7e$h!aq1$>@tLP}K%b`)-2V7 zBL=mf@x?{7E6KPfSCz!8$oRiL`br!i8uWI_-4>J*GBVy%;09t~!?@H6tjZJHZ@;6> zpaqwxuSOLKb|xeh!?tyPq0osXLVnk|+DR})^|eA!IB&J>D$iBEID|X*Ffmb?42^dt zIqm~1O?D6@K~=S`r2H(%(zni;kUDe^3R$w{prC4s-vBUdVuIOw<)=` z;)u@Mo3eK&>XRze3nyR7raa73B{4k_@d$IxMlPyx8BZYtgIrJUz(8bC zPwUK2Q<6+-A9C^uaR-zm0tD$Sb?zLf_WV+cAvWB%;xTC_*#Vnr!#?V`aX4xt&!(Aq zHGt{AkUOF2!mT@ZBx%MPc_|qke7n{Gddn;_E{8qP?-?2znaDz_NT!u!fn1&Is79X4 zuxxkCO{2v}1bJ>eAz___7!$)J#gKI+Zu zUT!_^eo^uyA{v=nnE`Yr3*0Yg(9_;WUQ-Q8#A#|C!PKbWMj#DGq-|sSP-d?Nti5Q= zQyZx#YtqS`53`}FX*-b|l*Z)2T=x|Gv#{l8(gOJ9tJ03t|AJ)Ck2HDDrwE?sUCi70 zITG6blB89nzzwW+K5F3!G{@?oq5V!;fgt#h4ODl=P+!L3uIQbQXQRe88V7=}7w9&~M6uMDoy!4)S;IM(54rMMlL0-VDU(QfU2%7#-4^ z*c zI3vFYn~(PGoqgdBuy3Q#;!tGlqR?CX;4{yO?ud+S5o)dQUpZvIk?z^|9L<{Bv9U|v zM?Rfph2Tt*espI-*8(*Vt9gZIoedndn$Ub~zVyv`uQWs9iEM^A?0}+6@lyaqA}7f= z5ldUN>DAE-yw7e5KZl&KXAi24ON6J}zpT4XQTsemMR^5<2pG>jryxAkI)2E0odpe< z;QF9pi%!)uKD2#~%e9cRaFw~HV6}tDrKC#$jJ5oWJeYN+Xu>~6(~P_kY3km_HTTB- zEgB9#7GOKmaQk>Zy}^FeoLM*ns>v|q!Pa}vE$@X~$(j1cc~pnlh`qwNcgFYvnZ+21 zMSf+Zs*ATSo=D*ZkCaSXZXxY*fOBCsTEwD9M~pi~@?^4ynb**PC-JbiYq1#FCsWt1 z8|T2ppQbMKr74jlh~&<0LNZ?$MR)0TkFIBt?$hsT3*I~c<46MiPt15FXgoKb{a~-eI;Hkom%MBlW_s6sb zK9xxVJ`u!$Shy=ynZ}?ZP5jPxvtmGsUrKu-61~%;aHg|{D7Es%;DP`6XBoKOQ^{2v zN84OFvtR~zU#Qp5*FZ`j8a!NL(mW??bC_o5?CtyUt@!Sz0zM7)h}v0n6qDaNP_~G| zH+D9Yeho#;P_DVOwTiSGjU@?kW&>=NrTyNCOcdb_+!2=W8ec&jPJ=ZW1yTaIa>`Dj zQBX$6ttLI^-@bc~fRET0nzTx8V(?DykY2d(A+G$s>Znw}gXERZojHlvHnxI&-GC*S z)>ULb59U-R2u{_+74oy>6ddIggwEBT$g@d#Fa7+0fY10qHiaWOz?I<5WQ*r62T z(^FgTFA4sEDF|6_0Y6-Weg5;qKY%s3l$j}`8HwYFS=o4>8JW+ZOj_sv*#}oZUr&1U zGt*VL28BdGXyu_TzEI@noOpoW?SSJw8zVWVVMbK=;+}-V6B2u$NNQL8wK8d2VF|q4 zImEsJdxiNbH60CI4Bogw5MI>Kl`AM1}uBXs?)pmc;6vZyl5{&d{? zVu(tnk?|1GO*e1bHd)(W{O57p@8?=H(md50tBzJ-B!by-pw~bCSvhYsb8i)Dc>3{= zA!vj3%|XAMjKA(bnZyyr1=K~oOrX_E3e|snJHrIbVS+WKg6&sRI{=;EfG_A|{_6>} z3^hXPwvUJ-ZD}o@au82l4X9=Rf)}H}n{Oq_44FHUOC-*zAD#g3>f?O^`xo$YbnajR z0Ku75q)>Jdy|_nd`vg~5uy8XB$SWwd3rJ?ak++Ze)LAa+3`rdPfru%)2)=7#3T;EA}FRD3c`BceH} zT+1({jbcrL?8~_W%CRVgHef{hX2~r8jt(?FSk!7L@;TDVb0`fXJ+5Il72_bMF%S+Q z1W+g~AC_G6h#-F|_WKD-sjx6j+NNLx{hu@r(T) zwSZt~iuk&{VcfXB!Z@XZmTeU#$iuOnPXF=jgx)c)6b$3ww9qi4wxoPdS*n^ZN^Lv~ zW2k~r1I_B=h(OGBMnj5^2K<~cKMfSISMhlp$(8Eg?1nn+Ms9dsrk+`{b5F&9_dR49 zAOcuyJLZ{>(iUfg?WPKZLkE=9*;F%-wJ`CSPNGb?6Fj1y3O6bOpbvoE+nXE9**|LO zIKIkr9+<{EZcKmJm_EhtF5p_waGZ$1))EvA%a8s(t^hnLG8U%AMkGO3l=S0i<un2O(bTnX1bYzVHv;-X-v^}o$e+m zEI!xOSv*QvvlZu>I)tuOq$r5o>UVXaKE@fdZrS;{lpLaULz+lzIP3ujz(3~6k(#78 zr|OMne2?6qj0rS{MyRl}pc~7vK1dl!64QFccL%`frDqn-*aPeYDh4&S^KsrcZ9)6+ zM*VlJyTUs7neMM**EGz1=s4xyp*jjzm(t$SQ3nua@2%;q%VrMDVoJ|^uIr2bp?8W` z%q-FVjUAp=P8DKo!%)2};UTRvaT6F@O{6fw)Z~)X4(G`&_g?*dgVM_PM2x46N;7_U zqE|`isM8scT{7_ms|fPY&;a3ZZ=wwQr3-2-lKGa%saL48 zZQ7XP)!$gqAH&4_%|>dk5Z`Y0$Gw=%&td<|`L#T)PG;umziB#fZ`fb&vygXzF#3P< zwffHmv2XSN+B-BKxYq|89CvYQ`Dl?7GXNP}Vdivpq&aU3D6f&+@z6#!D8gVU!vR5D0A+c zz_g-lBjS_PSoR~b--~bHlM3~4a+k`_Ve)>fhLv%o+#x&)6i)P3EX+EViCg!1f`50%VM+q{9;oU}Rwi!eLjF)?hS8PaNyBn>%0;0|hz)Cxz*&x7; zYZwkZqY4!7b9iqS$~duunwYFnMHbaGB^K5as2jig!kHl(hDo>3(YH)zuRTVKpRaN` zm=iSOt@xU{w-*Wr>gf{b9Q9aA+yChDCqT!*7@L4;UMqGJJA(#2&{WhaVzR&|wf<2r zyMC{HAqm@Wum!3yvRtPhMw)(Ta}}U)n$r3D%i}_}FVk_w(h?G)EdgrePuyv* z(1a+#&vtw=Pbr~w-CTkx$K9fO7GxbE{Lb((bP;Zmu8UmK3Cr7;bp!&c4$#p9F5FIU(KD z^a2^%94T3-FJ^JCz*G^daRWP=H%|Fprv9kp%|_$2yJH0O)Vyh&AiP$&fF3$nqLll8 zDrdWFGCI+)J|OQ_VB0`U&UK>!CvjR>&UVw6ge{({%C}wg9ABH7ocC~0<+2q)h3FN_ z5hR#M{U8*{mYyfrTW+Zz(vtJKH0%_x&r)(){0I#a->lMK4yi^*#gFDtvWjGu(0Q_T zM$f6>9%_9AP2=h(I4Ni-a$|W~N}*_+&ZwwGD~voN(E=qSbUf>`i_M;Af+JK7#?ynk z*X-{;AL*#b^pli;nCoyVS>rc9`SO-yUR~q+oa^7sr6$HeU)MRBi-DeGH43HE=mcU$ z#?w_@@kH6eS0jyIhNU%$$SoKcOd!(jhYufWn#Ac0FZYi8Rt)6S6b<6V=*iL86!MNA zS;kKDn1IVpe3f(8U&(}j4~`BKXO@}%Htu%g6nxVhQg8W;t& zfe4!j?RjMpejO7SxY!dS_8IE(N({E1AP*(fuE|;*Gwl%wX(X)|S}U2*kdetUV4@HA zd2qn?U>bWHhczXe9se%^cG+1Hkq*BXiU@wX{%rYS+9rS*hrG$EA;MpUg%~P%o zWPA5#6J?2Xb8T>&dXC=OWEzaVw{M&?fp=6I5=Q|Hzbu0K&>T?NUFCq9o)`#i0Oc)W zJlWqRIuo?b%L|4*Dj0&hI=QpccoxFj;GjhvBZ|`j2cB$(luwTMiQzMyIv#KeD%fQU zqje>C45J6%YFZQN9g%ifh}GOZ3OW3Sgn}>BeWe})Eiw806_Y}HKiot6gMBsPZjQ3t z`5?gS9pELDNgsl?%AY4hfh2kSWYN3jQd?J(<@)U3HFmQ;!e`EgJOLjx%>W{1!Dp*% zC%_@fL~zyw*T*k0g))~ATB6=q;(1W76tn07JMjq~bF=Wi@TQwmF(5Oyox=BatIhy8ox#hX3RU92kZy$IcO2BD;^)}W+ zWyGZgIOE`mzRv$nxjXwmebgKCO?9Q{z9k}m$g%&6+bqUbqim87`&aHZnfPCtRM~eD zhB-e&7cfoF$YCv+^%FS;{VJ{WY@ zmp4Ye9>LLvv$#ekG?~-I6s>*9q{$@`Dg-sD37O%<0lU$IA^b;w}n~dL&&yV zp^~bGcenMo>%P8(G5k8VT1li%y@$IA|WTjMykeZ+`n7W>S6Tb1K7{ zbJ92ZOA@(}n*GE!N@}19$CROiKSnGuD0?OnaVo9FdOi+9yMqIu=-akgupiKQbsIIt zcH#3#u}-gmmi?|nNWUgipNMqwh13s4j7Xa43N{uEKBuWodS$C|YO2zh2u-sZ9OE7} zE$pB$(-Y6e1B4bXMGCodN1@pD-k`X9(~wD-dpBb`GSOGF`+M4*tcZ02GPu#?6|iuo z1pD{jYX|yakK*J3zz_pp9G~p%a>R!zH1J^lAJt=v8CT>&MEV8|!xyo>ZWlUBXJ7_% zxXZk{T<(;Q*a6$gsYu^pNm7}i&TicnVV z#r_!|GsNxr?9Ir?-g{`UqcG;J&Af{ziF5{TL!ioI7wr6$vXU*E?K=mPi$s6&$3Prp z3Q_uf?B%_C2!ZK1LF8nj?GE3*UXo!n$AL&k`O;U<+6axOC*xN@h-;}8Omg^08}JoCE#4+KwjA8ow0zIE4>Ar7m24`LPDHj&{4@=4 zi`QH8oLd-9t90wZI+u;4no@>fsR~s2*O5fBOp;das{k1&;;n^3T>ydr-oFA-f*2lh zs&iNu#MDbMwrgqPHwlQ*Iu9_6z~*=PrIm)40jbxy-XBzevxs_oq`-#(wpMKC7xssI z#;k<1e{z@BB5u;`4}%(!6XK5Rpy#?(K02Mi2qFSv+Y|YL_(>YjE+1?zT?Wu*>adZ5 zXTT0#gbLGeA4~PdFz?ndM%m;&SXu#Jf^$?{q9;P^&dA`Ydji29_QF+0Eh3+Ox~1;37zy`I%(Kn^}lpPbL>f`8y<$IDHyw-*=7g| z&kEETP3~ptLuJ9d zwHloa)k<9flI~5SMkUmG&oKbwc6@xNPajWLywk#F0h5QBK5ZEj65$F!HZ_#d_v2Dd zA<(VZSd>h-Ge*lhpd}|oWCN+8G)bMibMt{TmneV~#0wUYAZ-vSU>D65MezSfNcujNHv~ z0(t5A$Eg(xlhb_qXR^cs*g1*l^K>5BwJT`>pezNWc{4_sP^%kichaSaj`M!fmpAB% zjhYGFd{v-TR8CPh`x!6Yx+i_){?WLvRI6o@q?~$JsD4ZnX2w5W>5L6a3`^oYP7gFMc0SyhB{RGbzF=F14KPPDK!a^O@<;hY5ic?i2Fbt8~ZX>h}XLX-5 zdv!7%b8TibdCS2J;SPj{Cn%eCO-uZv!rpG z3I@i%m6l%L`T9)Ri(B)R#f&3vm(V_Ylw)u5$ScS1mft6y89086#ZYmcW1G$DK z{}7h2cJt=9GmxcTQ5#6u(^%44Jg&MDIaN2b@WRB@hKJ2CY>Jo`FP{9p^W^UyMZ38K)?(eli2I$&U?P; zj0JJu@Hnt)WCq*^vMO*1m)h>cRJyHkk{Vm8dBBnaI@ zvZDI)=hQFf_-M&-|6QI#a_oJfD zLJz16YZ^1`HDU*0Bey|ns7g>UnDSgGuP`Bf3IVuwP*8LAQ28qCq-Um%0LNqtVENl1 z_=0WvO_hxrGd7!6rL)r;hQXLao|YUk9(D*>d1@3-nK*N;04MZ8R8$_1XC5{otL=ChvzxYsv-wyCT3C7B9RalQQ zQW_f-9)1cwY?+l$k5)r`l~c!aYQ^&LS89^c2{oY!4!;GSN5`!S-~Hczt3+Z*I43#9 z&>X}3Huf3&@!V*ipf|W8n#fHo%k=h;mZhQtiq5NB>7j$3``1G+uVpXB-9wVhAV2hJ zZ7_DrA^{-IO}nMNk?yPQLDfPKp^1bj2(ln8ZePaJKkpOavzJHBJC8VOL|vFXb!y>h zuQ{UQj}+m=B(givN(-ZmgX(y)jz{Vf81Ky-FfcPT?mV+NOh;&EaER`6UlxaFPt-L!S7-uqDG$v|(1^cssxw@&vhc-R20ci;>-_g7y!UB{0zDI7xOmU+ zzfA+_miWqUo|MO&6ERH!~wZ_Dy*2e zJzw1DA8tJypRO&n+(P&+`9}S1ALXy@4u5~+68glAs1S< z7_=4=%B%4@Ppi#j%Cl(zvMUHrM0vwe`fl$iBbP;(9}m3)$uz)onFcdKw;&1DBljts z%jA)_eU|^+^<3^O8Zd|d>kDo_g35{o7-UXNYHE&<7!6=s|7%T7aaVDi^{7--CDULD zGZyB!Ks*DZdA9lf;rx}8iO5SG05Y#p2GZ|x+Gox!?3>~VuJ99~#^5w{FAo_1*O(n- zT|Z-RjZt1p@FD3tXe4>gs6<$N{Gw<^C>#o@C(Bi=RqaNJZ{Xt)|ZUbNBNTMFcl1Sk#}i5!u;@D?L_UI z+gCDfhgB<}PQg$M$a^bL8{*MfHNk|UcX&KtiT$Pj4CW3>UNogRvp4@OZ3V2e>V{^? z8!xf@;gx1ClB^v;Wth`>pzb|dVQEp4^*qw9Zca`;sg}sS_#K7kMDp4@N~%1_qM}0M zc06JJ#nTr1QQZq(`8n&O>Z|#>jjGf#tU)EWHw_JX^{FeAT=_F(+r2X*4LE0B+$N09 zB8-j-Qc^b-;AHB_;z3s=`&w8_p=u1dE_Xo0$)_3s#=f*%l|sNQ&WX1kv{WV(|En@m zB8$TtgBQH)UYU=HsKBv+ePw{dvO7kjacMcemqoy?u9`|T2Z+0Ha%KN$xTNLL7sTR{ zRJubm+??X+GI9q~xw`0IF>%N!sm*PqCuc|EU0`>oBfL?G9R_GR+)xbHW=z|PJ0jFm z49SB!xD_ZnXCM7Y3l&%BUeJTqKT&dR#GD+Aw!p%tme%vCwM%aNeGZ*knfk6&fPiSu z2`B2=legFZxSVj*`s(BdQJg5? zH;lDC?;2G7fTGT98tNDO^nliLu z8P(^H&f5=s^;^@}wS+SQu`-?nF2saSc1LGwBLTTo4rww(a7K znu0n_>0crwIAC==%-?D}7iUicg4jb);s}4b&=n4U1HS~zKe>6vf58H@&g2;#5#V8% zm>wiPh$3)?Xd{tn=qad1O@&S#TAR5UAO6Zm-mLX+yVMn!DPNF{W#bHAfb2S=V23EA)}TQ;D86aUmrN-1mLR1W z*xad8gQdj%3+{a$&zJn08QrD+Wtnk)-@o;&f1C0zys9vK(3e-z)IAXYO*zp5L6!r9^WzM!= zeqMd}Zm-^b+u!?Bs-W5+y=r!0eM~}yR)zQL%DZElJ?b5GsvGU)?nE_}SDpS(DEwQ9Yh;=5@G-%;rHZIzihrk(L$@o!!N0RHuyS| z`3LhOZJl4MZ$Wqh_V=`gk9&0w0)ix8SqP#|UjkB)FFgPT(G=(>D_FzDgLJb6H-2qp zq$aaJa<=_oadTPsHU^dSZsJZ6#N`<`y)_oAgCY2TyE&^{7Vw5tprnr#GcdxB^3AA{ zKt(Q!6$JrgNy68ZDZP62ngUrt62k#KT>AT}Z|~W8)QFAm+Br9{1xuyE@<7PL#P@1y zRAT4^A&F5s6&}eXd)^HBeFsV`4}h&rR7a63FDPDq(#4NuBIM=+LjgV2JS-0CQUz*l9W9cT;XgR^W;Ei^0i|E_teyO!lvOH3du;S^d$ZI zvbKt;8|$k;0B?A=_}hyL{V(M0St&dew=FR3RH`WQ!t9S75Mo);1fbdhK&d?e#&e;P z7L`A+jAv;TqR~4JtT-iQjsh0|7&)gJ>qflO4rK%DoG-jg^-)!2up3IFda_V9T z8OgikppCwr-2*M=%asvW@9|ixCU6bbH_G1Lydw-M_~g;KXtNHBDlL>?qPjy_qo#R1 zdVFjVPD6qvrmzEI#2#w{pwIKQtO0~(W=xn%QR9H|>#zo?eLE();S(WEL`LMB0f`}I zfkV_$5o_v1P&D#h+`0_Az!R59G)UAfdQJTNgI-k*VUv(w%uoSvcqwH1rtfiTUh>N? zzpye6y++Xk+MUMca&y6Yaa$)+rDXuIaxU7mgcKLYfdzF?YN*#Ia0?=dQy|Ma!L$r3 z&lGLc>5*kY$VK;&rKk*KaK^1o%enQ?$=k0}^Ry}438^PaEI3=kFK=x+U9Lh{HO4dD zMxs*doWEZft2&M#EEau&%m5M=L%Jas^~W4D8@z7Hfq+^wr{pw>)e)#U#Bcq>Fneq2 zTr2#)hQ&zA57A%?b-V2eW=?NM8oRLR>!M8oP6&|~pGuxbYTq3oaK-2oY|0P7>vkJ) z$LkF#f#@m6iyCu8Yf8M)eUa1Jeq&|Dw{u2t1Kc(xmW-aDTs#F8BhTHqVd2y;Y3sY6 z_%5LA^8DpOROcXU+N^)6LiQQOBdP3blFVK*P-WYESZ=;kSLEN*jz%7AHhP;iOvMrv zmu?7LC8yKO%W7I=a>E8Z@Ifki5-$}SMHm1#%WFvzFWvkxq^~>D!J3W1`6aZlJcqJ; zrDrPOYj=P~?qSEtjjiQ+x|e-8>O?(@WsEleLfk;5PX%g#(*UiyUWrBc0AQM>g%t+? zf@32S+zghLRN8MX&WCl&0ZffSrXtAk9toCgQ+W25T4nw#Jq2Rxu(OzgI=Rea0=fm} zIK{75qAx?GofF5G)!qONouDa`WbzMy0I&3UfsRZ~U3#=n2Ja;fGpcy2BU**|@QR#? zp2CHBzPd|xb?D{>48`~$+I5o$T>!iFZ+@KP=3zVBhi}>r0#Hvo;s~xKPC~anA0T}b z6WYO@2(=BHhyje<0Wh2?4vA%_ZQyzU$ouH^*HMVq=GMvo2QTTMHerVH6D6{L^9BsH z3t%0N-LcPH4s|TLa*0H6pBEl#*_$VuIFO@_8r+&~Ysc`!Lb>j6M#TkXm}shCnz)x= z4?`vDaZ!TNU37KxQ5>38vJAilpIee&lg+Q;QEcJ>=`OI5-CuYR#02KjkSeh>H!eYa z-i#mofyNCTXSVzr(N|#IN zNsv11n^z$SuBWk_r6?nUNW`$1NcWmQ((c}c5L3@$j;oyJRwc#Y;I}wgW?kzxKvPxG zdOjM6>~;6F8^8N#>Um5?mrBY3&Oa@2X;pCfQrZ&f5tK`GCW`s<)*5fV*AA`eMH?Ck zw!qeQNW;T>G`SGhoIqZAm{~ICUdf#B3y*N__AI98(SLcvsQwzh;_FkRP1R7RYUJfoBs1^Z>TCu zJuj1FluQq&4jAuE6@0Ixz(aGw-`173cJ^Jg*F{A~Z-+{cN)@$uy8Y`-IO0t_gaowH ztZOpB2hk5TbpQ^FBTJJ*Oea4MSq@yab=2gG^|S4SJMaU+CghW$0=YmI<9sGcbk)r{ z!?H1hsGCK7r=e9q5RqGazndkeNC>z9z9#*S3&&|JIM?TP3D6nWC~cF?aRxh^5~1O z)09+57=}V^1$Sn!y{vV7KW9QE8^m0F`jWDRE&7%;r$?BfopRAnFuyCnV&COvNL*#K>6n5ch zIEX54=r{6wEe9Iw?7ad7jV(hUn3uJxVx~fLPx18y;nO`8NSSZ&fmp6lMTC^_#`<`9;Ysm_{7`;eC62pW^y*Z zU2|xTbyo!)uanwtQ!j=ec$nNc;bJ%hT%-C>>BeL}wlXrStbkxFSU2+9D>+{rsvFpT zw;WMWUHXnab2k0qRUCq4r*x0L{}2Q{!K=lZ@k3I*0Mv*mu^Q!8@FA-9PITNB8ye8K z6_Xba`6y8UZX%>5xo)exWGk510S&;6wXVBX+TY2VHnrZhc^{~4lj**WteD@qhd zT-0)lu%YZ0X>B~Vf}Ln`oC~d~gRc(c`(DSDOPBUV$0w=Q{+SuVGKJcSpU_4FsC<*N zD>UchDj+o9%}3*#7bOf#*Rot7gV$2MZK{@O ziSdmW8cWHQqEIvrvmsTkkSt;2^V0R38(?imRESryMtw)>Zu7-^|zNyEm%~O$I-uJPgGu3To1CKJ4DvqhR&R;Gg9Z z|K5!G!ey50Zli`ni300+Kxw)-kl3O1>EU3WjF%F>eR+cC7)~4?RTPZp8_|dwMpWzP5IoBmqE6! zn1)RKM8yCw89aj&uS>m(+w4>u70!|Zg;$U%xHw?FyE2-^nym=w_wDV(l>Z`}ng+h$ zO8tckQ_nYDIe-{#Xd0Dhk(h4NtT$)68I%jOwmBeU^K35rB7K77sOi~W$fB-eIz zVpKEWpsI2&D23-U@#{#+1pp9;zT@TB6Pe^UH**Isg}yA)eTtTs}x zhc6>gmuPkofwb+S?OUH+cynSIc0RE}k|U(e6|0Ch1=K8`q&rZLzWs4?#Yxy5`#VwY zL#vp!qwwl`+!lhJmZo^WF51RW61q8lqyi1f`Yv%q{V0!3__P9iVued3Rd~v22r@F5 z;83K3bXk_Bm%evYKR8^B8`{3pJ6e%MJQQZ%C*K7@)#$XB(r>j zmw3JUn*BP|kx0f3f&f$PJi-uigP|MbTRt}eCBDnmUeR|DIp>?{)-N-ekHUo*o{Q4b zwM2=U-x&)|`u8Z;+C#E-en}Vt7gOwem7W!iWlp**`ej(dE#}3BIAhi{KmqE}YzvZA z@c3d`QOz{w?1my_;jI2udRnQPQL$`;ZZt`pSIE#dAgZot zJL<|k>c#40cvSDT4WW}t?+k{{=aC=;xuw*7Jew<7jd;lT$b^P5z#Yyi!6VORh>i-_ zjyYz!fCLfjrM~r@<%w;|U$6iRu4`jbi0RWKrPB6{rHTkB7$%_WX7{9P8A7&?my>gN zEu>^CA($K+1?IBTL9AZ6%CJz{1oNqrGHmdf)m^kD02=Pb40_!iD3i|uyvy&Ygi0WZ ze?&!CIhN9}vP08y5m9IpJd1kI6ZQJjqK35)u!^2%cj*@v`GL1~!Sb69tkHD`E`xro zE2D-pl7igGXzLzEQDlW{g>tYMS;Zs^9Kc$5?8=wAgYpcb>lV|e&D0ow3qt)UjD>!g z$Mj;*AY350`*xH3x9?NWbO<&c3Q~(H;bg414Vbk412XmngppIlsV_L{M#wU)knuB0 zX82E}msrMOMR?Wa0>`3-zM5BWCtb{eky{^#ku~>$Sd5v8hT96vi2}q_>ACotb~hzW^yr7R^UG`rK!E1IFTiGQ;a-$=xa-Ipq9sKWMIWL zYUZN{0aV?!B(rbFM@ZQ!E-RM8L|l#ftIXf#6^hMgDRM}A2Ct+?m!kjL5)Ti}R1Lyp zDVhUE3gtIjC1G-|d$BoLQ5k_;Fq{OwM=JvHa;fQ>N2|<7wbC%ZQG#ZqZ!8HyKpGYo z+Cblx6+nu^2Rr^N*E=bUmFqwX8HT|XI-pZ9i-NZR5~-a}1U~4UsyGY|A6H2&8fjcR zOAMRgR{b`D;K zU}ZUSV9h7XFQ$_s^F>5~&Jjq<RvHs;F}TYh){ z4+L|M|6p%^znPY?`aUw>=ghaO$NBqeY8j62`%KF?4E(+Ww+zJhv#DhqzMtAHQDe5a(~*Ru(=-k?GE!C@q|zKLSMHYff1i(d7;lP?&?B=B;&eSBTZyU!y#{k zu>9i|rwlf1*wBC`>_H$w;vt6a7a7@j!#5Q82rB7&!6%9Bz$N7;-Y$n~zZSSCkq*+| zex0+wm;uq7T@_ z-nIYsfQuK0jfwpHj4BVN5aoFK>{*WwA3l`BL}O&D4#+-0b%OJ(p-@LH6iRB1$d0lJ zy?r|#sK?#_UaWi&EG;c<1(3o6G<@^@4(aT_b?X*cZ=}`3>-Y+BZ|5)_^Q_5FCkw#e zs_|-F-T`G3(CZ1K%#D(qsQQ!f+$oSIlp!W@gpVxLQdHGaZPkZ=!2+no!@=t(Li@bn zxktzNDUiCde?QxJKdlA4G_3O=MV2eF^WY(3Xr_10Qhmjw(8rg7$Q^uTv75;2_#q%}7oXV@kmu8&e2V@{Ke| ziaVs>^e~yC@KjkDu2n%_W=xRc$&P>Y19d8M-9aM*1A}o#BoJb+K5{+0FH*bJlun&J z(!@;NG$Nduh=QVw1c+64wNf$Ri0bK9TpPI#93*NqG0=~!`^P8D74;%Ub~xXx=2 z%EANj*3EAE1Y#$-Da|vxoxNqY*S54}+V+FLeRgNRy+YqQceuXA0@z}>y?~lEkd=#C zZbzLL@L$Gg1w-{VBiL;I?W)fqyF1JDNrLS<+T4envOj3My1KHVKBf@kd>}3^&Z11i zhzgxFhxSeatx|v7cnR>=89R*iUJ{UYR~#5~SBX%Mt0kVGKv03_i7h;Gc+-nBU-TsQ zm6p@5J@Bnmq`7V54I{l3?Qb=|$jInxY+pY0w#@)HGUs3(ade&;{ug~?W6|Gg5;INx zF4wa8x^*sKLG|__i|gtwOJD=X!6W9r3T4z^M%~ngdeiO-asptNydczp{3X!fwrVs( znv#-Oi?eKQa9L8_X_7Z+H>1adm)w+(k`SVZdCHAQY+Qy_wjyc%qz@r?8a_SoziSO# z^X>}L)FxWy8olsdgQJUH8xbE9VCS&lg*RU}Iexp%ctBh&y|x;7z4E^mnr@_Kg58$~ zVDg8j_20fbLGC)na=I2)%Q3@bgp*tU{{459jFI@N=_*oVKT8qdhpE!b#{)dc z;o&2-tFfz&T4Ol@ZemwA>sVypQHM6~)u?LH{(zgX(GY>LM=!O-qAU+m2+16pXGWI+ z$ktRnlwj)#KM9k4Q?j$=fTl0qveMXC0nAF}HPtwII~S6J2r$XXo8g9x0`AuW0`uGB zT!8-KpvKrKdC~r({%0d2wZT2eeQzln07;|{^4rf8MQiu}_CcHju-v*Wg)G)0uLc-C{XL1jJFUK(wGy9IY=_tYY$6@;^h}UC}6{W z9Z_OaO%i90jVR~+MmjQLr~0j0;@TgZdE+2*sdXv@MRUxyW}L2_3O(AqnpIXx$`&X{ zK_QLDb92BQJO|MKv77+|22kc`3J&B;6*$o8does*0-5p76RY1Dleu?Nbh)eLvAb0J zQT8&pYi#)vNMPQX8U%YFFg04M0+5&!H|@yE0v6Fm^E5zW)KI-pB8k*Hg>YpvfJldM zo?rWz0P&;B-^v!euLaX)_%@}Sfze{Q_kJc&7=a=6d6Pt77ZX*?!N7XNmUnT*%0r)q;9~7$msDuyaL+( z0aP+u<}!U{u9it?RK9xkqx0(@Nu$1BOCxCYf>T?Xuc)c2_Da$P<`p}|@XD@x{h!tQ zf41@8Gi%a_obmCY;h=}m>&iRH z5kW~D>{a}4Noa{W|Gh9POGdbB2Ds(!3ZEaB78ezfi1-xo$XkztQkxMMzV;qmw?r&G zOmvc_w>0#93HG^KqS0f*#EH`uE?oHD4!cwKd*3oRKs8}MI2q+@4`_4xTi<#QLAZLa zy1kIn(;h^WH5HLk!m&jB_kxKcSvj`=M+-rH2glW5_^JVzXos@NyW4GZWovTo=CL+K zF4bx{C+^!$$X$V3p}(gle!SHtPOQpEo;8hU26xuTTg~7WGc#D3HDAYZnBaV~HdhdK z?6mAEoY@!!9*X$C9~ao|8U%RMyALCUlqYWQKXevyDzM+lByHGWcd;TcuFR!|U%$>E)FD~T#BG>k@ef;#54~Dw-mm2&$t>WyFi<&?9?D}!dLFWrfyHfoN zW=D;0PE06i_OY?_ReZfC)TqpJw@g;7f*sJp;YO!H)c5-1<+{l}5;IzF8_uMpj?Nv* zp7aoC+6_o-^pj9GH@6z7SWP-FsbF<^jMUiYVW6{|+Z>6NJ*@h&Dy=LggvIME+7Z6* zWrVSZOFz@Y8 z!ou4-?Ckt5T{629IIaY1DzH~T`UoKxdBN))7wo$3%?VpLIydmzZLz30Fr(o{8#ZmC z1=m#TVC9{M_7OcRx9z$9g=E{}>$mfO_OJI9Sz1`QRaI3zD?FNvO(bxIqpYp9wKc*` zlfD*h1=aq(m=1;?J=zFLr^$%Qw8u<&Tu{+|*X!o$4theDZ2`}2|LxdRTR0(Xx_0}R z@QTE{q1&Tx=9ZE%j^+Ph%Lf8Qp|0AkD0`YJP;z93ytih23pR6Ib3+qDGO#;GIq1}C zLA{z`eRHit^E^R#kq5@jg3dbP#Q;{;*LzqsHukkp<3I3B(g!eKcNd4(9r|nhBF}~I zeg6L4MyE@9UgNEenZMo9Idwa{(8rF1@^GW#l9Gd9FG$zSk=PX0<2>1B0SeXb;?N(L zV#n$OrrW4&Ug~UU=madFPSwxz8b>7deV5e;&c;E=-Uf&&5fA5x+Dhzs?%0)!h&D91 z)AUHu_n70}91ne5=7M~##k z(A)E^U*S}ds5V=AG-y97?&v`3_1W5Pi!X#o+B8|m^vsyBH%IPQ;_z50DIa#DbK>6)Qmfv%X%w8gU&$omLXs0+c<1y>b3A@4 zYB)=g+~2dq5t)!pI{UQo`wuLR;GnvYC=t64RFE30>O4#8BX)z|UY0;iAs)F{=jzp6 zovQ)BRfkqzr|M(1j>nUd8vc-YHODZKrC;H!8EI5jTIvQK(XsJ%DB|Gdz&An;^6?iE z0#2Z!(>oy0DC}lP=JDLXXOeH%Trf4s^g5`(|ck$rA6|sha+hi+z`G zQZY+9h+xSv9Ve+Q%T)e4)i5_1VdM*%UY+H9iL0Hd!|NLuRi9JVCqS2ZCl>M5BqIo> ze8x|>4vYfSv2FNk26sU;x(a$C*Ec7Fx@=q-)=lf99`;7v)MiV#U_MPxH#llcx3UNI zi!@DPsL-aaR$>UFM)9i%aIe`E#PAAOYX7S$mY~1iuOu><$<_;xHMI~6G`4(y*v>pY? z0l1}Io|1t+vc1~Y|JDut9xV$PYP;;^mHNkyte7lEAi*T{bY z!M0Cn*xM7!^Pq@%5IMU2?c_!X^P3`AEk{@{Q#uJ7dmjEI`d}^brQ)TfM}moyYC8KRG7Wa-mT(w(f<-UdUG={PaxBqD|^<3T+74`q<9c*rCc}N6}_1Ri3e#wOkdGT`d3oZE=)NLejL3MaO2fDoxzqP*2_X}`*HL&H24 zd+`s8i{rn!RY5p25A*Jq0obx=5D`m9Q(yZ}GhgQ-J{v^KQp!?v(6&SokPahLX3u_d zCi&qT+~gXTi#Y+U%8>iyVH(JNzJ{%aDjD2;cIik2YtC^`wX$V|$11S;pafG1Qs)av z8ZbsA@oC(aHxGX+eE!VIFB@f)%g;5iU9;*%Wrf+^5*HFL#a&1U_JhDTJc@bVmZo+x zMn9o!zZF74caK%u?QGp8J`qM;+q)^1CjkRD4(ZFs<5er%hVm`E?iX*M?W zZHydYCQ++NQRjt`wDhNVI@#$~I1p)a*kRi|6wk6z>U^4$Gl1Ga$1Oe5Y1uGeyK)gl zfhg2uzG>5dkNv<@o=+v3yW!z9{Ux{R#O8$(Z?PyRrt`!z0j~Wgj3D)ya<3%jqJo)E zx-dvmgGrp=*^W?j6r_v-S+Ge;N}~PJIe-6=^Rz3U*D&o&txrNWgX4L)GZr7z0R*067_w z6eHn(uyOPqiYR^=-$4znbMiZ=p=BVxgBn`K;XA0Ibzyu5HM9)G_p_;WLVU+XwhY8~ zTx82Q{J(?{dkwEfe!&8WKk$A2e4jrpBk+GTf4bt&* zUSaX1@tllR&64RS>;F+V+^pKGq9ilfEKaRnODp-1 zfsW%LQLxZa|KAQ6e<}T&AOCBwf9JD5cZ&Ju?ctB^KebyW`8PB6{qQeCjv-T|`bz#k zJ&sO91E!% zg&JGv&rz9g=&2u_O%@96od;dHdR4R3>D!G(&mjaNu#oLvS~N~j+WGjmZvQ;9_)iUg z{$Fh=>sAy=31=?6L-ifLn#FB&DM<=F#$$XSU{0-|#?!5V_)Ovwd(3Go9Fye}^o@Y% z+B`UypP^UBBcf~Jn{(sxLKfmn? zx^d=Lh@nNlxS)e$)7fqgm)oWa!rO-OWiIE&$7m#JgPRINCX(Dz?f|6C(1FxhP+pF-HSkW@vMNx>{+@AKwI`mVMdZsb5ytXC=F>3 z5X~;=t$U=8-_A4)fKV|p_kd*Yhlo`?y~2U+7W+d0SqZO{Nl)>2<~RdreaAixSte{> zk3&D6t(9jNmesZwj;#!f#sc_cppVXyLDA0u4`ou6pAAh@z;bMTttb&kviz8 z3dP~xLnE8f_1gzOz2jTk3$J2v7MWmwrYkOcKBHFLRV7duGW^=FeKi0a%zt5EJUZ9C za>#TkXVnRps`tpX6P_(zzFZcxkbQ)B_fcLc$7Wm!V0UE|n(!GQ?!=|1BC)M-%~5q! zbhB?G%(`ThD~nNlwSr^V?k0Ll#BMayM>pFY^{%}#-(iGUO$~z1uZKKoHalzAf=MoDckA_7}(Cte2=|431v_MCnX68+|&}VadJUO!nTl521j#jqf(8 zROulB6ndJ(#n1va8*uV+fVtIX_EQ{+XIF~c;)L_<0tqp3Kp(7lK7QU58W-o&B@pfG zU~`+tYQh;+!)Mqr&BOSpo+%_u)D;IFx_kHT&fJ9t1~SIYb?G$DZ5K)W!hO-$tA!0l;wVaJa0(u3fNheK6-Hwf8h_O6928 zMs-!Erb4GUbY^APLNDkC3^&z2A1pKT?hPt~`PFCwQuOYL7l(88`ql+x1ux{O(TTf&A4$$1X?|teenbm9YYE_jJ%W>c@&^LG& zH~^0=^+#FmfXREh(EoW&sVtD44XL_~3yrouovM-Ca2ppmrMYcAFv34u8{_*-fLwVB z1KIY8T?ADHEEYv0S&Y4rW9{2^kxoQhLszlS=dQx58nQPi(S6j{4mT7JxWvmhg=u@a zHh!}xlg89I|JqJeztSEElgHUAK#%e*(%7V_=1{XbR*8E>HXi4JZgYihJe#0+K8w*?v-lkR_!pKs1LdCVOK6KY+CDInb{vHLc;l z5VSG#W(}S$wIgu@3yet!VF z&{yI$#^AP9EfZfyS`89UF-QnLI6w1f9&v^sgH5POhWz^^+L6Z^H#{(oMbDQ~gGt%O zoJvifPMQK|Mps??_$C3byQ&`o8NO(A_n3aYBiA=soK=oeDvLb|y z#LAREJ>;lrEuz;i{3pn4m4 zUiXWjJ;ahqMe>bUfZhLK#Y&)F4pN$v-EyG)A7_VS=aPHgBnBJ{J zJcD!-Iqe;v|0>2W`+z0T<@-vn>h26rpG2WcV| zJ9YPQ_B9`y>kB~%98tMcdJuNckmG-2EzWpC{Y9*-eaiN)J8K+JsTDh4W5cI6c!C2Y z-}e(<&xtrqG#rB$ax5R8d$q!`%~(Ni@J2XdHB}lnPq0p=6Uh8M<-i;cEC8k!hza4`4u>A;}mVdL4y zjSO4<3it6z;ZZo>;s7Z)9Y)pmahACe(?mmYM_Z2-^Nu39tMvb!0`)uq1G>SEi11m} zM=KUyn&+yLq@Mp*F%p;qfH3>bEagG^>?3_fXbc3WkP($iuEYMhg?NnO1LEWRV+xIV z>_8TibyHjpAdr`zRzJjR8t}G`uSpqo5N9pCjZpyJ8?P>{g_Y6M)uIvU;8{^Ab9^-^ zI>@22hE($qSM807EeH!{T=Lnmp12?nyQX~ICO`dU&RAH6w@eU93c2%9IT<*gu)K{x z*Zx&Z9ppl6U~_jAg2ds6lSh&IyXmIDhs@ofhzshOwrpI#0`Fr~PzTsPB};96l|@Kr z8hNL>;yWch$D^1I;V?@In^}eoX@e1XARcyG#6rOfHe$J9`%Td)cbWetI~c&7h~$$@ zUmWpEgfB8OJ)b_%$PROa1a|K?xkiOL!0)sRlfkD38n=EJ_}1>2)`{7{*c1Na^YV1l zps7iL54MipZ%V1YY3+dEg|=2Zvl-r`ENHpZQt}QGD%*7E`es`Iw;qGD$f$&PKWsqm zdujD!9SLFStN#9-x7c7}P%PHN4ywL}?qY^U|5@Uosn-)^v?}TTSFe83G>DQCBK#L1 z<#WzwHSFQvIIC3B_ku=|QopyGf=^f!c(FTkyWut#v_4T^+IJCESm1-9E!=hsx3W*E zgfnkDXWl2e^dwYTCu`q6Q|U-32b??;jzPpSx2sntdEc~;?$dITX&7Q3DX0T%zw-{K0B3WUh_{PW5N4!;H7kyb2rMP28=AOJfgThGX2ofv z0X6FhOR%Rb8)Cn01YMsDC#{Gy~A4K}b!dN}N;CQO)M>pdEiVNj>~+=qK{`;W!% zQXV`7uP_~WjO@(yEp8x#<+CGZH#f)Vh9}Vn$-1GU{DZTT_l~bd86b{(29;B}?E_|f z4jhB2o_z#!7wmm{Bk;?DsP!8*P&V7cZVYHYVkb6x?7<7(RZnxk7I$V1hu!=P+!^A* zI~rf@1;ItF`)Y)CXXE{sztQ4iRX+K7=O#dc_5YQ-|F z!;jw4AB53|apKKz!7q=~VG`mM+|~{bPyf6szn>9krQGaQFsUn-MYk- zhKWyoMwHSa2;34XVaYco{ErWvG$(^`;)iXBi>#yY(UCqsob!bFful91QeDvN=kAA` zlC$+ajr7Qr^ROeH8TGIE~hQ-4lkP|9+BSpk^1W~9cP^6;%*ZO<0Fq^ zoeX^L9dP@ z9d@OVO<5DkT%=bWCd6QHLBqBq=*h$UbAgI)dT~QDCEqy>K^g8zBZWVkCklERM{uWC zFr0d|wMjNnJwZHwl)Z4piUD+O@hd%y`+BnYTI*DN+cFg~pUncW{Ja#G1c+afsxA)a z{j-%LRe3;gzg%QsU{+d2wOE)XS6>c|V(%XVv6~aCJOa|Xt z6Fnno(D^(qZEa~iRhp@F>{oV_qq4B1I<6iI)Y)b@dIG8o0`x8+SDETDI9(e@=g7x$ zg5K**nKy^hDoh=*g=a|ud_!owLlY0NWkj|vb`Cmt9{;JNy#iVSgD;URAG zsHaaTb(@c7Gpaaop;wt}HEuyD`%Szv7>O?92zh!g;c&4}o&9XATdiK7PUjO@8wW-7 z-q_7N>fPkE`!g%Zz-`&`ows~ZD16Bn;4(O|7R^-j?nVCx961voMRL>Cm{pm(T^Gaq zaSTty_K$mK^eW!vJ$Sm?>HwJ$OMeg^&j*~CjDG#ai;stuQC%GfeVKJ5gfntT@tn6X zRC%UuU$dFieIFQlCOFV&X1cuX`IXTx0;0I8#vl6>slSomrz4I`l+x8M%InzQQL?UC z)j=?y#rT)+$HNYLWj+`Zqn}N|)D>?6Gq4FfU|O4QWIdNWacg5l&?Z2)6P7qE(im&( zZQ%1V*Wb9tDp)>D(Sv{LV^!QLP0a>eN$h1*Hz0$XctO@X~N;t!*F}>w?@6=!JQF0xDwHhFmuW;iCU7Dz7@qPib6~|-2to{5z3BE8Yt)mf8CTlb18_9Jw&5A2cO`{ zvNL%wpW*0BJHO|AhL%YRF3iFt%egr~zW!qNaGN7a>wZYg+IdR}O2!D95{*Qlh*`DA z18DOBO7Q?GA=DZW+hU0=2J)bf?$~|U5zLvendRT^`SM_&oD7Qsb5|S$7=bmn`aQPb zf;vP^2UI%>3%cTZdKyQur>52d7AsH3CPp(3r1*m;+I!tq5w{TA8MTr6voJ(0hlzZW zPJKy2C8|Cb&Q!yjW{kCVy1gJQqqSw2BQ*X8&Be*u=F5<$sDi$yK*@SPocY!w3O+y$ z1DWWeUh8g(zo6n|UF*vg4~!PX_eWVf0B?@07^NnUV$i=wziY&uOxpZPuV4r1^pX#d zuMJwf6?i-G0Q!%wb|_HsbqTXBoVI37d2_k}&v2%lEe~PvWXEyD?1zmMN~mgJw%}MG z3QBP}yHAD1cbJ5zo9T>oB+mA!o)YuZs?QjszI0tm5{*zpo_q&98b6TUrh1k%bD%0- zARoOjgb57y+Bd(0t&II<+x<#bUbr*t%x7Yz5%Iwi@7 zu0s1IAFTp{y82AKXA8QdFc9-$qRq(r!<=ObqI zsAsH4lh0XAqB3rLj-FX|ev7`YL#-7sLhvXiUFVn571)gm>OjBkyhRzCB{S(lH4%^a zsh;fxB^j=BIjr-6x{Q^uE@EL8q*Cn)g$&2qC&p|=9Z+31k#9>Ou`*J>6Q|s1adN^M z)|voi2uaY7V_2j$sSOBV*OYnyBz`ovqYyF*`&^1ff^3|pF52x$&AX@~%9Ohs)_jWDS!s=I+z&oasIHzC#PWbR_;aNdNkS!tOA!ZK+7KIXx+fH>U7zczdWFfY;YEbE zIw)722rJw_GC=8>D%SjA9FcDs%1T!h`3J^PDaJCQd|E*ix&P;;9>|-lP`BXlunm1N zs^W6V15TLF;!xoJgmj~x@DR~@%`JgD*4!=WbJcQsb?7Fq^?C;rc2s889SO%_UI;+` zA+S@{mLfKtZG@LF)$>O|NsaH+2nXny-&Z1cB}a+nW{>*1st>XUWR%_ThGo{>+{4x3 z`S^XLK6hGkdGYCa7G{VRNT(CDc|w67c|*UNj2KjWq7t<69uJ^|JE2G(i3{fovc+C+ z1L%#6TRdhhqALcnhpDG<8`F6kEH1hSARbhq_X3@kv(sV9(CQ6-cgE4TjAP#qKPfJE zsmt>mndXT&2W`aFr5+%#VXk+!^=@YMovzQ-_=h(Q&K(8wl?6%OvdHlcL6;#8DOsm2 z@$hCb1wEM2GE$7h>?~-l>~N@QBe+k++vv3uGvFCop#cc>w~}DyQBO)f*({ttGmcJR z&H9=CyfSILnax_9bFR;^E}>N8=pKgjOPe0j}eZVutvt%-+q&5jSg8rEyK;>A2F?I0KqV7a*DrpKboBU+A2G!@bDu@g^<>zkbLR$8 zUr8Lpg3+#+eH*JqT(N>wN?v=_EtP`yIYv zIPI2(nCnyZ=ogVDt01Jl6(dtNHxyG?mfsHe#i;;wSr-sP8viP$JGFh8ooK_yQN9gt z6ip%3A>CwMhC|pnM76r5iJ$@s&W_{8(N&>=EUE1u`?RbQ^+hU^4AYp6xo}}IN~vFm ze=ape*aTUMupzRFeyntEM#g?%p0_6Lu}m;2Nu7IMzdWnGbpKv-TERa}Si4mi_={rQ zs=`QEbn->;AL(94UKou@*?r%)53%tihAO1<)7K6h8qq5au}wU3Vjd*6joN~9+-c~C z;OQ?tH=QyimaarFH(LK$gD-5hwUf9bq0OsxX=3-H~8yWD5-6R^=ju z6yozm4+UZFc^qRwn_u6rsfpK>hswmGFeehZPz;GE^S^S1jI+80m=rf~@>9YnGFQHq zyx;sn-R7`v+XUxf3~ct##iUl9fU#Pzkt^7Cgt*zI0nV)p8Y9z@CU)MD>@3wL5B%wa zh?aKdwh=<+Fx@JH({{OX^CxANH-0O9u3OzCwE}Mw_{+P=z*2Cj}M%9nk(ue0_Oz+4Pn@OD2J)_ zs2!;D3^BtmDy+}4r*;nQr@32(VY|SJi-Y^Cen>rF4t+@Q5-17%mX26Q(i|Y=S6ej-A>P347>}s zE-J8LdvV2bP|Y0BrhS)vNU|TG1(gTMqD@RaFoQfx>;>mNe7M?{tQX&1iwIAMU--2d zXSg5JBy0a<1JqphLP&eB{rJpx5Uqo^Z(y&m^a;yoa7pGGb*b?Q@cIeR_Vp;{&VM` zbIxNQp6eaD&$+w*;$1J+2mQ8bX3y)l`fNDRKlMyE*Urb+&s{%9I^)>$ytK3dGCwW) z>(AeXWm~fs4DWsTciEVJ1-4H!nk$s8lgu>=b=3YYJo>S~$gEWKV1UR~M)#k=ozcC` zs(=2AfBOD6-;T%k(fDs3jZOs+Sa5?QuzA|GOdTiSYYgA*u&qWYFdemy{tflXr^flE zAj{^D^AF>YtB8NjtYXm=`h!`86@%T>2QlscL3I{s%XwG*1J;iX2XWg3q81&$h?hN! z5n5rW&O6CzMxQ(UUI`uVddbKrW?vp_0n2gN`lagl0=*DV5i#d!EnlX0w%-?Qtot1Z z08wpHHUXWfJ3RJ!S}an>&Y7hC*&E_C5umny{mxE_U%xXp2Q_O3P3?nOB!x3y4~s=h z$;v%;;zVhMt%HMukwfK+AoMMM2x;Z;c6#vT;{)44kMAe6GBW}nVb_#l09F<4>upgRtYNvA0&_vtn^w;Yw_~tsuv~j$g9A`PJ%`3DF9-!-= zvr1f{L{#6y;+Q<^Vg3Pkuim?c$Q?~z-67dOw%mkLuQsb%{^b0_aBh!3uTYnog33|P zjYoA+_udDxbKt#eh^NOv_hWVE3k&dX`K*2H%7oBIU#cVZgzSy@r`JxY)-y-%&o#1w z+J!8qGMH{2RLhu$p${Aa+o2h)Gf}B+n^i3rasJ^Y4pT~e_N%x! zUdTlfmzK4G{QY4W!*Y23F$CR}NzGQaK)*i6`LENfR|=#oO%ch9ui%3a99ouP_clVZ zhTge<$zE7)di%>@ty)KVNA`DG(K2wt zt5u89u0MYKI39bf01sw6ica>cfYj#LdlQ?ZA-U%`&A(6 zR?HZt%diih**JCsJ}&lK9fN-sD->Wv2*lu8M(~t;vMv*$*%WR(&|^8k_{s|UDG#92 z>xYorwm1tdV6oUM!b#}@+}oFtcOG_i8J4}n+1ahbpt=TwaYF(HH&mGoLRVYHxFU|V*BSrg=m@_?S0jh;kdNf^)*OaPft=Mi$lcWRd0be|BL zEK$=RyHKD@%tL~80EtOKgHg-3p1I*EbGP*d^cEWE>mPn+%j5%jp5l(RlTo+}=5`rp zk6MVWb~J=U>8h?Ya^wLhunfGEFWR>cTOvgo@~M-7;^EuRna0#SI*0F*UW*CIVSDrT z>-T-#Kt5fLiqb(Fucvkea72d+5<52+zk(9Q7$CsL7f{_NH!0xi)&2Brv6WiNiC}Napq@V3Iv-^5BPAD78V>KA(6W#ae)2HlX$>)&&>cj0`!KuM&S1pQ7pK@DoX~v1Ko0+^TBsY;q zhb2>`@==WnY*DGRi4b9#j{n;iM~2S6Sy0@hO@}Q&v!vFKSi=s)jmeqflzRl-xK! zvwbSIiXb4zB7C~FTz<%tuRDzZ*x-qAvapfgId_XC(kAXB2W@pMnqBu%jdJ{2HW>+8 zQ!bn~Wo7%sW;A4$rP)KE*H&Ah<#OMQ)qVC}km2^L_<8c4AsNG}sWn3>?KrLU+aISj z6!*!7IMnKdWUK@)Uyt)~xyx?do6vHZ&9AZD_+teh5sY*#}!81H&R zF7~*VPx9dMUC^`T!vj0Ek7@an(DBJcVa%8@Za|4myf-n-V4u`x>}qKd7~w**VOK&z zR6W&_8%8$8^DfCTu1$Wi%*48y=+UY}5n-QG^7hs3g&{dg~F{>y$W%t%3TJ0Fshk4|;#H-5;yiM2RryeFWM=&&+L z8@rgwS~@DTrm9>x>;l%{hTIH0;+pW&Rjz#uf5%V95z5NRo@%>gooz}o4o|Se4zx09 z0G4o?J$7`a)x<(PsjW@Ru-i})*{0=F9lEwz)$%9jwmi;F(-7SfX}fdNCqfOERoF{A zE6zFf6X9ZY-o(71>uQ4TN%^Z?-QrM0`1EY3!k7K()vMpXjF>wQ_?tIxLd|9>uI0Bt zO{jkNbTFj{l`C^4$&-9^3|xq$m^FKLK93R@fBy^+uvh*qV{E~5(<1P$&JJt2v|iNL zaBIlxr^GzxJv8G%HAvu#PRh2`-=&x9U8W|l-c24h${RzH>%s=z-2t4VOwSJ z6z>kP$FFl+uIg;B@+F{}@ld>d05Rr4>ZgIT%Zt&JWC)P{eSjxjce zc2NTk4>xQCcM$T@wc9K?7iBrRQy)UjIUf4#)>YXX|ErlHz9Ogku-X^6-)ps)MLpJk zQYM6TLtx}Y7AH}#6*u~Mq9e$!Z!E#IQ%5s3*e%?8XqMdu+yS84L(2xVj>PI-y}tw$ zG521j&ewGX$Zw#j4q)zWv)(|8FY;!Ag2QM1U*}dWhHvwlHEXP}@x=wK2&WJl6_Yqd z5lFJI{2Gt@EkU;cOGQG<0(8E3|H~#jP%0DKskxz= zpkVvv@Un_-x(#DJ2DzHE(bICY^y^MIxohu{OJafT=tZnJ&uL(D8!z~T0$6$qu|5SV zZQtJoyz=suE00d8O}yJ0@^>B8RBPP&ux(e%3b)t47}36~+$p@1SryVTnW~n#S{S1| z_PW`#E=Pqk7O%S(WR_l@tgA(2qq!2vUc}Z7CEgRhxorEGma7UKA7X*QIXwhd#y0c< zO^Iu@*qnNsdlD>{` zGO?Qk!o}G``Mcw-nOx!H*CIAQfO;S1ycz;>vH5n$#?0~gHgH(zi+_Aln~5N0S;fXO zfcN;L{;}_ubmmPaav!)y=$NitvgE|7)2mm955FA{Q0g4fPJPfhY{DclToYwN*D@(N zaiUNP49-@BbA?|duXdY$-SNz@G!s3^#X39e(YlgpFY%^_JRefcrxZ`}Ejv~siewSg z)MwMi)^tYh)R#3Pd@6y2chaeCnAZT{AH&_CMK}l{*Z6|BZ{K#j_2_z>MOF>~7W0yq zhizF?lKHo4_o0H&rGi+1U`5j=S4;cBmkL`Wirr@a+?lUq-MYAvl*!$2Vr|jon(*#bv`qjEN&Vi$ zM~@~70fB+Z??=ZF8m|SWh=$!tu{T9SW0_O(sguW!#X?H%XmAD1)Pbf+J{8_byeED< zhqYP7-+6PBKBr6$E+DMu*SSZy!Z9O~Pnm^hR{8G$Qz0Mikb^j6HRK&@Ub7LF8615B zsoR~;&t{8L-)L)s?QuFJC0)CGdEe;ew-CSJ*!J>n6~;cl_n&8whS|vm9ULmlWQaU;M4ghF3ai=Q?n#8RXKfwGlD7dq(6az2~5nLSQ;a$6)k3NWnI*F>&6HlQTtek{yP2UOY z7jb%F$wYm&e)8mrDeh6M+=o5!rlSqA|8ivVju&!W`)O_8j6gHuUI`KK{Z!Vz`K;A) zp92ScoxD9ZBaI<~e@j&an!12AtV!}YIUm3E3(wt}I+v*KMxDV~LQV5}z%v;&lLGk; zy$BSem^6bUlNN*>l7UhKg>Y$T0C+6DI*f}NNKUe~wUx6@7*}6!PtH5Yg&q|ZEu-oD z`D<-y#zU%80*N7F52(KJTATOnU!lFKMIy|>S^z6hLd({`VPT5ntNgm9!^pzqfNR$d zqRXXr3NSPs$B(-d-ZacY2YljUi99A@jutyS4LJMCH`o_2K`4$7xa1C=E?AiNMk=M+fTxB-y(I^eFm&wmyAZ=4CZd+TQVI)9FXR z8-%)mvG{CBwlnZTo<+bO0r1G?P5#$_o1;K0nHK>EJu9uDof||k#~=inIR&lll{(`G z+`|B}Del}_VCxc8Z+D4mF9IeJ(6CSia81l3V2RQRT1gB%{utC+z6cC6U?71SpKibo zGk9zUIF9h}etlPW_vcIR?au;-sen^*HxkMYvWg!87K5`qpat!M0(cC0oB>vAi}vi< zb8ro?83YU_;Gm`*@NSnR;7XMp2XlbS?hS#77%`}p9rprS@iNHRfLcvGH$ekJEVGwf z1~#cD6#lWU`&024+IFz;*a15kp~0p0vGn~8(6+ew=cBh|2mLFF( z1BJ(I2~f+qz#G4S9n<3Z=evP}8Nj8^pg~TiEm}Rmq$-G$+^vLfpd~QC=GmNr#VJ>>Uq22kGJp-mdKI;Vst E0D9wV`2YX_ literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-25_02-59-27/settings.yaml b/tuning logs/2025-02-25_02-59-27/settings.yaml new file mode 100644 index 000000000..d100089a5 --- /dev/null +++ b/tuning logs/2025-02-25_02-59-27/settings.yaml @@ -0,0 +1,335 @@ +control: + longitudinal_control: + pid_d: 0.0 + pid_i: 0.05 + pid_p: 1.0 + pure_pursuit: + crosstrack_gain: 0.5 + desired_speed: trajectory + lookahead: 2.0 + lookahead_scale: 2.0 + recovery: + brake_amount: 0.5 + brake_speed: 2.0 +model_predictive_controller: + dt: 0.1 + lookahead: 20 +run: + computation_graph: + components: + - state_estimation: + inputs: [] + outputs: + - vehicle + - roadgraph_update: + inputs: + - vehicle + outputs: + - roadgraph + - obstacle_detection: + inputs: + - vehicle + outputs: + - obstacles + - agent_detection: + inputs: + - vehicle + outputs: + - agents + - lane_detection: + inputs: + - vehicle + - roadgraph + outputs: + - vehicle_lane + - sign_detection: + inputs: + - vehicle + - roadgraph + outputs: + - roadgraph.signs + - environment_detection: + inputs: + - vehicle + outputs: + - environment + - intent_estimation: + inputs: + - vehicle + - roadgraph + - agents + outputs: + - agent_intents + - relations_estimation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - relations + - predicate_evaluation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - predicates + - perception_normalization: + inputs: + - all + outputs: [] + - mission_execution: + inputs: [] + outputs: + - mission + - route_planning: + inputs: + - vehicle + - roadgraph + - mission + outputs: + - route + - driving_logic: + inputs: + - all + outputs: + - intent + - motion_planning: + inputs: + - all + outputs: + - trajectory + - trajectory_tracking: + inputs: + - vehicle + - trajectory + outputs: [] + - signaling: + inputs: + - intent + outputs: [] + description: Run the yielding trajectory planner in simulation with faked perception + drive: + perception: + agent_detection: OmniscientAgentDetector + perception_normalization: StandardPerceptionNormalizer + state_estimation: OmniscientStateEstimator + planning: + motion_planning: + args: + mode: simulation + params: + acceleration: 0.75 + desired_speed: 1.0 + planner: dt + type: longitudinal_planning.YieldTrajectoryPlanner + relations_estimation: pedestrian_yield_logic.PedestrianYielder + route_planning: + args: + - GEMstack/knowledge/routes/forward_15m.csv + - start + type: StaticRoutePlanner + trajectory_tracking: + print: false + type: pure_pursuit.PurePursuitTrajectoryTracker + log: + auto_plot: true + components: + - state_estimation + - agent_detection + - motion_planning + folder: tuning logs + ros_topics: null + vehicle_interface: true + mission_execution: StandardExecutor + mode: simulation + name: launch/pedestrian_detection.yaml + recovery: + planning: + trajectory_tracking: recovery.StopTrajectoryTracker + replay: + components: [] + log: null + ros_topics: [] + variants: + detector_only: + drive: + planning: + trajectory_tracking: null + run: + description: Run the pedestrian detection code + fake_real: + run: + description: Run the yielding trajectory planner on the real vehicle with + faked perception + drive: + perception: + agent_detection: pedestrian_detection.FakePedestrianDetector2D + fake_sim: + run: + description: Run the yielding trajectory planner in simulation with faked + perception + drive: + perception: + agent_detection: OmniscientAgentDetector + state_estimation: OmniscientStateEstimator + planning: + motion_planning: + args: + mode: simulation + type: longitudinal_planning.YieldTrajectoryPlanner + mode: simulation + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization + real_sim: + run: + description: Run the pedestrian detection code with real detection and fake + simulation + drive: + perception: + state_estimation: OmniscientStateEstimator + mission_execution: StandardExecutor + mode: hardware + require_engaged: false + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_mixed.GEMRealSensorsWithSimMotionInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization +simulator: + dt: 0.01 + gnss_emulator: + dt: 0.1 + real_time_multiplier: 1.0 +variant: fake_sim +vehicle: + calibration: + calibration_date: '2024-03-05' + front_camera: + center_position: + - 1.78 + - 0 + - 1.58 + reference: rear_axle_center + rotation: + - - 0 + - 0 + - 1 + - - -1 + - 0 + - 0 + - - 0 + - -1 + - 0 + gnss_location: + - 1.1 + - 0 + - 1.62 + gnss_yaw: 0.0 + rear_axle_height: 0.33 + reference: rear_axle_center + top_lidar: + position: + - 1.1 + - 0 + - 2.03 + reference: rear_axle_center + rotation: + - - 1 + - 0 + - 0 + - - 0 + - 1 + - 0 + - - 0 + - 0 + - 1 + control_defaults: + accelerator_pedal_speed: 3.0 + brake_pedal_speed: 3.0 + steering_wheel_speed: 4.0 + dynamics: + acceleration_deadband: 0.1 + acceleration_model: hang_v1 + accelerator_active_range: + - 0.2 + - 1.0 + aerodynamic_drag_coefficient: 0.01 + brake_active_range: + - 0.5 + - 1 + gravity: 9.81 + internal_dry_deceleration: 0.2 + internal_viscous_deceleration: 0.05 + lateral_friction: 1.0 + longitudinal_friction: 1.0 + mass: 700.0 + max_accelerator_acceleration: + - 0.0 + - 5.0 + max_accelerator_acceleration_reverse: 2.5 + max_accelerator_power: + - 0.0 + - 5000.0 + max_accelerator_power_reverse: 5000.0 + max_brake_deceleration: 8.0 + enable_through_joystick: true + geometry: + bounds: + - - -0.35 + - 2.85 + - - -0.85 + - 0.85 + - - 0 + - 2.5 + height: 2.5 + length: 3.2 + max_steering_angle: 11.0 + max_wheel_angle: 0.6108 + min_steering_angle: -11.0 + min_wheel_angle: -0.6108 + urdf_model: /home/jasongao/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf + wheel_radius: 0.33 + wheelbase: 2.56 + width: 1.7 + limits: + max_acceleration: 1.0 + max_accelerator_pedal: 0.5 + max_brake_pedal: 0.5 + max_deceleration: 2.0 + max_reverse_speed: 0.25 + max_speed: 2.5 + max_steering_rate: 2.0 + max_command_rate: 10.0 + max_gear: 1 + name: GEM + num_wiper_settings: 1 + sensors: + ros_topics: + front_camera: /oak/rgb/image_raw + front_depth: /oak/stereo/image_raw + gnss: /septentrio_gnss/insnavgeod + top_lidar: /ouster/points + version: e4 From 2999a4fdce152f54532721e975971fa896ed0f93 Mon Sep 17 00:00:00 2001 From: Tianshun Gao Date: Tue, 25 Feb 2025 15:09:43 -0800 Subject: [PATCH 8/8] remove result for fake_sim with pedestrian detection launch yaml file --- .../PurePursuitTrajectoryTracker_debug.csv | 1241 -------- tuning logs/2025-02-25_02-59-27/behavior.json | 2834 ----------------- tuning logs/2025-02-25_02-59-27/meta.yaml | 19 - .../2025-02-25_02-59-27/plots/accel.png | Bin 229317 -> 0 bytes tuning logs/2025-02-25_02-59-27/plots/cte.png | Bin 153700 -> 0 bytes .../2025-02-25_02-59-27/plots/error_v.png | Bin 207875 -> 0 bytes .../2025-02-25_02-59-27/plots/error_x.png | Bin 221104 -> 0 bytes .../2025-02-25_02-59-27/plots/error_y.png | Bin 135775 -> 0 bytes .../plots/front_wheel_angle.png | Bin 144089 -> 0 bytes .../2025-02-25_02-59-27/plots/v_vs_vd.png | Bin 326630 -> 0 bytes .../2025-02-25_02-59-27/plots/x_vs_xd.png | Bin 279814 -> 0 bytes .../2025-02-25_02-59-27/plots/y_vs_yd.png | Bin 192169 -> 0 bytes tuning logs/2025-02-25_02-59-27/settings.yaml | 335 -- 13 files changed, 4429 deletions(-) delete mode 100644 tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv delete mode 100644 tuning logs/2025-02-25_02-59-27/behavior.json delete mode 100644 tuning logs/2025-02-25_02-59-27/meta.yaml delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/accel.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/cte.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_v.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_x.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/error_y.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/v_vs_vd.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/x_vs_xd.png delete mode 100644 tuning logs/2025-02-25_02-59-27/plots/y_vs_yd.png delete mode 100644 tuning logs/2025-02-25_02-59-27/settings.yaml diff --git a/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv deleted file mode 100644 index 5ba243644..000000000 --- a/tuning logs/2025-02-25_02-59-27/PurePursuitTrajectoryTracker_debug.csv +++ /dev/null @@ -1,1241 +0,0 @@ -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),Past the end of trajectory time,Past the end of trajectory vehicle time -1740481168.1550307,0.019999980926513672,0.0,1740481168.1550329,0.019999980926513672,0.0,1740481168.1550357,0.019999980926513672,0.0,1740481168.1550379,0.019999980926513672,2.0,1740481168.155039,0.019999980926513672,0.0,1740481168.1550407,0.019999980926513672,0.0,1740481168.1550417,0.019999980926513672,0.0,1740481168.1550431,0.019999980926513672,0.0,1740481168.155044,0.019999980926513672,0.061237243569579464,1740481168.1550453,0.019999980926513672,0.0,1740481168.1550467,0.019999980926513672,0.061237243569579464,1740481168.1550477,0.019999980926513672,0.0,1740481168.1550488,0.019999980926513672,0.0,1740481175.818341,7.639992713928223 -1740481168.1736927,0.039999961853027344,0.0,1740481168.1736946,0.039999961853027344,0.0,1740481168.173697,0.039999961853027344,0.0,1740481168.1736991,0.039999961853027344,2.0,1740481168.1737,0.039999961853027344,0.0,1740481168.1737013,0.039999961853027344,0.0,1740481168.1737027,0.039999961853027344,0.0,1740481168.1737037,0.039999961853027344,0.0,1740481168.1737046,0.039999961853027344,0.061237243569579464,1740481168.1737056,0.039999961853027344,0.0,1740481168.1737065,0.039999961853027344,0.061237243569579464,1740481168.1737075,0.039999961853027344,0.0,1740481168.1737082,0.039999961853027344,0.0,1740481175.838934,7.659992694854736 -1740481168.1907423,0.059999942779541016,0.0,1740481168.1907442,0.059999942779541016,0.0,1740481168.1907463,0.059999942779541016,0.0,1740481168.1907485,0.059999942779541016,2.0,1740481168.1907494,0.059999942779541016,0.0,1740481168.1907508,0.059999942779541016,0.0,1740481168.190752,0.059999942779541016,0.0,1740481168.1907527,0.059999942779541016,0.0,1740481168.1907537,0.059999942779541016,0.061237243569579464,1740481168.190755,0.059999942779541016,0.0,1740481168.1907556,0.059999942779541016,0.061237243569579464,1740481168.1907566,0.059999942779541016,0.0,1740481168.1907573,0.059999942779541016,0.0,1740481175.85758,7.67999267578125 -1740481168.210773,0.08999991416931152,9.179463234421092e-05,1740481168.2107751,0.08999991416931152,0.0,1740481168.210777,0.08999991416931152,9.179463234421094e-07,1740481168.2107792,0.08999991416931152,2.0073402035928103,1740481168.2107801,0.08999991416931152,0.0,1740481168.210781,0.08999991416931152,0.0,1740481168.2107825,0.08999991416931152,0.0,1740481168.2107832,0.08999991416931152,0.0,1740481168.2107842,0.08999991416931152,0.061237243569579464,1740481168.2107854,0.08999991416931152,1.0,1740481168.2107863,0.08999991416931152,1.0558995796904764,1740481168.210787,0.08999991416931152,0.0,1740481168.210788,0.08999991416931152,0.003669642823243459,1740481175.8787684,7.699992656707764 -1740481168.23064,0.09999990463256836,9.179463234421092e-05,1740481168.2306416,0.09999990463256836,0.0,1740481168.2306437,0.09999990463256836,9.179463234421094e-07,1740481168.2306461,0.09999990463256836,2.0073402035928103,1740481168.230647,0.09999990463256836,0.0,1740481168.2306483,0.09999990463256836,0.0,1740481168.2306497,0.09999990463256836,0.0,1740481168.2306507,0.09999990463256836,0.0,1740481168.2306516,0.09999990463256836,0.061237243569579464,1740481168.2306528,0.09999990463256836,1.0,1740481168.230654,0.09999990463256836,1.057567600746336,1740481168.230655,0.09999990463256836,0.0,1740481168.230656,0.09999990463256836,0.003669642823243459,1740481175.897922,7.719992637634277 -1740481168.2537935,0.11999988555908203,9.179463234421092e-05,1740481168.2537951,0.11999988555908203,0.0,1740481168.2537973,0.11999988555908203,0.0,1740481168.2537997,0.11999988555908203,2.007431080278831,1740481168.2538004,0.11999988555908203,0.0,1740481168.2538018,0.11999988555908203,0.0,1740481168.253803,0.11999988555908203,0.0,1740481168.253804,0.11999988555908203,0.0,1740481168.2538047,0.11999988555908203,0.06490688639282292,1740481168.2538059,0.11999988555908203,0.0,1740481168.2538068,0.11999988555908203,0.061237243569579464,1740481168.2538075,0.11999988555908203,0.0,1740481168.2538085,0.11999988555908203,0.003669642823243459,1740481175.9188528,7.739992618560791 -1740481168.2718706,0.14999985694885254,9.179463234421092e-05,1740481168.2718735,0.14999985694885254,0.0,1740481168.2718768,0.14999985694885254,0.0,1740481168.271879,0.14999985694885254,2.007431080278831,1740481168.27188,0.14999985694885254,0.0,1740481168.271881,0.14999985694885254,0.0,1740481168.2718823,0.14999985694885254,0.0,1740481168.2718832,0.14999985694885254,0.0,1740481168.2718842,0.14999985694885254,0.06490688639282292,1740481168.2718854,0.14999985694885254,0.0,1740481168.2718863,0.14999985694885254,0.061237243569579464,1740481168.271887,0.14999985694885254,0.0,1740481168.2718885,0.14999985694885254,0.003669642823243459,1740481175.9376323,7.759992599487305 -1740481168.2922604,0.1699998378753662,9.179463234421092e-05,1740481168.292262,0.1699998378753662,0.0,1740481168.2922645,0.1699998378753662,0.0,1740481168.2922666,0.1699998378753662,2.007431080278831,1740481168.2922676,0.1699998378753662,0.0,1740481168.292269,0.1699998378753662,0.0,1740481168.2922702,0.1699998378753662,0.0,1740481168.2922711,0.1699998378753662,0.0,1740481168.292272,0.1699998378753662,0.06490688639282292,1740481168.2922728,0.1699998378753662,0.0,1740481168.292274,0.1699998378753662,0.061237243569579464,1740481168.292275,0.1699998378753662,0.0,1740481168.292276,0.1699998378753662,0.003669642823243459,1740481175.9577725,7.779992580413818 -1740481168.3110068,0.18999981880187988,9.179463234421092e-05,1740481168.311009,0.18999981880187988,0.0,1740481168.3110113,0.18999981880187988,0.0,1740481168.311014,0.18999981880187988,2.007431080278831,1740481168.311015,0.18999981880187988,0.0,1740481168.311016,0.18999981880187988,0.0,1740481168.3110175,0.18999981880187988,0.0,1740481168.3110187,0.18999981880187988,0.0,1740481168.3110197,0.18999981880187988,0.06490688639282292,1740481168.3110209,0.18999981880187988,0.0,1740481168.3110218,0.18999981880187988,0.061237243569579464,1740481168.3110228,0.18999981880187988,0.0,1740481168.311024,0.18999981880187988,0.003669642823243459,1740481175.9780724,7.799992561340332 -1740481168.3316643,0.20999979972839355,0.004016390192037811,1740481168.3316665,0.20999979972839355,0.0,1740481168.3316684,0.20999979972839355,4.159777012846354e-05,1740481168.3316705,0.20999979972839355,2.0956501663273044,1740481168.3316715,0.20999979972839355,0.0,1740481168.331673,0.20999979972839355,0.0,1740481168.3316739,0.20999979972839355,0.0,1740481168.331675,0.20999979972839355,0.0,1740481168.331676,0.20999979972839355,0.06490688639282292,1740481168.331677,0.20999979972839355,1.0,1740481168.3316777,0.20999979972839355,0.9971081420733545,1740481168.3316786,0.20999979972839355,0.0,1740481168.3316796,0.20999979972839355,0.04775838696241595,1740481175.9982026,7.819992542266846 -1740481168.3549738,0.22999978065490723,0.004016390192037811,1740481168.3549755,0.22999978065490723,0.0,1740481168.3549778,0.22999978065490723,0.0,1740481168.3549798,0.22999978065490723,2.0995331641168695,1740481168.354981,0.22999978065490723,0.0,1740481168.3549821,0.22999978065490723,0.0,1740481168.3549833,0.22999978065490723,0.0,1740481168.3549845,0.22999978065490723,0.0,1740481168.3549855,0.22999978065490723,0.10899563053199542,1740481168.3549864,0.22999978065490723,0.0,1740481168.3549876,0.22999978065490723,0.061237243569579464,1740481168.3549883,0.22999978065490723,0.0,1740481168.3549893,0.22999978065490723,0.04775838696241595,1740481176.0186145,7.839992523193359 -1740481168.3719118,0.2499997615814209,0.004016390192037811,1740481168.3719134,0.2499997615814209,0.0,1740481168.3719158,0.2499997615814209,0.0,1740481168.3719177,0.2499997615814209,2.0995331641168695,1740481168.3719192,0.2499997615814209,0.0,1740481168.3719203,0.2499997615814209,0.0,1740481168.3719213,0.2499997615814209,0.0,1740481168.3719227,0.2499997615814209,0.0,1740481168.3719234,0.2499997615814209,0.10899563053199542,1740481168.3719244,0.2499997615814209,0.0,1740481168.3719256,0.2499997615814209,0.061237243569579464,1740481168.3719265,0.2499997615814209,0.0,1740481168.3719273,0.2499997615814209,0.04775838696241595,1740481176.0383296,7.859992504119873 -1740481168.3913038,0.26999974250793457,0.004016390192037811,1740481168.3913054,0.26999974250793457,0.0,1740481168.3913076,0.26999974250793457,0.0,1740481168.3913097,0.26999974250793457,2.0995331641168695,1740481168.391311,0.26999974250793457,0.0,1740481168.3913121,0.26999974250793457,0.0,1740481168.391313,0.26999974250793457,0.0,1740481168.3913143,0.26999974250793457,0.0,1740481168.3913152,0.26999974250793457,0.10899563053199542,1740481168.3913164,0.26999974250793457,0.0,1740481168.3913176,0.26999974250793457,0.061237243569579464,1740481168.3913186,0.26999974250793457,0.0,1740481168.3913195,0.26999974250793457,0.04775838696241595,1740481176.0575826,7.879992485046387 -1740481168.411221,0.28999972343444824,0.004016390192037811,1740481168.411223,0.28999972343444824,0.0,1740481168.4112253,0.28999972343444824,0.0,1740481168.4112275,0.28999972343444824,2.0995331641168695,1740481168.4112284,0.28999972343444824,0.0,1740481168.4112294,0.28999972343444824,0.0,1740481168.4112308,0.28999972343444824,0.0,1740481168.4112318,0.28999972343444824,0.0,1740481168.4112327,0.28999972343444824,0.10899563053199542,1740481168.4112334,0.28999972343444824,0.0,1740481168.4112346,0.28999972343444824,0.061237243569579464,1740481168.4112356,0.28999972343444824,0.0,1740481168.4112363,0.28999972343444824,0.04775838696241595,1740481176.0782351,7.8999924659729 -1740481168.431356,0.3099997043609619,0.011180782430692204,1740481168.4313579,0.3099997043609619,0.0,1740481168.4313602,0.3099997043609619,0.00012751838650990288,1740481168.4313624,0.3099997043609619,2.149841769486342,1740481168.4313784,0.3099997043609619,0.0,1740481168.43138,0.3099997043609619,0.0,1740481168.431381,0.3099997043609619,0.0,1740481168.4313822,0.3099997043609619,0.0,1740481168.4313831,0.3099997043609619,0.10899563053199542,1740481168.431384,0.3099997043609619,1.0,1740481168.431385,0.3099997043609619,1.0247418967055022,1740481168.4313858,0.3099997043609619,0.0,1740481168.431387,0.3099997043609619,0.07284893045389727,1740481176.1017585,7.919992446899414 -1740481168.4542625,0.31999969482421875,0.011180782430692204,1740481168.4542668,0.31999969482421875,0.0,1740481168.4542692,0.31999969482421875,0.0,1740481168.4542713,0.31999969482421875,2.156878643338487,1740481168.4542723,0.31999969482421875,0.0,1740481168.4542732,0.31999969482421875,0.0,1740481168.4542747,0.31999969482421875,0.0,1740481168.4542756,0.31999969482421875,0.0,1740481168.4542763,0.31999969482421875,0.13408617402347675,1740481168.4542773,0.31999969482421875,0.0,1740481168.4542782,0.31999969482421875,0.06123724356957948,1740481168.4542792,0.31999969482421875,0.0,1740481168.45428,0.31999969482421875,0.07284893045389727,1740481176.1185913,7.939992427825928 -1740481168.4715338,0.34999966621398926,0.011180782430692204,1740481168.4715357,0.34999966621398926,0.0,1740481168.4715378,0.34999966621398926,0.0,1740481168.4715607,0.34999966621398926,2.156878643338487,1740481168.471562,0.34999966621398926,0.0,1740481168.4715633,0.34999966621398926,0.0,1740481168.4715645,0.34999966621398926,0.0,1740481168.4715655,0.34999966621398926,0.0,1740481168.4715664,0.34999966621398926,0.13408617402347675,1740481168.4715674,0.34999966621398926,0.0,1740481168.4715683,0.34999966621398926,0.06123724356957948,1740481168.471583,0.34999966621398926,0.0,1740481168.471584,0.34999966621398926,0.07284893045389727,1740481176.138666,7.959992408752441 -1740481168.491414,0.3599996566772461,0.011180782430692204,1740481168.4914157,0.3599996566772461,0.0,1740481168.4914181,0.3599996566772461,0.0,1740481168.4914203,0.3599996566772461,2.156878643338487,1740481168.4914212,0.3599996566772461,0.0,1740481168.4914227,0.3599996566772461,0.0,1740481168.491424,0.3599996566772461,0.0,1740481168.4914248,0.3599996566772461,0.0,1740481168.491426,0.3599996566772461,0.13408617402347675,1740481168.4914272,0.3599996566772461,0.0,1740481168.4914281,0.3599996566772461,0.06123724356957948,1740481168.4914289,0.3599996566772461,0.0,1740481168.4914298,0.3599996566772461,0.07284893045389727,1740481176.1583812,7.979992389678955 -1740481168.5106363,0.37999963760375977,0.011180782430692204,1740481168.510638,0.37999963760375977,0.0,1740481168.5106404,0.37999963760375977,0.0,1740481168.5106428,0.37999963760375977,2.156878643338487,1740481168.5106435,0.37999963760375977,0.0,1740481168.510645,0.37999963760375977,0.0,1740481168.510646,0.37999963760375977,0.0,1740481168.510647,0.37999963760375977,0.0,1740481168.510648,0.37999963760375977,0.13408617402347675,1740481168.5106492,0.37999963760375977,0.0,1740481168.5106502,0.37999963760375977,0.06123724356957948,1740481168.510651,0.37999963760375977,0.0,1740481168.5106518,0.37999963760375977,0.07284893045389727,1740481176.1776118,7.999992370605469 -1740481168.5316155,0.4099996089935303,0.011180782430692204,1740481168.5316172,0.4099996089935303,0.0,1740481168.5316195,0.4099996089935303,0.0,1740481168.5316217,0.4099996089935303,2.156878643338487,1740481168.5316226,0.4099996089935303,0.0,1740481168.531624,0.4099996089935303,0.0,1740481168.5316255,0.4099996089935303,0.0,1740481168.5316265,0.4099996089935303,0.0,1740481168.5316272,0.4099996089935303,0.13408617402347675,1740481168.5316284,0.4099996089935303,0.0,1740481168.5316293,0.4099996089935303,0.06123724356957948,1740481168.5316303,0.4099996089935303,0.0,1740481168.5316315,0.4099996089935303,0.07284893045389727,1740481176.1982167,8.019992351531982 -1740481168.5550847,0.42999958992004395,0.02128988060126069,1740481168.5550866,0.42999958992004395,0.0,1740481168.555089,0.42999958992004395,0.0,1740481168.555091,0.42999958992004395,2.216980844298003,1740481168.5550919,0.42999958992004395,0.0,1740481168.5550933,0.42999958992004395,0.0,1740481168.5550942,0.42999958992004395,0.0,1740481168.5550952,0.42999958992004395,0.0,1740481168.5550961,0.42999958992004395,0.15908272541795052,1740481168.555097,0.42999958992004395,1.0,1740481168.555098,0.42999958992004395,1.0612372435695794,1740481168.5550988,0.42999958992004395,0.0,1740481168.5551002,0.42999958992004395,0.09784548184837108,1740481176.2188554,8.039992332458496 -1740481168.5717857,0.4399995803833008,0.02128988060126069,1740481168.5717878,0.4399995803833008,0.0,1740481168.5717897,0.4399995803833008,0.0,1740481168.571792,0.4399995803833008,2.216980844298003,1740481168.571793,0.4399995803833008,0.0,1740481168.5717945,0.4399995803833008,0.0,1740481168.5717955,0.4399995803833008,0.0,1740481168.5717964,0.4399995803833008,0.0,1740481168.5717976,0.4399995803833008,0.15908272541795052,1740481168.5717986,0.4399995803833008,1.0,1740481168.5717995,0.4399995803833008,1.0612372435695794,1740481168.5718005,0.4399995803833008,0.0,1740481168.5718017,0.4399995803833008,0.09784548184837108,1740481176.2375052,8.05999231338501 -1740481168.591285,0.4699995517730713,0.02128988060126069,1740481168.591287,0.4699995517730713,0.0,1740481168.591289,0.4699995517730713,0.0,1740481168.5912912,0.4699995517730713,2.216980844298003,1740481168.5912921,0.4699995517730713,0.0,1740481168.5912933,0.4699995517730713,0.0,1740481168.5912948,0.4699995517730713,0.0,1740481168.5912957,0.4699995517730713,0.0,1740481168.5912967,0.4699995517730713,0.15908272541795052,1740481168.5912979,0.4699995517730713,1.0,1740481168.5912988,0.4699995517730713,1.0612372435695794,1740481168.5912995,0.4699995517730713,0.0,1740481168.5913007,0.4699995517730713,0.09784548184837108,1740481176.2581203,8.079992294311523 -1740481168.6114552,0.48999953269958496,0.02128988060126069,1740481168.6114573,0.48999953269958496,0.0,1740481168.6114593,0.48999953269958496,0.0,1740481168.6114614,0.48999953269958496,2.216980844298003,1740481168.6114624,0.48999953269958496,0.0,1740481168.611464,0.48999953269958496,0.0,1740481168.611465,0.48999953269958496,0.0,1740481168.6114662,0.48999953269958496,0.0,1740481168.6114674,0.48999953269958496,0.15908272541795052,1740481168.6114683,0.48999953269958496,1.0,1740481168.6114693,0.48999953269958496,1.0612372435695794,1740481168.61147,0.48999953269958496,0.0,1740481168.6114712,0.48999953269958496,0.09784548184837108,1740481176.2775009,8.099992275238037 -1740481168.6330137,0.5099995136260986,0.02128988060126069,1740481168.633016,0.5099995136260986,0.0,1740481168.6330187,0.5099995136260986,0.0,1740481168.6330419,0.5099995136260986,2.216980844298003,1740481168.633043,0.5099995136260986,0.0,1740481168.6330445,0.5099995136260986,0.0,1740481168.6330454,0.5099995136260986,0.0,1740481168.6330469,0.5099995136260986,0.0,1740481168.6330478,0.5099995136260986,0.15908272541795052,1740481168.633049,0.5099995136260986,1.0,1740481168.6330502,0.5099995136260986,1.0612372435695794,1740481168.633051,0.5099995136260986,0.0,1740481168.6330519,0.5099995136260986,0.09784548184837108,1740481176.2985492,8.11999225616455 -1740481168.6543286,0.5199995040893555,0.02128988060126069,1740481168.654331,0.5199995040893555,0.0,1740481168.6543334,0.5199995040893555,0.0,1740481168.6543357,0.5199995040893555,2.216980844298003,1740481168.6543367,0.5199995040893555,0.0,1740481168.6543381,0.5199995040893555,0.0,1740481168.6543393,0.5199995040893555,0.0,1740481168.6543403,0.5199995040893555,0.0,1740481168.6543415,0.5199995040893555,0.15908272541795052,1740481168.6543427,0.5199995040893555,1.0,1740481168.6543436,0.5199995040893555,1.0612372435695794,1740481168.654345,0.5199995040893555,0.0,1740481168.6543462,0.5199995040893555,0.09784548184837108,1740481176.3194714,8.139992237091064 -1740481168.6774688,0.549999475479126,0.03658030270426593,1740481168.6774707,0.549999475479126,0.0,1740481168.6774728,0.549999475479126,0.0003972161186799886,1740481168.6774745,0.549999475479126,2.4170292552071655,1740481168.6774757,0.549999475479126,0.0,1740481168.677477,0.549999475479126,0.0,1740481168.677478,0.549999475479126,0.0,1740481168.6774793,0.549999475479126,0.0,1740481168.6774802,0.549999475479126,0.2815572125571095,1740481168.6774812,0.549999475479126,0.0,1740481168.6774821,0.549999475479126,0.09418109301513448,1740481168.6774833,0.549999475479126,0.0,1740481168.6774843,0.549999475479126,0.19767107924361257,1740481176.3397815,8.159992218017578 -1740481168.7391875,0.5899994373321533,0.03658030270426593,1740481168.7391894,0.5899994373321533,0.0,1740481168.7391918,0.5899994373321533,0.0003972161186799886,1740481168.7391942,0.5899994373321533,2.4170292552071655,1740481168.7391949,0.5899994373321533,0.0,1740481168.739196,0.5899994373321533,0.0,1740481168.7391975,0.5899994373321533,0.0,1740481168.7391984,0.5899994373321533,0.0,1740481168.7391994,0.5899994373321533,0.2815572125571095,1740481168.7392006,0.5899994373321533,0.0,1740481168.7392013,0.5899994373321533,0.08388613331349695,1740481168.7392023,0.5899994373321533,0.0,1740481168.7392032,0.5899994373321533,0.19767107924361257,1740481176.3589513,8.179992198944092 -1740481168.7969403,0.6299993991851807,0.03658030270426593,1740481168.7969422,0.6299993991851807,0.0,1740481168.7969449,0.6299993991851807,0.0,1740481168.7969472,0.6299993991851807,2.431922461191491,1740481168.7969482,0.6299993991851807,0.0,1740481168.7969494,0.6299993991851807,0.0,1740481168.7969506,0.6299993991851807,0.0,1740481168.7969515,0.6299993991851807,0.0,1740481168.7969525,0.6299993991851807,0.25890832281319204,1740481168.7969537,0.6299993991851807,0.0,1740481168.7969546,0.6299993991851807,0.061237243569579464,1740481168.7969556,0.6299993991851807,0.0,1740481168.7969568,0.6299993991851807,0.19767107924361257,1740481176.3779638,8.199992179870605 -1740481169.0216656,0.8399991989135742,0.08542104944423468,1740481169.0216675,0.8399991989135742,0.0,1740481169.0216696,0.8399991989135742,0.0,1740481169.0216718,0.8399991989135742,2.5446043705295285,1740481169.0216727,0.8399991989135742,0.0,1740481169.021674,0.8399991989135742,0.0,1740481169.0216753,0.8399991989135742,0.0,1740481169.0216763,0.8399991989135742,0.0,1740481169.0216773,0.8399991989135742,0.4133033912513854,1740481169.0216784,0.8399991989135742,0.0,1740481169.0216792,0.8399991989135742,0.21154686796783906,1740481169.02168,0.8399991989135742,0.0,1740481169.021681,0.8399991989135742,0.229591660542647,1740481176.3975103,8.21999216079712 -1740481169.0410554,0.8599991798400879,0.11094645689171756,1740481169.0410576,0.8599991798400879,0.0,1740481169.0410604,0.8599991798400879,0.0012122567643879484,1740481169.0410626,0.8599991798400879,2.5596240043301326,1740481169.0410638,0.8599991798400879,0.0,1740481169.0410652,0.8599991798400879,0.0,1740481169.0410664,0.8599991798400879,0.0,1740481169.0410678,0.8599991798400879,0.0,1740481169.0410688,0.8599991798400879,0.5357778783905444,1740481169.0410695,0.8599991798400879,0.0,1740481169.0410707,0.8599991798400879,0.3518147606198158,1740481169.0410717,0.8599991798400879,0.0,1740481169.0410724,0.8599991798400879,0.2364953490607551,1740481176.419309,8.239992141723633 -1740481169.056597,0.8799991607666016,0.11094645689171756,1740481169.0565994,0.8799991607666016,0.0,1740481169.0566015,0.8799991607666016,0.0012122567643879484,1740481169.056604,0.8799991607666016,2.5596240043301326,1740481169.0566049,0.8799991607666016,0.0,1740481169.0566063,0.8799991607666016,0.0,1740481169.0566075,0.8799991607666016,0.0,1740481169.0566084,0.8799991607666016,0.0,1740481169.05661,0.8799991607666016,0.5357778783905444,1740481169.056611,0.8799991607666016,0.0,1740481169.0566123,0.8799991607666016,0.29928252932978927,1740481169.056614,0.8799991607666016,0.0,1740481169.056615,0.8799991607666016,0.2364953490607551,1740481176.4394772,8.259992122650146 -1740481169.0771894,0.8999991416931152,0.11094645689171756,1740481169.0771914,0.8999991416931152,0.0,1740481169.0771935,0.8999991416931152,0.0012122567643879484,1740481169.077196,0.8999991416931152,2.5596240043301326,1740481169.0771968,0.8999991416931152,0.0,1740481169.077198,0.8999991416931152,0.0,1740481169.0771995,0.8999991416931152,0.0,1740481169.0772002,0.8999991416931152,0.0,1740481169.0772011,0.8999991416931152,0.5357778783905444,1740481169.077202,0.8999991416931152,0.0,1740481169.0772033,0.8999991416931152,0.29928252932978927,1740481169.077204,0.8999991416931152,0.0,1740481169.077205,0.8999991416931152,0.2364953490607551,1740481176.4592218,8.27999210357666 -1740481169.0964708,0.9199991226196289,0.11094645689171756,1740481169.0964725,0.9199991226196289,0.0,1740481169.0964751,0.9199991226196289,0.0012122567643879484,1740481169.0964773,0.9199991226196289,2.5596240043301326,1740481169.0964782,0.9199991226196289,0.0,1740481169.0964794,0.9199991226196289,0.0,1740481169.0964808,0.9199991226196289,0.0,1740481169.0964816,0.9199991226196289,0.0,1740481169.0964825,0.9199991226196289,0.5357778783905444,1740481169.0964835,0.9199991226196289,0.0,1740481169.0964844,0.9199991226196289,0.29928252932978927,1740481169.0964854,0.9199991226196289,0.0,1740481169.0964866,0.9199991226196289,0.2364953490607551,1740481176.4786985,8.299992084503174 -1740481169.1263273,0.9399991035461426,0.11094645689171756,1740481169.1263297,0.9399991035461426,0.0,1740481169.126332,0.9399991035461426,0.0,1740481169.1263342,0.9399991035461426,2.5839371550132277,1740481169.1263354,0.9399991035461426,0.0,1740481169.1263368,0.9399991035461426,0.0,1740481169.126338,0.9399991035461426,0.0,1740481169.1263394,0.9399991035461426,0.0,1740481169.1263404,0.9399991035461426,0.2977325926303346,1740481169.1263413,0.9399991035461426,0.0,1740481169.1263423,0.9399991035461426,0.06123724356957949,1740481169.1263435,0.9399991035461426,0.0,1740481169.1263444,0.9399991035461426,0.2364953490607551,1740481176.4974556,8.319992065429688 -1740481169.1386058,0.9599990844726562,0.11094645689171756,1740481169.1386082,0.9599990844726562,0.0,1740481169.1386106,0.9599990844726562,0.0,1740481169.138613,0.9599990844726562,2.5839371550132277,1740481169.138614,0.9599990844726562,0.0,1740481169.1386156,0.9599990844726562,0.0,1740481169.1386168,0.9599990844726562,0.0,1740481169.1386178,0.9599990844726562,0.0,1740481169.138619,0.9599990844726562,0.2977325926303346,1740481169.13862,0.9599990844726562,0.0,1740481169.138621,0.9599990844726562,0.06123724356957949,1740481169.1386223,0.9599990844726562,0.0,1740481169.1386232,0.9599990844726562,0.2364953490607551,1740481176.5210686,8.339992046356201 -1740481169.1595428,0.9799990653991699,0.1386120652195162,1740481169.1595445,0.9799990653991699,0.0,1740481169.1595469,0.9799990653991699,0.0013450888403838438,1740481169.159549,0.9799990653991699,2.6407979801627057,1740481169.15955,0.9799990653991699,0.0,1740481169.1595511,0.9799990653991699,0.0,1740481169.1595523,0.9799990653991699,0.0,1740481169.1595533,0.9799990653991699,0.0,1740481169.1595542,0.9799990653991699,0.2977325926303346,1740481169.1595554,0.9799990653991699,1.0,1740481169.1595562,0.9799990653991699,1.0208621505847875,1740481169.159557,0.9799990653991699,0.0,1740481169.159558,0.9799990653991699,0.26425321721530226,1740481176.5377154,8.359992027282715 -1740481169.1782062,0.9999990463256836,0.1386120652195162,1740481169.1782084,0.9999990463256836,0.0,1740481169.1782105,0.9999990463256836,0.0013450888403838438,1740481169.1782126,0.9999990463256836,2.6407979801627057,1740481169.1782136,0.9999990463256836,0.0,1740481169.178215,0.9999990463256836,0.0,1740481169.1782162,0.9999990463256836,0.0,1740481169.1782172,0.9999990463256836,0.0,1740481169.1782181,0.9999990463256836,0.2977325926303346,1740481169.1782193,0.9999990463256836,1.0,1740481169.1782203,0.9999990463256836,1.0334793754150322,1740481169.1782212,0.9999990463256836,0.0,1740481169.1782224,0.9999990463256836,0.26425321721530226,1740481176.5585482,8.379992008209229 -1740481169.1991549,1.0199990272521973,0.1386120652195162,1740481169.1991572,1.0199990272521973,0.0,1740481169.1991594,1.0199990272521973,0.0013450888403838438,1740481169.1991615,1.0199990272521973,2.6407979801627057,1740481169.1991627,1.0199990272521973,0.0,1740481169.199164,1.0199990272521973,0.0,1740481169.1991649,1.0199990272521973,0.0,1740481169.199166,1.0199990272521973,0.0,1740481169.199167,1.0199990272521973,0.2977325926303346,1740481169.199168,1.0199990272521973,1.0,1740481169.199169,1.0199990272521973,1.0334793754150322,1740481169.19917,1.0199990272521973,0.0,1740481169.199171,1.0199990272521973,0.26425321721530226,1740481176.5802834,8.399991989135742 -1740481169.2240694,1.039999008178711,0.1386120652195162,1740481169.224073,1.039999008178711,0.0,1740481169.224077,1.039999008178711,0.0,1740481169.2240794,1.039999008178711,2.6671184996501207,1740481169.2240803,1.039999008178711,0.0,1740481169.2240822,1.039999008178711,0.0,1740481169.2240834,1.039999008178711,0.0,1740481169.2240849,1.039999008178711,0.0,1740481169.2240863,1.039999008178711,0.3254904607848818,1740481169.2240875,1.039999008178711,0.0,1740481169.2240891,1.039999008178711,0.06123724356957955,1740481169.2240915,1.039999008178711,0.0,1740481169.2240932,1.039999008178711,0.26425321721530226,1740481176.598306,8.419991970062256 -1740481169.2386713,1.0599989891052246,0.1386120652195162,1740481169.2386734,1.0599989891052246,0.0,1740481169.2386756,1.0599989891052246,0.0,1740481169.238678,1.0599989891052246,2.6671184996501207,1740481169.238679,1.0599989891052246,0.0,1740481169.2386804,1.0599989891052246,0.0,1740481169.2386813,1.0599989891052246,0.0,1740481169.2386825,1.0599989891052246,0.0,1740481169.2386837,1.0599989891052246,0.3254904607848818,1740481169.2386847,1.0599989891052246,0.0,1740481169.2386856,1.0599989891052246,0.06123724356957955,1740481169.2386868,1.0599989891052246,0.0,1740481169.2386878,1.0599989891052246,0.26425321721530226,1740481176.6188796,8.43999195098877 -1740481169.258961,1.0799989700317383,0.17187636392815353,1740481169.2589626,1.0799989700317383,0.0,1740481169.2589648,1.0799989700317383,0.0017680763018110275,1740481169.258967,1.0799989700317383,2.8102564131064374,1740481169.258968,1.0799989700317383,0.0,1740481169.2589693,1.0799989700317383,0.0,1740481169.2589703,1.0799989700317383,0.0,1740481169.2589715,1.0799989700317383,0.0,1740481169.2589724,1.0799989700317383,0.3254904607848818,1740481169.2589734,1.0799989700317383,1.0,1740481169.2589746,1.0799989700317383,0.9584227859070047,1740481169.2589755,1.0799989700317383,0.0,1740481169.2589765,1.0799989700317383,0.3349381357925551,1740481176.6380754,8.459991931915283 -1740481169.2778692,1.099998950958252,0.17187636392815353,1740481169.2778711,1.099998950958252,0.0,1740481169.2778735,1.099998950958252,0.0017680763018110275,1740481169.2778754,1.099998950958252,2.8102564131064374,1740481169.2778764,1.099998950958252,0.0,1740481169.2778778,1.099998950958252,0.0,1740481169.2778788,1.099998950958252,0.0,1740481169.2778797,1.099998950958252,0.0,1740481169.277881,1.099998950958252,0.3254904607848818,1740481169.2778816,1.099998950958252,1.0,1740481169.2778955,1.099998950958252,0.9905523249923267,1740481169.2778983,1.099998950958252,0.0,1740481169.2778993,1.099998950958252,0.3349381357925551,1740481176.6598272,8.479991912841797 -1740481169.2983742,1.1199989318847656,0.17187636392815353,1740481169.2983758,1.1199989318847656,0.0,1740481169.2983782,1.1199989318847656,0.0017680763018110275,1740481169.2983806,1.1199989318847656,2.8102564131064374,1740481169.2983816,1.1199989318847656,0.0,1740481169.2983828,1.1199989318847656,0.0,1740481169.298384,1.1199989318847656,0.0,1740481169.298385,1.1199989318847656,0.0,1740481169.2983859,1.1199989318847656,0.3254904607848818,1740481169.298387,1.1199989318847656,1.0,1740481169.2983878,1.1199989318847656,0.9905523249923267,1740481169.298389,1.1199989318847656,0.0,1740481169.29839,1.1199989318847656,0.3349381357925551,1740481176.678172,8.49999189376831 -1740481169.3222163,1.1399989128112793,0.17187636392815353,1740481169.322222,1.1399989128112793,0.0,1740481169.322225,1.1399989128112793,0.0,1740481169.3222275,1.1399989128112793,2.841752635513264,1740481169.3222284,1.1399989128112793,0.0,1740481169.3222306,1.1399989128112793,0.0,1740481169.3222318,1.1399989128112793,0.0,1740481169.3222337,1.1399989128112793,0.0,1740481169.322235,1.1399989128112793,0.39617537936213454,1740481169.3222368,1.1399989128112793,0.0,1740481169.3222387,1.1399989128112793,0.061237243569579436,1740481169.3222404,1.1399989128112793,0.0,1740481169.3222415,1.1399989128112793,0.3349381357925551,1740481176.6995654,8.519991874694824 -1740481169.3391926,1.159998893737793,0.17187636392815353,1740481169.3391945,1.159998893737793,0.0,1740481169.339197,1.159998893737793,0.0,1740481169.339199,1.159998893737793,2.841752635513264,1740481169.3392,1.159998893737793,0.0,1740481169.3392012,1.159998893737793,0.0,1740481169.3392024,1.159998893737793,0.0,1740481169.3392034,1.159998893737793,0.0,1740481169.3392043,1.159998893737793,0.39617537936213454,1740481169.3392053,1.159998893737793,0.0,1740481169.3392065,1.159998893737793,0.061237243569579436,1740481169.3392074,1.159998893737793,0.0,1740481169.3392084,1.159998893737793,0.3349381357925551,1740481176.7200031,8.539991855621338 -1740481169.3585055,1.1799988746643066,0.17187636392815353,1740481169.358508,1.1799988746643066,0.0,1740481169.3585105,1.1799988746643066,0.0,1740481169.35853,1.1799988746643066,2.841752635513264,1740481169.3585312,1.1799988746643066,0.0,1740481169.3585327,1.1799988746643066,0.0,1740481169.3585336,1.1799988746643066,0.0,1740481169.3585348,1.1799988746643066,0.0,1740481169.358536,1.1799988746643066,0.39617537936213454,1740481169.3585374,1.1799988746643066,0.0,1740481169.3585384,1.1799988746643066,0.061237243569579436,1740481169.3585396,1.1799988746643066,0.0,1740481169.3585405,1.1799988746643066,0.3349381357925551,1740481176.737952,8.559991836547852 -1740481169.3798795,1.1999988555908203,0.21344188182821888,1740481169.3798814,1.1999988555908203,0.0,1740481169.3798835,1.1999988555908203,0.002689088185971574,1740481169.3798857,1.1999988555908203,2.982260865605955,1740481169.3798866,1.1999988555908203,0.0,1740481169.3798878,1.1999988555908203,0.0,1740481169.379889,1.1999988555908203,0.0,1740481169.37989,1.1999988555908203,0.0,1740481169.379891,1.1999988555908203,0.39617537936213454,1740481169.3798919,1.1999988555908203,1.0,1740481169.3798928,1.1999988555908203,0.9610051104931695,1740481169.3798938,1.1999988555908203,0.0,1740481169.3798947,1.1999988555908203,0.40384770674591486,1740481176.7598326,8.579991817474365 -1740481169.3981311,1.219998836517334,0.21344188182821888,1740481169.3981342,1.219998836517334,0.0,1740481169.3981378,1.219998836517334,0.002689088185971574,1740481169.3981407,1.219998836517334,2.982260865605955,1740481169.3981428,1.219998836517334,0.0,1740481169.3981445,1.219998836517334,0.0,1740481169.3981466,1.219998836517334,0.0,1740481169.3981483,1.219998836517334,0.0,1740481169.3981502,1.219998836517334,0.39617537936213454,1740481169.398152,1.219998836517334,1.0,1740481169.3981538,1.219998836517334,0.9923276726162197,1740481169.3981555,1.219998836517334,0.0,1740481169.3981574,1.219998836517334,0.40384770674591486,1740481176.778266,8.599991798400879 -1740481169.4276063,1.2399988174438477,0.21344188182821888,1740481169.4276085,1.2399988174438477,0.0,1740481169.4276109,1.2399988174438477,0.0,1740481169.427613,1.2399988174438477,3.021137295320049,1740481169.427614,1.2399988174438477,0.0,1740481169.4276152,1.2399988174438477,0.0,1740481169.4276164,1.2399988174438477,0.0,1740481169.4276173,1.2399988174438477,0.0,1740481169.4276183,1.2399988174438477,0.4650849503154945,1740481169.427619,1.2399988174438477,0.0,1740481169.4276202,1.2399988174438477,0.06123724356957966,1740481169.4276211,1.2399988174438477,0.0,1740481169.4276218,1.2399988174438477,0.40384770674591486,1740481176.7982213,8.619991779327393 -1740481169.4390292,1.2599987983703613,0.21344188182821888,1740481169.4390316,1.2599987983703613,0.0,1740481169.4390357,1.2599987983703613,0.0,1740481169.439038,1.2599987983703613,3.021137295320049,1740481169.439039,1.2599987983703613,0.0,1740481169.4390404,1.2599987983703613,0.0,1740481169.4390416,1.2599987983703613,0.0,1740481169.4390428,1.2599987983703613,0.0,1740481169.4390442,1.2599987983703613,0.4650849503154945,1740481169.4390461,1.2599987983703613,0.0,1740481169.439047,1.2599987983703613,0.06123724356957966,1740481169.4390485,1.2599987983703613,0.0,1740481169.439063,1.2599987983703613,0.40384770674591486,1740481176.8189104,8.639991760253906 -1740481169.4578896,1.279998779296875,0.21344188182821888,1740481169.4578912,1.279998779296875,0.0,1740481169.4578936,1.279998779296875,0.0,1740481169.457896,1.279998779296875,3.021137295320049,1740481169.457897,1.279998779296875,0.0,1740481169.4578981,1.279998779296875,0.0,1740481169.457985,1.279998779296875,0.0,1740481169.4579866,1.279998779296875,0.0,1740481169.4579875,1.279998779296875,0.4650849503154945,1740481169.4579885,1.279998779296875,0.0,1740481169.4579897,1.279998779296875,0.06123724356957966,1740481169.4579906,1.279998779296875,0.0,1740481169.4579916,1.279998779296875,0.40384770674591486,1740481176.8391314,8.65999174118042 -1740481169.478042,1.2999987602233887,0.2612812321811804,1740481169.4780438,1.2999987602233887,0.0,1740481169.4780462,1.2999987602233887,0.0036333055809006642,1740481169.4780486,1.2999987602233887,3.124898057195178,1740481169.4780495,1.2999987602233887,0.0,1740481169.4780507,1.2999987602233887,0.0,1740481169.478052,1.2999987602233887,0.0,1740481169.4780529,1.2999987602233887,0.0,1740481169.4780538,1.2999987602233887,0.4650849503154945,1740481169.478055,1.2999987602233887,1.0,1740481169.478056,1.2999987602233887,0.988417253653533,1740481169.478057,1.2999987602233887,0.0,1740481169.478058,1.2999987602233887,0.45391143489302915,1740481176.8589654,8.679991722106934 -1740481169.4983923,1.3199987411499023,0.2612812321811804,1740481169.4983943,1.3199987411499023,0.0,1740481169.4983966,1.3199987411499023,0.0036333055809006642,1740481169.498399,1.3199987411499023,3.124898057195178,1740481169.4984002,1.3199987411499023,0.0,1740481169.4984016,1.3199987411499023,0.0,1740481169.4984028,1.3199987411499023,0.0,1740481169.4984038,1.3199987411499023,0.0,1740481169.498405,1.3199987411499023,0.4650849503154945,1740481169.4984062,1.3199987411499023,1.0,1740481169.4984071,1.3199987411499023,1.0111735154224655,1740481169.498408,1.3199987411499023,0.0,1740481169.4984093,1.3199987411499023,0.45391143489302915,1740481176.8794858,8.699991703033447 -1740481169.528807,1.339998722076416,0.2612812321811804,1740481169.528809,1.339998722076416,0.0,1740481169.5288112,1.339998722076416,0.0,1740481169.5288134,1.339998722076416,3.1691041019672386,1740481169.5288143,1.339998722076416,0.0,1740481169.5288155,1.339998722076416,0.0,1740481169.5288167,1.339998722076416,0.0,1740481169.5288177,1.339998722076416,0.0,1740481169.5288186,1.339998722076416,0.5151486784626086,1740481169.5288198,1.339998722076416,0.0,1740481169.5288205,1.339998722076416,0.061237243569579436,1740481169.5288215,1.339998722076416,0.0,1740481169.5288224,1.339998722076416,0.45391143489302915,1740481176.8975391,8.719991683959961 -1740481169.5385935,1.3599987030029297,0.2612812321811804,1740481169.5385957,1.3599987030029297,0.0,1740481169.5385978,1.3599987030029297,0.0,1740481169.5386002,1.3599987030029297,3.1691041019672386,1740481169.5386012,1.3599987030029297,0.0,1740481169.5386026,1.3599987030029297,0.0,1740481169.5386038,1.3599987030029297,0.0,1740481169.538605,1.3599987030029297,0.0,1740481169.5386062,1.3599987030029297,0.5151486784626086,1740481169.5386071,1.3599987030029297,0.0,1740481169.5386083,1.3599987030029297,0.061237243569579436,1740481169.5386095,1.3599987030029297,0.0,1740481169.5386105,1.3599987030029297,0.45391143489302915,1740481176.9193647,8.739991664886475 -1740481169.5599134,1.3799986839294434,0.2612812321811804,1740481169.5599155,1.3799986839294434,0.0,1740481169.5599182,1.3799986839294434,0.0,1740481169.5599203,1.3799986839294434,3.1691041019672386,1740481169.5599215,1.3799986839294434,0.0,1740481169.5599227,1.3799986839294434,0.0,1740481169.559924,1.3799986839294434,0.0,1740481169.559925,1.3799986839294434,0.0,1740481169.5599263,1.3799986839294434,0.5151486784626086,1740481169.5599272,1.3799986839294434,0.0,1740481169.5599284,1.3799986839294434,0.061237243569579436,1740481169.5599294,1.3799986839294434,0.0,1740481169.5599303,1.3799986839294434,0.45391143489302915,1740481176.938086,8.759991645812988 -1740481169.5782979,1.399998664855957,0.2612812321811804,1740481169.5782998,1.399998664855957,0.0,1740481169.5783017,1.399998664855957,0.0,1740481169.578304,1.399998664855957,3.1691041019672386,1740481169.578305,1.399998664855957,0.0,1740481169.5783062,1.399998664855957,0.0,1740481169.5783074,1.399998664855957,0.0,1740481169.5783083,1.399998664855957,0.0,1740481169.5783093,1.399998664855957,0.5151486784626086,1740481169.5783105,1.399998664855957,0.0,1740481169.5783114,1.399998664855957,0.061237243569579436,1740481169.5783124,1.399998664855957,0.0,1740481169.578313,1.399998664855957,0.45391143489302915,1740481176.9599748,8.779991626739502 -1740481169.5985923,1.4199986457824707,0.31513679521697924,1740481169.598595,1.4199986457824707,0.0,1740481169.598597,1.4199986457824707,0.004530514521645381,1740481169.5985994,1.4199986457824707,3.2746061918453018,1740481169.5986006,1.4199986457824707,0.0,1740481169.598603,1.4199986457824707,0.0,1740481169.598605,1.4199986457824707,0.0,1740481169.598606,1.4199986457824707,0.0,1740481169.5986073,1.4199986457824707,0.5151486784626086,1740481169.5986087,1.4199986457824707,1.0,1740481169.5986097,1.4199986457824707,0.9878033486980732,1740481169.5986109,1.4199986457824707,0.0,1740481169.5986125,1.4199986457824707,0.5043972225712381,1740481176.9777746,8.799991607666016 -1740481169.632012,1.4399986267089844,0.31513679521697924,1740481169.632014,1.4399986267089844,0.0,1740481169.6320164,1.4399986267089844,0.0,1740481169.6320183,1.4399986267089844,3.3239312403594554,1740481169.6320195,1.4399986267089844,0.0,1740481169.6320207,1.4399986267089844,0.0,1740481169.632022,1.4399986267089844,0.0,1740481169.632023,1.4399986267089844,0.0,1740481169.632024,1.4399986267089844,0.5656344661408178,1740481169.632025,1.4399986267089844,0.0,1740481169.6320262,1.4399986267089844,0.061237243569579713,1740481169.6320271,1.4399986267089844,0.0,1740481169.632028,1.4399986267089844,0.5043972225712381,1740481176.9978573,8.81999158859253 -1740481169.638486,1.459998607635498,0.31513679521697924,1740481169.6384883,1.459998607635498,0.0,1740481169.6384907,1.459998607635498,0.0,1740481169.6384928,1.459998607635498,3.3239312403594554,1740481169.6384943,1.459998607635498,0.0,1740481169.6384954,1.459998607635498,0.0,1740481169.638512,1.459998607635498,0.0,1740481169.638513,1.459998607635498,0.0,1740481169.6385143,1.459998607635498,0.5656344661408178,1740481169.6385155,1.459998607635498,0.0,1740481169.6385164,1.459998607635498,0.061237243569579713,1740481169.6385176,1.459998607635498,0.0,1740481169.6385188,1.459998607635498,0.5043972225712381,1740481177.0183895,8.839991569519043 -1740481169.6578226,1.4799985885620117,0.31513679521697924,1740481169.6578248,1.4799985885620117,0.0,1740481169.6578271,1.4799985885620117,0.0,1740481169.657829,1.4799985885620117,3.3239312403594554,1740481169.6578302,1.4799985885620117,0.0,1740481169.657832,1.4799985885620117,0.0,1740481169.657833,1.4799985885620117,0.0,1740481169.6578343,1.4799985885620117,0.0,1740481169.6578352,1.4799985885620117,0.5656344661408178,1740481169.6578362,1.4799985885620117,0.0,1740481169.6578374,1.4799985885620117,0.061237243569579713,1740481169.657838,1.4799985885620117,0.0,1740481169.657839,1.4799985885620117,0.5043972225712381,1740481177.038142,8.859991550445557 -1740481169.6778302,1.4999985694885254,0.31513679521697924,1740481169.677832,1.4999985694885254,0.0,1740481169.6778343,1.4999985694885254,0.0,1740481169.6778367,1.4999985694885254,3.3239312403594554,1740481169.6778376,1.4999985694885254,0.0,1740481169.6778388,1.4999985694885254,0.0,1740481169.6778398,1.4999985694885254,0.0,1740481169.677841,1.4999985694885254,0.0,1740481169.677842,1.4999985694885254,0.5656344661408178,1740481169.6778429,1.4999985694885254,0.0,1740481169.677844,1.4999985694885254,0.061237243569579713,1740481169.677845,1.4999985694885254,0.0,1740481169.6778462,1.4999985694885254,0.5043972225712381,1740481177.0587397,8.87999153137207 -1740481169.6985795,1.519998550415039,0.37357836674119493,1740481169.6985815,1.519998550415039,0.0,1740481169.6985836,1.519998550415039,0.005398114804427861,1740481169.6985857,1.519998550415039,3.4104611495706667,1740481169.698587,1.519998550415039,0.0,1740481169.6985884,1.519998550415039,0.0,1740481169.6985893,1.519998550415039,0.0,1740481169.6985905,1.519998550415039,0.0,1740481169.6985915,1.519998550415039,0.5656344661408178,1740481169.6985924,1.519998550415039,1.0,1740481169.6985936,1.519998550415039,1.0022322845979683,1740481169.6985943,1.519998550415039,0.0,1740481169.6985953,1.519998550415039,0.5449631197746299,1740481177.0777144,8.899991512298584 -1740481169.7229435,1.5399985313415527,0.37357836674119493,1740481169.7229457,1.5399985313415527,0.0,1740481169.7229483,1.5399985313415527,0.0,1740481169.7229507,1.5399985313415527,3.4635046062904546,1740481169.7229517,1.5399985313415527,0.0,1740481169.7229528,1.5399985313415527,0.0,1740481169.7229543,1.5399985313415527,0.0,1740481169.7229552,1.5399985313415527,0.0,1740481169.7229562,1.5399985313415527,0.6062003633442093,1740481169.7229576,1.5399985313415527,0.0,1740481169.7229583,1.5399985313415527,0.06123724356957949,1740481169.7229593,1.5399985313415527,0.0,1740481169.7229605,1.5399985313415527,0.5449631197746299,1740481177.0974593,8.919991493225098 -1740481169.7393231,1.5599985122680664,0.37357836674119493,1740481169.7393253,1.5599985122680664,0.0,1740481169.7393274,1.5599985122680664,0.0,1740481169.7393296,1.5599985122680664,3.4635046062904546,1740481169.7393308,1.5599985122680664,0.0,1740481169.7393322,1.5599985122680664,0.0,1740481169.7393334,1.5599985122680664,0.0,1740481169.7393343,1.5599985122680664,0.0,1740481169.7393355,1.5599985122680664,0.6062003633442093,1740481169.7393367,1.5599985122680664,0.0,1740481169.7393377,1.5599985122680664,0.06123724356957949,1740481169.7393386,1.5599985122680664,0.0,1740481169.7393396,1.5599985122680664,0.5449631197746299,1740481177.1187258,8.939991474151611 -1740481169.7583575,1.57999849319458,0.37357836674119493,1740481169.7583597,1.57999849319458,0.0,1740481169.7583618,1.57999849319458,0.0,1740481169.758364,1.57999849319458,3.4635046062904546,1740481169.758365,1.57999849319458,0.0,1740481169.7583663,1.57999849319458,0.0,1740481169.7583678,1.57999849319458,0.0,1740481169.758369,1.57999849319458,0.0,1740481169.7583702,1.57999849319458,0.6062003633442093,1740481169.758371,1.57999849319458,0.0,1740481169.7583723,1.57999849319458,0.06123724356957949,1740481169.7583733,1.57999849319458,0.0,1740481169.7583745,1.57999849319458,0.5449631197746299,1740481177.1378493,8.959991455078125 -1740481169.7781882,1.5999984741210938,0.37357836674119493,1740481169.7781904,1.5999984741210938,0.0,1740481169.778193,1.5999984741210938,0.0,1740481169.7781951,1.5999984741210938,3.4635046062904546,1740481169.7781963,1.5999984741210938,0.0,1740481169.7781975,1.5999984741210938,0.0,1740481169.7781985,1.5999984741210938,0.0,1740481169.7782001,1.5999984741210938,0.0,1740481169.7782013,1.5999984741210938,0.6062003633442093,1740481169.7782028,1.5999984741210938,0.0,1740481169.778204,1.5999984741210938,0.06123724356957949,1740481169.778205,1.5999984741210938,0.0,1740481169.7782059,1.5999984741210938,0.5449631197746299,1740481177.1576073,8.979991436004639 -1740481169.7984197,1.6199984550476074,0.37357836674119493,1740481169.7984219,1.6199984550476074,0.0,1740481169.7984269,1.6199984550476074,0.0,1740481169.7984297,1.6199984550476074,3.4635046062904546,1740481169.7984307,1.6199984550476074,0.0,1740481169.798432,1.6199984550476074,0.0,1740481169.798433,1.6199984550476074,0.0,1740481169.7984343,1.6199984550476074,0.0,1740481169.798435,1.6199984550476074,0.6062003633442093,1740481169.7984362,1.6199984550476074,0.0,1740481169.798437,1.6199984550476074,0.06123724356957949,1740481169.7984378,1.6199984550476074,0.0,1740481169.798439,1.6199984550476074,0.5449631197746299,1740481177.1781566,8.999991416931152 -1740481169.8232284,1.639998435974121,0.4362230129252156,1740481169.8232307,1.639998435974121,0.0,1740481169.8232334,1.639998435974121,0.0,1740481169.8232355,1.639998435974121,3.588969008392792,1740481169.8232367,1.639998435974121,0.0,1740481169.8232381,1.639998435974121,0.0,1740481169.823239,1.639998435974121,0.0,1740481169.8232405,1.639998435974121,0.0,1740481169.8232415,1.639998435974121,0.6376102413033673,1740481169.823243,1.639998435974121,1.0,1740481169.823244,1.639998435974121,1.061237243569579,1740481169.823245,1.639998435974121,0.0,1740481169.823246,1.639998435974121,0.5763729977337881,1740481177.19819,9.019991397857666 -1740481169.839048,1.6599984169006348,0.4362230129252156,1740481169.83905,1.6599984169006348,0.0,1740481169.839053,1.6599984169006348,0.0,1740481169.8390553,1.6599984169006348,3.588969008392792,1740481169.8390565,1.6599984169006348,0.0,1740481169.839058,1.6599984169006348,0.0,1740481169.839059,1.6599984169006348,0.0,1740481169.8390605,1.6599984169006348,0.0,1740481169.8390615,1.6599984169006348,0.6376102413033673,1740481169.8390627,1.6599984169006348,1.0,1740481169.839064,1.6599984169006348,1.0612372435695792,1740481169.8390648,1.6599984169006348,0.0,1740481169.8390658,1.6599984169006348,0.5763729977337881,1740481177.2236977,9.03999137878418 -1740481169.8585994,1.6799983978271484,0.4362230129252156,1740481169.8586016,1.6799983978271484,0.0,1740481169.858604,1.6799983978271484,0.0,1740481169.8586063,1.6799983978271484,3.588969008392792,1740481169.8586073,1.6799983978271484,0.0,1740481169.858609,1.6799983978271484,0.0,1740481169.8586102,1.6799983978271484,0.0,1740481169.858611,1.6799983978271484,0.0,1740481169.8586125,1.6799983978271484,0.6376102413033673,1740481169.8586135,1.6799983978271484,1.0,1740481169.8586144,1.6799983978271484,1.0612372435695792,1740481169.8586159,1.6799983978271484,0.0,1740481169.858617,1.6799983978271484,0.5763729977337881,1740481177.2378645,9.059991359710693 -1740481169.8804579,1.699998378753662,0.4362230129252156,1740481169.8804624,1.699998378753662,0.0,1740481169.8804655,1.699998378753662,0.0,1740481169.8804862,1.699998378753662,3.588969008392792,1740481169.8804898,1.699998378753662,0.0,1740481169.8804924,1.699998378753662,0.0,1740481169.8804946,1.699998378753662,0.0,1740481169.8804967,1.699998378753662,0.0,1740481169.8804986,1.699998378753662,0.6376102413033673,1740481169.8805008,1.699998378753662,1.0,1740481169.8805025,1.699998378753662,1.0612372435695792,1740481169.880504,1.699998378753662,0.0,1740481169.8805053,1.699998378753662,0.5763729977337881,1740481177.2599726,9.079991340637207 -1740481169.8983943,1.7199983596801758,0.4362230129252156,1740481169.8983965,1.7199983596801758,0.0,1740481169.8983989,1.7199983596801758,0.0,1740481169.8984013,1.7199983596801758,3.588969008392792,1740481169.898402,1.7199983596801758,0.0,1740481169.898404,1.7199983596801758,0.0,1740481169.8984048,1.7199983596801758,0.0,1740481169.898406,1.7199983596801758,0.0,1740481169.8984072,1.7199983596801758,0.6376102413033673,1740481169.8984082,1.7199983596801758,1.0,1740481169.8984091,1.7199983596801758,1.0612372435695792,1740481169.8984103,1.7199983596801758,0.0,1740481169.898411,1.7199983596801758,0.5763729977337881,1740481177.2781425,9.09999132156372 -1740481169.9235692,1.7399983406066895,0.503158444844102,1740481169.9235713,1.7399983406066895,0.0,1740481169.9235742,1.7399983406066895,0.0,1740481169.9235764,1.7399983406066895,3.8308441580711294,1740481169.9235773,1.7399983406066895,0.0,1740481169.923579,1.7399983406066895,0.0,1740481169.92358,1.7399983406066895,0.0,1740481169.923581,1.7399983406066895,0.0,1740481169.9235818,1.7399983406066895,0.7250801001830938,1740481169.923583,1.7399983406066895,1.0,1740481169.923584,1.7399983406066895,1.0612372435695803,1740481169.9235852,1.7399983406066895,0.0,1740481169.9235864,1.7399983406066895,0.6638428566135138,1740481177.300216,9.119991302490234 -1740481169.9388692,1.7599983215332031,0.503158444844102,1740481169.9388714,1.7599983215332031,0.0,1740481169.9388735,1.7599983215332031,0.0,1740481169.938876,1.7599983215332031,3.8308441580711294,1740481169.9388769,1.7599983215332031,0.0,1740481169.9388785,1.7599983215332031,0.0,1740481169.9388795,1.7599983215332031,0.0,1740481169.9388807,1.7599983215332031,0.0,1740481169.9388819,1.7599983215332031,0.7250801001830938,1740481169.938883,1.7599983215332031,1.0,1740481169.9388838,1.7599983215332031,1.0612372435695798,1740481169.938885,1.7599983215332031,0.0,1740481169.938886,1.7599983215332031,0.6638428566135138,1740481177.3187077,9.139991283416748 -1740481169.9582236,1.7799983024597168,0.503158444844102,1740481169.9582255,1.7799983024597168,0.0,1740481169.9582279,1.7799983024597168,0.0,1740481169.9582305,1.7799983024597168,3.8308441580711294,1740481169.9582312,1.7799983024597168,0.0,1740481169.9582329,1.7799983024597168,0.0,1740481169.9582338,1.7799983024597168,0.0,1740481169.958235,1.7799983024597168,0.0,1740481169.958236,1.7799983024597168,0.7250801001830938,1740481169.9582372,1.7799983024597168,1.0,1740481169.9582381,1.7799983024597168,1.0612372435695798,1740481169.9582393,1.7799983024597168,0.0,1740481169.9582403,1.7799983024597168,0.6638428566135138,1740481177.3380313,9.159991264343262 -1740481169.9780123,1.7999982833862305,0.503158444844102,1740481169.978027,1.7999982833862305,0.0,1740481169.9780307,1.7999982833862305,0.0,1740481169.978033,1.7999982833862305,3.8308441580711294,1740481169.978034,1.7999982833862305,0.0,1740481169.9780354,1.7999982833862305,0.0,1740481169.9780364,1.7999982833862305,0.0,1740481169.9780376,1.7999982833862305,0.0,1740481169.9780385,1.7999982833862305,0.7250801001830938,1740481169.9780395,1.7999982833862305,1.0,1740481169.9780407,1.7999982833862305,1.0612372435695798,1740481169.9780416,1.7999982833862305,0.0,1740481169.9780426,1.7999982833862305,0.6638428566135138,1740481177.3575745,9.179991245269775 -1740481169.9979775,1.8199982643127441,0.503158444844102,1740481169.9979792,1.8199982643127441,0.0,1740481169.9979818,1.8199982643127441,0.0,1740481169.997984,1.8199982643127441,3.8308441580711294,1740481169.997985,1.8199982643127441,0.0,1740481169.9979863,1.8199982643127441,0.0,1740481169.9979873,1.8199982643127441,0.0,1740481169.9979885,1.8199982643127441,0.0,1740481169.9979892,1.8199982643127441,0.7250801001830938,1740481169.9979904,1.8199982643127441,1.0,1740481169.997991,1.8199982643127441,1.0612372435695798,1740481169.9979923,1.8199982643127441,0.0,1740481169.997993,1.8199982643127441,0.6638428566135138,1740481177.3792105,9.199991226196289 -1740481170.0222797,1.8399982452392578,0.503158444844102,1740481170.0222814,1.8399982452392578,0.0,1740481170.0222843,1.8399982452392578,0.0,1740481170.0222864,1.8399982452392578,3.8308441580711294,1740481170.0222874,1.8399982452392578,0.0,1740481170.0222886,1.8399982452392578,0.0,1740481170.0222898,1.8399982452392578,0.0,1740481170.0222907,1.8399982452392578,0.0,1740481170.0222917,1.8399982452392578,0.7250801001830938,1740481170.0223053,1.8399982452392578,1.0,1740481170.022307,1.8399982452392578,1.0612372435695798,1740481170.0223079,1.8399982452392578,0.0,1740481170.0223086,1.8399982452392578,0.6638428566135138,1740481177.3978274,9.219991207122803 -1740481170.0382164,1.8599982261657715,0.5814642529667085,1740481170.038218,1.8599982261657715,0.0,1740481170.03822,1.8599982261657715,0.009271805830702503,1740481170.038222,1.8599982261657715,4.051168484433473,1740481170.038223,1.8599982261657715,0.0,1740481170.0382245,1.8599982261657715,0.0,1740481170.0382252,1.8599982261657715,0.0,1740481170.0382261,1.8599982261657715,0.0,1740481170.038227,1.8599982261657715,0.8475545873222521,1740481170.0382283,1.8599982261657715,0.0,1740481170.038229,1.8599982261657715,0.0858892172776643,1740481170.03823,1.8599982261657715,0.0,1740481170.0382311,1.8599982261657715,0.7693691168793342,1740481177.4189968,9.239991188049316 -1740481170.0585172,1.8799982070922852,0.5814642529667085,1740481170.0585194,1.8799982070922852,0.0,1740481170.0585213,1.8799982070922852,0.009271805830702503,1740481170.0585234,1.8799982070922852,4.051168484433473,1740481170.0585244,1.8799982070922852,0.0,1740481170.0585258,1.8799982070922852,0.0,1740481170.058527,1.8799982070922852,0.0,1740481170.058528,1.8799982070922852,0.0,1740481170.0585291,1.8799982070922852,0.8475545873222521,1740481170.0585303,1.8799982070922852,0.0,1740481170.058531,1.8799982070922852,0.0781854704429179,1740481170.058532,1.8799982070922852,0.0,1740481170.0585332,1.8799982070922852,0.7693691168793342,1740481177.4387093,9.25999116897583 -1740481170.0788612,1.8999981880187988,0.5814642529667085,1740481170.0788667,1.8999981880187988,0.0,1740481170.078871,1.8999981880187988,0.009271805830702503,1740481170.0788739,1.8999981880187988,4.051168484433473,1740481170.0788767,1.8999981880187988,0.0,1740481170.0788786,1.8999981880187988,0.0,1740481170.07888,1.8999981880187988,0.0,1740481170.078882,1.8999981880187988,0.0,1740481170.078884,1.8999981880187988,0.8475545873222521,1740481170.0788865,1.8999981880187988,0.0,1740481170.0788887,1.8999981880187988,0.0781854704429179,1740481170.07889,1.8999981880187988,0.0,1740481170.0788915,1.8999981880187988,0.7693691168793342,1740481177.4577487,9.279991149902344 -1740481170.0982373,1.9199981689453125,0.5814642529667085,1740481170.0982392,1.9199981689453125,0.0,1740481170.0982413,1.9199981689453125,0.009271805830702503,1740481170.0982432,1.9199981689453125,4.051168484433473,1740481170.0982444,1.9199981689453125,0.0,1740481170.0982456,1.9199981689453125,0.0,1740481170.0982466,1.9199981689453125,0.0,1740481170.0982478,1.9199981689453125,0.0,1740481170.0982485,1.9199981689453125,0.8475545873222521,1740481170.0982494,1.9199981689453125,0.0,1740481170.0982504,1.9199981689453125,0.0781854704429179,1740481170.0982516,1.9199981689453125,0.0,1740481170.0982523,1.9199981689453125,0.7693691168793342,1740481177.477954,9.299991130828857 -1740481170.1221538,1.9399981498718262,0.5814642529667085,1740481170.1221561,1.9399981498718262,0.0,1740481170.122159,1.9399981498718262,0.0,1740481170.1221611,1.9399981498718262,4.120202486725377,1740481170.122162,1.9399981498718262,0.0,1740481170.1221638,1.9399981498718262,0.0,1740481170.1221647,1.9399981498718262,0.0,1740481170.1221657,1.9399981498718262,0.0,1740481170.1221676,1.9399981498718262,0.8306063604489139,1740481170.1221688,1.9399981498718262,0.0,1740481170.12217,1.9399981498718262,0.061237243569579713,1740481170.1221712,1.9399981498718262,0.0,1740481170.122172,1.9399981498718262,0.7693691168793342,1740481177.4974577,9.319991111755371 -1740481170.1384015,1.9599981307983398,0.6672108503575007,1740481170.1384077,1.9599981307983398,0.0,1740481170.1384118,1.9599981307983398,0.011630449874629035,1740481170.1384153,1.9599981307983398,4.157188752906128,1740481170.138417,1.9599981307983398,0.0,1740481170.138419,1.9599981307983398,0.0,1740481170.1384206,1.9599981307983398,0.0,1740481170.138423,1.9599981307983398,0.0,1740481170.1384246,1.9599981307983398,0.8306063604489139,1740481170.138426,1.9599981307983398,1.0,1740481170.138427,1.9599981307983398,1.042796644396669,1740481170.1384287,1.9599981307983398,0.0,1740481170.13843,1.9599981307983398,0.7820470250323956,1740481177.526004,9.339991092681885 -1740481170.1597226,1.9799981117248535,0.6672108503575007,1740481170.1597245,1.9799981117248535,0.0,1740481170.159744,1.9799981117248535,0.011630449874629035,1740481170.159746,1.9799981117248535,4.157188752906128,1740481170.159747,1.9799981117248535,0.0,1740481170.159748,1.9799981117248535,0.0,1740481170.159749,1.9799981117248535,0.0,1740481170.1597502,1.9799981117248535,0.0,1740481170.1597514,1.9799981117248535,0.8306063604489139,1740481170.1597524,1.9799981117248535,1.0,1740481170.1597536,1.9799981117248535,1.0485593354165181,1740481170.1597543,1.9799981117248535,0.0,1740481170.1597552,1.9799981117248535,0.7820470250323956,1740481177.5383248,9.359991073608398 -1740481170.1780453,1.9999980926513672,0.6672108503575007,1740481170.178047,1.9999980926513672,0.0,1740481170.178049,1.9999980926513672,0.011630449874629035,1740481170.178051,1.9999980926513672,4.157188752906128,1740481170.178052,1.9999980926513672,0.0,1740481170.1780744,1.9999980926513672,0.0,1740481170.178075,1.9999980926513672,0.0,1740481170.1780767,1.9999980926513672,0.0,1740481170.1780775,1.9999980926513672,0.8306063604489139,1740481170.1780784,1.9999980926513672,1.0,1740481170.1780796,1.9999980926513672,1.0485593354165181,1740481170.1780806,1.9999980926513672,0.0,1740481170.1780813,1.9999980926513672,0.7820470250323956,1740481177.5580506,9.379991054534912 -1740481170.1981606,2.019998073577881,0.6672108503575007,1740481170.1981628,2.019998073577881,0.0,1740481170.1981654,2.019998073577881,0.011630449874629035,1740481170.1981678,2.019998073577881,4.157188752906128,1740481170.1981688,2.019998073577881,0.0,1740481170.1981704,2.019998073577881,0.0,1740481170.1981714,2.019998073577881,0.0,1740481170.1981726,2.019998073577881,0.0,1740481170.1981738,2.019998073577881,0.8306063604489139,1740481170.198175,2.019998073577881,1.0,1740481170.198176,2.019998073577881,1.0485593354165181,1740481170.198177,2.019998073577881,0.0,1740481170.198178,2.019998073577881,0.7820470250323956,1740481177.577938,9.399991035461426 -1740481170.225539,2.0399980545043945,0.6672108503575007,1740481170.225544,2.0399980545043945,0.0,1740481170.225547,2.0399980545043945,0.0,1740481170.2255614,2.0399980545043945,4.231304900422292,1740481170.2255623,2.0399980545043945,0.0,1740481170.225564,2.0399980545043945,0.0,1740481170.225565,2.0399980545043945,0.0,1740481170.2255661,2.0399980545043945,0.0,1740481170.2255673,2.0399980545043945,0.843284268601975,1740481170.225568,2.0399980545043945,0.0,1740481170.225569,2.0399980545043945,0.06123724356957938,1740481170.22557,2.0399980545043945,0.0,1740481170.2255712,2.0399980545043945,0.7820470250323956,1740481177.5995765,9.41999101638794 -1740481170.2389002,2.059998035430908,0.6672108503575007,1740481170.238902,2.059998035430908,0.0,1740481170.2389042,2.059998035430908,0.0,1740481170.2389064,2.059998035430908,4.231304900422292,1740481170.2389073,2.059998035430908,0.0,1740481170.2389088,2.059998035430908,0.0,1740481170.23891,2.059998035430908,0.0,1740481170.238911,2.059998035430908,0.0,1740481170.2389123,2.059998035430908,0.843284268601975,1740481170.2389133,2.059998035430908,0.0,1740481170.238914,2.059998035430908,0.06123724356957938,1740481170.238915,2.059998035430908,0.0,1740481170.2389162,2.059998035430908,0.7820470250323956,1740481177.6184964,9.439990997314453 -1740481170.2596145,2.079998016357422,0.7583830437081547,1740481170.2596164,2.079998016357422,0.0,1740481170.2596185,2.079998016357422,0.012555117099479872,1740481170.2596204,2.079998016357422,4.415679117039821,1740481170.2596214,2.079998016357422,0.0,1740481170.2596226,2.079998016357422,0.0,1740481170.2596238,2.079998016357422,0.0,1740481170.2596247,2.079998016357422,0.0,1740481170.2596257,2.079998016357422,0.843284268601975,1740481170.2596273,2.079998016357422,1.0,1740481170.2596283,2.079998016357422,0.9362778612247208,1740481170.259629,2.079998016357422,0.0,1740481170.25963,2.079998016357422,0.8679565747914205,1740481177.6378593,9.459990978240967 -1740481170.2779005,2.0999979972839355,0.7583830437081547,1740481170.2779024,2.0999979972839355,0.0,1740481170.2779047,2.0999979972839355,0.012555117099479872,1740481170.2779067,2.0999979972839355,4.415679117039821,1740481170.2779076,2.0999979972839355,0.0,1740481170.277909,2.0999979972839355,0.0,1740481170.27791,2.0999979972839355,0.0,1740481170.277911,2.0999979972839355,0.0,1740481170.277912,2.0999979972839355,0.843284268601975,1740481170.2779133,2.0999979972839355,1.0,1740481170.277914,2.0999979972839355,0.9753276938105545,1740481170.2779155,2.0999979972839355,0.0,1740481170.2779162,2.0999979972839355,0.8679565747914205,1740481177.657836,9.47999095916748 -1740481170.2982712,2.119997978210449,0.7583830437081547,1740481170.298273,2.119997978210449,0.0,1740481170.298275,2.119997978210449,0.012555117099479872,1740481170.2982771,2.119997978210449,4.415679117039821,1740481170.298278,2.119997978210449,0.0,1740481170.2982795,2.119997978210449,0.0,1740481170.2982805,2.119997978210449,0.0,1740481170.2982814,2.119997978210449,0.0,1740481170.2982824,2.119997978210449,0.843284268601975,1740481170.2982967,2.119997978210449,1.0,1740481170.2982988,2.119997978210449,0.9753276938105545,1740481170.2982998,2.119997978210449,0.0,1740481170.298301,2.119997978210449,0.8679565747914205,1740481177.6784286,9.499990940093994 -1740481170.3218071,2.139997959136963,0.7583830437081547,1740481170.321809,2.139997959136963,0.0,1740481170.3218114,2.139997959136963,0.0,1740481170.3218136,2.139997959136963,4.494296193290996,1740481170.3218145,2.139997959136963,0.0,1740481170.3218157,2.139997959136963,0.0,1740481170.3218167,2.139997959136963,0.0,1740481170.3218176,2.139997959136963,0.0,1740481170.3218184,2.139997959136963,0.929193818361,1740481170.3218193,2.139997959136963,0.0,1740481170.3218203,2.139997959136963,0.06123724356957949,1740481170.321821,2.139997959136963,0.0,1740481170.321822,2.139997959136963,0.8679565747914205,1740481177.6980588,9.519990921020508 -1740481170.3382738,2.1599979400634766,0.7583830437081547,1740481170.338276,2.1599979400634766,0.0,1740481170.3382783,2.1599979400634766,0.0,1740481170.3382807,2.1599979400634766,4.494296193290996,1740481170.3382816,2.1599979400634766,0.0,1740481170.338283,2.1599979400634766,0.0,1740481170.338284,2.1599979400634766,0.0,1740481170.338285,2.1599979400634766,0.0,1740481170.3382864,2.1599979400634766,0.929193818361,1740481170.3382874,2.1599979400634766,0.0,1740481170.3382883,2.1599979400634766,0.06123724356957949,1740481170.3382895,2.1599979400634766,0.0,1740481170.3382902,2.1599979400634766,0.8679565747914205,1740481177.7183769,9.539990901947021 -1740481170.3602421,2.1799979209899902,0.8576804367323154,1740481170.360262,2.1799979209899902,0.0,1740481170.360267,2.1799979209899902,0.015067060239668865,1740481170.3602698,2.1799979209899902,4.637522356330925,1740481170.3602715,2.1799979209899902,0.0,1740481170.3602731,2.1799979209899902,0.0,1740481170.3602743,2.1799979209899902,0.0,1740481170.360276,2.1799979209899902,0.0,1740481170.3602982,2.1799979209899902,0.929193818361,1740481170.3602998,2.1799979209899902,0.7043237082372222,1740481170.3603008,2.1799979209899902,0.6723543038106665,1740481170.3603032,2.1799979209899902,0.0,1740481170.3603044,2.1799979209899902,0.9320361261915507,1740481177.7382362,9.559990882873535 -1740481170.3820112,2.199997901916504,0.8576804367323154,1740481170.3820126,2.199997901916504,0.0,1740481170.3820148,2.199997901916504,0.015067060239668865,1740481170.3820164,2.199997901916504,4.637522356330925,1740481170.3820174,2.199997901916504,0.0,1740481170.3820186,2.199997901916504,0.0,1740481170.3820195,2.199997901916504,0.0,1740481170.3820202,2.199997901916504,0.0,1740481170.3820214,2.199997901916504,0.929193818361,1740481170.3820221,2.199997901916504,0.7043237082372222,1740481170.3820229,2.199997901916504,0.7014814004066715,1740481170.382024,2.199997901916504,0.0,1740481170.3820248,2.199997901916504,0.9320361261915507,1740481177.7607284,9.579990863800049 -1740481170.3995028,2.2199978828430176,0.8576804367323154,1740481170.399505,2.2199978828430176,0.0,1740481170.3995078,2.2199978828430176,0.015067060239668865,1740481170.3995097,2.2199978828430176,4.637522356330925,1740481170.3995273,2.2199978828430176,0.0,1740481170.3995287,2.2199978828430176,0.0,1740481170.3995297,2.2199978828430176,0.0,1740481170.3995304,2.2199978828430176,0.0,1740481170.3995316,2.2199978828430176,0.929193818361,1740481170.3995323,2.2199978828430176,0.7043237082372222,1740481170.3995333,2.2199978828430176,0.7014814004066715,1740481170.399534,2.2199978828430176,0.0,1740481170.399535,2.2199978828430176,0.9320361261915507,1740481177.7787843,9.599990844726562 -1740481170.421014,2.2399978637695312,0.8576804367323154,1740481170.4210155,2.2399978637695312,0.0,1740481170.4210176,2.2399978637695312,0.0,1740481170.4210196,2.2399978637695312,4.721752689115417,1740481170.4210207,2.2399978637695312,0.0,1740481170.4210217,2.2399978637695312,0.0,1740481170.4210227,2.2399978637695312,0.0,1740481170.4210234,2.2399978637695312,0.0,1740481170.4210246,2.2399978637695312,0.9811426516209764,1740481170.4210255,2.2399978637695312,0.0,1740481170.4210262,2.2399978637695312,0.04910652542942562,1740481170.4210274,2.2399978637695312,0.0,1740481170.4210281,2.2399978637695312,0.9320361261915507,1740481177.7981882,9.619990825653076 -1740481170.4390104,2.259997844696045,0.8576804367323154,1740481170.4390118,2.259997844696045,0.0,1740481170.4390147,2.259997844696045,0.0,1740481170.4390168,2.259997844696045,4.721752689115417,1740481170.4390175,2.259997844696045,0.0,1740481170.4390187,2.259997844696045,0.0,1740481170.4390197,2.259997844696045,0.0,1740481170.4390209,2.259997844696045,0.0,1740481170.4390216,2.259997844696045,0.9811426516209764,1740481170.4390225,2.259997844696045,0.0,1740481170.4390233,2.259997844696045,0.04910652542942562,1740481170.4390244,2.259997844696045,0.0,1740481170.4390254,2.259997844696045,0.9320361261915507,1740481177.8191772,9.63999080657959 -1740481170.4600017,2.2799978256225586,0.8576804367323154,1740481170.460004,2.2799978256225586,0.0,1740481170.4600067,2.2799978256225586,0.0,1740481170.4600086,2.2799978256225586,4.721752689115417,1740481170.4600098,2.2799978256225586,0.0,1740481170.460011,2.2799978256225586,0.0,1740481170.460012,2.2799978256225586,0.0,1740481170.4600132,2.2799978256225586,0.0,1740481170.460014,2.2799978256225586,0.9811426516209764,1740481170.4600148,2.2799978256225586,0.0,1740481170.4600158,2.2799978256225586,0.04910652542942562,1740481170.460017,2.2799978256225586,0.0,1740481170.460018,2.2799978256225586,0.9320361261915507,1740481177.8375084,9.659990787506104 -1740481170.4780867,2.2999978065490723,0.9630207821372734,1740481170.4780889,2.2999978065490723,0.0,1740481170.478091,2.2999978065490723,0.0168776221444155,1740481170.4780931,2.2999978065490723,4.813419105955493,1740481170.478094,2.2999978065490723,0.0,1740481170.4780953,2.2999978065490723,0.0,1740481170.4780965,2.2999978065490723,0.0,1740481170.4780974,2.2999978065490723,0.0,1740481170.4780982,2.2999978065490723,0.9811426516209764,1740481170.478099,2.2999978065490723,0.18857348379024086,1740481170.4781,2.2999978065490723,0.18328814232186325,1740481170.478101,2.2999978065490723,0.0,1740481170.4781163,2.2999978065490723,0.969430523539381,1740481177.857514,9.679990768432617 -1740481170.4981601,2.319997787475586,0.9630207821372734,1740481170.4981623,2.319997787475586,0.0,1740481170.498164,2.319997787475586,0.0168776221444155,1740481170.498166,2.319997787475586,4.813419105955493,1740481170.4981673,2.319997787475586,0.0,1740481170.4981682,2.319997787475586,0.0,1740481170.4981694,2.319997787475586,0.0,1740481170.4981704,2.319997787475586,0.0,1740481170.4981713,2.319997787475586,0.9811426516209764,1740481170.4981725,2.319997787475586,0.18857348379024086,1740481170.4981735,2.319997787475586,0.20028561187183624,1740481170.4981744,2.319997787475586,0.0,1740481170.4981751,2.319997787475586,0.969430523539381,1740481177.8778837,9.69999074935913 -1740481170.523372,2.3399977684020996,0.9630207821372734,1740481170.5233746,2.3399977684020996,0.0,1740481170.523377,2.3399977684020996,0.0,1740481170.5233788,2.3399977684020996,4.901881829216036,1740481170.5233798,2.3399977684020996,0.0,1740481170.523381,2.3399977684020996,0.0,1740481170.5233817,2.3399977684020996,0.0,1740481170.523383,2.3399977684020996,0.0,1740481170.523384,2.3399977684020996,0.9961849487476745,1740481170.5233848,2.3399977684020996,0.0,1740481170.5233858,2.3399977684020996,0.02675442520829352,1740481170.523387,2.3399977684020996,0.0,1740481170.5233884,2.3399977684020996,0.969430523539381,1740481177.8974993,9.719990730285645 -1740481170.5389762,2.3599977493286133,0.9630207821372734,1740481170.5389793,2.3599977493286133,0.0,1740481170.5389836,2.3599977493286133,0.0,1740481170.5389872,2.3599977493286133,4.901881829216036,1740481170.5389888,2.3599977493286133,0.0,1740481170.5389903,2.3599977493286133,0.0,1740481170.5389926,2.3599977493286133,0.0,1740481170.5389938,2.3599977493286133,0.0,1740481170.5389953,2.3599977493286133,0.9961849487476745,1740481170.5389967,2.3599977493286133,0.0,1740481170.5389984,2.3599977493286133,0.02675442520829352,1740481170.5390003,2.3599977493286133,0.0,1740481170.5390024,2.3599977493286133,0.969430523539381,1740481177.9186459,9.739990711212158 -1740481170.5588038,2.379997730255127,0.9630207821372734,1740481170.5588074,2.379997730255127,0.0,1740481170.5588105,2.379997730255127,0.0,1740481170.558813,2.379997730255127,4.901881829216036,1740481170.5588143,2.379997730255127,0.0,1740481170.5588162,2.379997730255127,0.0,1740481170.558818,2.379997730255127,0.0,1740481170.5588195,2.379997730255127,0.0,1740481170.558821,2.379997730255127,0.9961849487476745,1740481170.5588224,2.379997730255127,0.0,1740481170.5588236,2.379997730255127,0.02675442520829352,1740481170.558825,2.379997730255127,0.0,1740481170.5588262,2.379997730255127,0.969430523539381,1740481177.937858,9.759990692138672 -1740481170.578557,2.3999977111816406,1.0700868604287033,1740481170.5785592,2.3999977111816406,0.0,1740481170.5785613,2.3999977111816406,0.01741711571229937,1740481170.5785632,2.3999977111816406,4.929514350966845,1740481170.5785642,2.3999977111816406,0.0,1740481170.5785656,2.3999977111816406,0.0,1740481170.5785663,2.3999977111816406,0.0,1740481170.5785677,2.3999977111816406,0.0,1740481170.5785685,2.3999977111816406,0.9961849487476745,1740481170.5785694,2.3999977111816406,0.03815051252325952,1740481170.5785706,2.3999977111816406,0.05747554930759551,1740481170.578761,2.3999977111816406,0.0,1740481170.5787635,2.3999977111816406,0.9745382265586362,1740481177.9587195,9.779990673065186 -1740481170.6006403,2.4199976921081543,1.0700868604287033,1740481170.600642,2.4199976921081543,0.0,1740481170.600644,2.4199976921081543,0.01741711571229937,1740481170.6006458,2.4199976921081543,4.929514350966845,1740481170.600647,2.4199976921081543,0.0,1740481170.6006482,2.4199976921081543,0.0,1740481170.600649,2.4199976921081543,0.0,1740481170.6006503,2.4199976921081543,0.0,1740481170.600651,2.4199976921081543,0.9961849487476745,1740481170.6006517,2.4199976921081543,0.03815051252325952,1740481170.6006525,2.4199976921081543,0.05979723471229781,1740481170.6006536,2.4199976921081543,0.0,1740481170.6006548,2.4199976921081543,0.9745382265586362,1740481177.9776332,9.7999906539917 -1740481170.6218095,2.439997673034668,1.0700868604287033,1740481170.6218114,2.439997673034668,0.0,1740481170.6218135,2.439997673034668,0.0,1740481170.6218154,2.439997673034668,5.019163313545976,1740481170.6218164,2.439997673034668,0.0,1740481170.6218176,2.439997673034668,0.0,1740481170.6218183,2.439997673034668,0.0,1740481170.6218195,2.439997673034668,0.0,1740481170.6218204,2.439997673034668,0.9973533185485289,1740481170.6218212,2.439997673034668,0.0,1740481170.621822,2.439997673034668,0.022815091989892733,1740481170.621823,2.439997673034668,0.0,1740481170.6218238,2.439997673034668,0.9745382265586362,1740481177.9981143,9.819990634918213 -1740481170.6378872,2.4599976539611816,1.0700868604287033,1740481170.637889,2.4599976539611816,0.0,1740481170.6378908,2.4599976539611816,0.0,1740481170.6378932,2.4599976539611816,5.019163313545976,1740481170.6378942,2.4599976539611816,0.0,1740481170.6378953,2.4599976539611816,0.0,1740481170.6378965,2.4599976539611816,0.0,1740481170.6378975,2.4599976539611816,0.0,1740481170.6378982,2.4599976539611816,0.9973533185485289,1740481170.6378992,2.4599976539611816,0.0,1740481170.6379,2.4599976539611816,0.022815091989892733,1740481170.637901,2.4599976539611816,0.0,1740481170.637902,2.4599976539611816,0.9745382265586362,1740481178.0201204,9.839990615844727 -1740481170.659494,2.4799976348876953,1.0700868604287033,1740481170.6594956,2.4799976348876953,0.0,1740481170.659498,2.4799976348876953,0.0,1740481170.6595001,2.4799976348876953,5.019163313545976,1740481170.659501,2.4799976348876953,0.0,1740481170.6595023,2.4799976348876953,0.0,1740481170.6595035,2.4799976348876953,0.0,1740481170.6595044,2.4799976348876953,0.0,1740481170.6595054,2.4799976348876953,0.9973533185485289,1740481170.6595063,2.4799976348876953,0.0,1740481170.6595075,2.4799976348876953,0.022815091989892733,1740481170.6595085,2.4799976348876953,0.0,1740481170.6595094,2.4799976348876953,0.9745382265586362,1740481178.0401168,9.85999059677124 -1740481170.679327,2.499997615814209,1.0700868604287033,1740481170.6793294,2.499997615814209,0.0,1740481170.6793315,2.499997615814209,0.0,1740481170.679334,2.499997615814209,5.019163313545976,1740481170.6793346,2.499997615814209,0.0,1740481170.6793358,2.499997615814209,0.0,1740481170.679337,2.499997615814209,0.0,1740481170.679338,2.499997615814209,0.0,1740481170.679339,2.499997615814209,0.9973533185485289,1740481170.6793401,2.499997615814209,0.0,1740481170.6793408,2.499997615814209,0.022815091989892733,1740481170.6793418,2.499997615814209,0.0,1740481170.6793425,2.499997615814209,0.9745382265586362,1740481178.0577493,9.879990577697754 -1740481170.6984458,2.5199975967407227,1.1772348792501717,1740481170.6984477,2.5199975967407227,0.0,1740481170.6984499,2.5199975967407227,0.017450888694242,1740481170.698452,2.5199975967407227,5.032436666993938,1740481170.6984527,2.5199975967407227,0.0,1740481170.698454,2.5199975967407227,0.0,1740481170.698455,2.5199975967407227,0.0,1740481170.698456,2.5199975967407227,0.0,1740481170.6984568,2.5199975967407227,0.9973533185485289,1740481170.6984582,2.5199975967407227,0.02646681451471511,1740481170.698459,2.5199975967407227,0.05232011486190497,1740481170.6984603,2.5199975967407227,0.0,1740481170.6984613,2.5199975967407227,0.9724494589354963,1740481178.0790164,9.899990558624268 -1740481170.7238507,2.5399975776672363,1.1772348792501717,1740481170.7238529,2.5399975776672363,0.0,1740481170.723855,2.5399975776672363,0.0,1740481170.7238572,2.5399975776672363,5.1221337971211645,1740481170.7238579,2.5399975776672363,0.0,1740481170.7238593,2.5399975776672363,0.0,1740481170.7238603,2.5399975776672363,0.0,1740481170.723861,2.5399975776672363,0.0,1740481170.723862,2.5399975776672363,0.996901263558326,1740481170.7238631,2.5399975776672363,0.0,1740481170.7238638,2.5399975776672363,0.024451804622829698,1740481170.7238646,2.5399975776672363,0.0,1740481170.7238655,2.5399975776672363,0.9724494589354963,1740481178.0979357,9.919990539550781 -1740481170.7383997,2.55999755859375,1.1772348792501717,1740481170.7384017,2.55999755859375,0.0,1740481170.738404,2.55999755859375,0.0,1740481170.738406,2.55999755859375,5.1221337971211645,1740481170.738407,2.55999755859375,0.0,1740481170.738408,2.55999755859375,0.0,1740481170.7384093,2.55999755859375,0.0,1740481170.7384102,2.55999755859375,0.0,1740481170.738411,2.55999755859375,0.996901263558326,1740481170.7384124,2.55999755859375,0.0,1740481170.738413,2.55999755859375,0.024451804622829698,1740481170.7384138,2.55999755859375,0.0,1740481170.7384148,2.55999755859375,0.9724494589354963,1740481178.11859,9.939990520477295 -1740481170.7588127,2.5799975395202637,1.1772348792501717,1740481170.7588158,2.5799975395202637,0.0,1740481170.758819,2.5799975395202637,0.0,1740481170.758821,2.5799975395202637,5.1221337971211645,1740481170.7588222,2.5799975395202637,0.0,1740481170.7588234,2.5799975395202637,0.0,1740481170.7588243,2.5799975395202637,0.0,1740481170.7588253,2.5799975395202637,0.0,1740481170.758826,2.5799975395202637,0.996901263558326,1740481170.758827,2.5799975395202637,0.0,1740481170.7588277,2.5799975395202637,0.024451804622829698,1740481170.7588286,2.5799975395202637,0.0,1740481170.7588296,2.5799975395202637,0.9724494589354963,1740481178.1394782,9.959990501403809 -1740481170.778319,2.5999975204467773,1.1772348792501717,1740481170.7783206,2.5999975204467773,0.0,1740481170.778323,2.5999975204467773,0.0,1740481170.7783253,2.5999975204467773,5.1221337971211645,1740481170.7783263,2.5999975204467773,0.0,1740481170.7783275,2.5999975204467773,0.0,1740481170.7783287,2.5999975204467773,0.0,1740481170.7783298,2.5999975204467773,0.0,1740481170.7783306,2.5999975204467773,0.996901263558326,1740481170.7783318,2.5999975204467773,0.0,1740481170.778333,2.5999975204467773,0.024451804622829698,1740481170.778334,2.5999975204467773,0.0,1740481170.7783346,2.5999975204467773,0.9724494589354963,1740481178.1589706,9.979990482330322 -1740481170.7985098,2.619997501373291,1.2840848427002083,1740481170.7985115,2.619997501373291,0.0,1740481170.7985141,2.619997501373291,0.01739445758257763,1740481170.798516,2.619997501373291,5.133786215648208,1740481170.798517,2.619997501373291,0.0,1740481170.798518,2.619997501373291,0.0,1740481170.7985191,2.619997501373291,0.0,1740481170.7985198,2.619997501373291,0.0,1740481170.7985208,2.619997501373291,0.996901263558326,1740481170.7985215,2.619997501373291,0.030987364416723562,1740481170.7985225,2.619997501373291,0.05961519868813234,1740481170.7985232,2.619997501373291,0.0,1740481170.7985241,2.619997501373291,0.9695784394077295,1740481178.1786032,9.999990463256836 -1740481170.8253512,2.6399974822998047,1.2840848427002083,1740481170.8253527,2.6399974822998047,0.0,1740481170.8253553,2.6399974822998047,0.0,1740481170.8253567,2.6399974822998047,5.2232417215156675,1740481170.825358,2.6399974822998047,0.0,1740481170.825359,2.6399974822998047,0.0,1740481170.8253598,2.6399974822998047,0.0,1740481170.8253605,2.6399974822998047,0.0,1740481170.8253617,2.6399974822998047,0.9962217790395091,1740481170.8253624,2.6399974822998047,0.0,1740481170.8253632,2.6399974822998047,0.026643339631779672,1740481170.8253639,2.6399974822998047,0.0,1740481170.825365,2.6399974822998047,0.9695784394077295,1740481178.2022965,10.029990434646606 -1740481170.8378723,2.6599974632263184,1.2840848427002083,1740481170.8378742,2.6599974632263184,0.0,1740481170.8378766,2.6599974632263184,0.0,1740481170.8378785,2.6599974632263184,5.2232417215156675,1740481170.8378797,2.6599974632263184,0.0,1740481170.8378808,2.6599974632263184,0.0,1740481170.8378816,2.6599974632263184,0.0,1740481170.8378825,2.6599974632263184,0.0,1740481170.8378837,2.6599974632263184,0.9962217790395091,1740481170.8378844,2.6599974632263184,0.0,1740481170.8378851,2.6599974632263184,0.026643339631779672,1740481170.837886,2.6599974632263184,0.0,1740481170.837887,2.6599974632263184,0.9695784394077295,1740481178.2189507,10.039990425109863 -1740481170.859544,2.679997444152832,1.2840848427002083,1740481170.8595462,2.679997444152832,0.0,1740481170.859548,2.679997444152832,0.0,1740481170.8595502,2.679997444152832,5.2232417215156675,1740481170.859551,2.679997444152832,0.0,1740481170.8595521,2.679997444152832,0.0,1740481170.8595533,2.679997444152832,0.0,1740481170.859554,2.679997444152832,0.0,1740481170.859555,2.679997444152832,0.9962217790395091,1740481170.8595557,2.679997444152832,0.0,1740481170.859557,2.679997444152832,0.026643339631779672,1740481170.8595579,2.679997444152832,0.0,1740481170.859559,2.679997444152832,0.9695784394077295,1740481178.238027,10.059990406036377 -1740481170.878756,2.6999974250793457,1.2840848427002083,1740481170.8787582,2.6999974250793457,0.0,1740481170.87876,2.6999974250793457,0.0,1740481170.8787622,2.6999974250793457,5.2232417215156675,1740481170.8787632,2.6999974250793457,0.0,1740481170.8787646,2.6999974250793457,0.0,1740481170.8787658,2.6999974250793457,0.0,1740481170.8787668,2.6999974250793457,0.0,1740481170.878768,2.6999974250793457,0.9962217790395091,1740481170.878769,2.6999974250793457,0.0,1740481170.87877,2.6999974250793457,0.026643339631779672,1740481170.8787708,2.6999974250793457,0.0,1740481170.878772,2.6999974250793457,0.9695784394077295,1740481178.2579613,10.07999038696289 -1740481170.9000983,2.7199974060058594,1.2840848427002083,1740481170.9001,2.7199974060058594,0.0,1740481170.9001026,2.7199974060058594,0.0,1740481170.900105,2.7199974060058594,5.2232417215156675,1740481170.9001057,2.7199974060058594,0.0,1740481170.900107,2.7199974060058594,0.0,1740481170.900108,2.7199974060058594,0.0,1740481170.900109,2.7199974060058594,0.0,1740481170.9001098,2.7199974060058594,0.9962217790395091,1740481170.900111,2.7199974060058594,0.0,1740481170.900112,2.7199974060058594,0.026643339631779672,1740481170.9001126,2.7199974060058594,0.0,1740481170.9001133,2.7199974060058594,0.9695784394077295,1740481178.278773,10.099990367889404 -1740481170.9273968,2.739997386932373,1.3906558029775251,1740481170.9273994,2.739997386932373,0.0,1740481170.927402,2.739997386932373,0.0,1740481170.927404,2.739997386932373,5.324930454437143,1740481170.927405,2.739997386932373,0.0,1740481170.927406,2.739997386932373,0.0,1740481170.927407,2.739997386932373,0.0,1740481170.9274082,2.739997386932373,0.0,1740481170.9274092,2.739997386932373,0.995591100704257,1740481170.9274101,2.739997386932373,0.04408899295743396,1740481170.9274108,2.739997386932373,0.07336569387244364,1740481170.927412,2.739997386932373,0.0,1740481170.9274127,2.739997386932373,0.967137325729809,1740481178.2978606,10.119990348815918 -1740481170.9384215,2.7599973678588867,1.3906558029775251,1740481170.938425,2.7599973678588867,0.0,1740481170.9384284,2.7599973678588867,0.0,1740481170.9384305,2.7599973678588867,5.324930454437143,1740481170.9384315,2.7599973678588867,0.0,1740481170.9384327,2.7599973678588867,0.0,1740481170.938434,2.7599973678588867,0.0,1740481170.9384348,2.7599973678588867,0.0,1740481170.938436,2.7599973678588867,0.995591100704257,1740481170.9384372,2.7599973678588867,0.04408899295743396,1740481170.9384382,2.7599973678588867,0.07254276793188197,1740481170.938439,2.7599973678588867,0.0,1740481170.9384398,2.7599973678588867,0.967137325729809,1740481178.3187675,10.139990329742432 -1740481170.9681683,2.7899973392486572,1.3906558029775251,1740481170.9681723,2.7899973392486572,0.0,1740481170.9681756,2.7899973392486572,0.0,1740481170.9681783,2.7899973392486572,5.324930454437143,1740481170.9681797,2.7899973392486572,0.0,1740481170.968182,2.7899973392486572,0.0,1740481170.9681835,2.7899973392486572,0.0,1740481170.9681857,2.7899973392486572,0.0,1740481170.9681869,2.7899973392486572,0.995591100704257,1740481170.968188,2.7899973392486572,0.04408899295743396,1740481170.9681897,2.7899973392486572,0.07254276793188197,1740481170.968191,2.7899973392486572,0.0,1740481170.9681926,2.7899973392486572,0.967137325729809,1740481178.3384495,10.159990310668945 -1740481170.9791732,2.799997329711914,1.3906558029775251,1740481170.979175,2.799997329711914,0.0,1740481170.9791775,2.799997329711914,0.0,1740481170.9791796,2.799997329711914,5.324930454437143,1740481170.9791806,2.799997329711914,0.0,1740481170.9791818,2.799997329711914,0.0,1740481170.979183,2.799997329711914,0.0,1740481170.9791842,2.799997329711914,0.0,1740481170.9791853,2.799997329711914,0.995591100704257,1740481170.9791865,2.799997329711914,0.04408899295743396,1740481170.9791875,2.799997329711914,0.07254276793188197,1740481170.9791882,2.799997329711914,0.0,1740481170.9791892,2.799997329711914,0.967137325729809,1740481178.360623,10.179990291595459 -1740481170.9984617,2.8199973106384277,1.3906558029775251,1740481170.9984634,2.8199973106384277,0.0,1740481170.9984658,2.8199973106384277,0.0,1740481170.9984677,2.8199973106384277,5.324930454437143,1740481170.9984686,2.8199973106384277,0.0,1740481170.9984698,2.8199973106384277,0.0,1740481170.998471,2.8199973106384277,0.0,1740481170.9984717,2.8199973106384277,0.0,1740481170.9984727,2.8199973106384277,0.995591100704257,1740481170.9984736,2.8199973106384277,0.04408899295743396,1740481170.9984746,2.8199973106384277,0.07254276793188197,1740481170.9984756,2.8199973106384277,0.0,1740481170.9984763,2.8199973106384277,0.967137325729809,1740481178.3775876,10.199990272521973 -1740481171.0205398,2.8399972915649414,1.4970360224747195,1740481171.0205414,2.8399972915649414,0.0,1740481171.0205436,2.8399972915649414,0.0,1740481171.0205455,2.8399972915649414,5.432754950925436,1740481171.0205462,2.8399972915649414,0.0,1740481171.0205476,2.8399972915649414,0.0,1740481171.0205486,2.8399972915649414,0.0,1740481171.0205495,2.8399972915649414,0.0,1740481171.0205505,2.8399972915649414,0.9957827378419335,1740481171.0205514,2.8399972915649414,0.04217262158066948,1740481171.0205522,2.8399972915649414,0.06985475798642689,1740481171.0205529,2.8399972915649414,0.0,1740481171.0205538,2.8399972915649414,0.9678594642253584,1740481178.3978026,10.219990253448486 -1740481171.0399754,2.859997272491455,1.4970360224747195,1740481171.0399778,2.859997272491455,0.0,1740481171.0399797,2.859997272491455,0.0,1740481171.0399818,2.859997272491455,5.432754950925436,1740481171.0399828,2.859997272491455,0.0,1740481171.0399842,2.859997272491455,0.0,1740481171.0399852,2.859997272491455,0.0,1740481171.0399861,2.859997272491455,0.0,1740481171.039987,2.859997272491455,0.9957827378419335,1740481171.0399883,2.859997272491455,0.04217262158066948,1740481171.0399892,2.859997272491455,0.07009589519724457,1740481171.0399902,2.859997272491455,0.0,1740481171.0399914,2.859997272491455,0.9678594642253584,1740481178.4183755,10.239990234375 -1740481171.0584614,2.8799972534179688,1.4970360224747195,1740481171.0584633,2.8799972534179688,0.0,1740481171.0584655,2.8799972534179688,0.0,1740481171.0584676,2.8799972534179688,5.432754950925436,1740481171.0584683,2.8799972534179688,0.0,1740481171.0584695,2.8799972534179688,0.0,1740481171.0584707,2.8799972534179688,0.0,1740481171.0584714,2.8799972534179688,0.0,1740481171.0584724,2.8799972534179688,0.9957827378419335,1740481171.058473,2.8799972534179688,0.04217262158066948,1740481171.058474,2.8799972534179688,0.07009589519724457,1740481171.058475,2.8799972534179688,0.0,1740481171.0584757,2.8799972534179688,0.9678594642253584,1740481178.437754,10.259990215301514 -1740481171.0799267,2.8999972343444824,1.4970360224747195,1740481171.0799322,2.8999972343444824,0.0,1740481171.0799365,2.8999972343444824,0.0,1740481171.07994,2.8999972343444824,5.432754950925436,1740481171.0799413,2.8999972343444824,0.0,1740481171.0799437,2.8999972343444824,0.0,1740481171.0799453,2.8999972343444824,0.0,1740481171.0799472,2.8999972343444824,0.0,1740481171.0799499,2.8999972343444824,0.9957827378419335,1740481171.0799527,2.8999972343444824,0.04217262158066948,1740481171.0799537,2.8999972343444824,0.07009589519724457,1740481171.0799553,2.8999972343444824,0.0,1740481171.079957,2.8999972343444824,0.9678594642253584,1740481178.4596097,10.279990196228027 -1740481171.0979698,2.919997215270996,1.4970360224747195,1740481171.0979714,2.919997215270996,0.0,1740481171.0979738,2.919997215270996,0.0,1740481171.0979757,2.919997215270996,5.432754950925436,1740481171.0979767,2.919997215270996,0.0,1740481171.0979776,2.919997215270996,0.0,1740481171.0979786,2.919997215270996,0.0,1740481171.09798,2.919997215270996,0.0,1740481171.097981,2.919997215270996,0.9957827378419335,1740481171.0979822,2.919997215270996,0.04217262158066948,1740481171.097983,2.919997215270996,0.07009589519724457,1740481171.097984,2.919997215270996,0.0,1740481171.0979848,2.919997215270996,0.9678594642253584,1740481178.4778354,10.299990177154541 -1740481171.1222508,2.9399971961975098,1.4970360224747195,1740481171.1222525,2.9399971961975098,0.0,1740481171.1222672,2.9399971961975098,0.0,1740481171.1222713,2.9399971961975098,5.432754950925436,1740481171.122272,2.9399971961975098,0.0,1740481171.1222734,2.9399971961975098,0.0,1740481171.1222746,2.9399971961975098,0.0,1740481171.1222756,2.9399971961975098,0.0,1740481171.1222763,2.9399971961975098,0.9957827378419335,1740481171.1222773,2.9399971961975098,0.04217262158066948,1740481171.1222782,2.9399971961975098,0.07009589519724457,1740481171.122279,2.9399971961975098,0.0,1740481171.12228,2.9399971961975098,0.9678594642253584,1740481178.4978065,10.319990158081055 -1740481171.1385708,2.9599971771240234,1.6035678104629802,1740481171.1385725,2.9599971771240234,0.0,1740481171.1385746,2.9599971771240234,0.017323202242049456,1740481171.1385767,2.9599971771240234,5.452772966974046,1740481171.1385775,2.9599971771240234,0.0,1740481171.1385787,2.9599971771240234,0.0,1740481171.1385796,2.9599971771240234,0.0,1740481171.1385806,2.9599971771240234,0.0,1740481171.1385815,2.9599971771240234,1.0000000000000004,1740481171.1385825,2.9599971771240234,6.661338147750939e-15,1740481171.1385832,2.9599971771240234,0.03209760977668519,1740481171.1385841,2.9599971771240234,0.0,1740481171.138585,2.9599971771240234,0.9692068711286386,1740481178.5190325,10.339990139007568 -1740481171.1584668,2.979997158050537,1.6035678104629802,1740481171.1584687,2.979997158050537,0.0,1740481171.1584704,2.979997158050537,0.017323202242049456,1740481171.1584725,2.979997158050537,5.452772966974046,1740481171.1584735,2.979997158050537,0.0,1740481171.1584744,2.979997158050537,0.0,1740481171.1584756,2.979997158050537,0.0,1740481171.1584766,2.979997158050537,0.0,1740481171.1584775,2.979997158050537,1.0000000000000004,1740481171.1584787,2.979997158050537,6.661338147750939e-15,1740481171.1584797,2.979997158050537,0.030793128871368536,1740481171.1584804,2.979997158050537,0.0,1740481171.1584811,2.979997158050537,0.9692068711286386,1740481178.5377736,10.359990119934082 -1740481171.1779776,2.999997138977051,1.6035678104629802,1740481171.1779797,2.999997138977051,0.0,1740481171.1779819,2.999997138977051,0.017323202242049456,1740481171.1779842,2.999997138977051,5.452772966974046,1740481171.1779854,2.999997138977051,0.0,1740481171.1779869,2.999997138977051,0.0,1740481171.1779878,2.999997138977051,0.0,1740481171.1779888,2.999997138977051,0.0,1740481171.1779902,2.999997138977051,1.0000000000000004,1740481171.1779914,2.999997138977051,6.661338147750939e-15,1740481171.1779928,2.999997138977051,0.030793128871368536,1740481171.1779938,2.999997138977051,0.0,1740481171.1779947,2.999997138977051,0.9692068711286386,1740481178.5590549,10.379990100860596 -1740481171.1986396,3.0199971199035645,1.6035678104629802,1740481171.198641,3.0199971199035645,0.0,1740481171.1986432,3.0199971199035645,0.017323202242049456,1740481171.1986449,3.0199971199035645,5.452772966974046,1740481171.198646,3.0199971199035645,0.0,1740481171.198647,3.0199971199035645,0.0,1740481171.198648,3.0199971199035645,0.0,1740481171.1986492,3.0199971199035645,0.0,1740481171.1986501,3.0199971199035645,1.0000000000000004,1740481171.198651,3.0199971199035645,6.661338147750939e-15,1740481171.1986518,3.0199971199035645,0.030793128871368536,1740481171.1986527,3.0199971199035645,0.0,1740481171.1986537,3.0199971199035645,0.9692068711286386,1740481178.578208,10.39999008178711 -1740481171.2212737,3.039997100830078,1.6035678104629802,1740481171.2212756,3.039997100830078,0.0,1740481171.221278,3.039997100830078,0.0,1740481171.22128,3.039997100830078,5.541981552720257,1740481171.221281,3.039997100830078,0.0,1740481171.2212822,3.039997100830078,0.0,1740481171.2212834,3.039997100830078,0.0,1740481171.2212842,3.039997100830078,0.0,1740481171.221285,3.039997100830078,0.996128921182537,1740481171.221286,3.039997100830078,0.0,1740481171.221287,3.039997100830078,0.026922050053898472,1740481171.2212877,3.039997100830078,0.0,1740481171.2212887,3.039997100830078,0.9692068711286386,1740481178.5984461,10.419990062713623 -1740481171.2381299,3.059997081756592,1.7100734331534495,1740481171.238132,3.059997081756592,0.0,1740481171.238134,3.059997081756592,0.017324968409132474,1740481171.2381358,3.059997081756592,5.554128813774792,1740481171.2381368,3.059997081756592,0.0,1740481171.238138,3.059997081756592,0.0,1740481171.238139,3.059997081756592,0.0,1740481171.2381396,3.059997081756592,0.0,1740481171.2381406,3.059997081756592,0.996128921182537,1740481171.2381418,3.059997081756592,0.03871078817461293,1740481171.2381425,3.059997081756592,0.06939844469954838,1740481171.2381432,3.059997081756592,0.0,1740481171.238144,3.059997081756592,0.9666180174513399,1740481178.6193225,10.439990043640137 -1740481171.2595892,3.0799970626831055,1.7100734331534495,1740481171.2595909,3.0799970626831055,0.0,1740481171.2595932,3.0799970626831055,0.017324968409132474,1740481171.2595952,3.0799970626831055,5.554128813774792,1740481171.2595963,3.0799970626831055,0.0,1740481171.2595978,3.0799970626831055,0.0,1740481171.2595987,3.0799970626831055,0.0,1740481171.2596,3.0799970626831055,0.0,1740481171.2596009,3.0799970626831055,0.996128921182537,1740481171.2596018,3.0799970626831055,0.03871078817461293,1740481171.2596028,3.0799970626831055,0.06822169190581007,1740481171.2596037,3.0799970626831055,0.0,1740481171.2596045,3.0799970626831055,0.9666180174513399,1740481178.6382673,10.45999002456665 -1740481171.2787387,3.099997043609619,1.7100734331534495,1740481171.2787404,3.099997043609619,0.0,1740481171.2787426,3.099997043609619,0.017324968409132474,1740481171.2787445,3.099997043609619,5.554128813774792,1740481171.2787457,3.099997043609619,0.0,1740481171.278747,3.099997043609619,0.0,1740481171.2787478,3.099997043609619,0.0,1740481171.278749,3.099997043609619,0.0,1740481171.27875,3.099997043609619,0.996128921182537,1740481171.278751,3.099997043609619,0.03871078817461293,1740481171.2787519,3.099997043609619,0.06822169190581007,1740481171.2787528,3.099997043609619,0.0,1740481171.2787535,3.099997043609619,0.9666180174513399,1740481178.658065,10.479990005493164 -1740481171.2980945,3.119997024536133,1.7100734331534495,1740481171.2980995,3.119997024536133,0.0,1740481171.2981033,3.119997024536133,0.017324968409132474,1740481171.2981052,3.119997024536133,5.554128813774792,1740481171.2981064,3.119997024536133,0.0,1740481171.2981076,3.119997024536133,0.0,1740481171.2981086,3.119997024536133,0.0,1740481171.2981098,3.119997024536133,0.0,1740481171.2981105,3.119997024536133,0.996128921182537,1740481171.2981114,3.119997024536133,0.03871078817461293,1740481171.2981122,3.119997024536133,0.06822169190581007,1740481171.298113,3.119997024536133,0.0,1740481171.298114,3.119997024536133,0.9666180174513399,1740481178.6781268,10.499989986419678 -1740481171.3204985,3.1399970054626465,1.7100734331534495,1740481171.3205001,3.1399970054626465,0.0,1740481171.3205023,3.1399970054626465,0.0,1740481171.3205044,3.1399970054626465,5.643309468056129,1740481171.3205051,3.1399970054626465,0.0,1740481171.3205063,3.1399970054626465,0.0,1740481171.320507,3.1399970054626465,0.0,1740481171.3205082,3.1399970054626465,0.0,1740481171.320509,3.1399970054626465,0.995450657582208,1740481171.32051,3.1399970054626465,0.0,1740481171.3205106,3.1399970054626465,0.02883264013086806,1740481171.3205116,3.1399970054626465,0.0,1740481171.3205125,3.1399970054626465,0.9666180174513399,1740481178.6980622,10.519989967346191 -1740481171.3382735,3.15999698638916,1.7100734331534495,1740481171.3382754,3.15999698638916,0.0,1740481171.338288,3.15999698638916,0.0,1740481171.338313,3.15999698638916,5.643309468056129,1740481171.3383143,3.15999698638916,0.0,1740481171.3383157,3.15999698638916,0.0,1740481171.338317,3.15999698638916,0.0,1740481171.3383179,3.15999698638916,0.0,1740481171.3383186,3.15999698638916,0.995450657582208,1740481171.3383195,3.15999698638916,0.0,1740481171.3383386,3.15999698638916,0.02883264013086806,1740481171.3383396,3.15999698638916,0.0,1740481171.3383403,3.15999698638916,0.9666180174513399,1740481178.7189372,10.539989948272705 -1740481171.3591807,3.179996967315674,1.8164497198994622,1740481171.3591993,3.179996967315674,0.0,1740481171.3592026,3.179996967315674,0.017292147461234777,1740481171.3592048,3.179996967315674,5.66059904694203,1740481171.3592057,3.179996967315674,0.0,1740481171.3592072,3.179996967315674,0.0,1740481171.3592083,3.179996967315674,0.0,1740481171.3592093,3.179996967315674,0.0,1740481171.3592103,3.179996967315674,0.995450657582208,1740481171.3592112,3.179996967315674,0.04549342417792479,1740481171.359212,3.179996967315674,0.07432793236413793,1740481171.3592129,3.179996967315674,0.0,1740481171.3592138,3.179996967315674,0.9666167331636729,1740481178.738027,10.559989929199219 -1740481171.378906,3.1999969482421875,1.8164497198994622,1740481171.3789084,3.1999969482421875,0.0,1740481171.3789117,3.1999969482421875,0.017292147461234777,1740481171.378914,3.1999969482421875,5.66059904694203,1740481171.378915,3.1999969482421875,0.0,1740481171.3789165,3.1999969482421875,0.0,1740481171.378918,3.1999969482421875,0.0,1740481171.3789191,3.1999969482421875,0.0,1740481171.37892,3.1999969482421875,0.995450657582208,1740481171.3789215,3.1999969482421875,0.04549342417792479,1740481171.3789222,3.1999969482421875,0.07432734859645984,1740481171.3789232,3.1999969482421875,0.0,1740481171.3789241,3.1999969482421875,0.9666167331636729,1740481178.7583654,10.579989910125732 -1740481171.3980122,3.219996929168701,1.8164497198994622,1740481171.398015,3.219996929168701,0.0,1740481171.3980176,3.219996929168701,0.017292147461234777,1740481171.3980198,3.219996929168701,5.66059904694203,1740481171.3980212,3.219996929168701,0.0,1740481171.398023,3.219996929168701,0.0,1740481171.3980238,3.219996929168701,0.0,1740481171.3980253,3.219996929168701,0.0,1740481171.3980267,3.219996929168701,0.995450657582208,1740481171.3980284,3.219996929168701,0.04549342417792479,1740481171.3980293,3.219996929168701,0.07432734859645984,1740481171.3980308,3.219996929168701,0.0,1740481171.398032,3.219996929168701,0.9666167331636729,1740481178.778938,10.599989891052246 -1740481171.4210105,3.239996910095215,1.8164497198994622,1740481171.421015,3.239996910095215,0.0,1740481171.4210184,3.239996910095215,0.0,1740481171.4210205,3.239996910095215,5.749683186226808,1740481171.4210212,3.239996910095215,0.0,1740481171.4210224,3.239996910095215,0.0,1740481171.4210234,3.239996910095215,0.0,1740481171.4210246,3.239996910095215,0.0,1740481171.4210253,3.239996910095215,0.9954503075265005,1740481171.421026,3.239996910095215,0.0,1740481171.4210272,3.239996910095215,0.02883357436282763,1740481171.421028,3.239996910095215,0.0,1740481171.4210289,3.239996910095215,0.9666167331636729,1740481178.7975457,10.61998987197876 -1740481171.438643,3.2599968910217285,1.8164497198994622,1740481171.438645,3.2599968910217285,0.0,1740481171.4386485,3.2599968910217285,0.0,1740481171.4386506,3.2599968910217285,5.749683186226808,1740481171.4386513,3.2599968910217285,0.0,1740481171.4386528,3.2599968910217285,0.0,1740481171.4386537,3.2599968910217285,0.0,1740481171.4386547,3.2599968910217285,0.0,1740481171.4386559,3.2599968910217285,0.9954503075265005,1740481171.4386566,3.2599968910217285,0.0,1740481171.4386575,3.2599968910217285,0.02883357436282763,1740481171.4386582,3.2599968910217285,0.0,1740481171.4386594,3.2599968910217285,0.9666167331636729,1740481178.8189993,10.639989852905273 -1740481171.4583857,3.279996871948242,1.922796326289891,1740481171.4583871,3.279996871948242,0.0,1740481171.4583893,3.279996871948242,0.01728731664995141,1740481171.458391,3.279996871948242,5.766082194939513,1740481171.4583921,3.279996871948242,0.0,1740481171.458393,3.279996871948242,0.0,1740481171.458394,3.279996871948242,0.0,1740481171.4583952,3.279996871948242,0.0,1740481171.458396,3.279996871948242,0.9954503075265005,1740481171.4583972,3.279996871948242,0.045496924734999,1740481171.458398,3.279996871948242,0.0749765414265414,1740481171.458399,3.279996871948242,0.0,1740481171.4583998,3.279996871948242,0.9661725791950498,1740481178.8387132,10.659989833831787 -1740481171.4801931,3.299996852874756,1.922796326289891,1740481171.4801955,3.299996852874756,0.0,1740481171.480198,3.299996852874756,0.01728731664995141,1740481171.4802175,3.299996852874756,5.766082194939513,1740481171.4802184,3.299996852874756,0.0,1740481171.4802198,3.299996852874756,0.0,1740481171.4802213,3.299996852874756,0.0,1740481171.480222,3.299996852874756,0.0,1740481171.480223,3.299996852874756,0.9954503075265005,1740481171.480224,3.299996852874756,0.045496924734999,1740481171.480236,3.299996852874756,0.0747746530664497,1740481171.4802372,3.299996852874756,0.0,1740481171.4802384,3.299996852874756,0.9661725791950498,1740481178.8578787,10.6799898147583 -1740481171.4982772,3.3199968338012695,1.922796326289891,1740481171.498279,3.3199968338012695,0.0,1740481171.498281,3.3199968338012695,0.01728731664995141,1740481171.498283,3.3199968338012695,5.766082194939513,1740481171.498284,3.3199968338012695,0.0,1740481171.4982858,3.3199968338012695,0.0,1740481171.498287,3.3199968338012695,0.0,1740481171.498288,3.3199968338012695,0.0,1740481171.4982889,3.3199968338012695,0.9954503075265005,1740481171.4982896,3.3199968338012695,0.045496924734999,1740481171.4982908,3.3199968338012695,0.0747746530664497,1740481171.4982915,3.3199968338012695,0.0,1740481171.4982922,3.3199968338012695,0.9661725791950498,1740481178.8786528,10.699989795684814 -1740481171.5230403,3.339996814727783,1.922796326289891,1740481171.5230422,3.339996814727783,0.0,1740481171.5230443,3.339996814727783,0.0,1740481171.5230467,3.339996814727783,5.855141484679991,1740481171.5230474,3.339996814727783,0.0,1740481171.5230486,3.339996814727783,0.0,1740481171.5230498,3.339996814727783,0.0,1740481171.5230505,3.339996814727783,0.0,1740481171.5230513,3.339996814727783,0.9953284376810047,1740481171.523052,3.339996814727783,0.0,1740481171.5230532,3.339996814727783,0.02915585848595481,1740481171.523054,3.339996814727783,0.0,1740481171.5230548,3.339996814727783,0.9661725791950498,1740481178.8975158,10.719989776611328 -1740481171.5410192,3.359996795654297,1.922796326289891,1740481171.5410223,3.359996795654297,0.0,1740481171.5410256,3.359996795654297,0.0,1740481171.5410275,3.359996795654297,5.855141484679991,1740481171.5410285,3.359996795654297,0.0,1740481171.5410297,3.359996795654297,0.0,1740481171.5410306,3.359996795654297,0.0,1740481171.5410314,3.359996795654297,0.0,1740481171.5410326,3.359996795654297,0.9953284376810047,1740481171.5410335,3.359996795654297,0.0,1740481171.5410342,3.359996795654297,0.02915585848595481,1740481171.541035,3.359996795654297,0.0,1740481171.5410361,3.359996795654297,0.9661725791950498,1740481178.918048,10.739989757537842 -1740481171.5586524,3.3799967765808105,1.922796326289891,1740481171.5586543,3.3799967765808105,0.0,1740481171.5586565,3.3799967765808105,0.0,1740481171.5586586,3.3799967765808105,5.855141484679991,1740481171.5586593,3.3799967765808105,0.0,1740481171.5586605,3.3799967765808105,0.0,1740481171.5586617,3.3799967765808105,0.0,1740481171.5586627,3.3799967765808105,0.0,1740481171.5586636,3.3799967765808105,0.9953284376810047,1740481171.558665,3.3799967765808105,0.0,1740481171.558666,3.3799967765808105,0.02915585848595481,1740481171.558667,3.3799967765808105,0.0,1740481171.5586681,3.3799967765808105,0.9661725791950498,1740481178.9390776,10.759989738464355 -1740481171.5781112,3.399996757507324,2.029142359340086,1740481171.5781136,3.399996757507324,0.0,1740481171.578117,3.399996757507324,0.017285107029540624,1740481171.5781193,3.399996757507324,5.872544714904555,1740481171.5781202,3.399996757507324,0.0,1740481171.5781217,3.399996757507324,0.0,1740481171.578123,3.399996757507324,0.0,1740481171.578124,3.399996757507324,0.0,1740481171.578125,3.399996757507324,0.9953284376810047,1740481171.5781262,3.399996757507324,0.04671562318995792,1740481171.5781271,3.399996757507324,0.07578557387211123,1740481171.578128,3.399996757507324,0.0,1740481171.5781293,3.399996757507324,0.9662316407925616,1740481178.957561,10.77998971939087 -1740481171.5982947,3.419996738433838,2.029142359340086,1740481171.5982966,3.419996738433838,0.0,1740481171.5982988,3.419996738433838,0.017285107029540624,1740481171.598301,3.419996738433838,5.872544714904555,1740481171.598302,3.419996738433838,0.0,1740481171.5983033,3.419996738433838,0.0,1740481171.5983045,3.419996738433838,0.0,1740481171.5983055,3.419996738433838,0.0,1740481171.5983067,3.419996738433838,0.9953284376810047,1740481171.5983074,3.419996738433838,0.04671562318995792,1740481171.5983083,3.419996738433838,0.07581242007840094,1740481171.598309,3.419996738433838,0.0,1740481171.5983102,3.419996738433838,0.9662316407925616,1740481178.9781556,10.799989700317383 -1740481171.6220782,3.4399967193603516,2.029142359340086,1740481171.6220806,3.4399967193603516,0.0,1740481171.6220827,3.4399967193603516,0.0,1740481171.6220846,3.4399967193603516,5.961605640925209,1740481171.6220856,3.4399967193603516,0.0,1740481171.622087,3.4399967193603516,0.0,1740481171.622088,3.4399967193603516,0.0,1740481171.622089,3.4399967193603516,0.0,1740481171.6220896,3.4399967193603516,0.9953447362377328,1740481171.6220908,3.4399967193603516,0.0,1740481171.6220915,3.4399967193603516,0.029113095445171155,1740481171.6220922,3.4399967193603516,0.0,1740481171.622093,3.4399967193603516,0.9662316407925616,1740481178.9974802,10.819989681243896 -1740481171.638625,3.4599967002868652,2.029142359340086,1740481171.6386268,3.4599967002868652,0.0,1740481171.6386294,3.4599967002868652,0.0,1740481171.6386316,3.4599967002868652,5.961605640925209,1740481171.6386325,3.4599967002868652,0.0,1740481171.6386337,3.4599967002868652,0.0,1740481171.6386347,3.4599967002868652,0.0,1740481171.6386359,3.4599967002868652,0.0,1740481171.6386368,3.4599967002868652,0.9953447362377328,1740481171.6386378,3.4599967002868652,0.0,1740481171.6386387,3.4599967002868652,0.029113095445171155,1740481171.6386397,3.4599967002868652,0.0,1740481171.6386406,3.4599967002868652,0.9662316407925616,1740481179.0181212,10.83998966217041 -1740481171.6596162,3.479996681213379,2.029142359340086,1740481171.6596189,3.479996681213379,0.0,1740481171.6596222,3.479996681213379,0.0,1740481171.659624,3.479996681213379,5.961605640925209,1740481171.6596253,3.479996681213379,0.0,1740481171.6596265,3.479996681213379,0.0,1740481171.6596274,3.479996681213379,0.0,1740481171.6596284,3.479996681213379,0.0,1740481171.6596293,3.479996681213379,0.9953447362377328,1740481171.6596303,3.479996681213379,0.0,1740481171.659631,3.479996681213379,0.029113095445171155,1740481171.6596322,3.479996681213379,0.0,1740481171.659633,3.479996681213379,0.9662316407925616,1740481179.038017,10.859989643096924 -1740481171.6792479,3.4999966621398926,2.1354343149822705,1740481171.6792498,3.4999966621398926,0.0,1740481171.6792705,3.4999966621398926,0.01727660038006992,1740481171.6792724,3.4999966621398926,5.977273462233186,1740481171.6792731,3.4999966621398926,0.0,1740481171.6792748,3.4999966621398926,0.0,1740481171.6792758,3.4999966621398926,0.0,1740481171.6792767,3.4999966621398926,0.0,1740481171.679278,3.4999966621398926,0.9953447362377328,1740481171.6793005,3.4999966621398926,0.046552637622633286,1740481171.6793017,3.4999966621398926,0.0768357545598387,1740481171.6793027,3.4999966621398926,0.0,1740481171.6793034,3.4999966621398926,0.9654272512565151,1740481179.057792,10.879989624023438 -1740481171.6983995,3.5199966430664062,2.1354343149822705,1740481171.698401,3.5199966430664062,0.0,1740481171.6984031,3.5199966430664062,0.01727660038006992,1740481171.698405,3.5199966430664062,5.977273462233186,1740481171.6984062,3.5199966430664062,0.0,1740481171.6984074,3.5199966430664062,0.0,1740481171.6984084,3.5199966430664062,0.0,1740481171.6984096,3.5199966430664062,0.0,1740481171.6984103,3.5199966430664062,0.9953447362377328,1740481171.6984112,3.5199966430664062,0.046552637622633286,1740481171.6984122,3.5199966430664062,0.076470122603851,1740481171.6984131,3.5199966430664062,0.0,1740481171.698414,3.5199966430664062,0.9654272512565151,1740481179.0775814,10.899989604949951 -1740481171.7210515,3.53999662399292,2.1354343149822705,1740481171.7210534,3.53999662399292,0.0,1740481171.7210567,3.53999662399292,0.0,1740481171.7210588,3.53999662399292,6.066288817495301,1740481171.7210596,3.53999662399292,0.0,1740481171.7210608,3.53999662399292,0.0,1740481171.7210617,3.53999662399292,0.0,1740481171.7210627,3.53999662399292,0.0,1740481171.7210634,3.53999662399292,0.9951203104270931,1740481171.721064,3.53999662399292,0.0,1740481171.721065,3.53999662399292,0.029693059170578073,1740481171.721066,3.53999662399292,0.0,1740481171.7210667,3.53999662399292,0.9654272512565151,1740481179.0989714,10.919989585876465 -1740481171.7385013,3.5599966049194336,2.1354343149822705,1740481171.7385032,3.5599966049194336,0.0,1740481171.7385051,3.5599966049194336,0.0,1740481171.7385073,3.5599966049194336,6.066288817495301,1740481171.7385082,3.5599966049194336,0.0,1740481171.7385094,3.5599966049194336,0.0,1740481171.7385104,3.5599966049194336,0.0,1740481171.738511,3.5599966049194336,0.0,1740481171.738512,3.5599966049194336,0.9951203104270931,1740481171.738513,3.5599966049194336,0.0,1740481171.738514,3.5599966049194336,0.029693059170578073,1740481171.7385147,3.5599966049194336,0.0,1740481171.7385154,3.5599966049194336,0.9654272512565151,1740481179.1181512,10.939989566802979 -1740481171.758492,3.5799965858459473,2.1354343149822705,1740481171.758494,3.5799965858459473,0.0,1740481171.7585132,3.5799965858459473,0.0,1740481171.7585154,3.5799965858459473,6.066288817495301,1740481171.7585166,3.5799965858459473,0.0,1740481171.7585177,3.5799965858459473,0.0,1740481171.7585187,3.5799965858459473,0.0,1740481171.75852,3.5799965858459473,0.0,1740481171.7585206,3.5799965858459473,0.9951203104270931,1740481171.7585218,3.5799965858459473,0.0,1740481171.7585225,3.5799965858459473,0.029693059170578073,1740481171.7585237,3.5799965858459473,0.0,1740481171.7585244,3.5799965858459473,0.9654272512565151,1740481179.1390676,10.959989547729492 -1740481171.7776988,3.599996566772461,2.1354343149822705,1740481171.7777007,3.599996566772461,0.0,1740481171.7777026,3.599996566772461,0.0,1740481171.7777047,3.599996566772461,6.066288817495301,1740481171.7777057,3.599996566772461,0.0,1740481171.7777069,3.599996566772461,0.0,1740481171.7777078,3.599996566772461,0.0,1740481171.7777088,3.599996566772461,0.0,1740481171.7777097,3.599996566772461,0.9951203104270931,1740481171.777711,3.599996566772461,0.0,1740481171.7777116,3.599996566772461,0.029693059170578073,1740481171.7777126,3.599996566772461,0.0,1740481171.7777138,3.599996566772461,0.9654272512565151,1740481179.158064,10.979989528656006 -1740481171.798155,3.6199965476989746,2.24163750167411,1740481171.7981575,3.6199965476989746,0.0,1740481171.7981606,3.6199965476989746,0.01725827975732575,1740481171.7981627,3.6199965476989746,6.081165292893379,1740481171.7981637,3.6199965476989746,0.0,1740481171.798165,3.6199965476989746,0.0,1740481171.798166,3.6199965476989746,0.0,1740481171.798167,3.6199965476989746,0.0,1740481171.7981682,3.6199965476989746,0.9951203104270931,1740481171.7981691,3.6199965476989746,0.048796895729072975,1740481171.79817,3.6199965476989746,0.0802221767680735,1740481171.798171,3.6199965476989746,0.0,1740481171.798172,3.6199965476989746,0.9642363490768915,1740481179.1777751,10.99998950958252 -1740481171.8213463,3.6399965286254883,2.24163750167411,1740481171.8213482,3.6399965286254883,0.0,1740481171.8213503,3.6399965286254883,0.0,1740481171.8213527,3.6399965286254883,6.170110199827893,1740481171.8213534,3.6399965286254883,0.0,1740481171.8213844,3.6399965286254883,0.0,1740481171.8213885,3.6399965286254883,0.0,1740481171.8213897,3.6399965286254883,0.0,1740481171.8213906,3.6399965286254883,0.9947783462612243,1740481171.8213913,3.6399965286254883,0.0,1740481171.8213923,3.6399965286254883,0.030541997184332814,1740481171.8213933,3.6399965286254883,0.0,1740481171.8213942,3.6399965286254883,0.9642363490768915,1740481179.1990256,11.019989490509033 -1740481171.8381422,3.659996509552002,2.24163750167411,1740481171.838144,3.659996509552002,0.0,1740481171.838146,3.659996509552002,0.0,1740481171.838148,3.659996509552002,6.170110199827893,1740481171.838149,3.659996509552002,0.0,1740481171.8381505,3.659996509552002,0.0,1740481171.8381512,3.659996509552002,0.0,1740481171.8381522,3.659996509552002,0.0,1740481171.8381531,3.659996509552002,0.9947783462612243,1740481171.8381543,3.659996509552002,0.0,1740481171.8381553,3.659996509552002,0.030541997184332814,1740481171.838156,3.659996509552002,0.0,1740481171.838157,3.659996509552002,0.9642363490768915,1740481179.2229452,11.039989471435547 -1740481171.8593853,3.6799964904785156,2.24163750167411,1740481171.8593872,3.6799964904785156,0.0,1740481171.8593895,3.6799964904785156,0.0,1740481171.8593915,3.6799964904785156,6.170110199827893,1740481171.8593924,3.6799964904785156,0.0,1740481171.8593938,3.6799964904785156,0.0,1740481171.8593948,3.6799964904785156,0.0,1740481171.8593955,3.6799964904785156,0.0,1740481171.859397,3.6799964904785156,0.9947783462612243,1740481171.8593976,3.6799964904785156,0.0,1740481171.8593986,3.6799964904785156,0.030541997184332814,1740481171.8593993,3.6799964904785156,0.0,1740481171.8594003,3.6799964904785156,0.9642363490768915,1740481179.238567,11.05998945236206 -1740481171.8780854,3.6999964714050293,2.24163750167411,1740481171.8780897,3.6999964714050293,0.0,1740481171.878093,3.6999964714050293,0.0,1740481171.8780951,3.6999964714050293,6.170110199827893,1740481171.8780959,3.6999964714050293,0.0,1740481171.8780973,3.6999964714050293,0.0,1740481171.8780985,3.6999964714050293,0.0,1740481171.8780992,3.6999964714050293,0.0,1740481171.8781,3.6999964714050293,0.9947783462612243,1740481171.878101,3.6999964714050293,0.0,1740481171.8781018,3.6999964714050293,0.030541997184332814,1740481171.8781028,3.6999964714050293,0.0,1740481171.8781037,3.6999964714050293,0.9642363490768915,1740481179.2578835,11.079989433288574 -1740481171.8982008,3.719996452331543,2.347638877618153,1740481171.8982038,3.719996452331543,0.0,1740481171.8982067,3.719996452331543,0.017219565629732606,1740481171.8982096,3.719996452331543,6.183376132733186,1740481171.898211,3.719996452331543,0.0,1740481171.8982127,3.719996452331543,0.0,1740481171.8982139,3.719996452331543,0.0,1740481171.898215,3.719996452331543,0.0,1740481171.8982162,3.719996452331543,0.9947783462612243,1740481171.8982177,3.719996452331543,0.05221653738776144,1740481171.8982189,3.719996452331543,0.08563390468315962,1740481171.89822,3.719996452331543,0.0,1740481171.8982213,3.719996452331543,0.9622595327146718,1740481179.2780669,11.099989414215088 -1740481171.9220347,3.7399964332580566,2.347638877618153,1740481171.922038,3.7399964332580566,0.0,1740481171.922041,3.7399964332580566,0.0,1740481171.9220433,3.7399964332580566,6.272157943047497,1740481171.9220443,3.7399964332580566,0.0,1740481171.922046,3.7399964332580566,0.0,1740481171.9220471,3.7399964332580566,0.0,1740481171.9220486,3.7399964332580566,0.0,1740481171.92205,3.7399964332580566,0.9941851445791459,1740481171.9220521,3.7399964332580566,0.0,1740481171.9220536,3.7399964332580566,0.03192561186447407,1740481171.9220548,3.7399964332580566,0.0,1740481171.9220557,3.7399964332580566,0.9622595327146718,1740481179.2977898,11.119989395141602 -1740481171.937985,3.7599964141845703,2.347638877618153,1740481171.9379866,3.7599964141845703,0.0,1740481171.9379885,3.7599964141845703,0.0,1740481171.9379907,3.7599964141845703,6.272157943047497,1740481171.9379914,3.7599964141845703,0.0,1740481171.9379928,3.7599964141845703,0.0,1740481171.9379935,3.7599964141845703,0.0,1740481171.9379945,3.7599964141845703,0.0,1740481171.9379954,3.7599964141845703,0.9941851445791459,1740481171.9379964,3.7599964141845703,0.0,1740481171.9379973,3.7599964141845703,0.03192561186447407,1740481171.937998,3.7599964141845703,0.0,1740481171.9379988,3.7599964141845703,0.9622595327146718,1740481179.3191392,11.139989376068115 -1740481171.9582222,3.779996395111084,2.347638877618153,1740481171.9582238,3.779996395111084,0.0,1740481171.958226,3.779996395111084,0.0,1740481171.9582279,3.779996395111084,6.272157943047497,1740481171.9582288,3.779996395111084,0.0,1740481171.95823,3.779996395111084,0.0,1740481171.958231,3.779996395111084,0.0,1740481171.9582324,3.779996395111084,0.0,1740481171.958233,3.779996395111084,0.9941851445791459,1740481171.9582345,3.779996395111084,0.0,1740481171.9582355,3.779996395111084,0.03192561186447407,1740481171.9582365,3.779996395111084,0.0,1740481171.9582372,3.779996395111084,0.9622595327146718,1740481179.3379867,11.159989356994629 -1740481171.9782128,3.7999963760375977,2.347638877618153,1740481171.978215,3.7999963760375977,0.0,1740481171.9782171,3.7999963760375977,0.0,1740481171.9782193,3.7999963760375977,6.272157943047497,1740481171.9782202,3.7999963760375977,0.0,1740481171.978222,3.7999963760375977,0.0,1740481171.9782228,3.7999963760375977,0.0,1740481171.9782238,3.7999963760375977,0.0,1740481171.9782248,3.7999963760375977,0.9941851445791459,1740481171.9782257,3.7999963760375977,0.0,1740481171.9782267,3.7999963760375977,0.03192561186447407,1740481171.9782274,3.7999963760375977,0.0,1740481171.9782286,3.7999963760375977,0.9622595327146718,1740481179.3578846,11.179989337921143 -1740481171.9978406,3.8199963569641113,2.347638877618153,1740481171.9978426,3.8199963569641113,0.0,1740481171.9978445,3.8199963569641113,0.0,1740481171.9978466,3.8199963569641113,6.272157943047497,1740481171.9978473,3.8199963569641113,0.0,1740481171.9978485,3.8199963569641113,0.0,1740481171.9978497,3.8199963569641113,0.0,1740481171.9978507,3.8199963569641113,0.0,1740481171.9978514,3.8199963569641113,0.9941851445791459,1740481171.9978523,3.8199963569641113,0.0,1740481171.9978533,3.8199963569641113,0.03192561186447407,1740481171.997854,3.8199963569641113,0.0,1740481171.997855,3.8199963569641113,0.9622595327146718,1740481179.3779762,11.199989318847656 -1740481172.0218134,3.839996337890625,2.4534495041910924,1740481172.0218155,3.839996337890625,0.0,1740481172.021818,3.839996337890625,0.0,1740481172.0218198,3.839996337890625,6.374523856260415,1740481172.0218208,3.839996337890625,0.0,1740481172.021822,3.839996337890625,0.0,1740481172.021823,3.839996337890625,0.0,1740481172.021824,3.839996337890625,0.0,1740481172.0218248,3.839996337890625,0.993642290277364,1740481172.0218258,3.839996337890625,0.06357709722632165,1740481172.0218265,3.839996337890625,0.09721834942497422,1740481172.0218277,3.839996337890625,0.0,1740481172.0218284,3.839996337890625,0.9605371760346616,1740481179.398089,11.21998929977417 -1740481172.0381656,3.8599963188171387,2.4534495041910924,1740481172.0381677,3.8599963188171387,0.0,1740481172.03817,3.8599963188171387,0.0,1740481172.038172,3.8599963188171387,6.374523856260415,1740481172.038173,3.8599963188171387,0.0,1740481172.0381742,3.8599963188171387,0.0,1740481172.0381753,3.8599963188171387,0.0,1740481172.0381765,3.8599963188171387,0.0,1740481172.0381775,3.8599963188171387,0.993642290277364,1740481172.0381784,3.8599963188171387,0.06357709722632165,1740481172.0381794,3.8599963188171387,0.096682211469024,1740481172.0381804,3.8599963188171387,0.0,1740481172.038181,3.8599963188171387,0.9605371760346616,1740481179.4198177,11.239989280700684 -1740481172.0607624,3.8799962997436523,2.4534495041910924,1740481172.060764,3.8799962997436523,0.0,1740481172.0607662,3.8799962997436523,0.0,1740481172.0607684,3.8799962997436523,6.374523856260415,1740481172.0607693,3.8799962997436523,0.0,1740481172.0607705,3.8799962997436523,0.0,1740481172.0607715,3.8799962997436523,0.0,1740481172.0607839,3.8799962997436523,0.0,1740481172.0607848,3.8799962997436523,0.993642290277364,1740481172.0607862,3.8799962997436523,0.06357709722632165,1740481172.060787,3.8799962997436523,0.096682211469024,1740481172.060788,3.8799962997436523,0.0,1740481172.060789,3.8799962997436523,0.9605371760346616,1740481179.4378529,11.259989261627197 -1740481172.0782177,3.899996280670166,2.4534495041910924,1740481172.0782201,3.899996280670166,0.0,1740481172.0782223,3.899996280670166,0.0,1740481172.0782242,3.899996280670166,6.374523856260415,1740481172.0782251,3.899996280670166,0.0,1740481172.0782263,3.899996280670166,0.0,1740481172.0782275,3.899996280670166,0.0,1740481172.0782285,3.899996280670166,0.0,1740481172.0782294,3.899996280670166,0.993642290277364,1740481172.0782304,3.899996280670166,0.06357709722632165,1740481172.0782313,3.899996280670166,0.096682211469024,1740481172.0782323,3.899996280670166,0.0,1740481172.0782332,3.899996280670166,0.9605371760346616,1740481179.459351,11.279989242553711 -1740481172.0982552,3.9199962615966797,2.4534495041910924,1740481172.0982566,3.9199962615966797,0.0,1740481172.098259,3.9199962615966797,0.0,1740481172.0982609,3.9199962615966797,6.374523856260415,1740481172.098262,3.9199962615966797,0.0,1740481172.098263,3.9199962615966797,0.0,1740481172.098264,3.9199962615966797,0.0,1740481172.0982652,3.9199962615966797,0.0,1740481172.0982661,3.9199962615966797,0.993642290277364,1740481172.098267,3.9199962615966797,0.06357709722632165,1740481172.0982678,3.9199962615966797,0.096682211469024,1740481172.0982687,3.9199962615966797,0.0,1740481172.0982695,3.9199962615966797,0.9605371760346616,1740481179.4778016,11.299989223480225 -1740481172.1219013,3.9399962425231934,2.5592027563078537,1740481172.1219032,3.9399962425231934,0.0,1740481172.121905,3.9399962425231934,0.0,1740481172.121907,3.9399962425231934,6.486358916970404,1740481172.121908,3.9399962425231934,0.0,1740481172.1219091,3.9399962425231934,0.0,1740481172.1219103,3.9399962425231934,0.0,1740481172.121911,3.9399962425231934,0.0,1740481172.121912,3.9399962425231934,0.9945843568593686,1740481172.1219132,3.9399962425231934,0.054156431406318095,1740481172.121914,3.9399962425231934,0.08420868988158524,1740481172.1219146,3.9399962425231934,0.0,1740481172.1219153,3.9399962425231934,0.963578080331275,1740481179.4985328,11.319989204406738 -1740481172.1380281,3.959996223449707,2.5592027563078537,1740481172.1380298,3.959996223449707,0.0,1740481172.1380322,3.959996223449707,0.0,1740481172.138034,3.959996223449707,6.486358916970404,1740481172.1380353,3.959996223449707,0.0,1740481172.1380365,3.959996223449707,0.0,1740481172.1380377,3.959996223449707,0.0,1740481172.1380389,3.959996223449707,0.0,1740481172.1380396,3.959996223449707,0.9945843568593686,1740481172.1380405,3.959996223449707,0.054156431406318095,1740481172.1380415,3.959996223449707,0.08516270793441172,1740481172.1380424,3.959996223449707,0.0,1740481172.1380432,3.959996223449707,0.963578080331275,1740481179.519249,11.339989185333252 -1740481172.1606562,3.9799962043762207,2.5592027563078537,1740481172.1606576,3.9799962043762207,0.0,1740481172.16066,3.9799962043762207,0.0,1740481172.1606617,3.9799962043762207,6.486358916970404,1740481172.160663,3.9799962043762207,0.0,1740481172.160664,3.9799962043762207,0.0,1740481172.160665,3.9799962043762207,0.0,1740481172.1606662,3.9799962043762207,0.0,1740481172.160667,3.9799962043762207,0.9945843568593686,1740481172.160668,3.9799962043762207,0.054156431406318095,1740481172.1606686,3.9799962043762207,0.08516270793441172,1740481172.1606698,3.9799962043762207,0.0,1740481172.1606705,3.9799962043762207,0.963578080331275,1740481179.5377562,11.359989166259766 -1740481172.178445,3.9999961853027344,2.5592027563078537,1740481172.1784468,3.9999961853027344,0.0,1740481172.1784492,3.9999961853027344,0.0,1740481172.178451,3.9999961853027344,6.486358916970404,1740481172.178452,3.9999961853027344,0.0,1740481172.1784532,3.9999961853027344,0.0,1740481172.1784542,3.9999961853027344,0.0,1740481172.178455,3.9999961853027344,0.0,1740481172.178456,3.9999961853027344,0.9945843568593686,1740481172.1784568,3.9999961853027344,0.054156431406318095,1740481172.1784575,3.9999961853027344,0.08516270793441172,1740481172.1784587,3.9999961853027344,0.0,1740481172.1784596,3.9999961853027344,0.963578080331275,1740481179.5577629,11.37998914718628 -1740481172.1993582,4.019996166229248,2.5592027563078537,1740481172.19936,4.019996166229248,0.0,1740481172.1993623,4.019996166229248,0.0,1740481172.1993642,4.019996166229248,6.486358916970404,1740481172.1993651,4.019996166229248,0.0,1740481172.1993663,4.019996166229248,0.0,1740481172.1993675,4.019996166229248,0.0,1740481172.1993682,4.019996166229248,0.0,1740481172.1993692,4.019996166229248,0.9945843568593686,1740481172.1993701,4.019996166229248,0.054156431406318095,1740481172.199371,4.019996166229248,0.08516270793441172,1740481172.199372,4.019996166229248,0.0,1740481172.1993728,4.019996166229248,0.963578080331275,1740481179.578207,11.399989128112793 -1740481172.222464,4.039996147155762,2.5592027563078537,1740481172.2224684,4.039996147155762,0.0,1740481172.2224712,4.039996147155762,0.0,1740481172.222474,4.039996147155762,6.486358916970404,1740481172.2224748,4.039996147155762,0.0,1740481172.222476,4.039996147155762,0.0,1740481172.2224777,4.039996147155762,0.0,1740481172.2224793,4.039996147155762,0.0,1740481172.2224803,4.039996147155762,0.9945843568593686,1740481172.2224822,4.039996147155762,0.054156431406318095,1740481172.2224832,4.039996147155762,0.08516270793441172,1740481172.2224846,4.039996147155762,0.0,1740481172.2224855,4.039996147155762,0.963578080331275,1740481179.5995076,11.419989109039307 -1740481172.238143,4.059996128082275,2.665359000707424,1740481172.2381454,4.059996128082275,0.0,1740481172.2381477,4.059996128082275,0.017241360634201,1740481172.23815,4.059996128082275,6.509882820846109,1740481172.2381508,4.059996128082275,0.0,1740481172.2381523,4.059996128082275,0.0,1740481172.2381532,4.059996128082275,0.0,1740481172.2381544,4.059996128082275,0.0,1740481172.2381556,4.059996128082275,1.0000000000000004,1740481172.2381568,4.059996128082275,6.661338147750939e-15,1740481172.2381577,4.059996128082275,0.03431445427020394,1740481172.238159,4.059996128082275,0.0,1740481172.23816,4.059996128082275,0.9667193519520267,1740481179.6196196,11.43998908996582 -1740481172.261053,4.079996109008789,2.665359000707424,1740481172.2610552,4.079996109008789,0.0,1740481172.2610574,4.079996109008789,0.017241360634201,1740481172.2610593,4.079996109008789,6.509882820846109,1740481172.2610602,4.079996109008789,0.0,1740481172.2610617,4.079996109008789,0.0,1740481172.2610624,4.079996109008789,0.0,1740481172.2610636,4.079996109008789,0.0,1740481172.2610648,4.079996109008789,1.0000000000000004,1740481172.2610657,4.079996109008789,6.661338147750939e-15,1740481172.2610664,4.079996109008789,0.033280648047980366,1740481172.2610676,4.079996109008789,0.0,1740481172.2610683,4.079996109008789,0.9667193519520267,1740481179.6374593,11.459989070892334 -1740481172.2801056,4.099996089935303,2.665359000707424,1740481172.280107,4.099996089935303,0.0,1740481172.2801092,4.099996089935303,0.017241360634201,1740481172.280111,4.099996089935303,6.509882820846109,1740481172.2801118,4.099996089935303,0.0,1740481172.2801132,4.099996089935303,0.0,1740481172.2801142,4.099996089935303,0.0,1740481172.280115,4.099996089935303,0.0,1740481172.2801156,4.099996089935303,1.0000000000000004,1740481172.2801168,4.099996089935303,6.661338147750939e-15,1740481172.2801175,4.099996089935303,0.033280648047980366,1740481172.2801182,4.099996089935303,0.0,1740481172.2801192,4.099996089935303,0.9667193519520267,1740481179.658635,11.479989051818848 -1740481172.2992628,4.119996070861816,2.665359000707424,1740481172.2992642,4.119996070861816,0.0,1740481172.2992666,4.119996070861816,0.017241360634201,1740481172.2992682,4.119996070861816,6.509882820846109,1740481172.2992694,4.119996070861816,0.0,1740481172.2992704,4.119996070861816,0.0,1740481172.2992713,4.119996070861816,0.0,1740481172.299285,4.119996070861816,0.0,1740481172.299287,4.119996070861816,1.0000000000000004,1740481172.299288,4.119996070861816,6.661338147750939e-15,1740481172.2992887,4.119996070861816,0.033280648047980366,1740481172.29929,4.119996070861816,0.0,1740481172.2992907,4.119996070861816,0.9667193519520267,1740481179.678342,11.499989032745361 -1740481172.3222828,4.13999605178833,2.665359000707424,1740481172.3222842,4.13999605178833,0.0,1740481172.3222866,4.13999605178833,0.0,1740481172.3222888,4.13999605178833,6.598797704611478,1740481172.3222897,4.13999605178833,0.0,1740481172.3222907,4.13999605178833,0.0,1740481172.3222916,4.13999605178833,0.0,1740481172.3222928,4.13999605178833,0.0,1740481172.3222935,4.13999605178833,0.9954782356702803,1740481172.3222942,4.13999605178833,0.0,1740481172.3222952,4.13999605178833,0.028758883718253525,1740481172.3222961,4.13999605178833,0.0,1740481172.3222969,4.13999605178833,0.9667193519520267,1740481179.6982167,11.519989013671875 -1740481172.3382654,4.159996032714844,2.771617677236139,1740481172.3382676,4.159996032714844,0.0,1740481172.3382707,4.159996032714844,0.017273507700469298,1740481172.338273,4.159996032714844,6.611702752244489,1740481172.338274,4.159996032714844,0.0,1740481172.3382754,4.159996032714844,0.0,1740481172.3382764,4.159996032714844,0.0,1740481172.3382773,4.159996032714844,0.0,1740481172.3382783,4.159996032714844,0.9954782356702803,1740481172.3382795,4.159996032714844,0.04521764329720179,1740481172.3382802,4.159996032714844,0.07715358982953618,1740481172.3382812,4.159996032714844,0.0,1740481172.3382819,4.159996032714844,0.964535121918298,1740481179.7186544,11.539988994598389 -1740481172.3598661,4.179996013641357,2.771617677236139,1740481172.359868,4.179996013641357,0.0,1740481172.3598707,4.179996013641357,0.017273507700469298,1740481172.3598728,4.179996013641357,6.611702752244489,1740481172.3598738,4.179996013641357,0.0,1740481172.359875,4.179996013641357,0.0,1740481172.3598762,4.179996013641357,0.0,1740481172.3598776,4.179996013641357,0.0,1740481172.3598783,4.179996013641357,0.9954782356702803,1740481172.3598795,4.179996013641357,0.04521764329720179,1740481172.3598804,4.179996013641357,0.07616075704918401,1740481172.3598814,4.179996013641357,0.0,1740481172.3598824,4.179996013641357,0.964535121918298,1740481179.7379985,11.559988975524902 -1740481172.3777785,4.199995994567871,2.771617677236139,1740481172.37778,4.199995994567871,0.0,1740481172.3777823,4.199995994567871,0.017273507700469298,1740481172.3777843,4.199995994567871,6.611702752244489,1740481172.3777854,4.199995994567871,0.0,1740481172.3777866,4.199995994567871,0.0,1740481172.3777876,4.199995994567871,0.0,1740481172.3777888,4.199995994567871,0.0,1740481172.3777895,4.199995994567871,0.9954782356702803,1740481172.3777905,4.199995994567871,0.04521764329720179,1740481172.3777914,4.199995994567871,0.07616075704918401,1740481172.3777924,4.199995994567871,0.0,1740481172.3777933,4.199995994567871,0.964535121918298,1740481179.7577453,11.579988956451416 -1740481172.398203,4.219995975494385,2.771617677236139,1740481172.3982043,4.219995975494385,0.0,1740481172.3982065,4.219995975494385,0.017273507700469298,1740481172.3982086,4.219995975494385,6.611702752244489,1740481172.3982098,4.219995975494385,0.0,1740481172.3982108,4.219995975494385,0.0,1740481172.398212,4.219995975494385,0.0,1740481172.398213,4.219995975494385,0.0,1740481172.3982139,4.219995975494385,0.9954782356702803,1740481172.3982148,4.219995975494385,0.04521764329720179,1740481172.3982158,4.219995975494385,0.07616075704918401,1740481172.3982167,4.219995975494385,0.0,1740481172.3982174,4.219995975494385,0.964535121918298,1740481179.7792456,11.59998893737793 -1740481172.422079,4.239995956420898,2.771617677236139,1740481172.4220808,4.239995956420898,0.0,1740481172.4220831,4.239995956420898,0.0,1740481172.4220848,4.239995956420898,6.700687921072735,1740481172.422086,4.239995956420898,0.0,1740481172.4220872,4.239995956420898,0.0,1740481172.4220881,4.239995956420898,0.0,1740481172.4220889,4.239995956420898,0.0,1740481172.42209,4.239995956420898,0.9948652261922886,1740481172.422091,4.239995956420898,0.0,1740481172.422092,4.239995956420898,0.03033010427399052,1740481172.422093,4.239995956420898,0.0,1740481172.4220939,4.239995956420898,0.964535121918298,1740481179.7989316,11.619988918304443 -1740481172.438392,4.259995937347412,2.771617677236139,1740481172.4384077,4.259995937347412,0.0,1740481172.4384115,4.259995937347412,0.0,1740481172.4384136,4.259995937347412,6.700687921072735,1740481172.4384146,4.259995937347412,0.0,1740481172.4384158,4.259995937347412,0.0,1740481172.4384172,4.259995937347412,0.0,1740481172.4384181,4.259995937347412,0.0,1740481172.4384189,4.259995937347412,0.9948652261922886,1740481172.4384203,4.259995937347412,0.0,1740481172.438421,4.259995937347412,0.03033010427399052,1740481172.438422,4.259995937347412,0.0,1740481172.4384227,4.259995937347412,0.964535121918298,1740481179.8181798,11.639988899230957 -1740481172.4597414,4.279995918273926,2.877816094627512,1740481172.4597447,4.279995918273926,0.0,1740481172.459748,4.279995918273926,0.01725308103054727,1740481172.4597504,4.279995918273926,6.7202324491408,1740481172.4597518,4.279995918273926,0.0,1740481172.4597535,4.279995918273926,0.0,1740481172.4597552,4.279995918273926,0.0,1740481172.4597566,4.279995918273926,0.0,1740481172.4597578,4.279995918273926,0.9948652261922886,1740481172.459759,4.279995918273926,0.05134773807711879,1740481172.4597604,4.279995918273926,0.08001133491807455,1740481172.4597614,4.279995918273926,0.0,1740481172.4597626,4.279995918273926,0.9656808454370569,1740481179.8385496,11.65998888015747 -1740481172.4780025,4.2999958992004395,2.877816094627512,1740481172.4780042,4.2999958992004395,0.0,1740481172.4780064,4.2999958992004395,0.01725308103054727,1740481172.4780083,4.2999958992004395,6.7202324491408,1740481172.4780095,4.2999958992004395,0.0,1740481172.4780107,4.2999958992004395,0.0,1740481172.4780116,4.2999958992004395,0.0,1740481172.4780126,4.2999958992004395,0.0,1740481172.4780135,4.2999958992004395,0.9948652261922886,1740481172.4780145,4.2999958992004395,0.05134773807711879,1740481172.4780152,4.2999958992004395,0.08053211883235045,1740481172.478016,4.2999958992004395,0.0,1740481172.478017,4.2999958992004395,0.9656808454370569,1740481179.8595586,11.679988861083984 -1740481172.4980793,4.319995880126953,2.877816094627512,1740481172.498081,4.319995880126953,0.0,1740481172.4980834,4.319995880126953,0.01725308103054727,1740481172.4980853,4.319995880126953,6.7202324491408,1740481172.4980865,4.319995880126953,0.0,1740481172.4980876,4.319995880126953,0.0,1740481172.4980886,4.319995880126953,0.0,1740481172.49809,4.319995880126953,0.0,1740481172.4980912,4.319995880126953,0.9948652261922886,1740481172.4980922,4.319995880126953,0.05134773807711879,1740481172.4980931,4.319995880126953,0.08053211883235045,1740481172.498094,4.319995880126953,0.0,1740481172.4980948,4.319995880126953,0.9656808454370569,1740481179.8806162,11.699988842010498 -1740481172.5227218,4.339995861053467,2.877816094627512,1740481172.5227234,4.339995861053467,0.0,1740481172.5227256,4.339995861053467,0.0,1740481172.5227275,4.339995861053467,6.8091777855016264,1740481172.5227284,4.339995861053467,0.0,1740481172.5227294,4.339995861053467,0.0,1740481172.5227306,4.339995861053467,0.0,1740481172.5227315,4.339995861053467,0.0,1740481172.5227325,4.339995861053467,0.9951916337948117,1740481172.5227332,4.339995861053467,0.0,1740481172.5227342,4.339995861053467,0.02951078835775478,1740481172.522735,4.339995861053467,0.0,1740481172.5227358,4.339995861053467,0.9656808454370569,1740481179.897898,11.719988822937012 -1740481172.5381398,4.3599958419799805,2.877816094627512,1740481172.5381417,4.3599958419799805,0.0,1740481172.538144,4.3599958419799805,0.0,1740481172.538146,4.3599958419799805,6.8091777855016264,1740481172.538147,4.3599958419799805,0.0,1740481172.5381482,4.3599958419799805,0.0,1740481172.538149,4.3599958419799805,0.0,1740481172.53815,4.3599958419799805,0.0,1740481172.538151,4.3599958419799805,0.9951916337948117,1740481172.5381517,4.3599958419799805,0.0,1740481172.5381527,4.3599958419799805,0.02951078835775478,1740481172.5381534,4.3599958419799805,0.0,1740481172.5381546,4.3599958419799805,0.9656808454370569,1740481179.9186335,11.739988803863525 -1740481172.5591023,4.379995822906494,2.9841005689551396,1740481172.559104,4.379995822906494,0.0,1740481172.5591059,4.379995822906494,0.017272727099963536,1740481172.5591078,4.379995822906494,6.827399090285288,1740481172.5591085,4.379995822906494,0.0,1740481172.5591102,4.379995822906494,0.0,1740481172.5591109,4.379995822906494,0.0,1740481172.5591123,4.379995822906494,0.0,1740481172.5591133,4.379995822906494,0.9951916337948117,1740481172.5591142,4.379995822906494,0.04808366205188763,1740481172.559115,4.379995822906494,0.07690457552499017,1740481172.5591161,4.379995822906494,0.0,1740481172.5591168,4.379995822906494,0.9661551342789061,1740481179.9389048,11.759988784790039 -1740481172.577849,4.399995803833008,2.9841005689551396,1740481172.5779047,4.399995803833008,0.0,1740481172.577908,4.399995803833008,0.017272727099963536,1740481172.57791,4.399995803833008,6.827399090285288,1740481172.5779111,4.399995803833008,0.0,1740481172.5779123,4.399995803833008,0.0,1740481172.5779133,4.399995803833008,0.0,1740481172.577915,4.399995803833008,0.0,1740481172.5779157,4.399995803833008,0.9951916337948117,1740481172.5779164,4.399995803833008,0.04808366205188763,1740481172.5779173,4.399995803833008,0.07712016156779322,1740481172.5779183,4.399995803833008,0.0,1740481172.5779192,4.399995803833008,0.9661551342789061,1740481179.9597578,11.779988765716553 -1740481172.5977962,4.4199957847595215,2.9841005689551396,1740481172.5977976,4.4199957847595215,0.0,1740481172.5977995,4.4199957847595215,0.017272727099963536,1740481172.5978014,4.4199957847595215,6.827399090285288,1740481172.5978024,4.4199957847595215,0.0,1740481172.597804,4.4199957847595215,0.0,1740481172.597805,4.4199957847595215,0.0,1740481172.597806,4.4199957847595215,0.0,1740481172.597807,4.4199957847595215,0.9951916337948117,1740481172.597808,4.4199957847595215,0.04808366205188763,1740481172.5978086,4.4199957847595215,0.07712016156779322,1740481172.5978096,4.4199957847595215,0.0,1740481172.5978105,4.4199957847595215,0.9661551342789061,1740481179.9777355,11.799988746643066 -1740481172.6223462,4.439995765686035,2.9841005689551396,1740481172.6223493,4.439995765686035,0.0,1740481172.6223526,4.439995765686035,0.0,1740481172.6223555,4.439995765686035,6.916410837512952,1740481172.6223564,4.439995765686035,0.0,1740481172.6223583,4.439995765686035,0.0,1740481172.6223593,4.439995765686035,0.0,1740481172.6223614,4.439995765686035,0.0,1740481172.622363,4.439995765686035,0.9953236181573983,1740481172.622365,4.439995765686035,0.0,1740481172.6223662,4.439995765686035,0.029168483878492246,1740481172.6223674,4.439995765686035,0.0,1740481172.6223686,4.439995765686035,0.9661551342789061,1740481179.998042,11.81998872756958 -1740481172.638083,4.459995746612549,2.9841005689551396,1740481172.638085,4.459995746612549,0.0,1740481172.6380873,4.459995746612549,0.0,1740481172.6380892,4.459995746612549,6.916410837512952,1740481172.6380901,4.459995746612549,0.0,1740481172.6380916,4.459995746612549,0.0,1740481172.6380923,4.459995746612549,0.0,1740481172.6380932,4.459995746612549,0.0,1740481172.6380942,4.459995746612549,0.9953236181573983,1740481172.6380951,4.459995746612549,0.0,1740481172.6380959,4.459995746612549,0.029168483878492246,1740481172.6380968,4.459995746612549,0.0,1740481172.6380978,4.459995746612549,0.9661551342789061,1740481191.5649443,23.339977741241455 -1740481172.6597524,4.4799957275390625,2.9841005689551396,1740481172.6597545,4.4799957275390625,0.0,1740481172.6597576,4.4799957275390625,0.0,1740481172.6597598,4.4799957275390625,6.916410837512952,1740481172.6597612,4.4799957275390625,0.0,1740481172.6597626,4.4799957275390625,0.0,1740481172.659764,4.4799957275390625,0.0,1740481172.6597652,4.4799957275390625,0.0,1740481172.6597662,4.4799957275390625,0.9953236181573983,1740481172.6597676,4.4799957275390625,0.0,1740481172.6597686,4.4799957275390625,0.029168483878492246,1740481172.6597695,4.4799957275390625,0.0,1740481172.6597707,4.4799957275390625,0.9661551342789061,1740481191.5876439,23.35997772216797 -1740481172.6784542,4.499995708465576,3.090455373258246,1740481172.678456,4.499995708465576,0.0,1740481172.6784582,4.499995708465576,0.017286448973999252,1740481172.6784601,4.499995708465576,6.934126875518829,1740481172.6784608,4.499995708465576,0.0,1740481172.6784623,4.499995708465576,0.0,1740481172.6784632,4.499995708465576,0.0,1740481172.6784642,4.499995708465576,0.0,1740481172.6784651,4.499995708465576,0.9953236181573983,1740481172.6784663,4.499995708465576,0.046763818426021064,1740481172.6784673,4.499995708465576,0.07561987382458214,1740481172.6784685,4.499995708465576,0.0,1740481172.6784694,4.499995708465576,0.966369928794845,1740481191.6032712,23.379977703094482 -1740481172.698065,4.51999568939209,3.090455373258246,1740481172.6980667,4.51999568939209,0.0,1740481172.6980686,4.51999568939209,0.017286448973999252,1740481172.6980708,4.51999568939209,6.934126875518829,1740481172.6980715,4.51999568939209,0.0,1740481172.698073,4.51999568939209,0.0,1740481172.6980739,4.51999568939209,0.0,1740481172.6980748,4.51999568939209,0.0,1740481172.698076,4.51999568939209,0.9953236181573983,1740481172.6980767,4.51999568939209,0.046763818426021064,1740481172.6980777,4.51999568939209,0.07571750778857445,1740481172.6980784,4.51999568939209,0.0,1740481172.6980796,4.51999568939209,0.966369928794845,1740481191.6233401,23.399977684020996 -1740481172.7221596,4.5399956703186035,3.090455373258246,1740481172.722162,4.5399956703186035,0.0,1740481172.7221642,4.5399956703186035,0.0,1740481172.7221663,4.5399956703186035,7.023195230847936,1740481172.7221675,4.5399956703186035,0.0,1740481172.722169,4.5399956703186035,0.0,1740481172.7221696,4.5399956703186035,0.0,1740481172.7221706,4.5399956703186035,0.0,1740481172.7221715,4.5399956703186035,0.9953827865881203,1740481172.7221727,4.5399956703186035,0.0,1740481172.7221735,4.5399956703186035,0.029012857793275337,1740481172.7221744,4.5399956703186035,0.0,1740481172.7221756,4.5399956703186035,0.966369928794845,1740481191.6448636,23.41997766494751 -1740481172.738831,4.559995651245117,3.090455373258246,1740481172.738833,4.559995651245117,0.0,1740481172.7388349,4.559995651245117,0.0,1740481172.738837,4.559995651245117,7.023195230847936,1740481172.7388382,4.559995651245117,0.0,1740481172.7388396,4.559995651245117,0.0,1740481172.7388406,4.559995651245117,0.0,1740481172.7388415,4.559995651245117,0.0,1740481172.7388427,4.559995651245117,0.9953827865881203,1740481172.7388437,4.559995651245117,0.0,1740481172.7388444,4.559995651245117,0.029012857793275337,1740481172.7388453,4.559995651245117,0.0,1740481172.7388463,4.559995651245117,0.966369928794845,1740481191.6643758,23.439977645874023 -1740481172.7595465,4.579995632171631,3.090455373258246,1740481172.7595487,4.579995632171631,0.0,1740481172.759551,4.579995632171631,0.0,1740481172.7595532,4.579995632171631,7.023195230847936,1740481172.7595544,4.579995632171631,0.0,1740481172.7595556,4.579995632171631,0.0,1740481172.7595568,4.579995632171631,0.0,1740481172.759558,4.579995632171631,0.0,1740481172.7595587,4.579995632171631,0.9953827865881203,1740481172.7595599,4.579995632171631,0.0,1740481172.759561,4.579995632171631,0.029012857793275337,1740481172.759562,4.579995632171631,0.0,1740481172.7595632,4.579995632171631,0.966369928794845,1740481191.6834335,23.459977626800537 -1740481172.7780385,4.5999956130981445,3.1967619488829992,1740481172.7780404,4.5999956130981445,0.0,1740481172.7780423,4.5999956130981445,0.017279637245229174,1740481172.7780442,4.5999956130981445,7.038841967901033,1740481172.7780452,4.5999956130981445,0.0,1740481172.7780464,4.5999956130981445,0.0,1740481172.7780476,4.5999956130981445,0.0,1740481172.7780488,4.5999956130981445,0.0,1740481172.7780495,4.5999956130981445,0.9953827865881203,1740481172.7780507,4.5999956130981445,0.0461721341188015,1740481172.7780516,4.5999956130981445,0.07637255604209527,1740481172.7780526,4.5999956130981445,0.0,1740481172.7780535,4.5999956130981445,0.9655534786987786,1740481191.7033026,23.47997760772705 -1740481172.7982173,4.619995594024658,3.1967619488829992,1740481172.7982192,4.619995594024658,0.0,1740481172.7982213,4.619995594024658,0.017279637245229174,1740481172.7982233,4.619995594024658,7.038841967901033,1740481172.7982244,4.619995594024658,0.0,1740481172.7982254,4.619995594024658,0.0,1740481172.7982264,4.619995594024658,0.0,1740481172.7982275,4.619995594024658,0.0,1740481172.7982285,4.619995594024658,0.9953827865881203,1740481172.7982295,4.619995594024658,0.0461721341188015,1740481172.7982304,4.619995594024658,0.07600144200814318,1740481172.7982314,4.619995594024658,0.0,1740481172.7982326,4.619995594024658,0.9655534786987786,1740481191.7243438,23.499977588653564 -1740481172.8203857,4.639995574951172,3.1967619488829992,1740481172.8203876,4.639995574951172,0.0,1740481172.8203897,4.639995574951172,0.0,1740481172.820392,4.639995574951172,7.127868906280557,1740481172.8203926,4.639995574951172,0.0,1740481172.820394,4.639995574951172,0.0,1740481172.820395,4.639995574951172,0.0,1740481172.8203957,4.639995574951172,0.0,1740481172.820397,4.639995574951172,0.9951558775322438,1740481172.8203976,4.639995574951172,0.0,1740481172.8203986,4.639995574951172,0.02960239883346516,1740481172.8203993,4.639995574951172,0.0,1740481172.8204005,4.639995574951172,0.9655534786987786,1740481191.7438195,23.519977569580078 -1740481172.8382857,4.6599955558776855,3.1967619488829992,1740481172.8382874,4.6599955558776855,0.0,1740481172.8382895,4.6599955558776855,0.0,1740481172.8382916,4.6599955558776855,7.127868906280557,1740481172.838293,4.6599955558776855,0.0,1740481172.8382943,4.6599955558776855,0.0,1740481172.8382952,4.6599955558776855,0.0,1740481172.8382964,4.6599955558776855,0.0,1740481172.8382971,4.6599955558776855,0.9951558775322438,1740481172.8382983,4.6599955558776855,0.0,1740481172.838299,4.6599955558776855,0.02960239883346516,1740481172.8383,4.6599955558776855,0.0,1740481172.838301,4.6599955558776855,0.9655534786987786,1740481191.7666519,23.539977550506592 -1740481172.859802,4.679995536804199,3.1967619488829992,1740481172.8598077,4.679995536804199,0.0,1740481172.8598151,4.679995536804199,0.0,1740481172.8598185,4.679995536804199,7.127868906280557,1740481172.8598208,4.679995536804199,0.0,1740481172.8598235,4.679995536804199,0.0,1740481172.859825,4.679995536804199,0.0,1740481172.8598268,4.679995536804199,0.0,1740481172.859829,4.679995536804199,0.9951558775322438,1740481172.859831,4.679995536804199,0.0,1740481172.8598323,4.679995536804199,0.02960239883346516,1740481172.8598337,4.679995536804199,0.0,1740481172.8598351,4.679995536804199,0.9655534786987786,1740481191.7835014,23.559977531433105 -1740481172.8778296,4.699995517730713,3.1967619488829992,1740481172.8778312,4.699995517730713,0.0,1740481172.8778334,4.699995517730713,0.0,1740481172.8778355,4.699995517730713,7.127868906280557,1740481172.8778365,4.699995517730713,0.0,1740481172.8778377,4.699995517730713,0.0,1740481172.8778386,4.699995517730713,0.0,1740481172.8778396,4.699995517730713,0.0,1740481172.8778403,4.699995517730713,0.9951558775322438,1740481172.8778415,4.699995517730713,0.0,1740481172.8778422,4.699995517730713,0.02960239883346516,1740481172.877843,4.699995517730713,0.0,1740481172.8778436,4.699995517730713,0.9655534786987786,1740481191.8037152,23.57997751235962 -1740481172.8982215,4.719995498657227,3.3029772034922757,1740481172.8982234,4.719995498657227,0.0,1740481172.8982463,4.719995498657227,0.017260857730786845,1740481172.8982487,4.719995498657227,7.14269631916025,1740481172.8982496,4.719995498657227,0.0,1740481172.898251,4.719995498657227,0.0,1740481172.898252,4.719995498657227,0.0,1740481172.898253,4.719995498657227,0.0,1740481172.898254,4.719995498657227,0.9951558775322438,1740481172.8982735,4.719995498657227,0.04844122467756673,1740481172.8982747,4.719995498657227,0.07981340211198937,1740481172.8982754,4.719995498657227,0.0,1740481172.8982763,4.719995498657227,0.9643367562732322,1740481191.8236918,23.599977493286133 -1740481172.9224331,4.73999547958374,3.3029772034922757,1740481172.9224353,4.73999547958374,0.0,1740481172.922438,4.73999547958374,0.0,1740481172.9224405,4.73999547958374,7.23165071603874,1740481172.9224415,4.73999547958374,0.0,1740481172.922443,4.73999547958374,0.0,1740481172.9224443,4.73999547958374,0.0,1740481172.9224453,4.73999547958374,0.0,1740481172.9224463,4.73999547958374,0.9948076249069352,1740481172.9224477,4.73999547958374,0.0,1740481172.9224486,4.73999547958374,0.030470868633702963,1740481172.9224494,4.73999547958374,0.0,1740481172.9224505,4.73999547958374,0.9643367562732322,1740481191.8445492,23.619977474212646 -1740481172.9379456,4.759995460510254,3.3029772034922757,1740481172.937947,4.759995460510254,0.0,1740481172.9379492,4.759995460510254,0.0,1740481172.9379513,4.759995460510254,7.23165071603874,1740481172.9379523,4.759995460510254,0.0,1740481172.9379532,4.759995460510254,0.0,1740481172.9379542,4.759995460510254,0.0,1740481172.9379554,4.759995460510254,0.0,1740481172.937956,4.759995460510254,0.9948076249069352,1740481172.9379568,4.759995460510254,0.0,1740481172.9379575,4.759995460510254,0.030470868633702963,1740481172.9379587,4.759995460510254,0.0,1740481172.9379594,4.759995460510254,0.9643367562732322,1740481191.8654392,23.63997745513916 -1740481172.960434,4.779995441436768,3.3029772034922757,1740481172.9604356,4.779995441436768,0.0,1740481172.960438,4.779995441436768,0.0,1740481172.9604402,4.779995441436768,7.23165071603874,1740481172.960441,4.779995441436768,0.0,1740481172.9604423,4.779995441436768,0.0,1740481172.9604435,4.779995441436768,0.0,1740481172.9604445,4.779995441436768,0.0,1740481172.9604454,4.779995441436768,0.9948076249069352,1740481172.9604461,4.779995441436768,0.0,1740481172.9604473,4.779995441436768,0.030470868633702963,1740481172.960448,4.779995441436768,0.0,1740481172.960449,4.779995441436768,0.9643367562732322,1740481191.8839915,23.659977436065674 -1740481172.9778142,4.799995422363281,3.3029772034922757,1740481172.977816,4.799995422363281,0.0,1740481172.9778187,4.799995422363281,0.0,1740481172.9778206,4.799995422363281,7.23165071603874,1740481172.9778216,4.799995422363281,0.0,1740481172.977823,4.799995422363281,0.0,1740481172.977824,4.799995422363281,0.0,1740481172.977825,4.799995422363281,0.0,1740481172.977826,4.799995422363281,0.9948076249069352,1740481172.977827,4.799995422363281,0.0,1740481172.9778278,4.799995422363281,0.030470868633702963,1740481172.977829,4.799995422363281,0.0,1740481172.9778302,4.799995422363281,0.9643367562732322,1740481191.9037452,23.679977416992188 -1740481172.9984632,4.819995403289795,3.409023071746164,1740481172.9984653,4.819995403289795,0.0,1740481172.99848,4.819995403289795,0.017227300279931405,1740481172.9984841,4.819995403289795,7.245875525216614,1740481172.9984853,4.819995403289795,0.0,1740481172.9984865,4.819995403289795,0.0,1740481172.9984875,4.819995403289795,0.0,1740481172.9984887,4.819995403289795,0.0,1740481172.9984896,4.819995403289795,0.9948076249069352,1740481172.9984906,4.819995403289795,0.05192375093060919,1740481172.9984913,4.819995403289795,0.08457825010749043,1740481172.9984925,4.819995403289795,0.0,1740481172.9984932,4.819995403289795,0.9628355107222036,1740481191.9240415,23.6999773979187 -1740481173.0219676,4.839995384216309,3.409023071746164,1740481173.0219696,4.839995384216309,0.0,1740481173.021972,4.839995384216309,0.0,1740481173.021974,4.839995384216309,7.3346940931905715,1740481173.0219753,4.839995384216309,0.0,1740481173.0219762,4.839995384216309,0.0,1740481173.0219774,4.839995384216309,0.0,1740481173.0219784,4.839995384216309,0.0,1740481173.0219793,4.839995384216309,0.9943612776197635,1740481173.0219805,4.839995384216309,0.0,1740481173.0219812,4.839995384216309,0.031525766897559815,1740481173.0219822,4.839995384216309,0.0,1740481173.021983,4.839995384216309,0.9628355107222036,1740481191.9437718,23.719977378845215 -1740481173.0382502,4.859995365142822,3.409023071746164,1740481173.0382524,4.859995365142822,0.0,1740481173.0382545,4.859995365142822,0.0,1740481173.0382566,4.859995365142822,7.3346940931905715,1740481173.0382576,4.859995365142822,0.0,1740481173.038259,4.859995365142822,0.0,1740481173.03826,4.859995365142822,0.0,1740481173.038261,4.859995365142822,0.0,1740481173.0382617,4.859995365142822,0.9943612776197635,1740481173.038263,4.859995365142822,0.0,1740481173.0382638,4.859995365142822,0.031525766897559815,1740481173.0382648,4.859995365142822,0.0,1740481173.0382657,4.859995365142822,0.9628355107222036,1740481191.9643826,23.73997735977173 -1740481173.0589054,4.879995346069336,3.409023071746164,1740481173.0589087,4.879995346069336,0.0,1740481173.0589125,4.879995346069336,0.0,1740481173.058915,4.879995346069336,7.3346940931905715,1740481173.0589159,4.879995346069336,0.0,1740481173.058917,4.879995346069336,0.0,1740481173.0589182,4.879995346069336,0.0,1740481173.0589192,4.879995346069336,0.0,1740481173.0589201,4.879995346069336,0.9943612776197635,1740481173.0589209,4.879995346069336,0.0,1740481173.058922,4.879995346069336,0.031525766897559815,1740481173.0589228,4.879995346069336,0.0,1740481173.0589237,4.879995346069336,0.9628355107222036,1740481191.9853327,23.759977340698242 -1740481173.0802686,4.89999532699585,3.409023071746164,1740481173.0802717,4.89999532699585,0.0,1740481173.080275,4.89999532699585,0.0,1740481173.0802774,4.89999532699585,7.3346940931905715,1740481173.0802786,4.89999532699585,0.0,1740481173.08028,4.89999532699585,0.0,1740481173.0802813,4.89999532699585,0.0,1740481173.0802824,4.89999532699585,0.0,1740481173.0802836,4.89999532699585,0.9943612776197635,1740481173.0802846,4.89999532699585,0.0,1740481173.0802858,4.89999532699585,0.031525766897559815,1740481173.0802867,4.89999532699585,0.0,1740481173.0802877,4.89999532699585,0.9628355107222036,1740481192.003502,23.779977321624756 -1740481173.098422,4.919995307922363,3.409023071746164,1740481173.0984244,4.919995307922363,0.0,1740481173.098427,4.919995307922363,0.0,1740481173.0984297,4.919995307922363,7.3346940931905715,1740481173.0984316,4.919995307922363,0.0,1740481173.0984335,4.919995307922363,0.0,1740481173.098435,4.919995307922363,0.0,1740481173.0984507,4.919995307922363,0.0,1740481173.0984526,4.919995307922363,0.9943612776197635,1740481173.0984538,4.919995307922363,0.0,1740481173.0984552,4.919995307922363,0.031525766897559815,1740481173.0984564,4.919995307922363,0.0,1740481173.0984576,4.919995307922363,0.9628355107222036,1740481192.0238292,23.79997730255127 -1740481173.1206872,4.939995288848877,3.514935739273505,1740481173.1206892,4.939995288848877,0.0,1740481173.1207032,4.939995288848877,0.0,1740481173.120706,4.939995288848877,7.438094766817164,1740481173.1207068,4.939995288848877,0.0,1740481173.120708,4.939995288848877,0.0,1740481173.1207092,4.939995288848877,0.0,1740481173.12071,4.939995288848877,0.0,1740481173.1207108,4.939995288848877,0.9939737091516396,1740481173.1207116,4.939995288848877,0.06026290848356486,1740481173.1207128,4.939995288848877,0.0930518444590335,1740481173.1207135,4.939995288848877,0.0,1740481173.1207147,4.939995288848877,0.9615795137718296,1740481192.0438447,23.819977283477783 -1740481173.1380413,4.959995269775391,3.514935739273505,1740481173.1380432,4.959995269775391,0.0,1740481173.1380455,4.959995269775391,0.0,1740481173.1380475,4.959995269775391,7.438094766817164,1740481173.1380484,4.959995269775391,0.0,1740481173.1380498,4.959995269775391,0.0,1740481173.1380508,4.959995269775391,0.0,1740481173.1380517,4.959995269775391,0.0,1740481173.1380527,4.959995269775391,0.9939737091516396,1740481173.1380541,4.959995269775391,0.06026290848356486,1740481173.1380548,4.959995269775391,0.09265710386337489,1740481173.138056,4.959995269775391,0.0,1740481173.1380568,4.959995269775391,0.9615795137718296,1740481192.0679011,23.839977264404297 -1740481173.1597822,4.979995250701904,3.514935739273505,1740481173.1597865,4.979995250701904,0.0,1740481173.1597915,4.979995250701904,0.0,1740481173.1597943,4.979995250701904,7.438094766817164,1740481173.1597965,4.979995250701904,0.0,1740481173.159799,4.979995250701904,0.0,1740481173.1598005,4.979995250701904,0.0,1740481173.159803,4.979995250701904,0.0,1740481173.1598043,4.979995250701904,0.9939737091516396,1740481173.159806,4.979995250701904,0.06026290848356486,1740481173.159807,4.979995250701904,0.09265710386337489,1740481173.1598084,4.979995250701904,0.0,1740481173.15981,4.979995250701904,0.9615795137718296,1740481192.0840387,23.85997724533081 -1740481173.1814733,4.999995231628418,3.514935739273505,1740481173.1814997,4.999995231628418,0.0,1740481173.1815026,4.999995231628418,0.0,1740481173.1815047,4.999995231628418,7.438094766817164,1740481173.1815062,4.999995231628418,0.0,1740481173.1815073,4.999995231628418,0.0,1740481173.1815274,4.999995231628418,0.0,1740481173.1815283,4.999995231628418,0.0,1740481173.181529,4.999995231628418,0.9939737091516396,1740481173.1815305,4.999995231628418,0.06026290848356486,1740481173.1815314,4.999995231628418,0.09265710386337489,1740481173.1815326,4.999995231628418,0.0,1740481173.181534,4.999995231628418,0.9615795137718296,1740481192.103669,23.879977226257324 -1740481173.1989486,5.019995212554932,3.514935739273505,1740481173.19895,5.019995212554932,0.0,1740481173.1989524,5.019995212554932,0.0,1740481173.1989546,5.019995212554932,7.438094766817164,1740481173.1989558,5.019995212554932,0.0,1740481173.1989567,5.019995212554932,0.0,1740481173.198958,5.019995212554932,0.0,1740481173.198959,5.019995212554932,0.0,1740481173.19896,5.019995212554932,0.9939737091516396,1740481173.1989608,5.019995212554932,0.06026290848356486,1740481173.198962,5.019995212554932,0.09265710386337489,1740481173.1989627,5.019995212554932,0.0,1740481173.1989634,5.019995212554932,0.9615795137718296,1740481192.1238554,23.899977207183838 -1740481173.2210166,5.039995193481445,3.6208431355408974,1740481173.2210183,5.039995193481445,0.0,1740481173.2210207,5.039995193481445,0.0,1740481173.2210226,5.039995193481445,7.55054980561302,1740481173.2210238,5.039995193481445,0.0,1740481173.2210248,5.039995193481445,0.0,1740481173.2210257,5.039995193481445,0.0,1740481173.2210267,5.039995193481445,0.0,1740481173.2210276,5.039995193481445,0.9949569576205534,1740481173.2210283,5.039995193481445,0.050430423794470824,1740481173.221029,5.039995193481445,0.07949287593360845,1740481173.22103,5.039995193481445,0.0,1740481173.221031,5.039995193481445,0.9648533350360611,1740481192.1439013,23.91997718811035 -1740481173.2380831,5.059995174407959,3.6208431355408974,1740481173.2380853,5.059995174407959,0.0,1740481173.2380881,5.059995174407959,0.0,1740481173.2380903,5.059995174407959,7.55054980561302,1740481173.2380912,5.059995174407959,0.0,1740481173.238093,5.059995174407959,0.0,1740481173.2380939,5.059995174407959,0.0,1740481173.2380948,5.059995174407959,0.0,1740481173.2380958,5.059995174407959,0.9949569576205534,1740481173.2380972,5.059995174407959,0.050430423794470824,1740481173.238098,5.059995174407959,0.08053404637896311,1740481173.2380989,5.059995174407959,0.0,1740481173.2380998,5.059995174407959,0.9648533350360611,1740481192.163591,23.939977169036865 -1740481173.2585278,5.079995155334473,3.6208431355408974,1740481173.2585294,5.079995155334473,0.0,1740481173.2585323,5.079995155334473,0.0,1740481173.2585342,5.079995155334473,7.55054980561302,1740481173.2585351,5.079995155334473,0.0,1740481173.2585363,5.079995155334473,0.0,1740481173.2585375,5.079995155334473,0.0,1740481173.2585385,5.079995155334473,0.0,1740481173.2585392,5.079995155334473,0.9949569576205534,1740481173.2585404,5.079995155334473,0.050430423794470824,1740481173.2585413,5.079995155334473,0.08053404637896311,1740481173.258542,5.079995155334473,0.0,1740481173.258543,5.079995155334473,0.9648533350360611,1740481192.18338,23.95997714996338 -1740481173.2777312,5.099995136260986,3.6208431355408974,1740481173.2777328,5.099995136260986,0.0,1740481173.277735,5.099995136260986,0.0,1740481173.277737,5.099995136260986,7.55054980561302,1740481173.2777376,5.099995136260986,0.0,1740481173.2777393,5.099995136260986,0.0,1740481173.2777402,5.099995136260986,0.0,1740481173.2777412,5.099995136260986,0.0,1740481173.2777424,5.099995136260986,0.9949569576205534,1740481173.2777436,5.099995136260986,0.050430423794470824,1740481173.2777443,5.099995136260986,0.08053404637896311,1740481173.2777452,5.099995136260986,0.0,1740481173.2777462,5.099995136260986,0.9648533350360611,1740481192.2041864,23.979977130889893 -1740481173.2979534,5.1199951171875,3.6208431355408974,1740481173.297955,5.1199951171875,0.0,1740481173.2979572,5.1199951171875,0.0,1740481173.297959,5.1199951171875,7.55054980561302,1740481173.2979603,5.1199951171875,0.0,1740481173.2979615,5.1199951171875,0.0,1740481173.2979624,5.1199951171875,0.0,1740481173.2979636,5.1199951171875,0.0,1740481173.2979643,5.1199951171875,0.9949569576205534,1740481173.2979653,5.1199951171875,0.050430423794470824,1740481173.2979662,5.1199951171875,0.08053404637896311,1740481173.2979672,5.1199951171875,0.0,1740481173.2979684,5.1199951171875,0.9648533350360611,1740481192.2232993,23.999977111816406 -1740481173.3230207,5.139995098114014,3.6208431355408974,1740481173.3230228,5.139995098114014,0.0,1740481173.3230252,5.139995098114014,0.0,1740481173.3230271,5.139995098114014,7.55054980561302,1740481173.3230278,5.139995098114014,0.0,1740481173.3230293,5.139995098114014,0.0,1740481173.3230302,5.139995098114014,0.0,1740481173.323031,5.139995098114014,0.0,1740481173.3230321,5.139995098114014,0.9949569576205534,1740481173.323033,5.139995098114014,0.050430423794470824,1740481173.3230338,5.139995098114014,0.08053404637896311,1740481173.3230348,5.139995098114014,0.0,1740481173.3230357,5.139995098114014,0.9648533350360611,1740481192.245339,24.01997709274292 -1740481173.3392768,5.159995079040527,3.72710116833111,1740481173.3392794,5.159995079040527,0.0,1740481173.3392823,5.159995079040527,0.01726435790787523,1740481173.3392847,5.159995079040527,7.57281133529811,1740481173.3392863,5.159995079040527,0.0,1740481173.3392878,5.159995079040527,0.0,1740481173.33929,5.159995079040527,0.0,1740481173.3392913,5.159995079040527,0.0,1740481173.3392928,5.159995079040527,1.0000000000000004,1740481173.339294,5.159995079040527,6.661338147750939e-15,1740481173.339295,5.159995079040527,0.03380465131053155,1740481173.3392963,5.159995079040527,0.0,1740481173.3392975,5.159995079040527,0.9673519209246686,1740481192.2670984,24.039977073669434 -1740481173.359935,5.179995059967041,3.72710116833111,1740481173.359937,5.179995059967041,0.0,1740481173.359939,5.179995059967041,0.01726435790787523,1740481173.359941,5.179995059967041,7.57281133529811,1740481173.3599422,5.179995059967041,0.0,1740481173.3599434,5.179995059967041,0.0,1740481173.3599443,5.179995059967041,0.0,1740481173.3599458,5.179995059967041,0.0,1740481173.3599465,5.179995059967041,1.0000000000000004,1740481173.3599477,5.179995059967041,6.661338147750939e-15,1740481173.3599489,5.179995059967041,0.03264807907533851,1740481173.3599498,5.179995059967041,0.0,1740481173.3599505,5.179995059967041,0.9673519209246686,1740481192.2861705,24.059977054595947 -1740481173.3788435,5.199995040893555,3.72710116833111,1740481173.3788457,5.199995040893555,0.0,1740481173.3788478,5.199995040893555,0.01726435790787523,1740481173.3788495,5.199995040893555,7.57281133529811,1740481173.3788505,5.199995040893555,0.0,1740481173.3788521,5.199995040893555,0.0,1740481173.378853,5.199995040893555,0.0,1740481173.3788538,5.199995040893555,0.0,1740481173.378855,5.199995040893555,1.0000000000000004,1740481173.378856,5.199995040893555,6.661338147750939e-15,1740481173.3788567,5.199995040893555,0.03264807907533851,1740481173.3788576,5.199995040893555,0.0,1740481173.3788586,5.199995040893555,0.9673519209246686,1740481192.303963,24.069977045059204 -1740481173.3989487,5.219995021820068,3.72710116833111,1740481173.3989503,5.219995021820068,0.0,1740481173.3989527,5.219995021820068,0.01726435790787523,1740481173.3989549,5.219995021820068,7.57281133529811,1740481173.3989558,5.219995021820068,0.0,1740481173.398957,5.219995021820068,0.0,1740481173.398958,5.219995021820068,0.0,1740481173.3989592,5.219995021820068,0.0,1740481173.39896,5.219995021820068,1.0000000000000004,1740481173.398961,5.219995021820068,6.661338147750939e-15,1740481173.398962,5.219995021820068,0.03264807907533851,1740481173.398963,5.219995021820068,0.0,1740481173.398964,5.219995021820068,0.9673519209246686,1740481192.3240693,24.099977016448975 -1740481173.420625,5.239995002746582,3.72710116833111,1740481173.4206266,5.239995002746582,0.0,1740481173.4206288,5.239995002746582,0.0,1740481173.4206307,5.239995002746582,7.661805010180448,1740481173.420632,5.239995002746582,0.0,1740481173.420633,5.239995002746582,0.0,1740481173.420634,5.239995002746582,0.0,1740481173.420635,5.239995002746582,0.0,1740481173.420636,5.239995002746582,0.9956484934446073,1740481173.420637,5.239995002746582,0.0,1740481173.4206376,5.239995002746582,0.028296572519938668,1740481173.4206388,5.239995002746582,0.0,1740481173.4206395,5.239995002746582,0.9673519209246686,1740481192.34381,24.11997699737549 -1740481173.438003,5.259994983673096,3.8334215041811595,1740481173.438005,5.259994983673096,0.0,1740481173.438007,5.259994983673096,0.01728648711814532,1740481173.438009,5.259994983673096,7.674416686663481,1740481173.4380102,5.259994983673096,0.0,1740481173.4380116,5.259994983673096,0.0,1740481173.4380126,5.259994983673096,0.0,1740481173.4380138,5.259994983673096,0.0,1740481173.4380147,5.259994983673096,0.9956484934446073,1740481173.4380155,5.259994983673096,0.04351506555388851,1740481173.4380164,5.259994983673096,0.07521150136714767,1740481173.4380174,5.259994983673096,0.0,1740481173.4380183,5.259994983673096,0.9650145156071125,1740481192.3640895,24.139976978302002 -1740481173.4616091,5.279994964599609,3.8334215041811595,1740481173.4616113,5.279994964599609,0.0,1740481173.4616134,5.279994964599609,0.01728648711814532,1740481173.4616153,5.279994964599609,7.674416686663481,1740481173.4616163,5.279994964599609,0.0,1740481173.4616177,5.279994964599609,0.0,1740481173.4616184,5.279994964599609,0.0,1740481173.4616194,5.279994964599609,0.0,1740481173.4616203,5.279994964599609,0.9956484934446073,1740481173.4616213,5.279994964599609,0.04351506555388851,1740481173.4616222,5.279994964599609,0.07414904339138328,1740481173.461623,5.279994964599609,0.0,1740481173.4616241,5.279994964599609,0.9650145156071125,1740481192.3851004,24.159976959228516 -1740481173.478058,5.299994945526123,3.8334215041811595,1740481173.4780598,5.299994945526123,0.0,1740481173.478062,5.299994945526123,0.01728648711814532,1740481173.478064,5.299994945526123,7.674416686663481,1740481173.478065,5.299994945526123,0.0,1740481173.4780662,5.299994945526123,0.0,1740481173.4780672,5.299994945526123,0.0,1740481173.478068,5.299994945526123,0.0,1740481173.4780693,5.299994945526123,0.9956484934446073,1740481173.4780703,5.299994945526123,0.04351506555388851,1740481173.4780712,5.299994945526123,0.07414904339138328,1740481173.4780722,5.299994945526123,0.0,1740481173.4780731,5.299994945526123,0.9650145156071125,1740481192.4032323,24.17997694015503 -1740481173.4979413,5.319994926452637,3.8334215041811595,1740481173.497943,5.319994926452637,0.0,1740481173.497945,5.319994926452637,0.01728648711814532,1740481173.4979475,5.319994926452637,7.674416686663481,1740481173.4979484,5.319994926452637,0.0,1740481173.4979496,5.319994926452637,0.0,1740481173.4979508,5.319994926452637,0.0,1740481173.4979517,5.319994926452637,0.0,1740481173.4979525,5.319994926452637,0.9956484934446073,1740481173.497954,5.319994926452637,0.04351506555388851,1740481173.4979546,5.319994926452637,0.07414904339138328,1740481173.4979556,5.319994926452637,0.0,1740481173.4979563,5.319994926452637,0.9650145156071125,1740481192.4237187,24.199976921081543 -1740481173.5223212,5.33999490737915,3.8334215041811595,1740481173.5223231,5.33999490737915,0.0,1740481173.5223253,5.33999490737915,0.0,1740481173.5223272,5.33999490737915,7.763450535395385,1740481173.5223284,5.33999490737915,0.0,1740481173.5223296,5.33999490737915,0.0,1740481173.5223303,5.33999490737915,0.0,1740481173.5223315,5.33999490737915,0.0,1740481173.5223322,5.33999490737915,0.9950031057618799,1740481173.5223331,5.33999490737915,0.0,1740481173.522334,5.33999490737915,0.029988590154767403,1740481173.522335,5.33999490737915,0.0,1740481173.5223358,5.33999490737915,0.9650145156071125,1740481192.4434695,24.219976902008057 -1740481173.538514,5.359994888305664,3.8334215041811595,1740481173.5385158,5.359994888305664,0.0,1740481173.538518,5.359994888305664,0.0,1740481173.53852,5.359994888305664,7.763450535395385,1740481173.5385208,5.359994888305664,0.0,1740481173.538522,5.359994888305664,0.0,1740481173.5385232,5.359994888305664,0.0,1740481173.5385242,5.359994888305664,0.0,1740481173.5385249,5.359994888305664,0.9950031057618799,1740481173.538526,5.359994888305664,0.0,1740481173.5385268,5.359994888305664,0.029988590154767403,1740481173.5385275,5.359994888305664,0.0,1740481173.5385284,5.359994888305664,0.9650145156071125,1740481192.4635134,24.23997688293457 -1740481173.55801,5.379994869232178,3.939661729988151,1740481173.5580125,5.379994869232178,0.0,1740481173.5580144,5.379994869232178,0.017262265326278118,1740481173.5580165,5.379994869232178,7.7826254681800044,1740481173.5580173,5.379994869232178,0.0,1740481173.5580184,5.379994869232178,0.0,1740481173.5580196,5.379994869232178,0.0,1740481173.5580204,5.379994869232178,0.0,1740481173.5580213,5.379994869232178,0.9950031057618799,1740481173.5580223,5.379994869232178,0.04996894238120553,1740481173.5580232,5.379994869232178,0.0785665012426188,1740481173.558024,5.379994869232178,0.0,1740481173.5580246,5.379994869232178,0.9659708493362835,1740481192.4833856,24.259976863861084 -1740481173.5798314,5.399994850158691,3.939661729988151,1740481173.579855,5.399994850158691,0.0,1740481173.5798597,5.399994850158691,0.017262265326278118,1740481173.579862,5.399994850158691,7.7826254681800044,1740481173.5798633,5.399994850158691,0.0,1740481173.5798645,5.399994850158691,0.0,1740481173.5798657,5.399994850158691,0.0,1740481173.5798666,5.399994850158691,0.0,1740481173.5798676,5.399994850158691,0.9950031057618799,1740481173.5798686,5.399994850158691,0.04996894238120553,1740481173.5798702,5.399994850158691,0.0790011988068019,1740481173.5798714,5.399994850158691,0.0,1740481173.5798738,5.399994850158691,0.9659708493362835,1740481192.5043118,24.279976844787598 -1740481173.5983834,5.419994831085205,3.939661729988151,1740481173.5983853,5.419994831085205,0.0,1740481173.5983875,5.419994831085205,0.017262265326278118,1740481173.5983894,5.419994831085205,7.7826254681800044,1740481173.5983906,5.419994831085205,0.0,1740481173.5983918,5.419994831085205,0.0,1740481173.5983927,5.419994831085205,0.0,1740481173.598394,5.419994831085205,0.0,1740481173.5983946,5.419994831085205,0.9950031057618799,1740481173.5983958,5.419994831085205,0.04996894238120553,1740481173.5983968,5.419994831085205,0.0790011988068019,1740481173.5983975,5.419994831085205,0.0,1740481173.5983984,5.419994831085205,0.9659708493362835,1740481192.5234537,24.29997682571411 -1740481173.6204135,5.439994812011719,3.939661729988151,1740481173.6204152,5.439994812011719,0.0,1740481173.6204176,5.439994812011719,0.0,1740481173.6204195,5.439994812011719,7.871603428660718,1740481173.6204205,5.439994812011719,0.0,1740481173.6204216,5.439994812011719,0.0,1740481173.6204224,5.439994812011719,0.0,1740481173.6204233,5.439994812011719,0.0,1740481173.6204243,5.439994812011719,0.9952725538112371,1740481173.6204252,5.439994812011719,0.0,1740481173.620426,5.439994812011719,0.029301704474953616,1740481173.6204267,5.439994812011719,0.0,1740481173.6204278,5.439994812011719,0.9659708493362835,1740481192.544881,24.319976806640625 -1740481173.6384158,5.459994792938232,3.939661729988151,1740481173.638418,5.459994792938232,0.0,1740481173.6384199,5.459994792938232,0.0,1740481173.638422,5.459994792938232,7.871603428660718,1740481173.638423,5.459994792938232,0.0,1740481173.6384244,5.459994792938232,0.0,1740481173.6384254,5.459994792938232,0.0,1740481173.6384263,5.459994792938232,0.0,1740481173.638427,5.459994792938232,0.9952725538112371,1740481173.6384282,5.459994792938232,0.0,1740481173.638429,5.459994792938232,0.029301704474953616,1740481173.6384296,5.459994792938232,0.0,1740481173.6384308,5.459994792938232,0.9659708493362835,1740481192.5671046,24.33997678756714 -1740481173.6585631,5.479994773864746,4.0459564204475225,1740481173.6585653,5.479994773864746,0.0,1740481173.6585672,5.479994773864746,0.017275791963083653,1740481173.658569,5.479994773864746,7.888602131522243,1740481173.6585863,5.479994773864746,0.0,1740481173.6585877,5.479994773864746,0.0,1740481173.6585886,5.479994773864746,0.0,1740481173.6585898,5.479994773864746,0.0,1740481173.6585908,5.479994773864746,0.9952725538112371,1740481173.6585917,5.479994773864746,0.04727446188758977,1740481173.6585927,5.479994773864746,0.07677768576918884,1740481173.658594,5.479994773864746,0.0,1740481173.6585948,5.479994773864746,0.9658323047855043,1740481192.5836554,24.359976768493652 -1740481173.6781647,5.49999475479126,4.0459564204475225,1740481173.6781664,5.49999475479126,0.0,1740481173.6781683,5.49999475479126,0.017275791963083653,1740481173.6781986,5.49999475479126,7.888602131522243,1740481173.6781993,5.49999475479126,0.0,1740481173.6782005,5.49999475479126,0.0,1740481173.6782017,5.49999475479126,0.0,1740481173.6782029,5.49999475479126,0.0,1740481173.6782038,5.49999475479126,0.9952725538112371,1740481173.6782048,5.49999475479126,0.04727446188758977,1740481173.6782057,5.49999475479126,0.0767147109133226,1740481173.6782067,5.49999475479126,0.0,1740481173.6782074,5.49999475479126,0.9658323047855043,1740481192.6033964,24.379976749420166 -1740481173.6984293,5.519994735717773,4.0459564204475225,1740481173.6984313,5.519994735717773,0.0,1740481173.6984334,5.519994735717773,0.017275791963083653,1740481173.6984353,5.519994735717773,7.888602131522243,1740481173.698437,5.519994735717773,0.0,1740481173.698438,5.519994735717773,0.0,1740481173.698439,5.519994735717773,0.0,1740481173.6984398,5.519994735717773,0.0,1740481173.698441,5.519994735717773,0.9952725538112371,1740481173.698442,5.519994735717773,0.04727446188758977,1740481173.6984427,5.519994735717773,0.0767147109133226,1740481173.698444,5.519994735717773,0.0,1740481173.6984446,5.519994735717773,0.9658323047855043,1740481192.6270502,24.39997673034668 -1740481173.721283,5.539994716644287,4.0459564204475225,1740481173.721285,5.539994716644287,0.0,1740481173.7212877,5.539994716644287,0.0,1740481173.7212896,5.539994716644287,7.977621030018531,1740481173.7212908,5.539994716644287,0.0,1740481173.7212923,5.539994716644287,0.0,1740481173.7212934,5.539994716644287,0.0,1740481173.7212954,5.539994716644287,0.0,1740481173.7212963,5.539994716644287,0.9952339812823865,1740481173.7212975,5.539994716644287,0.0,1740481173.7212985,5.539994716644287,0.02940167649688219,1740481173.7212996,5.539994716644287,0.0,1740481173.721301,5.539994716644287,0.9658323047855043,1740481192.6460357,24.419976711273193 -1740481173.7384903,5.559994697570801,4.0459564204475225,1740481173.7384923,5.559994697570801,0.0,1740481173.7384944,5.559994697570801,0.0,1740481173.7384965,5.559994697570801,7.977621030018531,1740481173.7384973,5.559994697570801,0.0,1740481173.7384984,5.559994697570801,0.0,1740481173.7384996,5.559994697570801,0.0,1740481173.7385006,5.559994697570801,0.0,1740481173.7385013,5.559994697570801,0.9952339812823865,1740481173.7385027,5.559994697570801,0.0,1740481173.7385037,5.559994697570801,0.02940167649688219,1740481173.7385044,5.559994697570801,0.0,1740481173.7385051,5.559994697570801,0.9658323047855043,1740481192.665951,24.439976692199707 -1740481173.7591774,5.5799946784973145,4.0459564204475225,1740481173.7591796,5.5799946784973145,0.0,1740481173.7591817,5.5799946784973145,0.0,1740481173.7591836,5.5799946784973145,7.977621030018531,1740481173.7591846,5.5799946784973145,0.0,1740481173.7591863,5.5799946784973145,0.0,1740481173.7591872,5.5799946784973145,0.0,1740481173.759188,5.5799946784973145,0.0,1740481173.759189,5.5799946784973145,0.9952339812823865,1740481173.75919,5.5799946784973145,0.0,1740481173.7591913,5.5799946784973145,0.02940167649688219,1740481173.7591922,5.5799946784973145,0.0,1740481173.7591934,5.5799946784973145,0.9658323047855043,1740481192.6843812,24.45997667312622 -1740481173.7794697,5.599994659423828,4.152274521718127,1740481173.779472,5.599994659423828,0.0,1740481173.7794745,5.599994659423828,0.017278927176025093,1740481173.7794766,5.599994659423828,7.995307670520598,1740481173.7794778,5.599994659423828,0.0,1740481173.779479,5.599994659423828,0.0,1740481173.77948,5.599994659423828,0.0,1740481173.7794812,5.599994659423828,0.0,1740481173.7794824,5.599994659423828,0.9952339812823865,1740481173.779483,5.599994659423828,0.047660187176096214,1740481173.7794838,5.599994659423828,0.07676534480203312,1740481173.779485,5.599994659423828,0.0,1740481173.7794862,5.599994659423828,0.9660361614485251,1740481192.7032478,24.479976654052734 -1740481173.7982159,5.619994640350342,4.152274521718127,1740481173.7982175,5.619994640350342,0.0,1740481173.7982197,5.619994640350342,0.017278927176025093,1740481173.7982218,5.619994640350342,7.995307670520598,1740481173.798223,5.619994640350342,0.0,1740481173.7982244,5.619994640350342,0.0,1740481173.7982254,5.619994640350342,0.0,1740481173.7982266,5.619994640350342,0.0,1740481173.7982275,5.619994640350342,0.9952339812823865,1740481173.7982287,5.619994640350342,0.047660187176096214,1740481173.7982295,5.619994640350342,0.0768580070099576,1740481173.7982304,5.619994640350342,0.0,1740481173.7982316,5.619994640350342,0.9660361614485251,1740481192.7234986,24.499976634979248 -1740481173.8201828,5.6399946212768555,4.152274521718127,1740481173.8201861,5.6399946212768555,0.0,1740481173.8201888,5.6399946212768555,0.0,1740481173.8201911,5.6399946212768555,8.084346844615176,1740481173.8201928,5.6399946212768555,0.0,1740481173.820195,5.6399946212768555,0.0,1740481173.8201966,5.6399946212768555,0.0,1740481173.8201976,5.6399946212768555,0.0,1740481173.820199,5.6399946212768555,0.995290683161467,1740481173.8202002,5.6399946212768555,0.0,1740481173.8202016,5.6399946212768555,0.02925452171294185,1740481173.8202028,5.6399946212768555,0.0,1740481173.8202043,5.6399946212768555,0.9660361614485251,1740481192.7458365,24.51997661590576 -1740481173.838331,5.659994602203369,4.152274521718127,1740481173.8383362,5.659994602203369,0.0,1740481173.8383424,5.659994602203369,0.0,1740481173.8383455,5.659994602203369,8.084346844615176,1740481173.8383467,5.659994602203369,0.0,1740481173.8383482,5.659994602203369,0.0,1740481173.8383496,5.659994602203369,0.0,1740481173.8383505,5.659994602203369,0.0,1740481173.8383517,5.659994602203369,0.995290683161467,1740481173.8383527,5.659994602203369,0.0,1740481173.8383534,5.659994602203369,0.02925452171294185,1740481173.8383543,5.659994602203369,0.0,1740481173.8383558,5.659994602203369,0.9660361614485251,1740481192.7659626,24.539976596832275 -1740481173.8588185,5.679994583129883,4.152274521718127,1740481173.8588216,5.679994583129883,0.0,1740481173.858824,5.679994583129883,0.0,1740481173.8588424,5.679994583129883,8.084346844615176,1740481173.8588436,5.679994583129883,0.0,1740481173.858846,5.679994583129883,0.0,1740481173.8588471,5.679994583129883,0.0,1740481173.8588483,5.679994583129883,0.0,1740481173.8588493,5.679994583129883,0.995290683161467,1740481173.858851,5.679994583129883,0.0,1740481173.8588521,5.679994583129883,0.02925452171294185,1740481173.858853,5.679994583129883,0.0,1740481173.8588538,5.679994583129883,0.9660361614485251,1740481192.7833128,24.55997657775879 -1740481173.8786516,5.6999945640563965,4.258525206621915,1740481173.878654,5.6999945640563965,0.0,1740481173.8786561,5.6999945640563965,0.017268954414009274,1740481173.8786585,5.6999945640563965,8.09918165711922,1740481173.8786597,5.6999945640563965,0.0,1740481173.8786612,5.6999945640563965,0.0,1740481173.8786623,5.6999945640563965,0.0,1740481173.8786635,5.6999945640563965,0.0,1740481173.8786645,5.6999945640563965,0.995290683161467,1740481173.8786654,5.6999945640563965,0.04709316838529154,1740481173.8786664,5.6999945640563965,0.07811797565125012,1740481173.8786676,5.6999945640563965,0.0,1740481173.8786683,5.6999945640563965,0.9648190904935419,1740481192.803506,24.579976558685303 -1740481173.8995078,5.71999454498291,4.258525206621915,1740481173.8995094,5.71999454498291,0.0,1740481173.8995113,5.71999454498291,0.017268954414009274,1740481173.8995132,5.71999454498291,8.09918165711922,1740481173.8995144,5.71999454498291,0.0,1740481173.8995154,5.71999454498291,0.0,1740481173.8995163,5.71999454498291,0.0,1740481173.8995173,5.71999454498291,0.0,1740481173.8995183,5.71999454498291,0.995290683161467,1740481173.8995194,5.71999454498291,0.04709316838529154,1740481173.8995202,5.71999454498291,0.07756476105321664,1740481173.8995214,5.71999454498291,0.0,1740481173.899522,5.71999454498291,0.9648190904935419,1740481192.8234148,24.599976539611816 -1740481173.9248567,5.739994525909424,4.258525206621915,1740481173.9248586,5.739994525909424,0.0,1740481173.9248607,5.739994525909424,0.0,1740481173.9248626,5.739994525909424,8.188163387608999,1740481173.9248636,5.739994525909424,0.0,1740481173.9248648,5.739994525909424,0.0,1740481173.9248657,5.739994525909424,0.0,1740481173.9248667,5.739994525909424,0.0,1740481173.9248674,5.739994525909424,0.0784648957130936,1740481173.9248683,5.739994525909424,0.0,1740481173.9248693,5.739994525909424,-0.8863541947804483,1740481173.9248703,5.739994525909424,0.0,1740481173.924871,5.739994525909424,0.9648190904935419,1740481192.8436036,24.61997652053833 -1740481173.9402678,5.7599945068359375,4.258525206621915,1740481173.9402695,5.7599945068359375,0.0,1740481173.940272,5.7599945068359375,0.0,1740481173.9402742,5.7599945068359375,8.188163387608999,1740481173.9402752,5.7599945068359375,0.0,1740481173.9402766,5.7599945068359375,0.0,1740481173.9402778,5.7599945068359375,0.0,1740481173.9402788,5.7599945068359375,0.0,1740481173.9402797,5.7599945068359375,0.0784648957130936,1740481173.940281,5.7599945068359375,0.0,1740481173.9402819,5.7599945068359375,-0.8863541947804483,1740481173.9402828,5.7599945068359375,0.0,1740481173.940284,5.7599945068359375,0.9648190904935419,1740481192.8648865,24.639976501464844 -1740481173.9578195,5.779994487762451,4.258525206621915,1740481173.9578211,5.779994487762451,0.0,1740481173.9578235,5.779994487762451,0.0,1740481173.9578254,5.779994487762451,8.188163387608999,1740481173.9578269,5.779994487762451,0.0,1740481173.9578283,5.779994487762451,0.0,1740481173.9578295,5.779994487762451,0.0,1740481173.9578304,5.779994487762451,0.0,1740481173.9578311,5.779994487762451,0.0784648957130936,1740481173.9578323,5.779994487762451,0.0,1740481173.9578335,5.779994487762451,-0.8863541947804483,1740481173.9578347,5.779994487762451,0.0,1740481173.9578354,5.779994487762451,0.9648190904935419,1740481192.8835857,24.659976482391357 -1740481173.9783127,5.799994468688965,4.258525206621915,1740481173.9783144,5.799994468688965,0.0,1740481173.9783168,5.799994468688965,0.0,1740481173.9783192,5.799994468688965,8.188163387608999,1740481173.9783201,5.799994468688965,0.0,1740481173.978321,5.799994468688965,0.0,1740481173.9783223,5.799994468688965,0.0,1740481173.9783232,5.799994468688965,0.0,1740481173.9783242,5.799994468688965,0.0784648957130936,1740481173.9783254,5.799994468688965,0.0,1740481173.9783263,5.799994468688965,-0.8863541947804483,1740481173.9783273,5.799994468688965,0.0,1740481173.978328,5.799994468688965,0.9648190904935419,1740481192.903419,24.67997646331787 -1740481173.9979563,5.8199944496154785,4.363321661517297,1740481173.9979582,5.8199944496154785,0.0,1740481173.99796,5.8199944496154785,0.006097030743570921,1740481173.997962,5.8199944496154785,8.083199493893048,1740481173.997963,5.8199944496154785,0.0,1740481173.9979644,5.8199944496154785,0.0,1740481173.9979653,5.8199944496154785,0.0,1740481173.997966,5.8199944496154785,0.0,1740481173.997967,5.8199944496154785,0.0784648957130936,1740481173.997968,5.8199944496154785,0.0,1740481173.997969,5.8199944496154785,-0.8055825892835112,1740481173.9979696,5.8199944496154785,0.0,1740481173.997971,5.8199944496154785,0.9092886282637808,1740481192.9233706,24.699976444244385 -1740481174.0229666,5.839994430541992,4.363321661517297,1740481174.0229683,5.839994430541992,0.0,1740481174.0229704,5.839994430541992,0.0,1740481174.022972,5.839994430541992,8.181898918044858,1740481174.0229733,5.839994430541992,0.0,1740481174.0229745,5.839994430541992,0.0,1740481174.0229754,5.839994430541992,0.0,1740481174.0229762,5.839994430541992,0.0,1740481174.0229774,5.839994430541992,0.08116400381433433,1740481174.022978,5.839994430541992,0.0,1740481174.022979,5.839994430541992,-0.8281246244494465,1740481174.0229797,5.839994430541992,0.0,1740481174.0229807,5.839994430541992,0.9092886282637808,1740481192.9437385,24.7199764251709 -1740481174.0377786,5.859994411468506,4.363321661517297,1740481174.0377805,5.859994411468506,0.0,1740481174.0377827,5.859994411468506,0.0,1740481174.0377846,5.859994411468506,8.181898918044858,1740481174.0377855,5.859994411468506,0.0,1740481174.037787,5.859994411468506,0.0,1740481174.0377877,5.859994411468506,0.0,1740481174.0377886,5.859994411468506,0.0,1740481174.0377893,5.859994411468506,0.08116400381433433,1740481174.0377905,5.859994411468506,0.0,1740481174.0377913,5.859994411468506,-0.8281246244494465,1740481174.037792,5.859994411468506,0.0,1740481174.037793,5.859994411468506,0.9092886282637808,1740481192.9660323,24.739976406097412 -1740481174.0593615,5.8799943923950195,4.363321661517297,1740481174.0593634,5.8799943923950195,0.0,1740481174.0593657,5.8799943923950195,0.0,1740481174.0593677,5.8799943923950195,8.181898918044858,1740481174.0593688,5.8799943923950195,0.0,1740481174.0593703,5.8799943923950195,0.0,1740481174.0593712,5.8799943923950195,0.0,1740481174.0593722,5.8799943923950195,0.0,1740481174.0593734,5.8799943923950195,0.08116400381433433,1740481174.059374,5.8799943923950195,0.0,1740481174.059375,5.8799943923950195,-0.8281246244494465,1740481174.0593762,5.8799943923950195,0.0,1740481174.0593772,5.8799943923950195,0.9092886282637808,1740481192.9845319,24.759976387023926 -1740481174.0800326,5.899994373321533,4.363321661517297,1740481174.0800343,5.899994373321533,0.0,1740481174.0800369,5.899994373321533,0.0,1740481174.080039,5.899994373321533,8.181898918044858,1740481174.08004,5.899994373321533,0.0,1740481174.0800412,5.899994373321533,0.0,1740481174.080042,5.899994373321533,0.0,1740481174.080043,5.899994373321533,0.0,1740481174.080044,5.899994373321533,0.08116400381433433,1740481174.080045,5.899994373321533,0.0,1740481174.080046,5.899994373321533,-0.8281246244494465,1740481174.080047,5.899994373321533,0.0,1740481174.0800476,5.899994373321533,0.9092886282637808,1740481193.0033278,24.77997636795044 -1740481174.0979693,5.919994354248047,4.458498959719952,1740481174.0979722,5.919994354248047,0.0,1740481174.097975,5.919994354248047,0.004918321442843803,1740481174.0979772,5.919994354248047,7.993651300263236,1740481174.0979779,5.919994354248047,0.0,1740481174.097979,5.919994354248047,0.0,1740481174.0979807,5.919994354248047,0.0,1740481174.0979815,5.919994354248047,0.0,1740481174.0979824,5.919994354248047,0.08116400381433433,1740481174.0979831,5.919994354248047,0.0,1740481174.0979843,5.919994354248047,-0.6876402631458411,1740481174.0979853,5.919994354248047,0.0,1740481174.097986,5.919994354248047,0.8127056586515475,1740481193.0234969,24.799976348876953 -1740481174.1231978,5.9399943351745605,4.458498959719952,1740481174.1231995,5.9399943351745605,0.0,1740481174.1232016,5.9399943351745605,0.0,1740481174.1232033,5.9399943351745605,8.083910277023048,1740481174.1232045,5.9399943351745605,0.0,1740481174.1232057,5.9399943351745605,0.0,1740481174.1232066,5.9399943351745605,0.0,1740481174.1232073,5.9399943351745605,0.0,1740481174.1232085,5.9399943351745605,0.0762337510079678,1740481174.1232097,5.9399943351745605,0.0,1740481174.1232104,5.9399943351745605,-0.7364719076435797,1740481174.1232111,5.9399943351745605,0.0,1740481174.1232123,5.9399943351745605,0.8127056586515475,1740481193.0444722,24.819976329803467 -1740481174.1382167,5.959994316101074,4.458498959719952,1740481174.138219,5.959994316101074,0.0,1740481174.1382217,5.959994316101074,0.0,1740481174.1382246,5.959994316101074,8.083910277023048,1740481174.138226,5.959994316101074,0.0,1740481174.1382277,5.959994316101074,0.0,1740481174.138229,5.959994316101074,0.0,1740481174.1382303,5.959994316101074,0.0,1740481174.1382315,5.959994316101074,0.0762337510079678,1740481174.138233,5.959994316101074,0.0,1740481174.138234,5.959994316101074,-0.7364719076435797,1740481174.138235,5.959994316101074,0.0,1740481174.138236,5.959994316101074,0.8127056586515475,1740481193.0643806,24.83997631072998 -1740481174.159897,5.979994297027588,4.458498959719952,1740481174.1598997,5.979994297027588,0.0,1740481174.1599019,5.979994297027588,0.0,1740481174.159904,5.979994297027588,8.083910277023048,1740481174.159905,5.979994297027588,0.0,1740481174.1599064,5.979994297027588,0.0,1740481174.1599073,5.979994297027588,0.0,1740481174.1599085,5.979994297027588,0.0,1740481174.1599097,5.979994297027588,0.0762337510079678,1740481174.1599104,5.979994297027588,0.0,1740481174.1599114,5.979994297027588,-0.7364719076435797,1740481174.159912,5.979994297027588,0.0,1740481174.159913,5.979994297027588,0.8127056586515475,1740481193.0840194,24.859976291656494 -1740481174.1782653,5.999994277954102,4.458498959719952,1740481174.1782691,5.999994277954102,0.0,1740481174.1782715,5.999994277954102,0.0,1740481174.1782901,5.999994277954102,8.083910277023048,1740481174.1782916,5.999994277954102,0.0,1740481174.1782951,5.999994277954102,0.0,1740481174.1782968,5.999994277954102,0.0,1740481174.1782978,5.999994277954102,0.0,1740481174.1782997,5.999994277954102,0.0762337510079678,1740481174.1783009,5.999994277954102,0.0,1740481174.178302,5.999994277954102,-0.7364719076435797,1740481174.1783032,5.999994277954102,0.0,1740481174.1783047,5.999994277954102,0.8127056586515475,1740481193.104641,24.879976272583008 -1740481174.1977243,6.019994258880615,4.458498959719952,1740481174.1977262,6.019994258880615,0.0,1740481174.1977282,6.019994258880615,0.0,1740481174.1977303,6.019994258880615,8.083910277023048,1740481174.1977313,6.019994258880615,0.0,1740481174.1977327,6.019994258880615,0.0,1740481174.1977336,6.019994258880615,0.0,1740481174.1977346,6.019994258880615,0.0,1740481174.1977353,6.019994258880615,0.0762337510079678,1740481174.1977367,6.019994258880615,0.0,1740481174.1977377,6.019994258880615,-0.7364719076435797,1740481174.1977386,6.019994258880615,0.0,1740481174.1977398,6.019994258880615,0.8127056586515475,1740481193.1232102,24.89997625350952 -1740481174.224787,6.039994239807129,4.543726168125094,1740481174.2247887,6.039994239807129,0.0,1740481174.224791,6.039994239807129,0.0,1740481174.2247927,6.039994239807129,8.000198870666292,1740481174.2247937,6.039994239807129,0.0,1740481174.224795,6.039994239807129,0.0,1740481174.224796,6.039994239807129,0.0,1740481174.2247972,6.039994239807129,0.0,1740481174.2247982,6.039994239807129,0.07264390184463282,1740481174.2247992,6.039994239807129,0.0,1740481174.2248,6.039994239807129,-0.6188290242667159,1740481174.224801,6.039994239807129,0.0,1740481174.224802,6.039994239807129,0.7282363512705986,1740481193.1447804,24.919976234436035 -1740481174.2380292,6.059994220733643,4.543726168125094,1740481174.2380314,6.059994220733643,0.0,1740481174.2380333,6.059994220733643,0.0,1740481174.2380354,6.059994220733643,8.000198870666292,1740481174.2380366,6.059994220733643,0.0,1740481174.238038,6.059994220733643,0.0,1740481174.238039,6.059994220733643,0.0,1740481174.23804,6.059994220733643,0.0,1740481174.2380412,6.059994220733643,0.07264390184463282,1740481174.238042,6.059994220733643,0.0,1740481174.238043,6.059994220733643,-0.6555924494259657,1740481174.2380438,6.059994220733643,0.0,1740481174.238045,6.059994220733643,0.7282363512705986,1740481193.1650975,24.93997621536255 -1740481174.2583518,6.079994201660156,4.543726168125094,1740481174.258354,6.079994201660156,0.0,1740481174.2583559,6.079994201660156,0.0,1740481174.258358,6.079994201660156,8.000198870666292,1740481174.258359,6.079994201660156,0.0,1740481174.2583604,6.079994201660156,0.0,1740481174.2583613,6.079994201660156,0.0,1740481174.2583623,6.079994201660156,0.0,1740481174.2583635,6.079994201660156,0.07264390184463282,1740481174.2583642,6.079994201660156,0.0,1740481174.2583652,6.079994201660156,-0.6555924494259657,1740481174.2583659,6.079994201660156,0.0,1740481174.258367,6.079994201660156,0.7282363512705986,1740481193.1845243,24.959976196289062 -1740481174.2779665,6.09999418258667,4.543726168125094,1740481174.2779682,6.09999418258667,0.0,1740481174.2779708,6.09999418258667,0.0,1740481174.2779727,6.09999418258667,8.000198870666292,1740481174.2779737,6.09999418258667,0.0,1740481174.277975,6.09999418258667,0.0,1740481174.2779765,6.09999418258667,0.0,1740481174.2779777,6.09999418258667,0.0,1740481174.277979,6.09999418258667,0.07264390184463282,1740481174.2779796,6.09999418258667,0.0,1740481174.2779806,6.09999418258667,-0.6555924494259657,1740481174.2779818,6.09999418258667,0.0,1740481174.277983,6.09999418258667,0.7282363512705986,1740481193.2037401,24.979976177215576 -1740481174.2978222,6.119994163513184,4.543726168125094,1740481174.297824,6.119994163513184,0.0,1740481174.2978263,6.119994163513184,0.0,1740481174.2978282,6.119994163513184,8.000198870666292,1740481174.2978294,6.119994163513184,0.0,1740481174.2978306,6.119994163513184,0.0,1740481174.2978318,6.119994163513184,0.0,1740481174.297833,6.119994163513184,0.0,1740481174.2978337,6.119994163513184,0.07264390184463282,1740481174.2978346,6.119994163513184,0.0,1740481174.2978358,6.119994163513184,-0.6555924494259657,1740481174.2978365,6.119994163513184,0.0,1740481174.2978375,6.119994163513184,0.7282363512705986,1740481193.2235522,24.99997615814209 -1740481174.323558,6.139994144439697,4.619880446984732,1740481174.32356,6.139994144439697,0.0,1740481174.3235621,6.139994144439697,0.0,1740481174.323564,6.139994144439697,7.920951940169915,1740481174.3235648,6.139994144439697,0.0,1740481174.3235662,6.139994144439697,0.0,1740481174.3235672,6.139994144439697,0.0,1740481174.323568,6.139994144439697,0.0,1740481174.3235688,6.139994144439697,0.06958283818830915,1740481174.3235698,6.139994144439697,0.0,1740481174.3235707,6.139994144439697,-0.5470258119481164,1740481174.3235714,6.139994144439697,0.0,1740481174.3235724,6.139994144439697,0.6505357465925913,1740481193.243731,25.019976139068604 -1740481174.3375752,6.159994125366211,4.619880446984732,1740481174.3375766,6.159994125366211,0.0,1740481174.3375788,6.159994125366211,0.0,1740481174.3375807,6.159994125366211,7.920951940169915,1740481174.3375819,6.159994125366211,0.0,1740481174.3375828,6.159994125366211,0.0,1740481174.3375838,6.159994125366211,0.0,1740481174.337585,6.159994125366211,0.0,1740481174.3375857,6.159994125366211,0.06958283818830915,1740481174.3375864,6.159994125366211,0.0,1740481174.3375874,6.159994125366211,-0.5809529084042822,1740481174.3375883,6.159994125366211,0.0,1740481174.337589,6.159994125366211,0.6505357465925913,1740481193.2645972,25.039976119995117 -1740481174.3578012,6.179994106292725,4.619880446984732,1740481174.357803,6.179994106292725,0.0,1740481174.357805,6.179994106292725,0.0,1740481174.3578072,6.179994106292725,7.920951940169915,1740481174.357808,6.179994106292725,0.0,1740481174.3578093,6.179994106292725,0.0,1740481174.3578105,6.179994106292725,0.0,1740481174.3578115,6.179994106292725,0.0,1740481174.3578122,6.179994106292725,0.06958283818830915,1740481174.3578134,6.179994106292725,0.0,1740481174.357814,6.179994106292725,-0.5809529084042822,1740481174.357815,6.179994106292725,0.0,1740481174.3578157,6.179994106292725,0.6505357465925913,1740481193.2834735,25.05997610092163 -1740481174.3775222,6.199994087219238,4.619880446984732,1740481174.377524,6.199994087219238,0.0,1740481174.377526,6.199994087219238,0.0,1740481174.377528,6.199994087219238,7.920951940169915,1740481174.377529,6.199994087219238,0.0,1740481174.37753,6.199994087219238,0.0,1740481174.377531,6.199994087219238,0.0,1740481174.377532,6.199994087219238,0.0,1740481174.3775327,6.199994087219238,0.06958283818830915,1740481174.3775337,6.199994087219238,0.0,1740481174.3775344,6.199994087219238,-0.5809529084042822,1740481174.3775353,6.199994087219238,0.0,1740481174.3775363,6.199994087219238,0.6505357465925913,, -1740481174.4006364,6.219994068145752,4.619880446984732,1740481174.4006388,6.219994068145752,0.0,1740481174.4006412,6.219994068145752,0.0,1740481174.4006436,6.219994068145752,7.920951940169915,1740481174.4006448,6.219994068145752,0.0,1740481174.4006464,6.219994068145752,0.0,1740481174.4006474,6.219994068145752,0.0,1740481174.4006486,6.219994068145752,0.0,1740481174.4006498,6.219994068145752,0.06958283818830915,1740481174.400651,6.219994068145752,0.0,1740481174.400652,6.219994068145752,-0.5809529084042822,1740481174.4006531,6.219994068145752,0.0,1740481174.400654,6.219994068145752,0.6505357465925913,, -1740481174.4182951,6.239994049072266,4.619880446984732,1740481174.4182968,6.239994049072266,0.0,1740481174.418299,6.239994049072266,0.0,1740481174.4183006,6.239994049072266,7.920951940169915,1740481174.4183016,6.239994049072266,0.0,1740481174.418303,6.239994049072266,0.0,1740481174.418304,6.239994049072266,0.0,1740481174.418305,6.239994049072266,0.0,1740481174.4183059,6.239994049072266,0.06958283818830915,1740481174.4183068,6.239994049072266,0.0,1740481174.4183075,6.239994049072266,-0.5809529084042822,1740481174.4183083,6.239994049072266,0.0,1740481174.4183092,6.239994049072266,0.6505357465925913,, -1740481174.4378195,6.259994029998779,4.688004376137906,1740481174.4378211,6.259994029998779,0.0,1740481174.4378233,6.259994029998779,0.0018018641207649835,1740481174.437825,6.259994029998779,7.786472891749344,1740481174.4378262,6.259994029998779,0.0,1740481174.4378273,6.259994029998779,0.0,1740481174.4378283,6.259994029998779,0.0,1740481174.4378295,6.259994029998779,0.0,1740481174.4378302,6.259994029998779,0.06958283818830915,1740481174.4378312,6.259994029998779,0.0,1740481174.437832,6.259994029998779,-0.48183948792700854,1740481174.437833,6.259994029998779,0.0,1740481174.4378338,6.259994029998779,0.5823952903219235,, -1740481174.4575794,6.279994010925293,4.688004376137906,1740481174.4575813,6.279994010925293,0.0,1740481174.4575834,6.279994010925293,0.0018018641207649835,1740481174.457585,6.279994010925293,7.786472891749344,1740481174.4575863,6.279994010925293,0.0,1740481174.4575875,6.279994010925293,0.0,1740481174.4575884,6.279994010925293,0.0,1740481174.4575891,6.279994010925293,0.0,1740481174.4575903,6.279994010925293,0.06958283818830915,1740481174.4575913,6.279994010925293,0.0,1740481174.457592,6.279994010925293,-0.5128124521336144,1740481174.4575932,6.279994010925293,0.0,1740481174.4575942,6.279994010925293,0.5823952903219235,, -1740481174.4791234,6.299993991851807,4.688004376137906,1740481174.479128,6.299993991851807,0.0,1740481174.479131,6.299993991851807,0.0018018641207649835,1740481174.479133,6.299993991851807,7.786472891749344,1740481174.4791346,6.299993991851807,0.0,1740481174.4791365,6.299993991851807,0.0,1740481174.4791384,6.299993991851807,0.0,1740481174.4791396,6.299993991851807,0.0,1740481174.4791417,6.299993991851807,0.06958283818830915,1740481174.4791439,6.299993991851807,0.0,1740481174.4791458,6.299993991851807,-0.5128124521336144,1740481174.479147,6.299993991851807,0.0,1740481174.479149,6.299993991851807,0.5823952903219235,, -1740481174.4997833,6.31999397277832,4.688004376137906,1740481174.499785,6.31999397277832,0.0,1740481174.499787,6.31999397277832,0.0018018641207649835,1740481174.499789,6.31999397277832,7.786472891749344,1740481174.4997902,6.31999397277832,0.0,1740481174.4997914,6.31999397277832,0.0,1740481174.4997923,6.31999397277832,0.0,1740481174.4997933,6.31999397277832,0.0,1740481174.4997945,6.31999397277832,0.06958283818830915,1740481174.4997952,6.31999397277832,0.0,1740481174.4997962,6.31999397277832,-0.5128124521336144,1740481174.4997973,6.31999397277832,0.0,1740481174.4997983,6.31999397277832,0.5823952903219235,, -1740481174.5181842,6.339993953704834,4.688004376137906,1740481174.5181856,6.339993953704834,0.0,1740481174.5181878,6.339993953704834,0.0,1740481174.51819,6.339993953704834,7.852794956781753,1740481174.5181906,6.339993953704834,0.0,1740481174.5181918,6.339993953704834,0.0,1740481174.518193,6.339993953704834,0.0,1740481174.518194,6.339993953704834,0.0,1740481174.5181947,6.339993953704834,0.06794652076976904,1740481174.5181954,6.339993953704834,0.0,1740481174.518196,6.339993953704834,-0.5144487695521545,1740481174.5181973,6.339993953704834,0.0,1740481174.518198,6.339993953704834,0.5823952903219235,, -1740481174.5384345,6.359993934631348,4.7490585078663,1740481174.5384362,6.359993934631348,0.0,1740481174.538438,6.359993934631348,0.0012942875847840602,1740481174.5384405,6.359993934631348,7.734297357610769,1740481174.5384412,6.359993934631348,0.0,1740481174.5384426,6.359993934631348,0.0,1740481174.5384436,6.359993934631348,0.0,1740481174.5384445,6.359993934631348,0.0,1740481174.5384452,6.359993934631348,0.06794652076976904,1740481174.5384464,6.359993934631348,0.0,1740481174.5384471,6.359993934631348,-0.42732737140192445,1740481174.5384479,6.359993934631348,0.0,1740481174.5384488,6.359993934631348,0.5224993469440395,, -1740481174.5579717,6.379993915557861,4.7490585078663,1740481174.5579734,6.379993915557861,0.0,1740481174.5579758,6.379993915557861,0.0012942875847840602,1740481174.5579777,6.379993915557861,7.734297357610769,1740481174.5579786,6.379993915557861,0.0,1740481174.5579796,6.379993915557861,0.0,1740481174.5579808,6.379993915557861,0.0,1740481174.5579817,6.379993915557861,0.0,1740481174.5579824,6.379993915557861,0.06794652076976904,1740481174.5579832,6.379993915557861,0.0,1740481174.5579844,6.379993915557861,-0.4545528261742705,1740481174.557985,6.379993915557861,0.0,1740481174.557986,6.379993915557861,0.5224993469440395,, -1740481174.577805,6.399993896484375,4.7490585078663,1740481174.5778067,6.399993896484375,0.0,1740481174.5778084,6.399993896484375,0.0012942875847840602,1740481174.5778105,6.399993896484375,7.734297357610769,1740481174.5778115,6.399993896484375,0.0,1740481174.5778124,6.399993896484375,0.0,1740481174.5778134,6.399993896484375,0.0,1740481174.5778143,6.399993896484375,0.0,1740481174.5778153,6.399993896484375,0.06794652076976904,1740481174.577816,6.399993896484375,0.0,1740481174.5778172,6.399993896484375,-0.4545528261742705,1740481174.577818,6.399993896484375,0.0,1740481174.5778189,6.399993896484375,0.5224993469440395,, -1740481174.5982761,6.419993877410889,4.7490585078663,1740481174.5982778,6.419993877410889,0.0,1740481174.59828,6.419993877410889,0.0012942875847840602,1740481174.5982816,6.419993877410889,7.734297357610769,1740481174.5982828,6.419993877410889,0.0,1740481174.598284,6.419993877410889,0.0,1740481174.5982847,6.419993877410889,0.0,1740481174.598286,6.419993877410889,0.0,1740481174.5982866,6.419993877410889,0.06794652076976904,1740481174.5982873,6.419993877410889,0.0,1740481174.598288,6.419993877410889,-0.4545528261742705,1740481174.5982893,6.419993877410889,0.0,1740481174.59829,6.419993877410889,0.5224993469440395,, -1740481174.6187005,6.439993858337402,4.7490585078663,1740481174.6187046,6.439993858337402,0.0,1740481174.6187084,6.439993858337402,0.0,1740481174.618711,6.439993858337402,7.794057201754379,1740481174.618712,6.439993858337402,0.0,1740481174.618714,6.439993858337402,0.0,1740481174.6187153,6.439993858337402,0.0,1740481174.6187165,6.439993858337402,0.0,1740481174.6187186,6.439993858337402,0.06799532363989615,1740481174.61872,6.439993858337402,0.0,1740481174.6187215,6.439993858337402,-0.4545040233041434,1740481174.6187227,6.439993858337402,0.0,1740481174.618724,6.439993858337402,0.5224993469440395,, -1740481174.6378224,6.459993839263916,4.7490585078663,1740481174.6378286,6.459993839263916,0.0,1740481174.6378326,6.459993839263916,0.0,1740481174.6378353,6.459993839263916,7.794057201754379,1740481174.6378362,6.459993839263916,0.0,1740481174.6378376,6.459993839263916,0.0,1740481174.6378388,6.459993839263916,0.0,1740481174.6378396,6.459993839263916,0.0,1740481174.6378407,6.459993839263916,0.06799532363989615,1740481174.6378417,6.459993839263916,0.0,1740481174.6378424,6.459993839263916,-0.4545040233041434,1740481174.6378434,6.459993839263916,0.0,1740481174.6378446,6.459993839263916,0.5224993469440395,, -1740481174.6594512,6.47999382019043,4.803931100187649,1740481174.659454,6.47999382019043,0.0,1740481174.6594589,6.47999382019043,0.0009362827006256878,1740481174.6594622,6.47999382019043,7.690048590947027,1740481174.659465,6.47999382019043,0.0,1740481174.659468,6.47999382019043,0.0,1740481174.6594698,6.47999382019043,0.0,1740481174.6594715,6.47999382019043,0.0,1740481174.6594737,6.47999382019043,0.06799532363989615,1740481174.6594756,6.47999382019043,0.0,1740481174.6594772,6.47999382019043,-0.37818044164303555,1740481174.6594794,6.47999382019043,0.0,1740481174.659481,6.47999382019043,0.47002690019005056,, -1740481174.6778462,6.499993801116943,4.803931100187649,1740481174.6778479,6.499993801116943,0.0,1740481174.67785,6.499993801116943,0.0009362827006256878,1740481174.677852,6.499993801116943,7.690048590947027,1740481174.6778529,6.499993801116943,0.0,1740481174.6778543,6.499993801116943,0.0,1740481174.6778553,6.499993801116943,0.0,1740481174.6778562,6.499993801116943,0.0,1740481174.6778574,6.499993801116943,0.06799532363989615,1740481174.6778584,6.499993801116943,0.0,1740481174.677859,6.499993801116943,-0.4020315765501544,1740481174.67786,6.499993801116943,0.0,1740481174.677861,6.499993801116943,0.47002690019005056,, -1740481174.6989336,6.519993782043457,4.803931100187649,1740481174.698936,6.519993782043457,0.0,1740481174.6989388,6.519993782043457,0.0009362827006256878,1740481174.698941,6.519993782043457,7.690048590947027,1740481174.698942,6.519993782043457,0.0,1740481174.6989431,6.519993782043457,0.0,1740481174.6989446,6.519993782043457,0.0,1740481174.6989455,6.519993782043457,0.0,1740481174.6989462,6.519993782043457,0.06799532363989615,1740481174.6989477,6.519993782043457,0.0,1740481174.6989484,6.519993782043457,-0.4020315765501544,1740481174.6989493,6.519993782043457,0.0,1740481174.69895,6.519993782043457,0.47002690019005056,, -1740481174.7193577,6.539993762969971,4.803931100187649,1740481174.7193594,6.539993762969971,0.0,1740481174.719362,6.539993762969971,0.0,1740481174.719364,6.539993762969971,7.7439849005677495,1740481174.719365,6.539993762969971,0.0,1740481174.7193658,6.539993762969971,0.0,1740481174.719367,6.539993762969971,0.0,1740481174.719368,6.539993762969971,0.0,1740481174.7193687,6.539993762969971,0.07042335854694941,1740481174.71937,6.539993762969971,0.0,1740481174.7193708,6.539993762969971,-0.39960354164310113,1740481174.7193716,6.539993762969971,0.0,1740481174.7193725,6.539993762969971,0.47002690019005056,, -1740481174.7379563,6.559993743896484,4.803931100187649,1740481174.7379582,6.559993743896484,0.0,1740481174.73796,6.559993743896484,0.0,1740481174.7379622,6.559993743896484,7.7439849005677495,1740481174.7379632,6.559993743896484,0.0,1740481174.737965,6.559993743896484,0.0,1740481174.7379658,6.559993743896484,0.0,1740481174.7379668,6.559993743896484,0.0,1740481174.7379677,6.559993743896484,0.07042335854694941,1740481174.737969,6.559993743896484,0.0,1740481174.7379696,6.559993743896484,-0.39960354164310113,1740481174.7379706,6.559993743896484,0.0,1740481174.7379715,6.559993743896484,0.47002690019005056,, -1740481174.759699,6.579993724822998,4.853275229652686,1740481174.7597013,6.579993724822998,0.0,1740481174.7597034,6.579993724822998,0.0006813353724378463,1740481174.759705,6.579993724822998,7.650940621381178,1740481174.759706,6.579993724822998,0.0,1740481174.7597075,6.579993724822998,0.0,1740481174.7597084,6.579993724822998,0.0,1740481174.7597094,6.579993724822998,0.0,1740481174.7597103,6.579993724822998,0.07042335854694941,1740481174.7597113,6.579993724822998,-0.704233585469494,1740481174.759712,6.579993724822998,-1.0356730234824518,1740481174.7597127,6.579993724822998,0.0,1740481174.759714,6.579993724822998,0.4231640929105453,, -1740481174.7784526,6.599993705749512,4.853275229652686,1740481174.7784545,6.599993705749512,0.0,1740481174.7784567,6.599993705749512,0.0006813353724378463,1740481174.7784584,6.599993705749512,7.650940621381178,1740481174.7784593,6.599993705749512,0.0,1740481174.7784605,6.599993705749512,0.0,1740481174.7784615,6.599993705749512,0.0,1740481174.7784624,6.599993705749512,0.0,1740481174.7784631,6.599993705749512,0.07042335854694941,1740481174.7784643,6.599993705749512,-0.704233585469494,1740481174.778465,6.599993705749512,-1.0569743198330899,1740481174.778466,6.599993705749512,0.0,1740481174.7784672,6.599993705749512,0.4231640929105453,, -1740481174.7983735,6.619993686676025,4.853275229652686,1740481174.7983756,6.619993686676025,0.0,1740481174.7983782,6.619993686676025,0.0006813353724378463,1740481174.7983809,6.619993686676025,7.650940621381178,1740481174.798382,6.619993686676025,0.0,1740481174.7983837,6.619993686676025,0.0,1740481174.7983847,6.619993686676025,0.0,1740481174.7983859,6.619993686676025,0.0,1740481174.798387,6.619993686676025,0.07042335854694941,1740481174.7983882,6.619993686676025,-0.704233585469494,1740481174.798389,6.619993686676025,-1.0569743198330899,1740481174.7983904,6.619993686676025,0.0,1740481174.7983913,6.619993686676025,0.4231640929105453,, -1740481174.8184056,6.639993667602539,4.853275229652686,1740481174.818407,6.639993667602539,0.0,1740481174.8184092,6.639993667602539,0.0,1740481174.8184114,6.639993667602539,7.699603415473777,1740481174.8184123,6.639993667602539,0.0,1740481174.8184133,6.639993667602539,0.0,1740481174.8184144,6.639993667602539,0.0,1740481174.8184154,6.639993667602539,0.0,1740481174.8184164,6.639993667602539,0.07627710419350667,1740481174.8184173,6.639993667602539,0.0,1740481174.8184183,6.639993667602539,-0.3468869887170386,1740481174.8184192,6.639993667602539,0.0,1740481174.8184202,6.639993667602539,0.4231640929105453,, -1740481174.8382065,6.659993648529053,4.853275229652686,1740481174.838208,6.659993648529053,0.0,1740481174.83821,6.659993648529053,0.0,1740481174.838212,6.659993648529053,7.699603415473777,1740481174.838213,6.659993648529053,0.0,1740481174.8382142,6.659993648529053,0.0,1740481174.838215,6.659993648529053,0.0,1740481174.8382158,6.659993648529053,0.0,1740481174.838217,6.659993648529053,0.07627710419350667,1740481174.838218,6.659993648529053,0.0,1740481174.8382187,6.659993648529053,-0.3468869887170386,1740481174.8382194,6.659993648529053,0.0,1740481174.8382206,6.659993648529053,0.4231640929105453,, -1740481174.8614912,6.679993629455566,4.853275229652686,1740481174.8614936,6.679993629455566,0.0,1740481174.8614962,6.679993629455566,0.0,1740481174.861501,6.679993629455566,7.699603415473777,1740481174.8615022,6.679993629455566,0.0,1740481174.8615057,6.679993629455566,0.0,1740481174.8615067,6.679993629455566,0.0,1740481174.8615086,6.679993629455566,0.0,1740481174.8615108,6.679993629455566,0.07627710419350667,1740481174.8615127,6.679993629455566,0.0,1740481174.8615146,6.679993629455566,-0.3468869887170386,1740481174.861517,6.679993629455566,0.0,1740481174.8615196,6.679993629455566,0.4231640929105453,, -1740481174.878261,6.69999361038208,4.89495712526174,1740481174.8782625,6.69999361038208,0.0,1740481174.8782647,6.69999361038208,0.00046649296318734454,1740481174.8782666,6.69999361038208,7.543475354945533,1740481174.8782673,6.69999361038208,0.0,1740481174.8782687,6.69999361038208,0.0,1740481174.8782697,6.69999361038208,0.0,1740481174.8782709,6.69999361038208,0.0,1740481174.8782718,6.69999361038208,0.07627710419350667,1740481174.8782728,6.69999361038208,-0.7627710419350666,1740481174.8782737,6.69999361038208,-0.9957710487173492,1740481174.878275,6.69999361038208,0.0,1740481174.8782756,6.69999361038208,0.34486681616482956,, -1740481174.8987336,6.719993591308594,4.89495712526174,1740481174.8987355,6.719993591308594,0.0,1740481174.898738,6.719993591308594,0.00046649296318734454,1740481174.8987403,6.719993591308594,7.543475354945533,1740481174.8987415,6.719993591308594,0.0,1740481174.8987432,6.719993591308594,0.0,1740481174.8987443,6.719993591308594,0.0,1740481174.8987455,6.719993591308594,0.0,1740481174.8987467,6.719993591308594,0.07627710419350667,1740481174.898748,6.719993591308594,-0.7627710419350666,1740481174.8987489,6.719993591308594,-1.0313607539063896,1740481174.8987503,6.719993591308594,0.0,1740481174.8987515,6.719993591308594,0.34486681616482956,, -1740481174.9241092,6.739993572235107,4.89495712526174,1740481174.9241114,6.739993572235107,0.0,1740481174.9241142,6.739993572235107,0.0,1740481174.9241168,6.739993572235107,7.5846907575913995,1740481174.9241178,6.739993572235107,0.0,1740481174.9241192,6.739993572235107,0.0,1740481174.9241211,6.739993572235107,0.0,1740481174.9241223,6.739993572235107,0.0,1740481174.9241233,6.739993572235107,0.07076462895985312,1740481174.9241247,6.739993572235107,0.0,1740481174.9241257,6.739993572235107,-0.2741021872049764,1740481174.9241266,6.739993572235107,0.0,1740481174.9241278,6.739993572235107,0.34486681616482956,, -1740481174.9391255,6.759993553161621,4.89495712526174,1740481174.9391272,6.759993553161621,0.0,1740481174.9391294,6.759993553161621,0.0,1740481174.9391315,6.759993553161621,7.5846907575913995,1740481174.9391325,6.759993553161621,0.0,1740481174.9391336,6.759993553161621,0.0,1740481174.9391344,6.759993553161621,0.0,1740481174.9391356,6.759993553161621,0.0,1740481174.9391365,6.759993553161621,0.07076462895985312,1740481174.9391372,6.759993553161621,0.0,1740481174.939138,6.759993553161621,-0.2741021872049764,1740481174.939139,6.759993553161621,0.0,1740481174.9391398,6.759993553161621,0.34486681616482956,, -1740481174.9575496,6.779993534088135,4.89495712526174,1740481174.9575512,6.779993534088135,0.0,1740481174.9575534,6.779993534088135,0.0,1740481174.9575555,6.779993534088135,7.5846907575913995,1740481174.9575565,6.779993534088135,0.0,1740481174.9575577,6.779993534088135,0.0,1740481174.9575589,6.779993534088135,0.0,1740481174.9575598,6.779993534088135,0.0,1740481174.9575605,6.779993534088135,0.07076462895985312,1740481174.957562,6.779993534088135,0.0,1740481174.9575627,6.779993534088135,-0.2741021872049764,1740481174.9575636,6.779993534088135,0.0,1740481174.9575644,6.779993534088135,0.34486681616482956,, -1740481174.9778745,6.799993515014648,4.9287378058620135,1740481174.9778764,6.799993515014648,0.0,1740481174.9778786,6.799993515014648,0.00025110261060219544,1740481174.9778802,6.799993515014648,7.448716630024784,1740481174.9778814,6.799993515014648,0.0,1740481174.9778826,6.799993515014648,0.0,1740481174.9778836,6.799993515014648,0.0,1740481174.9778848,6.799993515014648,0.0,1740481174.9778857,6.799993515014648,0.0,1740481174.9778867,6.799993515014648,0.0,1740481174.9778874,6.799993515014648,-0.27795966307640463,1740481174.9778883,6.799993515014648,0.0,1740481174.9778893,6.799993515014648,0.27675420107622084,, -1740481174.9988692,6.819993495941162,4.9287378058620135,1740481174.9988708,6.819993495941162,0.0,1740481174.9988732,6.819993495941162,0.00025110261060219544,1740481174.9988751,6.819993495941162,7.448716630024784,1740481174.998876,6.819993495941162,0.0,1740481174.9988775,6.819993495941162,0.0,1740481174.9988785,6.819993495941162,0.0,1740481174.9988792,6.819993495941162,0.0,1740481174.9988801,6.819993495941162,0.0,1740481174.9988813,6.819993495941162,0.0,1740481174.9988823,6.819993495941162,-0.27675420107622084,1740481174.9988832,6.819993495941162,0.0,1740481174.9988847,6.819993495941162,0.27675420107622084,, -1740481175.0184753,6.839993476867676,4.9287378058620135,1740481175.018477,6.839993476867676,0.0,1740481175.018479,6.839993476867676,0.0,1740481175.0184808,6.839993476867676,7.482246208014455,1740481175.018482,6.839993476867676,0.0,1740481175.018483,6.839993476867676,0.0,1740481175.0184839,6.839993476867676,0.0,1740481175.018485,6.839993476867676,0.0,1740481175.018486,6.839993476867676,0.06717524693477835,1740481175.0184867,6.839993476867676,-0.6717524693477834,1740481175.0184877,6.839993476867676,-0.881331423489226,1740481175.0184886,6.839993476867676,0.0,1740481175.0184896,6.839993476867676,0.27675420107622084,, -1740481175.0385375,6.8599934577941895,4.9287378058620135,1740481175.0385401,6.8599934577941895,0.0,1740481175.0385425,6.8599934577941895,0.0,1740481175.0385458,6.8599934577941895,7.482246208014455,1740481175.0385478,6.8599934577941895,0.0,1740481175.0385497,6.8599934577941895,0.0,1740481175.0385513,6.8599934577941895,0.0,1740481175.0385528,6.8599934577941895,0.0,1740481175.0385544,6.8599934577941895,0.06717524693477835,1740481175.0385559,6.8599934577941895,-0.6717524693477834,1740481175.0385568,6.8599934577941895,-0.881331423489226,1740481175.0385582,6.8599934577941895,0.0,1740481175.0385594,6.8599934577941895,0.27675420107622084,, -1740481175.0599551,6.879993438720703,4.9287378058620135,1740481175.0599575,6.879993438720703,0.0,1740481175.0599606,6.879993438720703,0.0,1740481175.0599632,6.879993438720703,7.482246208014455,1740481175.0599647,6.879993438720703,0.0,1740481175.0599666,6.879993438720703,0.0,1740481175.0599675,6.879993438720703,0.0,1740481175.0599692,6.879993438720703,0.0,1740481175.0599716,6.879993438720703,0.06717524693477835,1740481175.059973,6.879993438720703,-0.6717524693477834,1740481175.0599754,6.879993438720703,-0.881331423489226,1740481175.0599773,6.879993438720703,0.0,1740481175.0599785,6.879993438720703,0.27675420107622084,, -1740481175.0784097,6.899993419647217,4.9287378058620135,1740481175.0784125,6.899993419647217,0.0,1740481175.0784166,6.899993419647217,0.0,1740481175.0784204,6.899993419647217,7.482246208014455,1740481175.078422,6.899993419647217,0.0,1740481175.0784233,6.899993419647217,0.0,1740481175.0784252,6.899993419647217,0.0,1740481175.0784266,6.899993419647217,0.0,1740481175.0784278,6.899993419647217,0.06717524693477835,1740481175.0784297,6.899993419647217,-0.6717524693477834,1740481175.0784307,6.899993419647217,-0.881331423489226,1740481175.0784323,6.899993419647217,0.0,1740481175.0784342,6.899993419647217,0.27675420107622084,, -1740481175.0985484,6.9199934005737305,4.956310224595983,1740481175.09855,6.9199934005737305,0.0,1740481175.098552,6.9199934005737305,0.00013199069842707387,1740481175.0985544,6.9199934005737305,7.333906729051828,1740481175.0985553,6.9199934005737305,0.0,1740481175.0985568,6.9199934005737305,0.0,1740481175.0985577,6.9199934005737305,0.0,1740481175.0985587,6.9199934005737305,0.0,1740481175.0985594,6.9199934005737305,0.0,1740481175.0985606,6.9199934005737305,0.0,1740481175.0985615,6.9199934005737305,-0.1993091505051658,1740481175.0985625,6.9199934005737305,0.0,1740481175.0985637,6.9199934005737305,0.20251846624569364,, -1740481175.118446,6.939993381500244,4.956310224595983,1740481175.1184478,6.939993381500244,0.0,1740481175.11845,6.939993381500244,0.0,1740481175.1184523,6.939993381500244,7.36134715708737,1740481175.1184533,6.939993381500244,0.0,1740481175.1184545,6.939993381500244,0.0,1740481175.1184556,6.939993381500244,0.0,1740481175.1184566,6.939993381500244,0.0,1740481175.1184573,6.939993381500244,0.05867180706361628,1740481175.1184583,6.939993381500244,-0.5867180706361628,1740481175.1184595,6.939993381500244,-0.7305647298182402,1740481175.1184602,6.939993381500244,0.0,1740481175.118461,6.939993381500244,0.20251846624569364,, -1740481175.1385195,6.959993362426758,4.956310224595983,1740481175.138522,6.959993362426758,0.0,1740481175.1385238,6.959993362426758,0.0,1740481175.1385267,6.959993362426758,7.36134715708737,1740481175.1385276,6.959993362426758,0.0,1740481175.1385293,6.959993362426758,0.0,1740481175.1385305,6.959993362426758,0.0,1740481175.138532,6.959993362426758,0.0,1740481175.1385329,6.959993362426758,0.05867180706361628,1740481175.138534,6.959993362426758,-0.5867180706361628,1740481175.1385353,6.959993362426758,-0.7305647298182402,1740481175.1385362,6.959993362426758,0.0,1740481175.138538,6.959993362426758,0.20251846624569364,, -1740481175.1591873,6.9799933433532715,4.956310224595983,1740481175.1591902,6.9799933433532715,0.0,1740481175.1591928,6.9799933433532715,0.0,1740481175.159196,6.9799933433532715,7.36134715708737,1740481175.1591978,6.9799933433532715,0.0,1740481175.1591992,6.9799933433532715,0.0,1740481175.1592007,6.9799933433532715,0.0,1740481175.1592162,6.9799933433532715,0.0,1740481175.15922,6.9799933433532715,0.05867180706361628,1740481175.1592214,6.9799933433532715,-0.5867180706361628,1740481175.1592228,6.9799933433532715,-0.7305647298182402,1740481175.159224,6.9799933433532715,0.0,1740481175.1592257,6.9799933433532715,0.20251846624569364,, -1740481175.1799028,6.999993324279785,4.956310224595983,1740481175.179906,6.999993324279785,0.0,1740481175.1799088,6.999993324279785,0.0,1740481175.1799119,6.999993324279785,7.36134715708737,1740481175.1799133,6.999993324279785,0.0,1740481175.179915,6.999993324279785,0.0,1740481175.1799164,6.999993324279785,0.0,1740481175.1799183,6.999993324279785,0.0,1740481175.1799197,6.999993324279785,0.05867180706361628,1740481175.1799212,6.999993324279785,-0.5867180706361628,1740481175.1799219,6.999993324279785,-0.7305647298182402,1740481175.1799233,6.999993324279785,0.0,1740481175.1799245,6.999993324279785,0.20251846624569364,, -1740481175.1983645,7.019993305206299,4.975267502031452,1740481175.198366,7.019993305206299,0.0,1740481175.198368,7.019993305206299,4.859429015928988e-05,1740481175.19837,7.019993305206299,7.216916767271533,1740481175.1983712,7.019993305206299,0.0,1740481175.1983724,7.019993305206299,0.0,1740481175.1983733,7.019993305206299,0.0,1740481175.1983745,7.019993305206299,0.0,1740481175.1983755,7.019993305206299,0.0,1740481175.1983764,7.019993305206299,0.0,1740481175.1983771,7.019993305206299,-0.12411183877062822,1740481175.1983783,7.019993305206299,0.0,1740481175.198379,7.019993305206299,0.13027897419269516,, -1740481175.2187233,7.0399932861328125,4.975267502031452,1740481175.2187252,7.0399932861328125,0.0,1740481175.2187278,7.0399932861328125,0.0,1740481175.21873,7.0399932861328125,7.235825450416842,1740481175.218731,7.0399932861328125,0.0,1740481175.2187324,7.0399932861328125,0.0,1740481175.2187333,7.0399932861328125,0.0,1740481175.2187343,7.0399932861328125,0.0,1740481175.2187355,7.0399932861328125,0.04289045919028036,1740481175.2187364,7.0399932861328125,-0.42890459190280356,1740481175.2187374,7.0399932861328125,-0.5162931069052183,1740481175.2187383,7.0399932861328125,0.0,1740481175.2187393,7.0399932861328125,0.13027897419269516,, -1740481175.2377393,7.059993267059326,4.975267502031452,1740481175.2377415,7.059993267059326,0.0,1740481175.237744,7.059993267059326,0.0,1740481175.2377467,7.059993267059326,7.235825450416842,1740481175.2377477,7.059993267059326,0.0,1740481175.2377493,7.059993267059326,0.0,1740481175.2377503,7.059993267059326,0.0,1740481175.2377512,7.059993267059326,0.0,1740481175.2377524,7.059993267059326,0.04289045919028036,1740481175.2377536,7.059993267059326,-0.42890459190280356,1740481175.2377546,7.059993267059326,-0.5162931069052183,1740481175.2377555,7.059993267059326,0.0,1740481175.2377565,7.059993267059326,0.13027897419269516,, -1740481175.2594004,7.07999324798584,4.975267502031452,1740481175.2594023,7.07999324798584,0.0,1740481175.2594042,7.07999324798584,0.0,1740481175.2594063,7.07999324798584,7.235825450416842,1740481175.2594073,7.07999324798584,0.0,1740481175.2594087,7.07999324798584,0.0,1740481175.2594097,7.07999324798584,0.0,1740481175.2594106,7.07999324798584,0.0,1740481175.2594118,7.07999324798584,0.04289045919028036,1740481175.2594128,7.07999324798584,-0.42890459190280356,1740481175.2594135,7.07999324798584,-0.5162931069052183,1740481175.2594144,7.07999324798584,0.0,1740481175.2594154,7.07999324798584,0.13027897419269516,, -1740481175.2780843,7.0999932289123535,4.975267502031452,1740481175.2780862,7.0999932289123535,0.0,1740481175.2780883,7.0999932289123535,0.0,1740481175.2780905,7.0999932289123535,7.235825450416842,1740481175.2780912,7.0999932289123535,0.0,1740481175.2780926,7.0999932289123535,0.0,1740481175.2780933,7.0999932289123535,0.0,1740481175.2780943,7.0999932289123535,0.0,1740481175.2780952,7.0999932289123535,0.04289045919028036,1740481175.2780962,7.0999932289123535,-0.42890459190280356,1740481175.2780972,7.0999932289123535,-0.5162931069052183,1740481175.2780979,7.0999932289123535,0.0,1740481175.278099,7.0999932289123535,0.13027897419269516,, -1740481175.2997706,7.119993209838867,4.975267502031452,1740481175.2997723,7.119993209838867,0.0,1740481175.2997742,7.119993209838867,0.0,1740481175.2997766,7.119993209838867,7.235825450416842,1740481175.2997775,7.119993209838867,0.0,1740481175.2997787,7.119993209838867,0.0,1740481175.29978,7.119993209838867,0.0,1740481175.2997808,7.119993209838867,0.0,1740481175.2997818,7.119993209838867,0.04289045919028036,1740481175.299783,7.119993209838867,-0.42890459190280356,1740481175.299784,7.119993209838867,-0.5162931069052183,1740481175.2997847,7.119993209838867,0.0,1740481175.2997856,7.119993209838867,0.13027897419269516,, -1740481175.3188553,7.139993190765381,4.98732594902868,1740481175.318857,7.139993190765381,0.0,1740481175.318859,7.139993190765381,0.0,1740481175.3188612,7.139993190765381,7.145718340569713,1740481175.318862,7.139993190765381,0.0,1740481175.3188634,7.139993190765381,0.0,1740481175.3188646,7.139993190765381,0.0,1740481175.318866,7.139993190765381,0.0,1740481175.318867,7.139993190765381,0.0,1740481175.318868,7.139993190765381,0.0,1740481175.3188689,7.139993190765381,-0.0754724107501941,1740481175.31887,7.139993190765381,0.0,1740481175.3188708,7.139993190765381,0.07919619577051679,, -1740481175.3395753,7.1599931716918945,4.98732594902868,1740481175.3395772,7.1599931716918945,0.0,1740481175.3395789,7.1599931716918945,0.0,1740481175.339581,7.1599931716918945,7.145718340569713,1740481175.339582,7.1599931716918945,0.0,1740481175.3395832,7.1599931716918945,0.0,1740481175.3395844,7.1599931716918945,0.0,1740481175.3395853,7.1599931716918945,0.0,1740481175.339586,7.1599931716918945,0.0,1740481175.3395867,7.1599931716918945,0.0,1740481175.339588,7.1599931716918945,-0.07919619577051679,1740481175.3395886,7.1599931716918945,0.0,1740481175.3395896,7.1599931716918945,0.07919619577051679,, -1740481175.3593423,7.179993152618408,4.98732594902868,1740481175.3593445,7.179993152618408,0.0,1740481175.3593464,7.179993152618408,0.0,1740481175.359349,7.179993152618408,7.145718340569713,1740481175.35935,7.179993152618408,0.0,1740481175.3593514,7.179993152618408,0.0,1740481175.3593524,7.179993152618408,0.0,1740481175.3593535,7.179993152618408,0.0,1740481175.3593547,7.179993152618408,0.0,1740481175.3593557,7.179993152618408,0.0,1740481175.3593564,7.179993152618408,-0.07919619577051679,1740481175.359357,7.179993152618408,0.0,1740481175.3593585,7.179993152618408,0.07919619577051679,, -1740481175.3789616,7.199993133544922,4.98732594902868,1740481175.3789644,7.199993133544922,0.0,1740481175.3789682,7.199993133544922,0.0,1740481175.3789716,7.199993133544922,7.145718340569713,1740481175.3789735,7.199993133544922,0.0,1740481175.3789752,7.199993133544922,0.0,1740481175.3789775,7.199993133544922,0.0,1740481175.3789785,7.199993133544922,0.0,1740481175.3789797,7.199993133544922,0.0,1740481175.378981,7.199993133544922,0.0,1740481175.3789825,7.199993133544922,-0.07919619577051679,1740481175.3789837,7.199993133544922,0.0,1740481175.3789847,7.199993133544922,0.07919619577051679,, -1740481175.3992891,7.2199931144714355,4.98732594902868,1740481175.3992906,7.2199931144714355,0.0,1740481175.399293,7.2199931144714355,0.0,1740481175.3992953,7.2199931144714355,7.145718340569713,1740481175.3992963,7.2199931144714355,0.0,1740481175.3992975,7.2199931144714355,0.0,1740481175.3992982,7.2199931144714355,0.0,1740481175.3992994,7.2199931144714355,0.0,1740481175.3993003,7.2199931144714355,0.0,1740481175.399301,7.2199931144714355,0.0,1740481175.399302,7.2199931144714355,-0.07919619577051679,1740481175.399303,7.2199931144714355,0.0,1740481175.399304,7.2199931144714355,0.07919619577051679,, -1740481175.418495,7.239993095397949,4.9946015754600595,1740481175.4184968,7.239993095397949,0.0,1740481175.4184988,7.239993095397949,0.0,1740481175.418501,7.239993095397949,7.1019308120111155,1740481175.4185019,7.239993095397949,0.0,1740481175.4185033,7.239993095397949,0.0,1740481175.4185042,7.239993095397949,0.0,1740481175.4185052,7.239993095397949,0.0,1740481175.418506,7.239993095397949,6.8607612444537835e-06,1740481175.4185069,7.239993095397949,0.0,1740481175.4185078,7.239993095397949,-0.04204936541809744,1740481175.4185085,7.239993095397949,0.0,1740481175.4185092,7.239993095397949,0.053664618275527896,, -1740481175.437816,7.259993076324463,4.9946015754600595,1740481175.4378173,7.259993076324463,0.0,1740481175.4378195,7.259993076324463,0.0,1740481175.4378214,7.259993076324463,7.1019308120111155,1740481175.4378226,7.259993076324463,0.0,1740481175.4378235,7.259993076324463,0.0,1740481175.4378245,7.259993076324463,0.0,1740481175.4378254,7.259993076324463,0.0,1740481175.4378264,7.259993076324463,6.8607612444537835e-06,1740481175.4378273,7.259993076324463,0.0,1740481175.437828,7.259993076324463,-0.05365775751428344,1740481175.4378288,7.259993076324463,0.0,1740481175.43783,7.259993076324463,0.053664618275527896,, -1740481175.4575279,7.279993057250977,4.9946015754600595,1740481175.4575295,7.279993057250977,0.0,1740481175.4575317,7.279993057250977,0.0,1740481175.4575334,7.279993057250977,7.1019308120111155,1740481175.4575346,7.279993057250977,0.0,1740481175.4575357,7.279993057250977,0.0,1740481175.4575365,7.279993057250977,0.0,1740481175.4575377,7.279993057250977,0.0,1740481175.4575384,7.279993057250977,6.8607612444537835e-06,1740481175.4575393,7.279993057250977,0.0,1740481175.45754,7.279993057250977,-0.05365775751428344,1740481175.4575408,7.279993057250977,0.0,1740481175.457542,7.279993057250977,0.053664618275527896,, -1740481175.4776907,7.29999303817749,4.9946015754600595,1740481175.4776921,7.29999303817749,0.0,1740481175.4776943,7.29999303817749,0.0,1740481175.4776962,7.29999303817749,7.1019308120111155,1740481175.4776974,7.29999303817749,0.0,1740481175.4776983,7.29999303817749,0.0,1740481175.4776993,7.29999303817749,0.0,1740481175.4777002,7.29999303817749,0.0,1740481175.4777012,7.29999303817749,6.8607612444537835e-06,1740481175.477702,7.29999303817749,0.0,1740481175.4777029,7.29999303817749,-0.05365775751428344,1740481175.4777036,7.29999303817749,0.0,1740481175.4777045,7.29999303817749,0.053664618275527896,, -1740481175.4984784,7.319993019104004,4.9946015754600595,1740481175.49848,7.319993019104004,0.0,1740481175.4984822,7.319993019104004,0.0,1740481175.4984841,7.319993019104004,7.1019308120111155,1740481175.4984853,7.319993019104004,0.0,1740481175.4984865,7.319993019104004,0.0,1740481175.4984875,7.319993019104004,0.0,1740481175.4984884,7.319993019104004,0.0,1740481175.4984891,7.319993019104004,6.8607612444537835e-06,1740481175.49849,7.319993019104004,0.0,1740481175.498491,7.319993019104004,-0.05365775751428344,1740481175.498492,7.319993019104004,0.0,1740481175.498493,7.319993019104004,0.053664618275527896,, -1740481175.518728,7.339993000030518,4.9946015754600595,1740481175.5187304,7.339993000030518,0.0,1740481175.518733,7.339993000030518,0.0,1740481175.5187366,7.339993000030518,7.1019308120111155,1740481175.5187385,7.339993000030518,0.0,1740481175.5187402,7.339993000030518,0.0,1740481175.5187416,7.339993000030518,0.0,1740481175.518743,7.339993000030518,0.0,1740481175.5187445,7.339993000030518,6.8607612444537835e-06,1740481175.518746,7.339993000030518,0.0,1740481175.5187469,7.339993000030518,-0.05365775751428344,1740481175.5187485,7.339993000030518,0.0,1740481175.5187497,7.339993000030518,0.053664618275527896,, -1740481175.5381873,7.359992980957031,4.999391470456887,1740481175.5381896,7.359992980957031,0.0,1740481175.5381918,7.359992980957031,8.292862185443946e-07,1740481175.5381942,7.359992980957031,7.057448390336796,1740481175.5381954,7.359992980957031,0.0,1740481175.538197,7.359992980957031,0.0,1740481175.538198,7.359992980957031,0.0,1740481175.5381992,7.359992980957031,0.0,1740481175.5382001,7.359992980957031,6.8607612444537835e-06,1740481175.5382023,7.359992980957031,0.0,1740481175.5382035,7.359992980957031,-0.021306292628761783,1740481175.5382044,7.359992980957031,0.0,1740481175.5382054,7.359992980957031,0.03142299279525901,, -1740481175.5586,7.379992961883545,4.999391470456887,1740481175.5586023,7.379992961883545,0.0,1740481175.5586047,7.379992961883545,8.292862185443946e-07,1740481175.5586069,7.379992961883545,7.057448390336796,1740481175.558608,7.379992961883545,0.0,1740481175.55861,7.379992961883545,0.0,1740481175.5586112,7.379992961883545,0.0,1740481175.5586126,7.379992961883545,0.0,1740481175.5586135,7.379992961883545,6.8607612444537835e-06,1740481175.5586145,7.379992961883545,0.0,1740481175.558616,7.379992961883545,-0.031416132034014554,1740481175.558617,7.379992961883545,0.0,1740481175.558618,7.379992961883545,0.03142299279525901,, -1740481175.5780513,7.399992942810059,4.999391470456887,1740481175.5780528,7.399992942810059,0.0,1740481175.578055,7.399992942810059,8.292862185443946e-07,1740481175.5780568,7.399992942810059,7.057448390336796,1740481175.578058,7.399992942810059,0.0,1740481175.5780594,7.399992942810059,0.0,1740481175.5780606,7.399992942810059,0.0,1740481175.5780618,7.399992942810059,0.0,1740481175.5780628,7.399992942810059,6.8607612444537835e-06,1740481175.578064,7.399992942810059,0.0,1740481175.5780647,7.399992942810059,-0.031416132034014554,1740481175.5780659,7.399992942810059,0.0,1740481175.5780666,7.399992942810059,0.03142299279525901,, -1740481175.5996542,7.419992923736572,4.999391470456887,1740481175.5996563,7.419992923736572,0.0,1740481175.599659,7.419992923736572,8.292862185443946e-07,1740481175.5996616,7.419992923736572,7.057448390336796,1740481175.5996628,7.419992923736572,0.0,1740481175.5996644,7.419992923736572,0.0,1740481175.5996656,7.419992923736572,0.0,1740481175.5996668,7.419992923736572,0.0,1740481175.5996683,7.419992923736572,6.8607612444537835e-06,1740481175.5996695,7.419992923736572,0.0,1740481175.5996704,7.419992923736572,-0.031416132034014554,1740481175.5996716,7.419992923736572,0.0,1740481175.5996728,7.419992923736572,0.03142299279525901,, -1740481175.618341,7.439992904663086,4.999391470456887,1740481175.6183426,7.439992904663086,0.0,1740481175.6183448,7.439992904663086,0.0,1740481175.6183465,7.439992904663086,7.062237456047405,1740481175.6183474,7.439992904663086,0.0,1740481175.6183603,7.439992904663086,0.0,1740481175.618362,7.439992904663086,0.0,1740481175.618363,7.439992904663086,0.0,1740481175.6183639,7.439992904663086,0.028988874622964175,1740481175.6183646,7.439992904663086,-0.289448024298301,1740481175.6183658,7.439992904663086,-0.29188214247059585,1740481175.6183665,7.439992904663086,0.0,1740481175.6183674,7.439992904663086,0.03142299279525901,, -1740481175.6392107,7.4599928855896,5.001731794721099,1740481175.6392124,7.4599928855896,0.0,1740481175.6392155,7.4599928855896,1.7742952393302485e-05,1740481175.6392176,7.4599928855896,7.014344792196951,1740481175.6392183,7.4599928855896,0.0,1740481175.6392198,7.4599928855896,0.0,1740481175.6392207,7.4599928855896,0.0,1740481175.6392214,7.4599928855896,0.0,1740481175.6392224,7.4599928855896,4.40721931340704e-05,1740481175.6392233,7.4599928855896,0.0,1740481175.6392243,7.4599928855896,-0.00969171892200337,1740481175.639225,7.4599928855896,0.0,1740481175.6392262,7.4599928855896,0.0074677893938357165,, -1740481175.6577368,7.479992866516113,5.001731794721099,1740481175.6577384,7.479992866516113,0.0,1740481175.6577404,7.479992866516113,1.7742952393302485e-05,1740481175.6577425,7.479992866516113,7.014344792196951,1740481175.6577435,7.479992866516113,0.0,1740481175.6577446,7.479992866516113,0.0,1740481175.6577454,7.479992866516113,0.0,1740481175.6577463,7.479992866516113,0.0,1740481175.6577475,7.479992866516113,4.40721931340704e-05,1740481175.6577485,7.479992866516113,0.0,1740481175.6577492,7.479992866516113,-0.007423717200701646,1740481175.6577501,7.479992866516113,0.0,1740481175.6577508,7.479992866516113,0.0074677893938357165,, -1740481175.6782453,7.499992847442627,5.001731794721099,1740481175.6782472,7.499992847442627,0.0,1740481175.6782491,7.499992847442627,1.7742952393302485e-05,1740481175.678251,7.499992847442627,7.014344792196951,1740481175.678252,7.499992847442627,0.0,1740481175.6782532,7.499992847442627,0.0,1740481175.6782541,7.499992847442627,0.0,1740481175.678255,7.499992847442627,0.0,1740481175.678256,7.499992847442627,4.40721931340704e-05,1740481175.678257,7.499992847442627,0.0,1740481175.678258,7.499992847442627,-0.007423717200701646,1740481175.6782587,7.499992847442627,0.0,1740481175.6782594,7.499992847442627,0.0074677893938357165,, -1740481175.6981564,7.519992828369141,5.001731794721099,1740481175.698158,7.519992828369141,0.0,1740481175.69816,7.519992828369141,1.7742952393302485e-05,1740481175.6981616,7.519992828369141,7.014344792196951,1740481175.6981628,7.519992828369141,0.0,1740481175.6981637,7.519992828369141,0.0,1740481175.6981647,7.519992828369141,0.0,1740481175.6981657,7.519992828369141,0.0,1740481175.6981666,7.519992828369141,4.40721931340704e-05,1740481175.6981676,7.519992828369141,0.0,1740481175.6981685,7.519992828369141,-0.007423717200701646,1740481175.6981692,7.519992828369141,0.0,1740481175.6981702,7.519992828369141,0.0074677893938357165,, -1740481175.7236679,7.539992809295654,5.001731794721099,1740481175.7236698,7.539992809295654,0.0,1740481175.7236722,7.539992809295654,0.0,1740481175.723674,7.539992809295654,7.016667373508771,1740481175.7236753,7.539992809295654,0.0,1740481175.7236764,7.539992809295654,0.0,1740481175.7236774,7.539992809295654,0.0,1740481175.7236784,7.539992809295654,0.0,1740481175.7236795,7.539992809295654,3.491539030228257e-06,1740481175.7236803,7.539992809295654,0.0,1740481175.7236812,7.539992809295654,-0.0074642978548054885,1740481175.7236822,7.539992809295654,0.0,1740481175.723683,7.539992809295654,0.0074677893938357165,, -1740481175.7379806,7.559992790222168,5.001731794721099,1740481175.7379823,7.559992790222168,0.0,1740481175.7379847,7.559992790222168,0.0,1740481175.737987,7.559992790222168,7.016667373508771,1740481175.7379878,7.559992790222168,0.0,1740481175.7379892,7.559992790222168,0.0,1740481175.7379901,7.559992790222168,0.0,1740481175.737991,7.559992790222168,0.0,1740481175.737992,7.559992790222168,3.491539030228257e-06,1740481175.737993,7.559992790222168,0.0,1740481175.7379937,7.559992790222168,-0.0074642978548054885,1740481175.7379947,7.559992790222168,0.0,1740481175.7379956,7.559992790222168,0.0074677893938357165,, -1740481175.7577147,7.579992771148682,5.001910322093941,1740481175.7577164,7.579992771148682,0.0,1740481175.7577188,7.579992771148682,6.222558014778727e-10,1740481175.757721,7.579992771148682,7.001731795343355,1740481175.757722,7.579992771148682,0.0,1740481175.7577233,7.579992771148682,0.0,1740481175.7577245,7.579992771148682,0.0,1740481175.7577255,7.579992771148682,0.0,1740481175.7577267,7.579992771148682,3.491539030228257e-06,1740481175.7577279,7.579992771148682,0.0,1740481175.7577288,7.579992771148682,0.0033979445007036166,1740481175.7577298,7.579992771148682,0.0,1740481175.7577305,7.579992771148682,0.0,, -1740481175.777653,7.599992752075195,5.001910322093941,1740481175.7776554,7.599992752075195,0.0,1740481175.7776573,7.599992752075195,6.222558014778727e-10,1740481175.7776597,7.599992752075195,7.001731795343355,1740481175.7776606,7.599992752075195,0.0,1740481175.777662,7.599992752075195,0.0,1740481175.777663,7.599992752075195,0.0,1740481175.777664,7.599992752075195,0.0,1740481175.7776651,7.599992752075195,3.491539030228257e-06,1740481175.777666,7.599992752075195,0.0,1740481175.7776668,7.599992752075195,3.491539030228257e-06,1740481175.7776678,7.599992752075195,0.0,1740481175.777669,7.599992752075195,0.0,, -1740481175.7987216,7.619992733001709,5.001910322093941,1740481175.7987237,7.619992733001709,0.0,1740481175.7987256,7.619992733001709,6.222558014778727e-10,1740481175.798728,7.619992733001709,7.001731795343355,1740481175.798729,7.619992733001709,0.0,1740481175.7987301,7.619992733001709,0.0,1740481175.7987313,7.619992733001709,0.0,1740481175.7987323,7.619992733001709,0.0,1740481175.7987332,7.619992733001709,3.491539030228257e-06,1740481175.7987344,7.619992733001709,0.0,1740481175.7987354,7.619992733001709,3.491539030228257e-06,1740481175.798736,7.619992733001709,0.0,1740481175.798737,7.619992733001709,0.0,, -1740481175.818356,7.639992713928223,5.001910322093941,1740481175.8183575,7.639992713928223,0.0,1740481175.8183594,7.639992713928223,0.0,1740481175.818361,7.639992713928223,7.001910322093941,1740481175.818362,7.639992713928223,0.0,1740481175.8183632,7.639992713928223,0.0,1740481175.8183641,7.639992713928223,0.0,1740481175.818365,7.639992713928223,0.0,1740481175.818366,7.639992713928223,0.0,1740481175.818367,7.639992713928223,-2.0,1740481175.818368,7.639992713928223,-2.0,1740481175.8183687,7.639992713928223,0.0,1740481175.8183696,7.639992713928223,0.0,, -1740481175.838949,7.659992694854736,5.001910322093941,1740481175.8389504,7.659992694854736,0.0,1740481175.8389525,7.659992694854736,0.0,1740481175.8389544,7.659992694854736,7.001910322093941,1740481175.8389554,7.659992694854736,0.0,1740481175.8389566,7.659992694854736,0.0,1740481175.8389575,7.659992694854736,0.0,1740481175.8389585,7.659992694854736,0.0,1740481175.8389595,7.659992694854736,0.0,1740481175.8389604,7.659992694854736,-2.0,1740481175.8389611,7.659992694854736,-2.0,1740481175.838962,7.659992694854736,0.0,1740481175.838963,7.659992694854736,0.0,, -1740481175.8575957,7.67999267578125,5.001914059077752,1740481175.8575969,7.67999267578125,0.0,1740481175.8575988,7.67999267578125,0.0,1740481175.8576007,7.67999267578125,7.001910322093941,1740481175.857602,7.67999267578125,0.0,1740481175.8576028,7.67999267578125,0.0,1740481175.8576038,7.67999267578125,0.0,1740481175.857605,7.67999267578125,0.0,1740481175.857606,7.67999267578125,0.0,1740481175.857607,7.67999267578125,-2.0,1740481175.8576076,7.67999267578125,-2.0,1740481175.8576088,7.67999267578125,0.0,1740481175.8576097,7.67999267578125,0.0,, -1740481175.8788037,7.699992656707764,5.001914059077752,1740481175.878806,7.699992656707764,0.0,1740481175.8788085,7.699992656707764,0.0,1740481175.8788106,7.699992656707764,7.001910322093941,1740481175.8788116,7.699992656707764,0.0,1740481175.8788137,7.699992656707764,0.0,1740481175.8788147,7.699992656707764,0.0,1740481175.878816,7.699992656707764,0.0,1740481175.8788176,7.699992656707764,0.0,1740481175.878819,7.699992656707764,-2.0,1740481175.8788207,7.699992656707764,-2.0,1740481175.8788218,7.699992656707764,0.0,1740481175.8788233,7.699992656707764,0.0,, -1740481175.8979528,7.719992637634277,5.001914059077752,1740481175.8979542,7.719992637634277,0.0,1740481175.8979564,7.719992637634277,0.0,1740481175.8979585,7.719992637634277,7.001910322093941,1740481175.8979597,7.719992637634277,0.0,1740481175.8979607,7.719992637634277,0.0,1740481175.8979616,7.719992637634277,0.0,1740481175.8979628,7.719992637634277,0.0,1740481175.8979635,7.719992637634277,0.0,1740481175.8979645,7.719992637634277,-2.0,1740481175.8979657,7.719992637634277,-2.0,1740481175.8979666,7.719992637634277,0.0,1740481175.8979673,7.719992637634277,0.0,, -1740481175.9188716,7.739992618560791,5.001914059077752,1740481175.918873,7.739992618560791,0.0,1740481175.9188752,7.739992618560791,0.0,1740481175.918877,7.739992618560791,7.001914059077752,1740481175.9188778,7.739992618560791,0.0,1740481175.9188793,7.739992618560791,0.0,1740481175.9188802,7.739992618560791,0.0,1740481175.9188812,7.739992618560791,0.0,1740481175.9188824,7.739992618560791,0.0,1740481175.918883,7.739992618560791,-2.0,1740481175.918884,7.739992618560791,-2.0,1740481175.9188848,7.739992618560791,0.0,1740481175.918886,7.739992618560791,0.0,, -1740481175.9376473,7.759992599487305,5.001914059077752,1740481175.9376485,7.759992599487305,0.0,1740481175.9376507,7.759992599487305,0.0,1740481175.9376526,7.759992599487305,7.001914059077752,1740481175.9376535,7.759992599487305,0.0,1740481175.937655,7.759992599487305,0.0,1740481175.9376562,7.759992599487305,0.0,1740481175.937657,7.759992599487305,0.0,1740481175.9376578,7.759992599487305,0.0,1740481175.9376588,7.759992599487305,-2.0,1740481175.93766,7.759992599487305,-2.0,1740481175.9376607,7.759992599487305,0.0,1740481175.9376616,7.759992599487305,0.0,, -1740481175.957789,7.779992580413818,5.001914059077752,1740481175.9577901,7.779992580413818,0.0,1740481175.9577925,7.779992580413818,0.0,1740481175.9577947,7.779992580413818,7.001914059077752,1740481175.9577956,7.779992580413818,0.0,1740481175.9577968,7.779992580413818,0.0,1740481175.957798,7.779992580413818,0.0,1740481175.957799,7.779992580413818,0.0,1740481175.9578,7.779992580413818,0.0,1740481175.9578009,7.779992580413818,-2.0,1740481175.9578018,7.779992580413818,-2.0,1740481175.9578028,7.779992580413818,0.0,1740481175.9578035,7.779992580413818,0.0,, -1740481175.9780893,7.799992561340332,5.001914059077752,1740481175.9780908,7.799992561340332,0.0,1740481175.9780924,7.799992561340332,0.0,1740481175.9780946,7.799992561340332,7.001914059077752,1740481175.978108,7.799992561340332,0.0,1740481175.978111,7.799992561340332,0.0,1740481175.978112,7.799992561340332,0.0,1740481175.978113,7.799992561340332,0.0,1740481175.9781141,7.799992561340332,0.0,1740481175.978115,7.799992561340332,-2.0,1740481175.9781158,7.799992561340332,-2.0,1740481175.9781168,7.799992561340332,0.0,1740481175.978118,7.799992561340332,0.0,, -1740481175.9982185,7.819992542266846,5.001914059077752,1740481175.99822,7.819992542266846,0.0,1740481175.9982219,7.819992542266846,0.0,1740481175.9982238,7.819992542266846,7.001914059077752,1740481175.998225,7.819992542266846,0.0,1740481175.9982262,7.819992542266846,0.0,1740481175.9982271,7.819992542266846,0.0,1740481175.9982283,7.819992542266846,0.0,1740481175.9982293,7.819992542266846,0.0,1740481175.9982302,7.819992542266846,-2.0,1740481175.9982314,7.819992542266846,-2.0,1740481175.9982321,7.819992542266846,0.0,1740481175.998233,7.819992542266846,0.0,, -1740481176.0186312,7.839992523193359,5.001914059077752,1740481176.0186327,7.839992523193359,0.0,1740481176.0186346,7.839992523193359,0.0,1740481176.0186365,7.839992523193359,7.001914059077752,1740481176.0186377,7.839992523193359,0.0,1740481176.0186388,7.839992523193359,0.0,1740481176.0186398,7.839992523193359,0.0,1740481176.018641,7.839992523193359,0.0,1740481176.018642,7.839992523193359,0.0,1740481176.0186427,7.839992523193359,-2.0,1740481176.0186436,7.839992523193359,-2.0,1740481176.0186446,7.839992523193359,0.0,1740481176.0186453,7.839992523193359,0.0,, -1740481176.0383449,7.859992504119873,5.001914059077752,1740481176.0383465,7.859992504119873,0.0,1740481176.0383482,7.859992504119873,0.0,1740481176.0383503,7.859992504119873,7.001914059077752,1740481176.0383642,7.859992504119873,0.0,1740481176.0383668,7.859992504119873,0.0,1740481176.0383675,7.859992504119873,0.0,1740481176.0383685,7.859992504119873,0.0,1740481176.0383694,7.859992504119873,0.0,1740481176.0383704,7.859992504119873,-2.0,1740481176.038371,7.859992504119873,-2.0,1740481176.038372,7.859992504119873,0.0,1740481176.0383728,7.859992504119873,0.0,, -1740481176.0576034,7.879992485046387,5.001914059077752,1740481176.0576048,7.879992485046387,0.0,1740481176.057607,7.879992485046387,0.0,1740481176.0576093,7.879992485046387,7.001914059077752,1740481176.0576105,7.879992485046387,0.0,1740481176.057612,7.879992485046387,0.0,1740481176.0576131,7.879992485046387,0.0,1740481176.0576138,7.879992485046387,0.0,1740481176.057615,7.879992485046387,0.0,1740481176.0576162,7.879992485046387,-2.0,1740481176.0576172,7.879992485046387,-2.0,1740481176.0576181,7.879992485046387,0.0,1740481176.057619,7.879992485046387,0.0,, -1740481176.0782528,7.8999924659729,5.001914059077752,1740481176.0782542,7.8999924659729,0.0,1740481176.0782564,7.8999924659729,0.0,1740481176.0782585,7.8999924659729,7.001914059077752,1740481176.0782595,7.8999924659729,0.0,1740481176.0782607,7.8999924659729,0.0,1740481176.0782619,7.8999924659729,0.0,1740481176.0782628,7.8999924659729,0.0,1740481176.0782635,7.8999924659729,0.0,1740481176.0782645,7.8999924659729,-2.0,1740481176.0782657,7.8999924659729,-2.0,1740481176.0782664,7.8999924659729,0.0,1740481176.0782673,7.8999924659729,0.0,, -1740481176.1017756,7.919992446899414,5.001914059077752,1740481176.101777,7.919992446899414,0.0,1740481176.1017792,7.919992446899414,0.0,1740481176.1017811,7.919992446899414,7.001914059077752,1740481176.1017823,7.919992446899414,0.0,1740481176.1017835,7.919992446899414,0.0,1740481176.101785,7.919992446899414,0.0,1740481176.101786,7.919992446899414,0.0,1740481176.1017866,7.919992446899414,0.0,1740481176.1017878,7.919992446899414,-2.0,1740481176.1017888,7.919992446899414,-2.0,1740481176.1017897,7.919992446899414,0.0,1740481176.1017904,7.919992446899414,0.0,, -1740481176.1186087,7.939992427825928,5.001914059077752,1740481176.1186101,7.939992427825928,0.0,1740481176.1186125,7.939992427825928,0.0,1740481176.1186144,7.939992427825928,7.001914059077752,1740481176.1186156,7.939992427825928,0.0,1740481176.118617,7.939992427825928,0.0,1740481176.118618,7.939992427825928,0.0,1740481176.1186192,7.939992427825928,0.0,1740481176.1186337,7.939992427825928,0.0,1740481176.118635,7.939992427825928,-2.0,1740481176.1186361,7.939992427825928,-2.0,1740481176.1186368,7.939992427825928,0.0,1740481176.1186378,7.939992427825928,0.0,, -1740481176.1386824,7.959992408752441,5.001914059077752,1740481176.1386836,7.959992408752441,0.0,1740481176.1386857,7.959992408752441,0.0,1740481176.1386886,7.959992408752441,7.001914059077752,1740481176.1386893,7.959992408752441,0.0,1740481176.1386905,7.959992408752441,0.0,1740481176.1386917,7.959992408752441,0.0,1740481176.1386926,7.959992408752441,0.0,1740481176.1386936,7.959992408752441,0.0,1740481176.1386948,7.959992408752441,-2.0,1740481176.1386955,7.959992408752441,-2.0,1740481176.1386962,7.959992408752441,0.0,1740481176.1386971,7.959992408752441,0.0,, -1740481176.1584785,7.979992389678955,5.001914059077752,1740481176.1584835,7.979992389678955,0.0,1740481176.158487,7.979992389678955,0.0,1740481176.1584892,7.979992389678955,7.001914059077752,1740481176.1584904,7.979992389678955,0.0,1740481176.1584916,7.979992389678955,0.0,1740481176.1584926,7.979992389678955,0.0,1740481176.1584938,7.979992389678955,0.0,1740481176.1584947,7.979992389678955,0.0,1740481176.1584957,7.979992389678955,-2.0,1740481176.1584969,7.979992389678955,-2.0,1740481176.1584976,7.979992389678955,0.0,1740481176.1584988,7.979992389678955,0.0,, -1740481176.1776597,7.999992370605469,5.001914059077752,1740481176.1776612,7.999992370605469,0.0,1740481176.1776633,7.999992370605469,0.0,1740481176.1776655,7.999992370605469,7.001914059077752,1740481176.1776667,7.999992370605469,0.0,1740481176.1776679,7.999992370605469,0.0,1740481176.1776688,7.999992370605469,0.0,1740481176.17767,7.999992370605469,0.0,1740481176.177671,7.999992370605469,0.0,1740481176.1776721,7.999992370605469,-2.0,1740481176.1776729,7.999992370605469,-2.0,1740481176.177674,7.999992370605469,0.0,1740481176.1776748,7.999992370605469,0.0,, -1740481176.1982331,8.019992351531982,5.001914059077752,1740481176.1982346,8.019992351531982,0.0,1740481176.1982367,8.019992351531982,0.0,1740481176.1982386,8.019992351531982,7.001914059077752,1740481176.1982398,8.019992351531982,0.0,1740481176.1982412,8.019992351531982,0.0,1740481176.1982422,8.019992351531982,0.0,1740481176.1982434,8.019992351531982,0.0,1740481176.1982443,8.019992351531982,0.0,1740481176.1982455,8.019992351531982,-2.0,1740481176.1982467,8.019992351531982,-2.0,1740481176.1982477,8.019992351531982,0.0,1740481176.1982486,8.019992351531982,0.0,, -1740481176.2188714,8.039992332458496,5.001914059077752,1740481176.2188728,8.039992332458496,0.0,1740481176.2188752,8.039992332458496,0.0,1740481176.218877,8.039992332458496,7.001914059077752,1740481176.218878,8.039992332458496,0.0,1740481176.2188792,8.039992332458496,0.0,1740481176.2188802,8.039992332458496,0.0,1740481176.2188814,8.039992332458496,0.0,1740481176.2188823,8.039992332458496,0.0,1740481176.2188833,8.039992332458496,-2.0,1740481176.218884,8.039992332458496,-2.0,1740481176.2188852,8.039992332458496,0.0,1740481176.218886,8.039992332458496,0.0,, -1740481176.2375383,8.05999231338501,5.001914059077752,1740481176.2375398,8.05999231338501,0.0,1740481176.2375422,8.05999231338501,0.0,1740481176.2375443,8.05999231338501,7.001914059077752,1740481176.2375453,8.05999231338501,0.0,1740481176.2375467,8.05999231338501,0.0,1740481176.237548,8.05999231338501,0.0,1740481176.237549,8.05999231338501,0.0,1740481176.23755,8.05999231338501,0.0,1740481176.2375512,8.05999231338501,-2.0,1740481176.2375522,8.05999231338501,-2.0,1740481176.2375531,8.05999231338501,0.0,1740481176.2375538,8.05999231338501,0.0,, -1740481176.2581446,8.079992294311523,5.001914059077752,1740481176.258146,8.079992294311523,0.0,1740481176.2581482,8.079992294311523,0.0,1740481176.2581506,8.079992294311523,7.001914059077752,1740481176.2581518,8.079992294311523,0.0,1740481176.258153,8.079992294311523,0.0,1740481176.258154,8.079992294311523,0.0,1740481176.258155,8.079992294311523,0.0,1740481176.258156,8.079992294311523,0.0,1740481176.2581573,8.079992294311523,-2.0,1740481176.258158,8.079992294311523,-2.0,1740481176.2581592,8.079992294311523,0.0,1740481176.25816,8.079992294311523,0.0,, -1740481176.277517,8.099992275238037,5.001914059077752,1740481176.2775183,8.099992275238037,0.0,1740481176.2775202,8.099992275238037,0.0,1740481176.277522,8.099992275238037,7.001914059077752,1740481176.2775233,8.099992275238037,0.0,1740481176.2775245,8.099992275238037,0.0,1740481176.2775252,8.099992275238037,0.0,1740481176.2775264,8.099992275238037,0.0,1740481176.2775273,8.099992275238037,0.0,1740481176.277528,8.099992275238037,-2.0,1740481176.2775292,8.099992275238037,-2.0,1740481176.2775302,8.099992275238037,0.0,1740481176.2775314,8.099992275238037,0.0,, -1740481176.2985659,8.11999225616455,5.001914059077752,1740481176.2985675,8.11999225616455,0.0,1740481176.2985694,8.11999225616455,0.0,1740481176.2985716,8.11999225616455,7.001914059077752,1740481176.2985725,8.11999225616455,0.0,1740481176.2985737,8.11999225616455,0.0,1740481176.298575,8.11999225616455,0.0,1740481176.298576,8.11999225616455,0.0,1740481176.298577,8.11999225616455,0.0,1740481176.2985783,8.11999225616455,-2.0,1740481176.298579,8.11999225616455,-2.0,1740481176.29858,8.11999225616455,0.0,1740481176.298581,8.11999225616455,0.0,, -1740481176.319487,8.139992237091064,5.001914059077752,1740481176.3194883,8.139992237091064,0.0,1740481176.3194902,8.139992237091064,0.0,1740481176.319492,8.139992237091064,7.001914059077752,1740481176.319493,8.139992237091064,0.0,1740481176.3194942,8.139992237091064,0.0,1740481176.319495,8.139992237091064,0.0,1740481176.319496,8.139992237091064,0.0,1740481176.3194969,8.139992237091064,0.0,1740481176.319498,8.139992237091064,-2.0,1740481176.3194988,8.139992237091064,-2.0,1740481176.3194997,8.139992237091064,0.0,1740481176.3195004,8.139992237091064,0.0,, -1740481176.339816,8.159992218017578,5.001914059077752,1740481176.3398182,8.159992218017578,0.0,1740481176.339821,8.159992218017578,0.0,1740481176.339824,8.159992218017578,7.001914059077752,1740481176.3398252,8.159992218017578,0.0,1740481176.339827,8.159992218017578,0.0,1740481176.3398287,8.159992218017578,0.0,1740481176.33983,8.159992218017578,0.0,1740481176.3398314,8.159992218017578,0.0,1740481176.3398325,8.159992218017578,-2.0,1740481176.3398335,8.159992218017578,-2.0,1740481176.3398354,8.159992218017578,0.0,1740481176.3398366,8.159992218017578,0.0,, -1740481176.3589685,8.179992198944092,5.001914059077752,1740481176.3589702,8.179992198944092,0.0,1740481176.358972,8.179992198944092,0.0,1740481176.3589742,8.179992198944092,7.001914059077752,1740481176.3589752,8.179992198944092,0.0,1740481176.3589766,8.179992198944092,0.0,1740481176.3589773,8.179992198944092,0.0,1740481176.3589783,8.179992198944092,0.0,1740481176.3589792,8.179992198944092,0.0,1740481176.3589802,8.179992198944092,-2.0,1740481176.3589811,8.179992198944092,-2.0,1740481176.359036,8.179992198944092,0.0,1740481176.359038,8.179992198944092,0.0,, -1740481176.37798,8.199992179870605,5.001914059077752,1740481176.3779812,8.199992179870605,0.0,1740481176.3779833,8.199992179870605,0.0,1740481176.3779855,8.199992179870605,7.001914059077752,1740481176.3779862,8.199992179870605,0.0,1740481176.3779876,8.199992179870605,0.0,1740481176.3779886,8.199992179870605,0.0,1740481176.3779893,8.199992179870605,0.0,1740481176.3779905,8.199992179870605,0.0,1740481176.3779914,8.199992179870605,-2.0,1740481176.3779924,8.199992179870605,-2.0,1740481176.377993,8.199992179870605,0.0,1740481176.3779943,8.199992179870605,0.0,, -1740481176.397568,8.21999216079712,5.001914059077752,1740481176.3975694,8.21999216079712,0.0,1740481176.3975902,8.21999216079712,0.0,1740481176.3975925,8.21999216079712,7.001914059077752,1740481176.3975933,8.21999216079712,0.0,1740481176.397595,8.21999216079712,0.0,1740481176.3975961,8.21999216079712,0.0,1740481176.397597,8.21999216079712,0.0,1740481176.3975983,8.21999216079712,0.0,1740481176.397599,8.21999216079712,-2.0,1740481176.3975997,8.21999216079712,-2.0,1740481176.3976007,8.21999216079712,0.0,1740481176.3976254,8.21999216079712,0.0,, -1740481176.4193244,8.239992141723633,5.001914059077752,1740481176.4193263,8.239992141723633,0.0,1740481176.419328,8.239992141723633,0.0,1740481176.4193301,8.239992141723633,7.001914059077752,1740481176.4193308,8.239992141723633,0.0,1740481176.419332,8.239992141723633,0.0,1740481176.4193332,8.239992141723633,0.0,1740481176.4193342,8.239992141723633,0.0,1740481176.419335,8.239992141723633,0.0,1740481176.4193358,8.239992141723633,-2.0,1740481176.419337,8.239992141723633,-2.0,1740481176.4193377,8.239992141723633,0.0,1740481176.4193385,8.239992141723633,0.0,, -1740481176.4394937,8.259992122650146,5.001914059077752,1740481176.439495,8.259992122650146,0.0,1740481176.4394972,8.259992122650146,0.0,1740481176.4394994,8.259992122650146,7.001914059077752,1740481176.4395006,8.259992122650146,0.0,1740481176.4395018,8.259992122650146,0.0,1740481176.4395025,8.259992122650146,0.0,1740481176.439504,8.259992122650146,0.0,1740481176.4395049,8.259992122650146,0.0,1740481176.4395058,8.259992122650146,-2.0,1740481176.439507,8.259992122650146,-2.0,1740481176.439508,8.259992122650146,0.0,1740481176.4395087,8.259992122650146,0.0,, -1740481176.4592407,8.27999210357666,5.001914059077752,1740481176.4592423,8.27999210357666,0.0,1740481176.4592443,8.27999210357666,0.0,1740481176.4592464,8.27999210357666,7.001914059077752,1740481176.4592474,8.27999210357666,0.0,1740481176.4592488,8.27999210357666,0.0,1740481176.45925,8.27999210357666,0.0,1740481176.459251,8.27999210357666,0.0,1740481176.4592519,8.27999210357666,0.0,1740481176.459253,8.27999210357666,-2.0,1740481176.4592543,8.27999210357666,-2.0,1740481176.4592552,8.27999210357666,0.0,1740481176.4592562,8.27999210357666,0.0,, -1740481176.4787219,8.299992084503174,5.001914059077752,1740481176.4787235,8.299992084503174,0.0,1740481176.4787257,8.299992084503174,0.0,1740481176.4787276,8.299992084503174,7.001914059077752,1740481176.4787288,8.299992084503174,0.0,1740481176.47873,8.299992084503174,0.0,1740481176.4787312,8.299992084503174,0.0,1740481176.4787323,8.299992084503174,0.0,1740481176.4787333,8.299992084503174,0.0,1740481176.4787343,8.299992084503174,-2.0,1740481176.4787354,8.299992084503174,-2.0,1740481176.4787364,8.299992084503174,0.0,1740481176.4787374,8.299992084503174,0.0,, -1740481176.4974728,8.319992065429688,5.001914059077752,1740481176.497474,8.319992065429688,0.0,1740481176.4974759,8.319992065429688,0.0,1740481176.4974785,8.319992065429688,7.001914059077752,1740481176.4974794,8.319992065429688,0.0,1740481176.4974804,8.319992065429688,0.0,1740481176.4974816,8.319992065429688,0.0,1740481176.4974825,8.319992065429688,0.0,1740481176.4974835,8.319992065429688,0.0,1740481176.4974844,8.319992065429688,-2.0,1740481176.4974854,8.319992065429688,-2.0,1740481176.497486,8.319992065429688,0.0,1740481176.497487,8.319992065429688,0.0,, -1740481176.52111,8.339992046356201,5.001914059077752,1740481176.5211115,8.339992046356201,0.0,1740481176.5211136,8.339992046356201,0.0,1740481176.5211155,8.339992046356201,7.001914059077752,1740481176.5211165,8.339992046356201,0.0,1740481176.5211177,8.339992046356201,0.0,1740481176.5211186,8.339992046356201,0.0,1740481176.52112,8.339992046356201,0.0,1740481176.5211213,8.339992046356201,0.0,1740481176.5211222,8.339992046356201,-2.0,1740481176.5211234,8.339992046356201,-2.0,1740481176.5211244,8.339992046356201,0.0,1740481176.5211253,8.339992046356201,0.0,, -1740481176.5377321,8.359992027282715,5.001914059077752,1740481176.537735,8.359992027282715,0.0,1740481176.537738,8.359992027282715,0.0,1740481176.537741,8.359992027282715,7.001914059077752,1740481176.537743,8.359992027282715,0.0,1740481176.537745,8.359992027282715,0.0,1740481176.537746,8.359992027282715,0.0,1740481176.5377476,8.359992027282715,0.0,1740481176.5377493,8.359992027282715,0.0,1740481176.5377507,8.359992027282715,-2.0,1740481176.537757,8.359992027282715,-2.0,1740481176.5377584,8.359992027282715,0.0,1740481176.5377598,8.359992027282715,0.0,, -1740481176.5586507,8.379992008209229,5.001914059077752,1740481176.5586524,8.379992008209229,0.0,1740481176.559082,8.379992008209229,0.0,1740481176.5590863,8.379992008209229,7.001914059077752,1740481176.5590875,8.379992008209229,0.0,1740481176.5590892,8.379992008209229,0.0,1740481176.5590901,8.379992008209229,0.0,1740481176.559091,8.379992008209229,0.0,1740481176.5590923,8.379992008209229,0.0,1740481176.5590932,8.379992008209229,-2.0,1740481176.5590947,8.379992008209229,-2.0,1740481176.5590963,8.379992008209229,0.0,1740481176.559098,8.379992008209229,0.0,, -1740481176.580332,8.399991989135742,5.001914059077752,1740481176.5803342,8.399991989135742,0.0,1740481176.580337,8.399991989135742,0.0,1740481176.58034,8.399991989135742,7.001914059077752,1740481176.5803418,8.399991989135742,0.0,1740481176.5803432,8.399991989135742,0.0,1740481176.5803447,8.399991989135742,0.0,1740481176.5803459,8.399991989135742,0.0,1740481176.580348,8.399991989135742,0.0,1740481176.5803494,8.399991989135742,-2.0,1740481176.5803509,8.399991989135742,-2.0,1740481176.580352,8.399991989135742,0.0,1740481176.580353,8.399991989135742,0.0,, -1740481176.5983229,8.419991970062256,5.001914059077752,1740481176.5983245,8.419991970062256,0.0,1740481176.5983264,8.419991970062256,0.0,1740481176.5983286,8.419991970062256,7.001914059077752,1740481176.5983298,8.419991970062256,0.0,1740481176.5983312,8.419991970062256,0.0,1740481176.5983322,8.419991970062256,0.0,1740481176.5983331,8.419991970062256,0.0,1740481176.5983343,8.419991970062256,0.0,1740481176.5983353,8.419991970062256,-2.0,1740481176.598336,8.419991970062256,-2.0,1740481176.598337,8.419991970062256,0.0,1740481176.5983381,8.419991970062256,0.0,, -1740481176.6189077,8.43999195098877,5.001914059077752,1740481176.6189108,8.43999195098877,0.0,1740481176.6189141,8.43999195098877,0.0,1740481176.618916,8.43999195098877,7.001914059077752,1740481176.6189172,8.43999195098877,0.0,1740481176.6189184,8.43999195098877,0.0,1740481176.6189194,8.43999195098877,0.0,1740481176.61892,8.43999195098877,0.0,1740481176.6189215,8.43999195098877,0.0,1740481176.6189222,8.43999195098877,-2.0,1740481176.6189232,8.43999195098877,-2.0,1740481176.6189244,8.43999195098877,0.0,1740481176.6189253,8.43999195098877,0.0,, -1740481176.6380923,8.459991931915283,5.001914059077752,1740481176.6380935,8.459991931915283,0.0,1740481176.6380956,8.459991931915283,0.0,1740481176.6380978,8.459991931915283,7.001914059077752,1740481176.6380987,8.459991931915283,0.0,1740481176.6381001,8.459991931915283,0.0,1740481176.6381013,8.459991931915283,0.0,1740481176.6381023,8.459991931915283,0.0,1740481176.6381032,8.459991931915283,0.0,1740481176.638104,8.459991931915283,-2.0,1740481176.6381052,8.459991931915283,-2.0,1740481176.6381059,8.459991931915283,0.0,1740481176.6381068,8.459991931915283,0.0,, -1740481176.6598444,8.479991912841797,5.001914059077752,1740481176.6598458,8.479991912841797,0.0,1740481176.659848,8.479991912841797,0.0,1740481176.65985,8.479991912841797,7.001914059077752,1740481176.659851,8.479991912841797,0.0,1740481176.6598525,8.479991912841797,0.0,1740481176.6598535,8.479991912841797,0.0,1740481176.6598547,8.479991912841797,0.0,1740481176.6598556,8.479991912841797,0.0,1740481176.6598566,8.479991912841797,-2.0,1740481176.6598577,8.479991912841797,-2.0,1740481176.6598587,8.479991912841797,0.0,1740481176.6598597,8.479991912841797,0.0,, -1740481176.6781893,8.49999189376831,5.001914059077752,1740481176.6781907,8.49999189376831,0.0,1740481176.6781926,8.49999189376831,0.0,1740481176.6781948,8.49999189376831,7.001914059077752,1740481176.6781957,8.49999189376831,0.0,1740481176.678197,8.49999189376831,0.0,1740481176.6781979,8.49999189376831,0.0,1740481176.6781988,8.49999189376831,0.0,1740481176.6781998,8.49999189376831,0.0,1740481176.6782007,8.49999189376831,-2.0,1740481176.6782017,8.49999189376831,-2.0,1740481176.6782026,8.49999189376831,0.0,1740481176.6782033,8.49999189376831,0.0,, -1740481176.6995814,8.519991874694824,5.001914059077752,1740481176.699583,8.519991874694824,0.0,1740481176.699585,8.519991874694824,0.0,1740481176.699587,8.519991874694824,7.001914059077752,1740481176.699588,8.519991874694824,0.0,1740481176.6995895,8.519991874694824,0.0,1740481176.6995904,8.519991874694824,0.0,1740481176.6995914,8.519991874694824,0.0,1740481176.6995924,8.519991874694824,0.0,1740481176.6995935,8.519991874694824,-2.0,1740481176.6995945,8.519991874694824,-2.0,1740481176.6995955,8.519991874694824,0.0,1740481176.6995964,8.519991874694824,0.0,, -1740481176.720019,8.539991855621338,5.001914059077752,1740481176.7200205,8.539991855621338,0.0,1740481176.7200224,8.539991855621338,0.0,1740481176.7200246,8.539991855621338,7.001914059077752,1740481176.7200255,8.539991855621338,0.0,1740481176.720027,8.539991855621338,0.0,1740481176.7200277,8.539991855621338,0.0,1740481176.7200286,8.539991855621338,0.0,1740481176.7200296,8.539991855621338,0.0,1740481176.7200308,8.539991855621338,-2.0,1740481176.7200317,8.539991855621338,-2.0,1740481176.7200325,8.539991855621338,0.0,1740481176.7200336,8.539991855621338,0.0,, -1740481176.7379687,8.559991836547852,5.001914059077752,1740481176.73797,8.559991836547852,0.0,1740481176.737972,8.559991836547852,0.0,1740481176.7379742,8.559991836547852,7.001914059077752,1740481176.7379751,8.559991836547852,0.0,1740481176.7379892,8.559991836547852,0.0,1740481176.7379916,8.559991836547852,0.0,1740481176.737993,8.559991836547852,0.0,1740481176.737994,8.559991836547852,0.0,1740481176.737995,8.559991836547852,-2.0,1740481176.7379959,8.559991836547852,-2.0,1740481176.7379968,8.559991836547852,0.0,1740481176.7379975,8.559991836547852,0.0,, -1740481176.75985,8.579991817474365,5.001914059077752,1740481176.7598515,8.579991817474365,0.0,1740481176.7598534,8.579991817474365,0.0,1740481176.7598553,8.579991817474365,7.001914059077752,1740481176.7598567,8.579991817474365,0.0,1740481176.7598581,8.579991817474365,0.0,1740481176.75986,8.579991817474365,0.0,1740481176.759861,8.579991817474365,0.0,1740481176.759862,8.579991817474365,0.0,1740481176.7598634,8.579991817474365,-2.0,1740481176.7598646,8.579991817474365,-2.0,1740481176.759866,8.579991817474365,0.0,1740481176.7598674,8.579991817474365,0.0,, -1740481176.778283,8.599991798400879,5.001914059077752,1740481176.7782843,8.599991798400879,0.0,1740481176.7782862,8.599991798400879,0.0,1740481176.7782884,8.599991798400879,7.001914059077752,1740481176.778289,8.599991798400879,0.0,1740481176.7782905,8.599991798400879,0.0,1740481176.7782915,8.599991798400879,0.0,1740481176.7782924,8.599991798400879,0.0,1740481176.7782936,8.599991798400879,0.0,1740481176.7782946,8.599991798400879,-2.0,1740481176.7782953,8.599991798400879,-2.0,1740481176.7782962,8.599991798400879,0.0,1740481176.7782974,8.599991798400879,0.0,, -1740481176.7982366,8.619991779327393,5.001914059077752,1740481176.7982383,8.619991779327393,0.0,1740481176.79824,8.619991779327393,0.0,1740481176.798242,8.619991779327393,7.001914059077752,1740481176.798243,8.619991779327393,0.0,1740481176.7982442,8.619991779327393,0.0,1740481176.7982457,8.619991779327393,0.0,1740481176.7982466,8.619991779327393,0.0,1740481176.7982476,8.619991779327393,0.0,1740481176.7982488,8.619991779327393,-2.0,1740481176.7982495,8.619991779327393,-2.0,1740481176.7982507,8.619991779327393,0.0,1740481176.7982519,8.619991779327393,0.0,, -1740481176.8189254,8.639991760253906,5.001914059077752,1740481176.8189266,8.639991760253906,0.0,1740481176.8189287,8.639991760253906,0.0,1740481176.8189304,8.639991760253906,7.001914059077752,1740481176.8189313,8.639991760253906,0.0,1740481176.8189328,8.639991760253906,0.0,1740481176.8189335,8.639991760253906,0.0,1740481176.8189347,8.639991760253906,0.0,1740481176.8189359,8.639991760253906,0.0,1740481176.8189368,8.639991760253906,-2.0,1740481176.8189375,8.639991760253906,-2.0,1740481176.8189387,8.639991760253906,0.0,1740481176.8189397,8.639991760253906,0.0,, -1740481176.8391473,8.65999174118042,5.001914059077752,1740481176.8391485,8.65999174118042,0.0,1740481176.8391507,8.65999174118042,0.0,1740481176.8391526,8.65999174118042,7.001914059077752,1740481176.8391533,8.65999174118042,0.0,1740481176.8391547,8.65999174118042,0.0,1740481176.8391557,8.65999174118042,0.0,1740481176.8391566,8.65999174118042,0.0,1740481176.8391578,8.65999174118042,0.0,1740481176.8391588,8.65999174118042,-2.0,1740481176.8391597,8.65999174118042,-2.0,1740481176.8391612,8.65999174118042,0.0,1740481176.8391619,8.65999174118042,0.0,, -1740481176.8589845,8.679991722106934,5.001914059077752,1740481176.858986,8.679991722106934,0.0,1740481176.858988,8.679991722106934,0.0,1740481176.8589904,8.679991722106934,7.001914059077752,1740481176.8589914,8.679991722106934,0.0,1740481176.8589926,8.679991722106934,0.0,1740481176.8589938,8.679991722106934,0.0,1740481176.8589947,8.679991722106934,0.0,1740481176.8589957,8.679991722106934,0.0,1740481176.8589966,8.679991722106934,-2.0,1740481176.8589978,8.679991722106934,-2.0,1740481176.8589985,8.679991722106934,0.0,1740481176.8589995,8.679991722106934,0.0,, -1740481176.8795247,8.699991703033447,5.001914059077752,1740481176.8795261,8.699991703033447,0.0,1740481176.8795285,8.699991703033447,0.0,1740481176.8795307,8.699991703033447,7.001914059077752,1740481176.8795323,8.699991703033447,0.0,1740481176.8795354,8.699991703033447,0.0,1740481176.8795369,8.699991703033447,0.0,1740481176.8795376,8.699991703033447,0.0,1740481176.8795393,8.699991703033447,0.0,1740481176.8795402,8.699991703033447,-2.0,1740481176.8795412,8.699991703033447,-2.0,1740481176.8795424,8.699991703033447,0.0,1740481176.8795433,8.699991703033447,0.0,, -1740481176.8975554,8.719991683959961,5.001914059077752,1740481176.897557,8.719991683959961,0.0,1740481176.897559,8.719991683959961,0.0,1740481176.8975608,8.719991683959961,7.001914059077752,1740481176.8975618,8.719991683959961,0.0,1740481176.8975632,8.719991683959961,0.0,1740481176.8975642,8.719991683959961,0.0,1740481176.897565,8.719991683959961,0.0,1740481176.8975663,8.719991683959961,0.0,1740481176.897567,8.719991683959961,-2.0,1740481176.897568,8.719991683959961,-2.0,1740481176.897569,8.719991683959961,0.0,1740481176.89757,8.719991683959961,0.0,, -1740481176.9193811,8.739991664886475,5.001914059077752,1740481176.9193828,8.739991664886475,0.0,1740481176.9193847,8.739991664886475,0.0,1740481176.9194171,8.739991664886475,7.001914059077752,1740481176.9194183,8.739991664886475,0.0,1740481176.9194207,8.739991664886475,0.0,1740481176.9194217,8.739991664886475,0.0,1740481176.9194226,8.739991664886475,0.0,1740481176.9194238,8.739991664886475,0.0,1740481176.9194248,8.739991664886475,-2.0,1740481176.9194255,8.739991664886475,-2.0,1740481176.9194264,8.739991664886475,0.0,1740481176.9194274,8.739991664886475,0.0,, -1740481176.938103,8.759991645812988,5.001914059077752,1740481176.9381046,8.759991645812988,0.0,1740481176.9381063,8.759991645812988,0.0,1740481176.9381084,8.759991645812988,7.001914059077752,1740481176.9381094,8.759991645812988,0.0,1740481176.9381108,8.759991645812988,0.0,1740481176.9381118,8.759991645812988,0.0,1740481176.9381125,8.759991645812988,0.0,1740481176.9381137,8.759991645812988,0.0,1740481176.9381146,8.759991645812988,-2.0,1740481176.9381158,8.759991645812988,-2.0,1740481176.9381168,8.759991645812988,0.0,1740481176.9381177,8.759991645812988,0.0,, -1740481176.9600208,8.779991626739502,5.001914059077752,1740481176.9600239,8.779991626739502,0.0,1740481176.9600277,8.779991626739502,0.0,1740481176.960031,8.779991626739502,7.001914059077752,1740481176.9600325,8.779991626739502,0.0,1740481176.9600346,8.779991626739502,0.0,1740481176.9600358,8.779991626739502,0.0,1740481176.9600375,8.779991626739502,0.0,1740481176.960039,8.779991626739502,0.0,1740481176.9600408,8.779991626739502,-2.0,1740481176.9600418,8.779991626739502,-2.0,1740481176.960043,8.779991626739502,0.0,1740481176.9600444,8.779991626739502,0.0,, -1740481176.9777925,8.799991607666016,5.001914059077752,1740481176.977794,8.799991607666016,0.0,1740481176.977796,8.799991607666016,0.0,1740481176.9777982,8.799991607666016,7.001914059077752,1740481176.9777992,8.799991607666016,0.0,1740481176.9778004,8.799991607666016,0.0,1740481176.9778016,8.799991607666016,0.0,1740481176.9778025,8.799991607666016,0.0,1740481176.9778035,8.799991607666016,0.0,1740481176.9778047,8.799991607666016,-2.0,1740481176.9778059,8.799991607666016,-2.0,1740481176.9778066,8.799991607666016,0.0,1740481176.9778075,8.799991607666016,0.0,, -1740481176.9978952,8.81999158859253,5.001914059077752,1740481176.9978971,8.81999158859253,0.0,1740481176.9979005,8.81999158859253,0.0,1740481176.9979026,8.81999158859253,7.001914059077752,1740481176.9979038,8.81999158859253,0.0,1740481176.9979048,8.81999158859253,0.0,1740481176.997906,8.81999158859253,0.0,1740481176.997907,8.81999158859253,0.0,1740481176.9979079,8.81999158859253,0.0,1740481176.997909,8.81999158859253,-2.0,1740481176.9979098,8.81999158859253,-2.0,1740481176.9979107,8.81999158859253,0.0,1740481176.9979117,8.81999158859253,0.0,, -1740481177.0184054,8.839991569519043,5.001914059077752,1740481177.0184069,8.839991569519043,0.0,1740481177.0184088,8.839991569519043,0.0,1740481177.0184107,8.839991569519043,7.001914059077752,1740481177.0184116,8.839991569519043,0.0,1740481177.0184128,8.839991569519043,0.0,1740481177.0184138,8.839991569519043,0.0,1740481177.0184147,8.839991569519043,0.0,1740481177.018416,8.839991569519043,0.0,1740481177.018417,8.839991569519043,-2.0,1740481177.0184176,8.839991569519043,-2.0,1740481177.0184186,8.839991569519043,0.0,1740481177.0184195,8.839991569519043,0.0,, -1740481177.038158,8.859991550445557,5.001914059077752,1740481177.0381594,8.859991550445557,0.0,1740481177.0381615,8.859991550445557,0.0,1740481177.0381634,8.859991550445557,7.001914059077752,1740481177.0381644,8.859991550445557,0.0,1740481177.0381658,8.859991550445557,0.0,1740481177.0381668,8.859991550445557,0.0,1740481177.0381677,8.859991550445557,0.0,1740481177.0381691,8.859991550445557,0.0,1740481177.0381699,8.859991550445557,-2.0,1740481177.0381708,8.859991550445557,-2.0,1740481177.0381722,8.859991550445557,0.0,1740481177.038173,8.859991550445557,0.0,, -1740481177.05876,8.87999153137207,5.001914059077752,1740481177.0587614,8.87999153137207,0.0,1740481177.0587637,8.87999153137207,0.0,1740481177.058766,8.87999153137207,7.001914059077752,1740481177.0587668,8.87999153137207,0.0,1740481177.0587683,8.87999153137207,0.0,1740481177.0587695,8.87999153137207,0.0,1740481177.0587704,8.87999153137207,0.0,1740481177.0587716,8.87999153137207,0.0,1740481177.0587728,8.87999153137207,-2.0,1740481177.0587738,8.87999153137207,-2.0,1740481177.058775,8.87999153137207,0.0,1740481177.0587761,8.87999153137207,0.0,, -1740481177.0777314,8.899991512298584,5.001914059077752,1740481177.0777326,8.899991512298584,0.0,1740481177.077735,8.899991512298584,0.0,1740481177.0777366,8.899991512298584,7.001914059077752,1740481177.0777378,8.899991512298584,0.0,1740481177.0777392,8.899991512298584,0.0,1740481177.0777402,8.899991512298584,0.0,1740481177.0777411,8.899991512298584,0.0,1740481177.0777423,8.899991512298584,0.0,1740481177.0777433,8.899991512298584,-2.0,1740481177.0777442,8.899991512298584,-2.0,1740481177.0777452,8.899991512298584,0.0,1740481177.077746,8.899991512298584,0.0,, -1740481177.0974758,8.919991493225098,5.001914059077752,1740481177.0974774,8.919991493225098,0.0,1740481177.0974793,8.919991493225098,0.0,1740481177.0974817,8.919991493225098,7.001914059077752,1740481177.0974827,8.919991493225098,0.0,1740481177.0974839,8.919991493225098,0.0,1740481177.0974848,8.919991493225098,0.0,1740481177.0974858,8.919991493225098,0.0,1740481177.0974872,8.919991493225098,0.0,1740481177.097488,8.919991493225098,-2.0,1740481177.0974889,8.919991493225098,-2.0,1740481177.0974898,8.919991493225098,0.0,1740481177.097491,8.919991493225098,0.0,, -1740481177.1187427,8.939991474151611,5.001914059077752,1740481177.1187441,8.939991474151611,0.0,1740481177.118746,8.939991474151611,0.0,1740481177.1187482,8.939991474151611,7.001914059077752,1740481177.118749,8.939991474151611,0.0,1740481177.11875,8.939991474151611,0.0,1740481177.1187513,8.939991474151611,0.0,1740481177.1187522,8.939991474151611,0.0,1740481177.1187532,8.939991474151611,0.0,1740481177.1187544,8.939991474151611,-2.0,1740481177.118755,8.939991474151611,-2.0,1740481177.118756,8.939991474151611,0.0,1740481177.118757,8.939991474151611,0.0,, -1740481177.1378658,8.959991455078125,5.001914059077752,1740481177.1378672,8.959991455078125,0.0,1740481177.1378691,8.959991455078125,0.0,1740481177.137871,8.959991455078125,7.001914059077752,1740481177.137872,8.959991455078125,0.0,1740481177.1378734,8.959991455078125,0.0,1740481177.1378744,8.959991455078125,0.0,1740481177.1378753,8.959991455078125,0.0,1740481177.1378767,8.959991455078125,0.0,1740481177.1378775,8.959991455078125,-2.0,1740481177.1378784,8.959991455078125,-2.0,1740481177.1378796,8.959991455078125,0.0,1740481177.1378803,8.959991455078125,0.0,, -1740481177.1576254,8.979991436004639,5.001914059077752,1740481177.157627,8.979991436004639,0.0,1740481177.157629,8.979991436004639,0.0,1740481177.1576312,8.979991436004639,7.001914059077752,1740481177.157632,8.979991436004639,0.0,1740481177.1576335,8.979991436004639,0.0,1740481177.1576343,8.979991436004639,0.0,1740481177.1576352,8.979991436004639,0.0,1740481177.1576364,8.979991436004639,0.0,1740481177.1576374,8.979991436004639,-2.0,1740481177.157638,8.979991436004639,-2.0,1740481177.1576393,8.979991436004639,0.0,1740481177.1576407,8.979991436004639,0.0,, -1740481177.178174,8.999991416931152,5.001914059077752,1740481177.1781752,8.999991416931152,0.0,1740481177.1781776,8.999991416931152,0.0,1740481177.1781795,8.999991416931152,7.001914059077752,1740481177.1781807,8.999991416931152,0.0,1740481177.178182,8.999991416931152,0.0,1740481177.1781828,8.999991416931152,0.0,1740481177.178184,8.999991416931152,0.0,1740481177.1781852,8.999991416931152,0.0,1740481177.178186,8.999991416931152,-2.0,1740481177.178187,8.999991416931152,-2.0,1740481177.178188,8.999991416931152,0.0,1740481177.178189,8.999991416931152,0.0,, -1740481177.198207,9.019991397857666,5.001914059077752,1740481177.1982086,9.019991397857666,0.0,1740481177.1982105,9.019991397857666,0.0,1740481177.1982126,9.019991397857666,7.001914059077752,1740481177.1982136,9.019991397857666,0.0,1740481177.198215,9.019991397857666,0.0,1740481177.1982162,9.019991397857666,0.0,1740481177.1982172,9.019991397857666,0.0,1740481177.1982183,9.019991397857666,0.0,1740481177.1982193,9.019991397857666,-2.0,1740481177.1982203,9.019991397857666,-2.0,1740481177.198221,9.019991397857666,0.0,1740481177.1982222,9.019991397857666,0.0,, -1740481177.2237139,9.03999137878418,5.001914059077752,1740481177.223715,9.03999137878418,0.0,1740481177.2237172,9.03999137878418,0.0,1740481177.2237191,9.03999137878418,7.001914059077752,1740481177.2237198,9.03999137878418,0.0,1740481177.2237213,9.03999137878418,0.0,1740481177.2237222,9.03999137878418,0.0,1740481177.223723,9.03999137878418,0.0,1740481177.2237244,9.03999137878418,0.0,1740481177.223725,9.03999137878418,-2.0,1740481177.2237258,9.03999137878418,-2.0,1740481177.2237267,9.03999137878418,0.0,1740481177.2237277,9.03999137878418,0.0,, -1740481177.2378802,9.059991359710693,5.001914059077752,1740481177.2378817,9.059991359710693,0.0,1740481177.2378836,9.059991359710693,0.0,1740481177.2378857,9.059991359710693,7.001914059077752,1740481177.2378867,9.059991359710693,0.0,1740481177.2378879,9.059991359710693,0.0,1740481177.2378888,9.059991359710693,0.0,1740481177.2378898,9.059991359710693,0.0,1740481177.2378907,9.059991359710693,0.0,1740481177.2378917,9.059991359710693,-2.0,1740481177.2378924,9.059991359710693,-2.0,1740481177.2378933,9.059991359710693,0.0,1740481177.237894,9.059991359710693,0.0,, -1740481177.259997,9.079991340637207,5.001914059077752,1740481177.2599983,9.079991340637207,0.0,1740481177.2600002,9.079991340637207,0.0,1740481177.2600026,9.079991340637207,7.001914059077752,1740481177.2600033,9.079991340637207,0.0,1740481177.2600048,9.079991340637207,0.0,1740481177.260006,9.079991340637207,0.0,1740481177.260007,9.079991340637207,0.0,1740481177.260008,9.079991340637207,0.0,1740481177.2600095,9.079991340637207,-2.0,1740481177.2600105,9.079991340637207,-2.0,1740481177.2600117,9.079991340637207,0.0,1740481177.260013,9.079991340637207,0.0,, -1740481177.278161,9.09999132156372,5.001914059077752,1740481177.2781627,9.09999132156372,0.0,1740481177.2781653,9.09999132156372,0.0,1740481177.2781677,9.09999132156372,7.001914059077752,1740481177.2781692,9.09999132156372,0.0,1740481177.2781706,9.09999132156372,0.0,1740481177.278172,9.09999132156372,0.0,1740481177.2781732,9.09999132156372,0.0,1740481177.2781749,9.09999132156372,0.0,1740481177.2781763,9.09999132156372,-2.0,1740481177.2781773,9.09999132156372,-2.0,1740481177.2781785,9.09999132156372,0.0,1740481177.2781796,9.09999132156372,0.0,, -1740481177.300316,9.119991302490234,5.001914059077752,1740481177.300318,9.119991302490234,0.0,1740481177.3003201,9.119991302490234,0.0,1740481177.3003225,9.119991302490234,7.001914059077752,1740481177.3003235,9.119991302490234,0.0,1740481177.3003252,9.119991302490234,0.0,1740481177.300326,9.119991302490234,0.0,1740481177.300327,9.119991302490234,0.0,1740481177.3003283,9.119991302490234,0.0,1740481177.3003292,9.119991302490234,-2.0,1740481177.3003302,9.119991302490234,-2.0,1740481177.3003314,9.119991302490234,0.0,1740481177.3003325,9.119991302490234,0.0,, -1740481177.3187237,9.139991283416748,5.001914059077752,1740481177.318725,9.139991283416748,0.0,1740481177.318727,9.139991283416748,0.0,1740481177.3187435,9.139991283416748,7.001914059077752,1740481177.318745,9.139991283416748,0.0,1740481177.318746,9.139991283416748,0.0,1740481177.318747,9.139991283416748,0.0,1740481177.3187568,9.139991283416748,0.0,1740481177.3187592,9.139991283416748,0.0,1740481177.3187602,9.139991283416748,-2.0,1740481177.318761,9.139991283416748,-2.0,1740481177.318762,9.139991283416748,0.0,1740481177.3187628,9.139991283416748,0.0,, -1740481177.3380487,9.159991264343262,5.001914059077752,1740481177.3380504,9.159991264343262,0.0,1740481177.338052,9.159991264343262,0.0,1740481177.3380542,9.159991264343262,7.001914059077752,1740481177.3380551,9.159991264343262,0.0,1740481177.3380566,9.159991264343262,0.0,1740481177.3380575,9.159991264343262,0.0,1740481177.3380585,9.159991264343262,0.0,1740481177.3380594,9.159991264343262,0.0,1740481177.3380606,9.159991264343262,-2.0,1740481177.3380616,9.159991264343262,-2.0,1740481177.3380625,9.159991264343262,0.0,1740481177.3380637,9.159991264343262,0.0,, -1740481177.3575914,9.179991245269775,5.001914059077752,1740481177.3575928,9.179991245269775,0.0,1740481177.357595,9.179991245269775,0.0,1740481177.3575969,9.179991245269775,7.001914059077752,1740481177.3575976,9.179991245269775,0.0,1740481177.3575993,9.179991245269775,0.0,1740481177.3576002,9.179991245269775,0.0,1740481177.357601,9.179991245269775,0.0,1740481177.3576021,9.179991245269775,0.0,1740481177.3576028,9.179991245269775,-2.0,1740481177.3576038,9.179991245269775,-2.0,1740481177.3576045,9.179991245269775,0.0,1740481177.3576057,9.179991245269775,0.0,, -1740481177.3792806,9.199991226196289,5.001914059077752,1740481177.3792837,9.199991226196289,0.0,1740481177.3793705,9.199991226196289,0.0,1740481177.3793757,9.199991226196289,7.001914059077752,1740481177.3793776,9.199991226196289,0.0,1740481177.3793805,9.199991226196289,0.0,1740481177.3793821,9.199991226196289,0.0,1740481177.3794043,9.199991226196289,0.0,1740481177.379407,9.199991226196289,0.0,1740481177.3794096,9.199991226196289,-2.0,1740481177.3794115,9.199991226196289,-2.0,1740481177.3794136,9.199991226196289,0.0,1740481177.379415,9.199991226196289,0.0,, -1740481177.3978448,9.219991207122803,5.001914059077752,1740481177.397846,9.219991207122803,0.0,1740481177.3978484,9.219991207122803,0.0,1740481177.3978503,9.219991207122803,7.001914059077752,1740481177.3978515,9.219991207122803,0.0,1740481177.3978524,9.219991207122803,0.0,1740481177.3978534,9.219991207122803,0.0,1740481177.3978546,9.219991207122803,0.0,1740481177.3978555,9.219991207122803,0.0,1740481177.3978565,9.219991207122803,-2.0,1740481177.3978574,9.219991207122803,-2.0,1740481177.3978584,9.219991207122803,0.0,1740481177.397859,9.219991207122803,0.0,, -1740481177.4190118,9.239991188049316,5.001914059077752,1740481177.4190133,9.239991188049316,0.0,1740481177.4190154,9.239991188049316,0.0,1740481177.4190173,9.239991188049316,7.001914059077752,1740481177.4190183,9.239991188049316,0.0,1740481177.4190192,9.239991188049316,0.0,1740481177.4190202,9.239991188049316,0.0,1740481177.4190214,9.239991188049316,0.0,1740481177.4190223,9.239991188049316,0.0,1740481177.419023,9.239991188049316,-2.0,1740481177.419024,9.239991188049316,-2.0,1740481177.419025,9.239991188049316,0.0,1740481177.4190257,9.239991188049316,0.0,, -1740481177.4387457,9.25999116897583,5.001914059077752,1740481177.4387476,9.25999116897583,0.0,1740481177.4387498,9.25999116897583,0.0,1740481177.4387522,9.25999116897583,7.001914059077752,1740481177.438754,9.25999116897583,0.0,1740481177.438756,9.25999116897583,0.0,1740481177.438758,9.25999116897583,0.0,1740481177.4387596,9.25999116897583,0.0,1740481177.4387617,9.25999116897583,0.0,1740481177.4387634,9.25999116897583,-2.0,1740481177.4387648,9.25999116897583,-2.0,1740481177.438766,9.25999116897583,0.0,1740481177.4387677,9.25999116897583,0.0,, -1740481177.4577658,9.279991149902344,5.001914059077752,1740481177.4577675,9.279991149902344,0.0,1740481177.4578965,9.279991149902344,0.0,1740481177.4579003,9.279991149902344,7.001914059077752,1740481177.4579012,9.279991149902344,0.0,1740481177.4579027,9.279991149902344,0.0,1740481177.4579039,9.279991149902344,0.0,1740481177.4579046,9.279991149902344,0.0,1740481177.457906,9.279991149902344,0.0,1740481177.457907,9.279991149902344,-2.0,1740481177.4579077,9.279991149902344,-2.0,1740481177.4579086,9.279991149902344,0.0,1740481177.4579096,9.279991149902344,0.0,, -1740481177.477983,9.299991130828857,5.001914059077752,1740481177.4779844,9.299991130828857,0.0,1740481177.4779866,9.299991130828857,0.0,1740481177.4779887,9.299991130828857,7.001914059077752,1740481177.4779897,9.299991130828857,0.0,1740481177.4779909,9.299991130828857,0.0,1740481177.4779918,9.299991130828857,0.0,1740481177.477993,9.299991130828857,0.0,1740481177.4779942,9.299991130828857,0.0,1740481177.4779952,9.299991130828857,-2.0,1740481177.477996,9.299991130828857,-2.0,1740481177.477997,9.299991130828857,0.0,1740481177.477998,9.299991130828857,0.0,, -1740481177.4974856,9.319991111755371,5.001914059077752,1740481177.4974875,9.319991111755371,0.0,1740481177.4974906,9.319991111755371,0.0,1740481177.4974928,9.319991111755371,7.001914059077752,1740481177.4974937,9.319991111755371,0.0,1740481177.4974957,9.319991111755371,0.0,1740481177.4974966,9.319991111755371,0.0,1740481177.4974973,9.319991111755371,0.0,1740481177.4974985,9.319991111755371,0.0,1740481177.4974995,9.319991111755371,-2.0,1740481177.4975004,9.319991111755371,-2.0,1740481177.4975011,9.319991111755371,0.0,1740481177.4975023,9.319991111755371,0.0,, -1740481177.5260217,9.339991092681885,5.001914059077752,1740481177.526023,9.339991092681885,0.0,1740481177.526025,9.339991092681885,0.0,1740481177.526027,9.339991092681885,7.001914059077752,1740481177.5260277,9.339991092681885,0.0,1740481177.526029,9.339991092681885,0.0,1740481177.52603,9.339991092681885,0.0,1740481177.526031,9.339991092681885,0.0,1740481177.5260324,9.339991092681885,0.0,1740481177.5260332,9.339991092681885,-2.0,1740481177.526034,9.339991092681885,-2.0,1740481177.5260348,9.339991092681885,0.0,1740481177.526036,9.339991092681885,0.0,, -1740481177.5383494,9.359991073608398,5.001914059077752,1740481177.5383515,9.359991073608398,0.0,1740481177.5383558,9.359991073608398,0.0,1740481177.5383587,9.359991073608398,7.001914059077752,1740481177.5383604,9.359991073608398,0.0,1740481177.5383623,9.359991073608398,0.0,1740481177.5383644,9.359991073608398,0.0,1740481177.5383658,9.359991073608398,0.0,1740481177.5383677,9.359991073608398,0.0,1740481177.5383692,9.359991073608398,-2.0,1740481177.5383708,9.359991073608398,-2.0,1740481177.5383723,9.359991073608398,0.0,1740481177.538374,9.359991073608398,0.0,, -1740481177.5580654,9.379991054534912,5.001914059077752,1740481177.5580668,9.379991054534912,0.0,1740481177.5580688,9.379991054534912,0.0,1740481177.558071,9.379991054534912,7.001914059077752,1740481177.5580719,9.379991054534912,0.0,1740481177.558073,9.379991054534912,0.0,1740481177.558074,9.379991054534912,0.0,1740481177.558075,9.379991054534912,0.0,1740481177.5580761,9.379991054534912,0.0,1740481177.5580769,9.379991054534912,-2.0,1740481177.5580783,9.379991054534912,-2.0,1740481177.5580792,9.379991054534912,0.0,1740481177.55808,9.379991054534912,0.0,, -1740481177.577969,9.399991035461426,5.001914059077752,1740481177.5779707,9.399991035461426,0.0,1740481177.577973,9.399991035461426,0.0,1740481177.5779748,9.399991035461426,7.001914059077752,1740481177.5779757,9.399991035461426,0.0,1740481177.5779772,9.399991035461426,0.0,1740481177.5779781,9.399991035461426,0.0,1740481177.5779788,9.399991035461426,0.0,1740481177.57798,9.399991035461426,0.0,1740481177.5779812,9.399991035461426,-2.0,1740481177.577982,9.399991035461426,-2.0,1740481177.577983,9.399991035461426,0.0,1740481177.5779839,9.399991035461426,0.0,, -1740481177.5995927,9.41999101638794,5.001914059077752,1740481177.5995939,9.41999101638794,0.0,1740481177.599596,9.41999101638794,0.0,1740481177.5995982,9.41999101638794,7.001914059077752,1740481177.599599,9.41999101638794,0.0,1740481177.5996,9.41999101638794,0.0,1740481177.5996013,9.41999101638794,0.0,1740481177.599602,9.41999101638794,0.0,1740481177.599603,9.41999101638794,0.0,1740481177.599604,9.41999101638794,-2.0,1740481177.5996048,9.41999101638794,-2.0,1740481177.5996058,9.41999101638794,0.0,1740481177.5996065,9.41999101638794,0.0,, -1740481177.6185117,9.439990997314453,5.001914059077752,1740481177.618513,9.439990997314453,0.0,1740481177.618515,9.439990997314453,0.0,1740481177.6185167,9.439990997314453,7.001914059077752,1740481177.6185179,9.439990997314453,0.0,1740481177.618519,9.439990997314453,0.0,1740481177.6185203,9.439990997314453,0.0,1740481177.6185215,9.439990997314453,0.0,1740481177.6185224,9.439990997314453,0.0,1740481177.6185231,9.439990997314453,-2.0,1740481177.618524,9.439990997314453,-2.0,1740481177.6185253,9.439990997314453,0.0,1740481177.618526,9.439990997314453,0.0,, -1740481177.6378763,9.459990978240967,5.001914059077752,1740481177.6378777,9.459990978240967,0.0,1740481177.6378798,9.459990978240967,0.0,1740481177.6378949,9.459990978240967,7.001914059077752,1740481177.6378958,9.459990978240967,0.0,1740481177.6378984,9.459990978240967,0.0,1740481177.6378996,9.459990978240967,0.0,1740481177.6379004,9.459990978240967,0.0,1740481177.6379015,9.459990978240967,0.0,1740481177.6379023,9.459990978240967,-2.0,1740481177.6379035,9.459990978240967,-2.0,1740481177.6379044,9.459990978240967,0.0,1740481177.6379051,9.459990978240967,0.0,, -1740481177.6578524,9.47999095916748,5.001914059077752,1740481177.6578538,9.47999095916748,0.0,1740481177.657856,9.47999095916748,0.0,1740481177.6578581,9.47999095916748,7.001914059077752,1740481177.6578588,9.47999095916748,0.0,1740481177.6578603,9.47999095916748,0.0,1740481177.6578612,9.47999095916748,0.0,1740481177.6578622,9.47999095916748,0.0,1740481177.6578634,9.47999095916748,0.0,1740481177.657864,9.47999095916748,-2.0,1740481177.6578653,9.47999095916748,-2.0,1740481177.6578662,9.47999095916748,0.0,1740481177.6578672,9.47999095916748,0.0,, -1740481177.6784797,9.499990940093994,5.001914059077752,1740481177.6784909,9.499990940093994,0.0,1740481177.678497,9.499990940093994,0.0,1740481177.6785028,9.499990940093994,7.001914059077752,1740481177.6785054,9.499990940093994,0.0,1740481177.6785083,9.499990940093994,0.0,1740481177.6785097,9.499990940093994,0.0,1740481177.6785152,9.499990940093994,0.0,1740481177.6785216,9.499990940093994,0.0,1740481177.6785264,9.499990940093994,-2.0,1740481177.678529,9.499990940093994,-2.0,1740481177.6785333,9.499990940093994,0.0,1740481177.678538,9.499990940093994,0.0,, -1740481177.6980753,9.519990921020508,5.001914059077752,1740481177.6980767,9.519990921020508,0.0,1740481177.6980786,9.519990921020508,0.0,1740481177.698081,9.519990921020508,7.001914059077752,1740481177.6980817,9.519990921020508,0.0,1740481177.6980832,9.519990921020508,0.0,1740481177.6980844,9.519990921020508,0.0,1740481177.6980853,9.519990921020508,0.0,1740481177.6980867,9.519990921020508,0.0,1740481177.6980877,9.519990921020508,-2.0,1740481177.6980886,9.519990921020508,-2.0,1740481177.6980898,9.519990921020508,0.0,1740481177.6980908,9.519990921020508,0.0,, -1740481177.718393,9.539990901947021,5.001914059077752,1740481177.7183943,9.539990901947021,0.0,1740481177.7183964,9.539990901947021,0.0,1740481177.718398,9.539990901947021,7.001914059077752,1740481177.7183993,9.539990901947021,0.0,1740481177.7184005,9.539990901947021,0.0,1740481177.7184012,9.539990901947021,0.0,1740481177.7184024,9.539990901947021,0.0,1740481177.7184033,9.539990901947021,0.0,1740481177.7184043,9.539990901947021,-2.0,1740481177.718405,9.539990901947021,-2.0,1740481177.718406,9.539990901947021,0.0,1740481177.718407,9.539990901947021,0.0,, -1740481177.7382565,9.559990882873535,5.001914059077752,1740481177.738258,9.559990882873535,0.0,1740481177.7382603,9.559990882873535,0.0,1740481177.7382622,9.559990882873535,7.001914059077752,1740481177.7382634,9.559990882873535,0.0,1740481177.738265,9.559990882873535,0.0,1740481177.7382662,9.559990882873535,0.0,1740481177.7382672,9.559990882873535,0.0,1740481177.7382681,9.559990882873535,0.0,1740481177.7382693,9.559990882873535,-2.0,1740481177.7382708,9.559990882873535,-2.0,1740481177.7382717,9.559990882873535,0.0,1740481177.7382727,9.559990882873535,0.0,, -1740481177.7607455,9.579990863800049,5.001914059077752,1740481177.760747,9.579990863800049,0.0,1740481177.7607489,9.579990863800049,0.0,1740481177.7607508,9.579990863800049,7.001914059077752,1740481177.760752,9.579990863800049,0.0,1740481177.760753,9.579990863800049,0.0,1740481177.7607539,9.579990863800049,0.0,1740481177.760755,9.579990863800049,0.0,1740481177.760756,9.579990863800049,0.0,1740481177.760757,9.579990863800049,-2.0,1740481177.760758,9.579990863800049,-2.0,1740481177.7607589,9.579990863800049,0.0,1740481177.7607598,9.579990863800049,0.0,, -1740481177.7788272,9.599990844726562,5.001914059077752,1740481177.7788289,9.599990844726562,0.0,1740481177.7788308,9.599990844726562,0.0,1740481177.778833,9.599990844726562,7.001914059077752,1740481177.7788339,9.599990844726562,0.0,1740481177.7788355,9.599990844726562,0.0,1740481177.7788365,9.599990844726562,0.0,1740481177.7788374,9.599990844726562,0.0,1740481177.7788389,9.599990844726562,0.0,1740481177.7788403,9.599990844726562,-2.0,1740481177.778841,9.599990844726562,-2.0,1740481177.7788422,9.599990844726562,0.0,1740481177.778843,9.599990844726562,0.0,, -1740481177.7982247,9.619990825653076,5.001914059077752,1740481177.7982264,9.619990825653076,0.0,1740481177.798229,9.619990825653076,0.0,1740481177.7982316,9.619990825653076,7.001914059077752,1740481177.7982326,9.619990825653076,0.0,1740481177.7982337,9.619990825653076,0.0,1740481177.7982352,9.619990825653076,0.0,1740481177.7982361,9.619990825653076,0.0,1740481177.7982383,9.619990825653076,0.0,1740481177.7982392,9.619990825653076,-2.0,1740481177.7982407,9.619990825653076,-2.0,1740481177.7982419,9.619990825653076,0.0,1740481177.7982428,9.619990825653076,0.0,, -1740481177.8191936,9.63999080657959,5.001914059077752,1740481177.8191955,9.63999080657959,0.0,1740481177.8191974,9.63999080657959,0.0,1740481177.8191993,9.63999080657959,7.001914059077752,1740481177.8192003,9.63999080657959,0.0,1740481177.8192012,9.63999080657959,0.0,1740481177.8192024,9.63999080657959,0.0,1740481177.8192034,9.63999080657959,0.0,1740481177.8192043,9.63999080657959,0.0,1740481177.8192053,9.63999080657959,-2.0,1740481177.8192062,9.63999080657959,-2.0,1740481177.8192072,9.63999080657959,0.0,1740481177.819208,9.63999080657959,0.0,, -1740481177.8375235,9.659990787506104,5.001914059077752,1740481177.8375247,9.659990787506104,0.0,1740481177.8375268,9.659990787506104,0.0,1740481177.838243,9.659990787506104,7.001914059077752,1740481177.8382454,9.659990787506104,0.0,1740481177.8382504,9.659990787506104,0.0,1740481177.8382518,9.659990787506104,0.0,1740481177.838253,9.659990787506104,0.0,1740481177.8382547,9.659990787506104,0.0,1740481177.8382561,9.659990787506104,-2.0,1740481177.838257,9.659990787506104,-2.0,1740481177.8382583,9.659990787506104,0.0,1740481177.8382592,9.659990787506104,0.0,, -1740481177.857534,9.679990768432617,5.001914059077752,1740481177.8575356,9.679990768432617,0.0,1740481177.8575542,9.679990768432617,0.0,1740481177.8575566,9.679990768432617,7.001914059077752,1740481177.8575573,9.679990768432617,0.0,1740481177.8575585,9.679990768432617,0.0,1740481177.8575594,9.679990768432617,0.0,1740481177.8575606,9.679990768432617,0.0,1740481177.8575618,9.679990768432617,0.0,1740481177.8575814,9.679990768432617,-2.0,1740481177.857582,9.679990768432617,-2.0,1740481177.857583,9.679990768432617,0.0,1740481177.8575838,9.679990768432617,0.0,, -1740481177.8779,9.69999074935913,5.001914059077752,1740481177.8779018,9.69999074935913,0.0,1740481177.877904,9.69999074935913,0.0,1740481177.8779058,9.69999074935913,7.001914059077752,1740481177.877907,9.69999074935913,0.0,1740481177.8779082,9.69999074935913,0.0,1740481177.8779092,9.69999074935913,0.0,1740481177.8779104,9.69999074935913,0.0,1740481177.8779113,9.69999074935913,0.0,1740481177.8779123,9.69999074935913,-2.0,1740481177.877913,9.69999074935913,-2.0,1740481177.8779142,9.69999074935913,0.0,1740481177.877915,9.69999074935913,0.0,, -1740481177.8975158,9.719990730285645,5.001914059077752,1740481177.8975172,9.719990730285645,0.0,1740481177.8975194,9.719990730285645,0.0,1740481177.8975213,9.719990730285645,7.001914059077752,1740481177.8975222,9.719990730285645,0.0,1740481177.8975234,9.719990730285645,0.0,1740481177.8975246,9.719990730285645,0.0,1740481177.8975255,9.719990730285645,0.0,1740481177.8975265,9.719990730285645,0.0,1740481177.8975275,9.719990730285645,-2.0,1740481177.8975286,9.719990730285645,-2.0,1740481177.8975294,9.719990730285645,0.0,1740481177.8975303,9.719990730285645,0.0,, -1740481177.918662,9.739990711212158,5.001914059077752,1740481177.9186637,9.739990711212158,0.0,1740481177.9186656,9.739990711212158,0.0,1740481177.9186678,9.739990711212158,7.001914059077752,1740481177.9186687,9.739990711212158,0.0,1740481177.9186702,9.739990711212158,0.0,1740481177.9186711,9.739990711212158,0.0,1740481177.918672,9.739990711212158,0.0,1740481177.918673,9.739990711212158,0.0,1740481177.9186742,9.739990711212158,-2.0,1740481177.918675,9.739990711212158,-2.0,1740481177.918676,9.739990711212158,0.0,1740481177.9186769,9.739990711212158,0.0,, -1740481177.9378774,9.759990692138672,5.001914059077752,1740481177.937879,9.759990692138672,0.0,1740481177.937881,9.759990692138672,0.0,1740481177.9378834,9.759990692138672,7.001914059077752,1740481177.9378843,9.759990692138672,0.0,1740481177.9378858,9.759990692138672,0.0,1740481177.9378867,9.759990692138672,0.0,1740481177.9378877,9.759990692138672,0.0,1740481177.937889,9.759990692138672,0.0,1740481177.93789,9.759990692138672,-2.0,1740481177.937891,9.759990692138672,-2.0,1740481177.9378922,9.759990692138672,0.0,1740481177.9378932,9.759990692138672,0.0,, -1740481177.9587533,9.779990673065186,5.001914059077752,1740481177.9587548,9.779990673065186,0.0,1740481177.9587572,9.779990673065186,0.0,1740481177.958759,9.779990673065186,7.001914059077752,1740481177.9587603,9.779990673065186,0.0,1740481177.9587615,9.779990673065186,0.0,1740481177.9587624,9.779990673065186,0.0,1740481177.9587636,9.779990673065186,0.0,1740481177.9587646,9.779990673065186,0.0,1740481177.9587655,9.779990673065186,-2.0,1740481177.9587662,9.779990673065186,-2.0,1740481177.9587674,9.779990673065186,0.0,1740481177.9587681,9.779990673065186,0.0,, -1740481177.977649,9.7999906539917,5.001914059077752,1740481177.9776504,9.7999906539917,0.0,1740481177.9776525,9.7999906539917,0.0,1740481177.9776542,9.7999906539917,7.001914059077752,1740481177.9776554,9.7999906539917,0.0,1740481177.9776566,9.7999906539917,0.0,1740481177.9776573,9.7999906539917,0.0,1740481177.9776583,9.7999906539917,0.0,1740481177.9776595,9.7999906539917,0.0,1740481177.9776602,9.7999906539917,-2.0,1740481177.9776611,9.7999906539917,-2.0,1740481177.9776618,9.7999906539917,0.0,1740481177.9776628,9.7999906539917,0.0,, -1740481177.998132,9.819990634918213,5.001914059077752,1740481177.9981337,9.819990634918213,0.0,1740481177.998136,9.819990634918213,0.0,1740481177.9981384,9.819990634918213,7.001914059077752,1740481177.9981394,9.819990634918213,0.0,1740481177.9981408,9.819990634918213,0.0,1740481177.9981422,9.819990634918213,0.0,1740481177.9981432,9.819990634918213,0.0,1740481177.9981446,9.819990634918213,0.0,1740481177.9981458,9.819990634918213,-2.0,1740481177.9981465,9.819990634918213,-2.0,1740481177.9981475,9.819990634918213,0.0,1740481177.9981487,9.819990634918213,0.0,, -1740481178.0201411,9.839990615844727,5.001914059077752,1740481178.0201426,9.839990615844727,0.0,1740481178.0201452,9.839990615844727,0.0,1740481178.0201478,9.839990615844727,7.001914059077752,1740481178.0201488,9.839990615844727,0.0,1740481178.02015,9.839990615844727,0.0,1740481178.0201514,9.839990615844727,0.0,1740481178.0201523,9.839990615844727,0.0,1740481178.0201535,9.839990615844727,0.0,1740481178.0201547,9.839990615844727,-2.0,1740481178.0201557,9.839990615844727,-2.0,1740481178.0201566,9.839990615844727,0.0,1740481178.0201578,9.839990615844727,0.0,, -1740481178.0401335,9.85999059677124,5.001914059077752,1740481178.040135,9.85999059677124,0.0,1740481178.040137,9.85999059677124,0.0,1740481178.0401394,9.85999059677124,7.001914059077752,1740481178.0401404,9.85999059677124,0.0,1740481178.0401416,9.85999059677124,0.0,1740481178.0401425,9.85999059677124,0.0,1740481178.040144,9.85999059677124,0.0,1740481178.040145,9.85999059677124,0.0,1740481178.040146,9.85999059677124,-2.0,1740481178.0401473,9.85999059677124,-2.0,1740481178.040148,9.85999059677124,0.0,1740481178.040149,9.85999059677124,0.0,, -1740481178.0577662,9.879990577697754,5.001914059077752,1740481178.0577676,9.879990577697754,0.0,1740481178.05777,9.879990577697754,0.0,1740481178.057772,9.879990577697754,7.001914059077752,1740481178.057773,9.879990577697754,0.0,1740481178.0577743,9.879990577697754,0.0,1740481178.0577753,9.879990577697754,0.0,1740481178.0577767,9.879990577697754,0.0,1740481178.0577776,9.879990577697754,0.0,1740481178.0577786,9.879990577697754,-2.0,1740481178.0577796,9.879990577697754,-2.0,1740481178.0577805,9.879990577697754,0.0,1740481178.0577815,9.879990577697754,0.0,, -1740481178.079036,9.899990558624268,5.001914059077752,1740481178.0790374,9.899990558624268,0.0,1740481178.07904,9.899990558624268,0.0,1740481178.0790422,9.899990558624268,7.001914059077752,1740481178.0790434,9.899990558624268,0.0,1740481178.0790448,9.899990558624268,0.0,1740481178.0790462,9.899990558624268,0.0,1740481178.0790474,9.899990558624268,0.0,1740481178.0790486,9.899990558624268,0.0,1740481178.07905,9.899990558624268,-2.0,1740481178.079051,9.899990558624268,-2.0,1740481178.0790522,9.899990558624268,0.0,1740481178.0790536,9.899990558624268,0.0,, -1740481178.097971,9.919990539550781,5.001914059077752,1740481178.0979724,9.919990539550781,0.0,1740481178.0979745,9.919990539550781,0.0,1740481178.0979762,9.919990539550781,7.001914059077752,1740481178.0979774,9.919990539550781,0.0,1740481178.0979786,9.919990539550781,0.0,1740481178.09798,9.919990539550781,0.0,1740481178.097981,9.919990539550781,0.0,1740481178.097982,9.919990539550781,0.0,1740481178.0979831,9.919990539550781,-2.0,1740481178.0979843,9.919990539550781,-2.0,1740481178.097985,9.919990539550781,0.0,1740481178.0979857,9.919990539550781,0.0,, -1740481178.1186078,9.939990520477295,5.001914059077752,1740481178.1186094,9.939990520477295,0.0,1740481178.1186116,9.939990520477295,0.0,1740481178.1186137,9.939990520477295,7.001914059077752,1740481178.1186147,9.939990520477295,0.0,1740481178.1186163,9.939990520477295,0.0,1740481178.1186173,9.939990520477295,0.0,1740481178.1186182,9.939990520477295,0.0,1740481178.1186197,9.939990520477295,0.0,1740481178.1186206,9.939990520477295,-2.0,1740481178.1186216,9.939990520477295,-2.0,1740481178.118623,9.939990520477295,0.0,1740481178.1186242,9.939990520477295,0.0,, -1740481178.1394978,9.959990501403809,5.001914059077752,1740481178.1394994,9.959990501403809,0.0,1740481178.139502,9.959990501403809,0.0,1740481178.1395047,9.959990501403809,7.001914059077752,1740481178.1395059,9.959990501403809,0.0,1740481178.1395075,9.959990501403809,0.0,1740481178.1395087,9.959990501403809,0.0,1740481178.13951,9.959990501403809,0.0,1740481178.1395113,9.959990501403809,0.0,1740481178.1395125,9.959990501403809,-2.0,1740481178.1395135,9.959990501403809,-2.0,1740481178.1395147,9.959990501403809,0.0,1740481178.1395159,9.959990501403809,0.0,, -1740481178.1589875,9.979990482330322,5.001914059077752,1740481178.1589894,9.979990482330322,0.0,1740481178.1589913,9.979990482330322,0.0,1740481178.1589935,9.979990482330322,7.001914059077752,1740481178.1589944,9.979990482330322,0.0,1740481178.158996,9.979990482330322,0.0,1740481178.1589973,9.979990482330322,0.0,1740481178.1589983,9.979990482330322,0.0,1740481178.1589992,9.979990482330322,0.0,1740481178.1590004,9.979990482330322,-2.0,1740481178.1590014,9.979990482330322,-2.0,1740481178.1590023,9.979990482330322,0.0,1740481178.159003,9.979990482330322,0.0,, -1740481178.17863,9.999990463256836,5.001914059077752,1740481178.1786323,9.999990463256836,0.0,1740481178.1786351,9.999990463256836,0.0,1740481178.1786375,9.999990463256836,7.001914059077752,1740481178.178639,9.999990463256836,0.0,1740481178.1786406,9.999990463256836,0.0,1740481178.1786416,9.999990463256836,0.0,1740481178.178643,9.999990463256836,0.0,1740481178.1786442,9.999990463256836,0.0,1740481178.1786456,9.999990463256836,-2.0,1740481178.1786466,9.999990463256836,-2.0,1740481178.1786478,9.999990463256836,0.0,1740481178.178649,9.999990463256836,0.0,, -1740481178.2023137,10.029990434646606,5.001914059077752,1740481178.2023156,10.029990434646606,0.0,1740481178.2023177,10.029990434646606,0.0,1740481178.20232,10.029990434646606,7.001914059077752,1740481178.202321,10.029990434646606,0.0,1740481178.2023227,10.029990434646606,0.0,1740481178.2023237,10.029990434646606,0.0,1740481178.2023246,10.029990434646606,0.0,1740481178.2023263,10.029990434646606,0.0,1740481178.2023273,10.029990434646606,-2.0,1740481178.2023282,10.029990434646606,-2.0,1740481178.2023294,10.029990434646606,0.0,1740481178.2023304,10.029990434646606,0.0,, -1740481178.2189968,10.039990425109863,5.001914059077752,1740481178.2189994,10.039990425109863,0.0,1740481178.2190032,10.039990425109863,0.0,1740481178.2190056,10.039990425109863,7.001914059077752,1740481178.219007,10.039990425109863,0.0,1740481178.2190084,10.039990425109863,0.0,1740481178.2190099,10.039990425109863,0.0,1740481178.219011,10.039990425109863,0.0,1740481178.2190123,10.039990425109863,0.0,1740481178.2190135,10.039990425109863,-2.0,1740481178.2190144,10.039990425109863,-2.0,1740481178.2190156,10.039990425109863,0.0,1740481178.2190168,10.039990425109863,0.0,, -1740481178.2380466,10.059990406036377,5.001914059077752,1740481178.2380486,10.059990406036377,0.0,1740481178.2380514,10.059990406036377,0.0,1740481178.2380538,10.059990406036377,7.001914059077752,1740481178.2380552,10.059990406036377,0.0,1740481178.2380567,10.059990406036377,0.0,1740481178.238058,10.059990406036377,0.0,1740481178.238059,10.059990406036377,0.0,1740481178.2380602,10.059990406036377,0.0,1740481178.238062,10.059990406036377,-2.0,1740481178.238063,10.059990406036377,-2.0,1740481178.238064,10.059990406036377,0.0,1740481178.2380652,10.059990406036377,0.0,, -1740481178.2579803,10.07999038696289,5.001914059077752,1740481178.2579823,10.07999038696289,0.0,1740481178.257985,10.07999038696289,0.0,1740481178.2579875,10.07999038696289,7.001914059077752,1740481178.2579887,10.07999038696289,0.0,1740481178.2579904,10.07999038696289,0.0,1740481178.2579913,10.07999038696289,0.0,1740481178.2579932,10.07999038696289,0.0,1740481178.2579944,10.07999038696289,0.0,1740481178.257996,10.07999038696289,-2.0,1740481178.257997,10.07999038696289,-2.0,1740481178.257998,10.07999038696289,0.0,1740481178.2579992,10.07999038696289,0.0,, -1740481178.2788377,10.099990367889404,5.001914059077752,1740481178.27884,10.099990367889404,0.0,1740481178.278844,10.099990367889404,0.0,1740481178.2788477,10.099990367889404,7.001914059077752,1740481178.2788503,10.099990367889404,0.0,1740481178.278853,10.099990367889404,0.0,1740481178.2788544,10.099990367889404,0.0,1740481178.2788565,10.099990367889404,0.0,1740481178.2788587,10.099990367889404,0.0,1740481178.2788608,10.099990367889404,-2.0,1740481178.2788622,10.099990367889404,-2.0,1740481178.2788644,10.099990367889404,0.0,1740481178.2788663,10.099990367889404,0.0,, -1740481178.2978802,10.119990348815918,5.001914059077752,1740481178.2978818,10.119990348815918,0.0,1740481178.2978847,10.119990348815918,0.0,1740481178.297887,10.119990348815918,7.001914059077752,1740481178.2978883,10.119990348815918,0.0,1740481178.2978897,10.119990348815918,0.0,1740481178.2978911,10.119990348815918,0.0,1740481178.297892,10.119990348815918,0.0,1740481178.2978935,10.119990348815918,0.0,1740481178.2978952,10.119990348815918,-2.0,1740481178.2978961,10.119990348815918,-2.0,1740481178.297897,10.119990348815918,0.0,1740481178.2978985,10.119990348815918,0.0,, -1740481178.318786,10.139990329742432,5.001914059077752,1740481178.318804,10.139990329742432,0.0,1740481178.3188083,10.139990329742432,0.0,1740481178.3188112,10.139990329742432,7.001914059077752,1740481178.3188121,10.139990329742432,0.0,1740481178.3188138,10.139990329742432,0.0,1740481178.318815,10.139990329742432,0.0,1740481178.318816,10.139990329742432,0.0,1740481178.3188174,10.139990329742432,0.0,1740481178.3188186,10.139990329742432,-2.0,1740481178.3188195,10.139990329742432,-2.0,1740481178.3188207,10.139990329742432,0.0,1740481178.3188221,10.139990329742432,0.0,, -1740481178.338471,10.159990310668945,5.001914059077752,1740481178.3384726,10.159990310668945,0.0,1740481178.3384755,10.159990310668945,0.0,1740481178.338478,10.159990310668945,7.001914059077752,1740481178.3384793,10.159990310668945,0.0,1740481178.3384812,10.159990310668945,0.0,1740481178.3384824,10.159990310668945,0.0,1740481178.3384838,10.159990310668945,0.0,1740481178.3384852,10.159990310668945,0.0,1740481178.3384871,10.159990310668945,-2.0,1740481178.3384883,10.159990310668945,-2.0,1740481178.3384893,10.159990310668945,0.0,1740481178.3384907,10.159990310668945,0.0,, -1740481178.3606756,10.179990291595459,5.001914059077752,1740481178.360681,10.179990291595459,0.0,1740481178.3606868,10.179990291595459,0.0,1740481178.36069,10.179990291595459,7.001914059077752,1740481178.3606915,10.179990291595459,0.0,1740481178.3606935,10.179990291595459,0.0,1740481178.3606951,10.179990291595459,0.0,1740481178.3606968,10.179990291595459,0.0,1740481178.3606994,10.179990291595459,0.0,1740481178.3607008,10.179990291595459,-2.0,1740481178.3607028,10.179990291595459,-2.0,1740481178.3607047,10.179990291595459,0.0,1740481178.3607066,10.179990291595459,0.0,, -1740481178.3776069,10.199990272521973,5.001914059077752,1740481178.3776088,10.199990272521973,0.0,1740481178.3776116,10.199990272521973,0.0,1740481178.377614,10.199990272521973,7.001914059077752,1740481178.3776155,10.199990272521973,0.0,1740481178.377617,10.199990272521973,0.0,1740481178.3776178,10.199990272521973,0.0,1740481178.3776193,10.199990272521973,0.0,1740481178.3776205,10.199990272521973,0.0,1740481178.3776217,10.199990272521973,-2.0,1740481178.3776228,10.199990272521973,-2.0,1740481178.377624,10.199990272521973,0.0,1740481178.377625,10.199990272521973,0.0,, -1740481178.3978202,10.219990253448486,5.001914059077752,1740481178.397822,10.219990253448486,0.0,1740481178.3978245,10.219990253448486,0.0,1740481178.3978267,10.219990253448486,7.001914059077752,1740481178.3978279,10.219990253448486,0.0,1740481178.3978293,10.219990253448486,0.0,1740481178.3978307,10.219990253448486,0.0,1740481178.3978317,10.219990253448486,0.0,1740481178.397833,10.219990253448486,0.0,1740481178.3978345,10.219990253448486,-2.0,1740481178.3978355,10.219990253448486,-2.0,1740481178.3978367,10.219990253448486,0.0,1740481178.3978379,10.219990253448486,0.0,, -1740481178.418393,10.239990234375,5.001914059077752,1740481178.4183943,10.239990234375,0.0,1740481178.4183967,10.239990234375,0.0,1740481178.4183989,10.239990234375,7.001914059077752,1740481178.4184003,10.239990234375,0.0,1740481178.4184015,10.239990234375,0.0,1740481178.418403,10.239990234375,0.0,1740481178.4184039,10.239990234375,0.0,1740481178.4184048,10.239990234375,0.0,1740481178.4184062,10.239990234375,-2.0,1740481178.4184072,10.239990234375,-2.0,1740481178.4184082,10.239990234375,0.0,1740481178.4184089,10.239990234375,0.0,, -1740481178.4377713,10.259990215301514,5.001914059077752,1740481178.437773,10.259990215301514,0.0,1740481178.4377754,10.259990215301514,0.0,1740481178.4377778,10.259990215301514,7.001914059077752,1740481178.4377787,10.259990215301514,0.0,1740481178.4377801,10.259990215301514,0.0,1740481178.4377813,10.259990215301514,0.0,1740481178.4377823,10.259990215301514,0.0,1740481178.4377835,10.259990215301514,0.0,1740481178.4377847,10.259990215301514,-2.0,1740481178.4377856,10.259990215301514,-2.0,1740481178.4377866,10.259990215301514,0.0,1740481178.4377875,10.259990215301514,0.0,, -1740481178.4596295,10.279990196228027,5.001914059077752,1740481178.4596312,10.279990196228027,0.0,1740481178.4596334,10.279990196228027,0.0,1740481178.459636,10.279990196228027,7.001914059077752,1740481178.4596372,10.279990196228027,0.0,1740481178.4596388,10.279990196228027,0.0,1740481178.4596553,10.279990196228027,0.0,1740481178.4596567,10.279990196228027,0.0,1740481178.4596581,10.279990196228027,0.0,1740481178.4596593,10.279990196228027,-2.0,1740481178.4596603,10.279990196228027,-2.0,1740481178.4596612,10.279990196228027,0.0,1740481178.4596627,10.279990196228027,0.0,, -1740481178.4778545,10.299990177154541,5.001914059077752,1740481178.4778562,10.299990177154541,0.0,1740481178.4778588,10.299990177154541,0.0,1740481178.4778612,10.299990177154541,7.001914059077752,1740481178.4778621,10.299990177154541,0.0,1740481178.4778638,10.299990177154541,0.0,1740481178.4778647,10.299990177154541,0.0,1740481178.4778657,10.299990177154541,0.0,1740481178.4778671,10.299990177154541,0.0,1740481178.477868,10.299990177154541,-2.0,1740481178.477869,10.299990177154541,-2.0,1740481178.47787,10.299990177154541,0.0,1740481178.4778714,10.299990177154541,0.0,, -1740481178.4978259,10.319990158081055,5.001914059077752,1740481178.4978275,10.319990158081055,0.0,1740481178.4978302,10.319990158081055,0.0,1740481178.4978325,10.319990158081055,7.001914059077752,1740481178.4978337,10.319990158081055,0.0,1740481178.497835,10.319990158081055,0.0,1740481178.4978364,10.319990158081055,0.0,1740481178.4978375,10.319990158081055,0.0,1740481178.4978387,10.319990158081055,0.0,1740481178.4978402,10.319990158081055,-2.0,1740481178.4978414,10.319990158081055,-2.0,1740481178.4978426,10.319990158081055,0.0,1740481178.4978435,10.319990158081055,0.0,, -1740481178.5190554,10.339990139007568,5.001914059077752,1740481178.519057,10.339990139007568,0.0,1740481178.51906,10.339990139007568,0.0,1740481178.5190625,10.339990139007568,7.001914059077752,1740481178.5190635,10.339990139007568,0.0,1740481178.5190651,10.339990139007568,0.0,1740481178.5190666,10.339990139007568,0.0,1740481178.5190678,10.339990139007568,0.0,1740481178.519092,10.339990139007568,0.0,1740481178.5190935,10.339990139007568,-2.0,1740481178.5190947,10.339990139007568,-2.0,1740481178.519096,10.339990139007568,0.0,1740481178.519097,10.339990139007568,0.0,, -1740481178.5378122,10.359990119934082,5.001914059077752,1740481178.537814,10.359990119934082,0.0,1740481178.5378168,10.359990119934082,0.0,1740481178.5378199,10.359990119934082,7.001914059077752,1740481178.5378213,10.359990119934082,0.0,1740481178.5378227,10.359990119934082,0.0,1740481178.5378242,10.359990119934082,0.0,1740481178.5378256,10.359990119934082,0.0,1740481178.5378275,10.359990119934082,0.0,1740481178.5378292,10.359990119934082,-2.0,1740481178.5378304,10.359990119934082,-2.0,1740481178.5378318,10.359990119934082,0.0,1740481178.5378332,10.359990119934082,0.0,, -1740481178.5590754,10.379990100860596,5.001914059077752,1740481178.559077,10.379990100860596,0.0,1740481178.5590796,10.379990100860596,0.0,1740481178.559082,10.379990100860596,7.001914059077752,1740481178.5590832,10.379990100860596,0.0,1740481178.5590851,10.379990100860596,0.0,1740481178.5590863,10.379990100860596,0.0,1740481178.5590873,10.379990100860596,0.0,1740481178.5590887,10.379990100860596,0.0,1740481178.55909,10.379990100860596,-2.0,1740481178.559091,10.379990100860596,-2.0,1740481178.5590923,10.379990100860596,0.0,1740481178.5590932,10.379990100860596,0.0,, -1740481178.578226,10.39999008178711,5.001914059077752,1740481178.578228,10.39999008178711,0.0,1740481178.5782304,10.39999008178711,0.0,1740481178.5782328,10.39999008178711,7.001914059077752,1740481178.5782342,10.39999008178711,0.0,1740481178.5782354,10.39999008178711,0.0,1740481178.5782366,10.39999008178711,0.0,1740481178.5782378,10.39999008178711,0.0,1740481178.578239,10.39999008178711,0.0,1740481178.5782402,10.39999008178711,-2.0,1740481178.5782413,10.39999008178711,-2.0,1740481178.5782423,10.39999008178711,0.0,1740481178.5782435,10.39999008178711,0.0,, -1740481178.5984643,10.419990062713623,5.001914059077752,1740481178.5984662,10.419990062713623,0.0,1740481178.5984688,10.419990062713623,0.0,1740481178.5984716,10.419990062713623,7.001914059077752,1740481178.5984726,10.419990062713623,0.0,1740481178.5984745,10.419990062713623,0.0,1740481178.5984757,10.419990062713623,0.0,1740481178.5984771,10.419990062713623,0.0,1740481178.5984783,10.419990062713623,0.0,1740481178.5984795,10.419990062713623,-2.0,1740481178.5984807,10.419990062713623,-2.0,1740481178.598482,10.419990062713623,0.0,1740481178.5984828,10.419990062713623,0.0,, -1740481178.6193986,10.439990043640137,5.001914059077752,1740481178.619402,10.439990043640137,0.0,1740481178.6194072,10.439990043640137,0.0,1740481178.6194096,10.439990043640137,7.001914059077752,1740481178.619411,10.439990043640137,0.0,1740481178.6194124,10.439990043640137,0.0,1740481178.6194139,10.439990043640137,0.0,1740481178.619415,10.439990043640137,0.0,1740481178.6194162,10.439990043640137,0.0,1740481178.6194177,10.439990043640137,-2.0,1740481178.6194186,10.439990043640137,-2.0,1740481178.6194198,10.439990043640137,0.0,1740481178.619421,10.439990043640137,0.0,, -1740481178.6382873,10.45999002456665,5.001914059077752,1740481178.6382895,10.45999002456665,0.0,1740481178.6382923,10.45999002456665,0.0,1740481178.6382945,10.45999002456665,7.001914059077752,1740481178.6382957,10.45999002456665,0.0,1740481178.6382976,10.45999002456665,0.0,1740481178.638299,10.45999002456665,0.0,1740481178.6383002,10.45999002456665,0.0,1740481178.6383014,10.45999002456665,0.0,1740481178.6383028,10.45999002456665,-2.0,1740481178.6383038,10.45999002456665,-2.0,1740481178.638305,10.45999002456665,0.0,1740481178.6383061,10.45999002456665,0.0,, -1740481178.6581042,10.479990005493164,5.001914059077752,1740481178.6581078,10.479990005493164,0.0,1740481178.6581116,10.479990005493164,0.0,1740481178.6581137,10.479990005493164,7.001914059077752,1740481178.6581151,10.479990005493164,0.0,1740481178.6581166,10.479990005493164,0.0,1740481178.6581178,10.479990005493164,0.0,1740481178.6581192,10.479990005493164,0.0,1740481178.6581204,10.479990005493164,0.0,1740481178.6581216,10.479990005493164,-2.0,1740481178.6581225,10.479990005493164,-2.0,1740481178.6581235,10.479990005493164,0.0,1740481178.6581244,10.479990005493164,0.0,, -1740481178.6781485,10.499989986419678,5.001914059077752,1740481178.6781504,10.499989986419678,0.0,1740481178.6781533,10.499989986419678,0.0,1740481178.6781554,10.499989986419678,7.001914059077752,1740481178.6781569,10.499989986419678,0.0,1740481178.6781583,10.499989986419678,0.0,1740481178.67816,10.499989986419678,0.0,1740481178.678161,10.499989986419678,0.0,1740481178.6781623,10.499989986419678,0.0,1740481178.6781635,10.499989986419678,-2.0,1740481178.6781647,10.499989986419678,-2.0,1740481178.6781657,10.499989986419678,0.0,1740481178.6781673,10.499989986419678,0.0,, -1740481178.6980817,10.519989967346191,5.001914059077752,1740481178.6980839,10.519989967346191,0.0,1740481178.6980863,10.519989967346191,0.0,1740481178.6980886,10.519989967346191,7.001914059077752,1740481178.69809,10.519989967346191,0.0,1740481178.6980917,10.519989967346191,0.0,1740481178.698093,10.519989967346191,0.0,1740481178.6980944,10.519989967346191,0.0,1740481178.6980958,10.519989967346191,0.0,1740481178.6980972,10.519989967346191,-2.0,1740481178.6980982,10.519989967346191,-2.0,1740481178.6980994,10.519989967346191,0.0,1740481178.6981006,10.519989967346191,0.0,, -1740481178.718956,10.539989948272705,5.001914059077752,1740481178.718958,10.539989948272705,0.0,1740481178.7189603,10.539989948272705,0.0,1740481178.7189627,10.539989948272705,7.001914059077752,1740481178.7189636,10.539989948272705,0.0,1740481178.7189653,10.539989948272705,0.0,1740481178.7189662,10.539989948272705,0.0,1740481178.7189674,10.539989948272705,0.0,1740481178.7189689,10.539989948272705,0.0,1740481178.7189698,10.539989948272705,-2.0,1740481178.7189713,10.539989948272705,-2.0,1740481178.7189722,10.539989948272705,0.0,1740481178.7189732,10.539989948272705,0.0,, -1740481178.738047,10.559989929199219,5.001914059077752,1740481178.7380488,10.559989929199219,0.0,1740481178.7380514,10.559989929199219,0.0,1740481178.7380698,10.559989929199219,7.001914059077752,1740481178.7380712,10.559989929199219,0.0,1740481178.7380736,10.559989929199219,0.0,1740481178.7380748,10.559989929199219,0.0,1740481178.738076,10.559989929199219,0.0,1740481178.7380774,10.559989929199219,0.0,1740481178.7380788,10.559989929199219,-2.0,1740481178.73808,10.559989929199219,-2.0,1740481178.738081,10.559989929199219,0.0,1740481178.7380824,10.559989929199219,0.0,, -1740481178.7583869,10.579989910125732,5.001914059077752,1740481178.7583888,10.579989910125732,0.0,1740481178.7583916,10.579989910125732,0.0,1740481178.7583938,10.579989910125732,7.001914059077752,1740481178.7583954,10.579989910125732,0.0,1740481178.7583969,10.579989910125732,0.0,1740481178.7583983,10.579989910125732,0.0,1740481178.7583995,10.579989910125732,0.0,1740481178.7584007,10.579989910125732,0.0,1740481178.758402,10.579989910125732,-2.0,1740481178.758403,10.579989910125732,-2.0,1740481178.758404,10.579989910125732,0.0,1740481178.7584054,10.579989910125732,0.0,, -1740481178.7789674,10.599989891052246,5.001914059077752,1740481178.7789693,10.599989891052246,0.0,1740481178.7789721,10.599989891052246,0.0,1740481178.7789748,10.599989891052246,7.001914059077752,1740481178.7789757,10.599989891052246,0.0,1740481178.7789774,10.599989891052246,0.0,1740481178.7789788,10.599989891052246,0.0,1740481178.7789798,10.599989891052246,0.0,1740481178.7789812,10.599989891052246,0.0,1740481178.7789824,10.599989891052246,-2.0,1740481178.7789834,10.599989891052246,-2.0,1740481178.7789845,10.599989891052246,0.0,1740481178.7789857,10.599989891052246,0.0,, -1740481178.797568,10.61998987197876,5.001914059077752,1740481178.7975698,10.61998987197876,0.0,1740481178.7975726,10.61998987197876,0.0,1740481178.797575,10.61998987197876,7.001914059077752,1740481178.797576,10.61998987197876,0.0,1740481178.7975774,10.61998987197876,0.0,1740481178.7975788,10.61998987197876,0.0,1740481178.7975798,10.61998987197876,0.0,1740481178.797581,10.61998987197876,0.0,1740481178.7975824,10.61998987197876,-2.0,1740481178.7975836,10.61998987197876,-2.0,1740481178.7975845,10.61998987197876,0.0,1740481178.7975857,10.61998987197876,0.0,, -1740481178.8190198,10.639989852905273,5.001914059077752,1740481178.8190215,10.639989852905273,0.0,1740481178.819024,10.639989852905273,0.0,1740481178.8190265,10.639989852905273,7.001914059077752,1740481178.8190274,10.639989852905273,0.0,1740481178.819029,10.639989852905273,0.0,1740481178.8190303,10.639989852905273,0.0,1740481178.8190312,10.639989852905273,0.0,1740481178.8190327,10.639989852905273,0.0,1740481178.8190339,10.639989852905273,-2.0,1740481178.8190348,10.639989852905273,-2.0,1740481178.819036,10.639989852905273,0.0,1740481178.8190374,10.639989852905273,0.0,, -1740481178.8390582,10.659989833831787,5.001914059077752,1740481178.8390653,10.659989833831787,0.0,1740481178.8390708,10.659989833831787,0.0,1740481178.8390741,10.659989833831787,7.001914059077752,1740481178.839075,10.659989833831787,0.0,1740481178.8390768,10.659989833831787,0.0,1740481178.8390784,10.659989833831787,0.0,1740481178.8390799,10.659989833831787,0.0,1740481178.8390813,10.659989833831787,0.0,1740481178.8390825,10.659989833831787,-2.0,1740481178.8390834,10.659989833831787,-2.0,1740481178.839085,10.659989833831787,0.0,1740481178.8390863,10.659989833831787,0.0,, -1740481178.8578994,10.6799898147583,5.001914059077752,1740481178.8579016,10.6799898147583,0.0,1740481178.8579044,10.6799898147583,0.0,1740481178.8579066,10.6799898147583,7.001914059077752,1740481178.857908,10.6799898147583,0.0,1740481178.8579097,10.6799898147583,0.0,1740481178.857911,10.6799898147583,0.0,1740481178.8579123,10.6799898147583,0.0,1740481178.857914,10.6799898147583,0.0,1740481178.8579152,10.6799898147583,-2.0,1740481178.8579164,10.6799898147583,-2.0,1740481178.8579178,10.6799898147583,0.0,1740481178.857919,10.6799898147583,0.0,, -1740481178.8786728,10.699989795684814,5.001914059077752,1740481178.8786747,10.699989795684814,0.0,1740481178.8786771,10.699989795684814,0.0,1740481178.8786802,10.699989795684814,7.001914059077752,1740481178.8786817,10.699989795684814,0.0,1740481178.878683,10.699989795684814,0.0,1740481178.878684,10.699989795684814,0.0,1740481178.8786855,10.699989795684814,0.0,1740481178.8786867,10.699989795684814,0.0,1740481178.878688,10.699989795684814,-2.0,1740481178.8786893,10.699989795684814,-2.0,1740481178.8786902,10.699989795684814,0.0,1740481178.8786914,10.699989795684814,0.0,, -1740481178.8975325,10.719989776611328,5.001914059077752,1740481178.8975341,10.719989776611328,0.0,1740481178.8975365,10.719989776611328,0.0,1740481178.897539,10.719989776611328,7.001914059077752,1740481178.89754,10.719989776611328,0.0,1740481178.8975413,10.719989776611328,0.0,1740481178.8975427,10.719989776611328,0.0,1740481178.8975437,10.719989776611328,0.0,1740481178.8975449,10.719989776611328,0.0,1740481178.8975463,10.719989776611328,-2.0,1740481178.8975475,10.719989776611328,-2.0,1740481178.8975484,10.719989776611328,0.0,1740481178.8975496,10.719989776611328,0.0,, -1740481178.9180644,10.739989757537842,5.001914059077752,1740481178.918066,10.739989757537842,0.0,1740481178.9180684,10.739989757537842,0.0,1740481178.9180708,10.739989757537842,7.001914059077752,1740481178.918072,10.739989757537842,0.0,1740481178.9181302,10.739989757537842,0.0,1740481178.9181318,10.739989757537842,0.0,1740481178.9181328,10.739989757537842,0.0,1740481178.9181342,10.739989757537842,0.0,1740481178.9181354,10.739989757537842,-2.0,1740481178.9181366,10.739989757537842,-2.0,1740481178.9181376,10.739989757537842,0.0,1740481178.9181387,10.739989757537842,0.0,, -1740481178.9390953,10.759989738464355,5.001914059077752,1740481178.939097,10.759989738464355,0.0,1740481178.9390993,10.759989738464355,0.0,1740481178.9391017,10.759989738464355,7.001914059077752,1740481178.9391026,10.759989738464355,0.0,1740481178.9391043,10.759989738464355,0.0,1740481178.9391055,10.759989738464355,0.0,1740481178.9391067,10.759989738464355,0.0,1740481178.9391081,10.759989738464355,0.0,1740481178.939109,10.759989738464355,-2.0,1740481178.93911,10.759989738464355,-2.0,1740481178.9391115,10.759989738464355,0.0,1740481178.9391124,10.759989738464355,0.0,, -1740481178.957579,10.77998971939087,5.001914059077752,1740481178.9575818,10.77998971939087,0.0,1740481178.957585,10.77998971939087,0.0,1740481178.9575875,10.77998971939087,7.001914059077752,1740481178.957589,10.77998971939087,0.0,1740481178.957591,10.77998971939087,0.0,1740481178.9575934,10.77998971939087,0.0,1740481178.9575949,10.77998971939087,0.0,1740481178.9575968,10.77998971939087,0.0,1740481178.9575982,10.77998971939087,-2.0,1740481178.9576094,10.77998971939087,-2.0,1740481178.957612,10.77998971939087,0.0,1740481178.9576135,10.77998971939087,0.0,, -1740481178.9781895,10.799989700317383,5.001914059077752,1740481178.9781926,10.799989700317383,0.0,1740481178.9781961,10.799989700317383,0.0,1740481178.9781985,10.799989700317383,7.001914059077752,1740481178.9781995,10.799989700317383,0.0,1740481178.9782012,10.799989700317383,0.0,1740481178.978202,10.799989700317383,0.0,1740481178.978203,10.799989700317383,0.0,1740481178.9782043,10.799989700317383,0.0,1740481178.9782052,10.799989700317383,-2.0,1740481178.9782062,10.799989700317383,-2.0,1740481178.9782073,10.799989700317383,0.0,1740481178.9782083,10.799989700317383,0.0,, -1740481178.9974968,10.819989681243896,5.001914059077752,1740481178.9974983,10.819989681243896,0.0,1740481178.9975007,10.819989681243896,0.0,1740481178.9975028,10.819989681243896,7.001914059077752,1740481178.9975038,10.819989681243896,0.0,1740481178.997505,10.819989681243896,0.0,1740481178.9975216,10.819989681243896,0.0,1740481178.9975228,10.819989681243896,0.0,1740481178.997524,10.819989681243896,0.0,1740481178.997525,10.819989681243896,-2.0,1740481178.997526,10.819989681243896,-2.0,1740481178.9975271,10.819989681243896,0.0,1740481178.997528,10.819989681243896,0.0,, -1740481179.0181386,10.83998966217041,5.001914059077752,1740481179.01814,10.83998966217041,0.0,1740481179.0181422,10.83998966217041,0.0,1740481179.0181444,10.83998966217041,7.001914059077752,1740481179.0181453,10.83998966217041,0.0,1740481179.0181465,10.83998966217041,0.0,1740481179.0181475,10.83998966217041,0.0,1740481179.0181487,10.83998966217041,0.0,1740481179.0181496,10.83998966217041,0.0,1740481179.0181506,10.83998966217041,-2.0,1740481179.0181518,10.83998966217041,-2.0,1740481179.0181527,10.83998966217041,0.0,1740481179.0181537,10.83998966217041,0.0,, -1740481179.038036,10.859989643096924,5.001914059077752,1740481179.0380378,10.859989643096924,0.0,1740481179.0380402,10.859989643096924,0.0,1740481179.0380423,10.859989643096924,7.001914059077752,1740481179.0380435,10.859989643096924,0.0,1740481179.0380447,10.859989643096924,0.0,1740481179.0380456,10.859989643096924,0.0,1740481179.0380468,10.859989643096924,0.0,1740481179.0380478,10.859989643096924,0.0,1740481179.038049,10.859989643096924,-2.0,1740481179.03805,10.859989643096924,-2.0,1740481179.0380514,10.859989643096924,0.0,1740481179.0380523,10.859989643096924,0.0,, -1740481179.0578086,10.879989624023438,5.001914059077752,1740481179.057826,10.879989624023438,0.0,1740481179.0578282,10.879989624023438,0.0,1740481179.0578299,10.879989624023438,7.001914059077752,1740481179.0578308,10.879989624023438,0.0,1740481179.057832,10.879989624023438,0.0,1740481179.057833,10.879989624023438,0.0,1740481179.057834,10.879989624023438,0.0,1740481179.057835,10.879989624023438,0.0,1740481179.057836,10.879989624023438,-2.0,1740481179.0578368,10.879989624023438,-2.0,1740481179.0578375,10.879989624023438,0.0,1740481179.0578387,10.879989624023438,0.0,, -1740481179.0775988,10.899989604949951,5.001914059077752,1740481179.0776,10.899989604949951,0.0,1740481179.0776021,10.899989604949951,0.0,1740481179.0776038,10.899989604949951,7.001914059077752,1740481179.0776048,10.899989604949951,0.0,1740481179.0776062,10.899989604949951,0.0,1740481179.0776072,10.899989604949951,0.0,1740481179.077608,10.899989604949951,0.0,1740481179.0776093,10.899989604949951,0.0,1740481179.0776103,10.899989604949951,-2.0,1740481179.077611,10.899989604949951,-2.0,1740481179.077612,10.899989604949951,0.0,1740481179.0776129,10.899989604949951,0.0,, -1740481179.0989885,10.919989585876465,5.001914059077752,1740481179.0989897,10.919989585876465,0.0,1740481179.0989919,10.919989585876465,0.0,1740481179.098994,10.919989585876465,7.001914059077752,1740481179.0990076,10.919989585876465,0.0,1740481179.09901,10.919989585876465,0.0,1740481179.0990112,10.919989585876465,0.0,1740481179.0990121,10.919989585876465,0.0,1740481179.0990133,10.919989585876465,0.0,1740481179.0990143,10.919989585876465,-2.0,1740481179.0990152,10.919989585876465,-2.0,1740481179.0990162,10.919989585876465,0.0,1740481179.099017,10.919989585876465,0.0,, -1740481179.1181674,10.939989566802979,5.001914059077752,1740481179.1181688,10.939989566802979,0.0,1740481179.1181712,10.939989566802979,0.0,1740481179.1181731,10.939989566802979,7.001914059077752,1740481179.1181746,10.939989566802979,0.0,1740481179.1181757,10.939989566802979,0.0,1740481179.1181767,10.939989566802979,0.0,1740481179.118178,10.939989566802979,0.0,1740481179.1181788,10.939989566802979,0.0,1740481179.11818,10.939989566802979,-2.0,1740481179.1181808,10.939989566802979,-2.0,1740481179.118182,10.939989566802979,0.0,1740481179.118183,10.939989566802979,0.0,, -1740481179.1391075,10.959989547729492,5.001914059077752,1740481179.139109,10.959989547729492,0.0,1740481179.1391115,10.959989547729492,0.0,1740481179.1391144,10.959989547729492,7.001914059077752,1740481179.1391158,10.959989547729492,0.0,1740481179.1391175,10.959989547729492,0.0,1740481179.1391191,10.959989547729492,0.0,1740481179.1391206,10.959989547729492,0.0,1740481179.1391222,10.959989547729492,0.0,1740481179.1391237,10.959989547729492,-2.0,1740481179.1391246,10.959989547729492,-2.0,1740481179.1391256,10.959989547729492,0.0,1740481179.1391268,10.959989547729492,0.0,, -1740481179.1580799,10.979989528656006,5.001914059077752,1740481179.1580813,10.979989528656006,0.0,1740481179.1580834,10.979989528656006,0.0,1740481179.158085,10.979989528656006,7.001914059077752,1740481179.158086,10.979989528656006,0.0,1740481179.1580875,10.979989528656006,0.0,1740481179.1580884,10.979989528656006,0.0,1740481179.1580894,10.979989528656006,0.0,1740481179.1580906,10.979989528656006,0.0,1740481179.1580918,10.979989528656006,-2.0,1740481179.1580925,10.979989528656006,-2.0,1740481179.1580935,10.979989528656006,0.0,1740481179.1580946,10.979989528656006,0.0,, -1740481179.1777923,10.99998950958252,5.001914059077752,1740481179.1777937,10.99998950958252,0.0,1740481179.177796,10.99998950958252,0.0,1740481179.1777976,10.99998950958252,7.001914059077752,1740481179.1777987,10.99998950958252,0.0,1740481179.1778004,10.99998950958252,0.0,1740481179.1778014,10.99998950958252,0.0,1740481179.1778023,10.99998950958252,0.0,1740481179.1778033,10.99998950958252,0.0,1740481179.1778042,10.99998950958252,-2.0,1740481179.177805,10.99998950958252,-2.0,1740481179.1778061,10.99998950958252,0.0,1740481179.177807,10.99998950958252,0.0,, -1740481179.1990416,11.019989490509033,5.001914059077752,1740481179.199043,11.019989490509033,0.0,1740481179.199045,11.019989490509033,0.0,1740481179.1990469,11.019989490509033,7.001914059077752,1740481179.199048,11.019989490509033,0.0,1740481179.199049,11.019989490509033,0.0,1740481179.1990502,11.019989490509033,0.0,1740481179.199051,11.019989490509033,0.0,1740481179.199052,11.019989490509033,0.0,1740481179.199053,11.019989490509033,-2.0,1740481179.1990538,11.019989490509033,-2.0,1740481179.1990545,11.019989490509033,0.0,1740481179.1990557,11.019989490509033,0.0,, -1740481179.2229753,11.039989471435547,5.001914059077752,1740481179.222977,11.039989471435547,0.0,1740481179.2229798,11.039989471435547,0.0,1740481179.2229822,11.039989471435547,7.001914059077752,1740481179.2229831,11.039989471435547,0.0,1740481179.2229846,11.039989471435547,0.0,1740481179.2229855,11.039989471435547,0.0,1740481179.2229862,11.039989471435547,0.0,1740481179.2229872,11.039989471435547,0.0,1740481179.2229884,11.039989471435547,-2.0,1740481179.222989,11.039989471435547,-2.0,1740481179.2229898,11.039989471435547,0.0,1740481179.2229908,11.039989471435547,0.0,, -1740481179.2385824,11.05998945236206,5.001914059077752,1740481179.2385838,11.05998945236206,0.0,1740481179.2385857,11.05998945236206,0.0,1740481179.2385876,11.05998945236206,7.001914059077752,1740481179.2385883,11.05998945236206,0.0,1740481179.2385898,11.05998945236206,0.0,1740481179.2385907,11.05998945236206,0.0,1740481179.2385917,11.05998945236206,0.0,1740481179.2385929,11.05998945236206,0.0,1740481179.2385938,11.05998945236206,-2.0,1740481179.2385945,11.05998945236206,-2.0,1740481179.2385955,11.05998945236206,0.0,1740481179.2385964,11.05998945236206,0.0,, -1740481179.2578998,11.079989433288574,5.001914059077752,1740481179.257901,11.079989433288574,0.0,1740481179.2579033,11.079989433288574,0.0,1740481179.2579052,11.079989433288574,7.001914059077752,1740481179.2579062,11.079989433288574,0.0,1740481179.2579072,11.079989433288574,0.0,1740481179.257908,11.079989433288574,0.0,1740481179.2579093,11.079989433288574,0.0,1740481179.2579103,11.079989433288574,0.0,1740481179.257911,11.079989433288574,-2.0,1740481179.2579122,11.079989433288574,-2.0,1740481179.257913,11.079989433288574,0.0,1740481179.2579138,11.079989433288574,0.0,, -1740481179.2780852,11.099989414215088,5.001914059077752,1740481179.2780867,11.099989414215088,0.0,1740481179.2780888,11.099989414215088,0.0,1740481179.2780905,11.099989414215088,7.001914059077752,1740481179.2780914,11.099989414215088,0.0,1740481179.2780926,11.099989414215088,0.0,1740481179.2780936,11.099989414215088,0.0,1740481179.2780943,11.099989414215088,0.0,1740481179.2780952,11.099989414215088,0.0,1740481179.2780964,11.099989414215088,-2.0,1740481179.2780972,11.099989414215088,-2.0,1740481179.2780979,11.099989414215088,0.0,1740481179.278099,11.099989414215088,0.0,, -1740481179.297805,11.119989395141602,5.001914059077752,1740481179.2978065,11.119989395141602,0.0,1740481179.2978084,11.119989395141602,0.0,1740481179.2978103,11.119989395141602,7.001914059077752,1740481179.2978115,11.119989395141602,0.0,1740481179.2978127,11.119989395141602,0.0,1740481179.2978134,11.119989395141602,0.0,1740481179.2978146,11.119989395141602,0.0,1740481179.2978156,11.119989395141602,0.0,1740481179.2978163,11.119989395141602,-2.0,1740481179.2978172,11.119989395141602,-2.0,1740481179.2978182,11.119989395141602,0.0,1740481179.2978194,11.119989395141602,0.0,, -1740481179.3191564,11.139989376068115,5.001914059077752,1740481179.3191578,11.139989376068115,0.0,1740481179.3191597,11.139989376068115,0.0,1740481179.319162,11.139989376068115,7.001914059077752,1740481179.3191626,11.139989376068115,0.0,1740481179.3191638,11.139989376068115,0.0,1740481179.319165,11.139989376068115,0.0,1740481179.3191657,11.139989376068115,0.0,1740481179.3191667,11.139989376068115,0.0,1740481179.3191679,11.139989376068115,-2.0,1740481179.3191688,11.139989376068115,-2.0,1740481179.3191695,11.139989376068115,0.0,1740481179.3191707,11.139989376068115,0.0,, -1740481179.3380055,11.159989356994629,5.001914059077752,1740481179.338007,11.159989356994629,0.0,1740481179.338009,11.159989356994629,0.0,1740481179.338011,11.159989356994629,7.001914059077752,1740481179.3380122,11.159989356994629,0.0,1740481179.3380134,11.159989356994629,0.0,1740481179.3380144,11.159989356994629,0.0,1740481179.3380158,11.159989356994629,0.0,1740481179.3380165,11.159989356994629,0.0,1740481179.338018,11.159989356994629,-2.0,1740481179.338019,11.159989356994629,-2.0,1740481179.3380198,11.159989356994629,0.0,1740481179.3380206,11.159989356994629,0.0,, -1740481179.3579063,11.179989337921143,5.001914059077752,1740481179.357908,11.179989337921143,0.0,1740481179.35791,11.179989337921143,0.0,1740481179.357912,11.179989337921143,7.001914059077752,1740481179.3579133,11.179989337921143,0.0,1740481179.3579152,11.179989337921143,0.0,1740481179.3579164,11.179989337921143,0.0,1740481179.3579175,11.179989337921143,0.0,1740481179.3579185,11.179989337921143,0.0,1740481179.3579202,11.179989337921143,-2.0,1740481179.3579211,11.179989337921143,-2.0,1740481179.357922,11.179989337921143,0.0,1740481179.3579228,11.179989337921143,0.0,, -1740481179.377991,11.199989318847656,5.001914059077752,1740481179.3779924,11.199989318847656,0.0,1740481179.3779945,11.199989318847656,0.0,1740481179.3779962,11.199989318847656,7.001914059077752,1740481179.3779974,11.199989318847656,0.0,1740481179.3779984,11.199989318847656,0.0,1740481179.3779993,11.199989318847656,0.0,1740481179.3780005,11.199989318847656,0.0,1740481179.3780015,11.199989318847656,0.0,1740481179.3780022,11.199989318847656,-2.0,1740481179.3780031,11.199989318847656,-2.0,1740481179.378004,11.199989318847656,0.0,1740481179.378005,11.199989318847656,0.0,, -1740481179.398106,11.21998929977417,5.001914059077752,1740481179.3981287,11.21998929977417,0.0,1740481179.3981307,11.21998929977417,0.0,1740481179.3981328,11.21998929977417,7.001914059077752,1740481179.3981338,11.21998929977417,0.0,1740481179.398135,11.21998929977417,0.0,1740481179.3981361,11.21998929977417,0.0,1740481179.398154,11.21998929977417,0.0,1740481179.3981547,11.21998929977417,0.0,1740481179.3981557,11.21998929977417,-2.0,1740481179.398157,11.21998929977417,-2.0,1740481179.3981578,11.21998929977417,0.0,1740481179.398159,11.21998929977417,0.0,, -1740481179.4198349,11.239989280700684,5.001914059077752,1740481179.419836,11.239989280700684,0.0,1740481179.419838,11.239989280700684,0.0,1740481179.41984,11.239989280700684,7.001914059077752,1740481179.419841,11.239989280700684,0.0,1740481179.4198422,11.239989280700684,0.0,1740481179.4198434,11.239989280700684,0.0,1740481179.4198442,11.239989280700684,0.0,1740481179.419845,11.239989280700684,0.0,1740481179.419846,11.239989280700684,-2.0,1740481179.4198472,11.239989280700684,-2.0,1740481179.419848,11.239989280700684,0.0,1740481179.4198487,11.239989280700684,0.0,, -1740481179.4378688,11.259989261627197,5.001914059077752,1740481179.4378703,11.259989261627197,0.0,1740481179.4378722,11.259989261627197,0.0,1740481179.4378743,11.259989261627197,7.001914059077752,1740481179.4378755,11.259989261627197,0.0,1740481179.4378767,11.259989261627197,0.0,1740481179.4378777,11.259989261627197,0.0,1740481179.4378788,11.259989261627197,0.0,1740481179.4378798,11.259989261627197,0.0,1740481179.4378805,11.259989261627197,-2.0,1740481179.4378817,11.259989261627197,-2.0,1740481179.4378827,11.259989261627197,0.0,1740481179.4378834,11.259989261627197,0.0,, -1740481179.4593956,11.279989242553711,5.001914059077752,1740481179.459397,11.279989242553711,0.0,1740481179.4593997,11.279989242553711,0.0,1740481179.4594018,11.279989242553711,7.001914059077752,1740481179.459403,11.279989242553711,0.0,1740481179.459405,11.279989242553711,0.0,1740481179.4594066,11.279989242553711,0.0,1740481179.4594076,11.279989242553711,0.0,1740481179.4594085,11.279989242553711,0.0,1740481179.4594097,11.279989242553711,-2.0,1740481179.4594107,11.279989242553711,-2.0,1740481179.4594114,11.279989242553711,0.0,1740481179.4594128,11.279989242553711,0.0,, -1740481179.4778204,11.299989223480225,5.001914059077752,1740481179.477822,11.299989223480225,0.0,1740481179.4778244,11.299989223480225,0.0,1740481179.4778266,11.299989223480225,7.001914059077752,1740481179.4778278,11.299989223480225,0.0,1740481179.4778295,11.299989223480225,0.0,1740481179.4778306,11.299989223480225,0.0,1740481179.4778316,11.299989223480225,0.0,1740481179.477833,11.299989223480225,0.0,1740481179.477834,11.299989223480225,-2.0,1740481179.477835,11.299989223480225,-2.0,1740481179.477836,11.299989223480225,0.0,1740481179.4778368,11.299989223480225,0.0,, -1740481179.498597,11.319989204406738,5.001914059077752,1740481179.4985988,11.319989204406738,0.0,1740481179.4986017,11.319989204406738,0.0,1740481179.4986043,11.319989204406738,7.001914059077752,1740481179.4986057,11.319989204406738,0.0,1740481179.4986079,11.319989204406738,0.0,1740481179.4986098,11.319989204406738,0.0,1740481179.4986112,11.319989204406738,0.0,1740481179.4986124,11.319989204406738,0.0,1740481179.4986145,11.319989204406738,-2.0,1740481179.4986155,11.319989204406738,-2.0,1740481179.4986174,11.319989204406738,0.0,1740481179.4986186,11.319989204406738,0.0,, -1740481179.5192676,11.339989185333252,5.001914059077752,1740481179.5192692,11.339989185333252,0.0,1740481179.5192711,11.339989185333252,0.0,1740481179.5192733,11.339989185333252,7.001914059077752,1740481179.5192742,11.339989185333252,0.0,1740481179.5192754,11.339989185333252,0.0,1740481179.5192766,11.339989185333252,0.0,1740481179.5192776,11.339989185333252,0.0,1740481179.5192785,11.339989185333252,0.0,1740481179.51928,11.339989185333252,-2.0,1740481179.5192807,11.339989185333252,-2.0,1740481179.5192816,11.339989185333252,0.0,1740481179.5192823,11.339989185333252,0.0,, -1740481179.5377727,11.359989166259766,5.001914059077752,1740481179.5377738,11.359989166259766,0.0,1740481179.5377758,11.359989166259766,0.0,1740481179.537778,11.359989166259766,7.001914059077752,1740481179.5377789,11.359989166259766,0.0,1740481179.5377805,11.359989166259766,0.0,1740481179.5377817,11.359989166259766,0.0,1740481179.5377827,11.359989166259766,0.0,1740481179.5377839,11.359989166259766,0.0,1740481179.5377848,11.359989166259766,-2.0,1740481179.537786,11.359989166259766,-2.0,1740481179.5377874,11.359989166259766,0.0,1740481179.5377882,11.359989166259766,0.0,, -1740481179.5577796,11.37998914718628,5.001914059077752,1740481179.557781,11.37998914718628,0.0,1740481179.557783,11.37998914718628,0.0,1740481179.5577848,11.37998914718628,7.001914059077752,1740481179.5577862,11.37998914718628,0.0,1740481179.5577874,11.37998914718628,0.0,1740481179.5577884,11.37998914718628,0.0,1740481179.5577893,11.37998914718628,0.0,1740481179.5577905,11.37998914718628,0.0,1740481179.5577915,11.37998914718628,-2.0,1740481179.5577924,11.37998914718628,-2.0,1740481179.5577934,11.37998914718628,0.0,1740481179.557794,11.37998914718628,0.0,, -1740481179.5783503,11.399989128112793,5.001914059077752,1740481179.5783525,11.399989128112793,0.0,1740481179.5783556,11.399989128112793,0.0,1740481179.5783582,11.399989128112793,7.001914059077752,1740481179.5783594,11.399989128112793,0.0,1740481179.5783608,11.399989128112793,0.0,1740481179.5783617,11.399989128112793,0.0,1740481179.578364,11.399989128112793,0.0,1740481179.5783648,11.399989128112793,0.0,1740481179.5783665,11.399989128112793,-2.0,1740481179.5783672,11.399989128112793,-2.0,1740481179.5783682,11.399989128112793,0.0,1740481179.5783696,11.399989128112793,0.0,, -1740481179.599526,11.419989109039307,5.001914059077752,1740481179.5995276,11.419989109039307,0.0,1740481179.5995297,11.419989109039307,0.0,1740481179.5995314,11.419989109039307,7.001914059077752,1740481179.5995326,11.419989109039307,0.0,1740481179.5995338,11.419989109039307,0.0,1740481179.5995345,11.419989109039307,0.0,1740481179.5995357,11.419989109039307,0.0,1740481179.5995367,11.419989109039307,0.0,1740481179.5995376,11.419989109039307,-2.0,1740481179.5995388,11.419989109039307,-2.0,1740481179.5995398,11.419989109039307,0.0,1740481179.5995405,11.419989109039307,0.0,, -1740481179.6196475,11.43998908996582,5.001914059077752,1740481179.619649,11.43998908996582,0.0,1740481179.619651,11.43998908996582,0.0,1740481179.6196527,11.43998908996582,7.001914059077752,1740481179.619654,11.43998908996582,0.0,1740481179.6196551,11.43998908996582,0.0,1740481179.619656,11.43998908996582,0.0,1740481179.6196573,11.43998908996582,0.0,1740481179.619658,11.43998908996582,0.0,1740481179.619659,11.43998908996582,-2.0,1740481179.6196601,11.43998908996582,-2.0,1740481179.6196609,11.43998908996582,0.0,1740481179.6196618,11.43998908996582,0.0,, -1740481179.6374786,11.459989070892334,5.001914059077752,1740481179.6374803,11.459989070892334,0.0,1740481179.637482,11.459989070892334,0.0,1740481179.6374843,11.459989070892334,7.001914059077752,1740481179.6374853,11.459989070892334,0.0,1740481179.6374862,11.459989070892334,0.0,1740481179.6374874,11.459989070892334,0.0,1740481179.6374884,11.459989070892334,0.0,1740481179.6374893,11.459989070892334,0.0,1740481179.6374905,11.459989070892334,-2.0,1740481179.6374915,11.459989070892334,-2.0,1740481179.6374922,11.459989070892334,0.0,1740481179.6374931,11.459989070892334,0.0,, -1740481179.658676,11.479989051818848,5.001914059077752,1740481179.6586778,11.479989051818848,0.0,1740481179.6586807,11.479989051818848,0.0,1740481179.658683,11.479989051818848,7.001914059077752,1740481179.658685,11.479989051818848,0.0,1740481179.658697,11.479989051818848,0.0,1740481179.6587007,11.479989051818848,0.0,1740481179.6587021,11.479989051818848,0.0,1740481179.6587033,11.479989051818848,0.0,1740481179.6587043,11.479989051818848,-2.0,1740481179.6587057,11.479989051818848,-2.0,1740481179.658707,11.479989051818848,0.0,1740481179.6587079,11.479989051818848,0.0,, -1740481179.6783593,11.499989032745361,5.001914059077752,1740481179.678361,11.499989032745361,0.0,1740481179.6783626,11.499989032745361,0.0,1740481179.6783648,11.499989032745361,7.001914059077752,1740481179.6783657,11.499989032745361,0.0,1740481179.678367,11.499989032745361,0.0,1740481179.678368,11.499989032745361,0.0,1740481179.6783688,11.499989032745361,0.0,1740481179.6783698,11.499989032745361,0.0,1740481179.6783707,11.499989032745361,-2.0,1740481179.678372,11.499989032745361,-2.0,1740481179.6783726,11.499989032745361,0.0,1740481179.6783733,11.499989032745361,0.0,, -1740481179.6982338,11.519989013671875,5.001914059077752,1740481179.6982353,11.519989013671875,0.0,1740481179.6982374,11.519989013671875,0.0,1740481179.6982396,11.519989013671875,7.001914059077752,1740481179.6982408,11.519989013671875,0.0,1740481179.698242,11.519989013671875,0.0,1740481179.6982431,11.519989013671875,0.0,1740481179.698244,11.519989013671875,0.0,1740481179.698245,11.519989013671875,0.0,1740481179.6982462,11.519989013671875,-2.0,1740481179.6982472,11.519989013671875,-2.0,1740481179.698248,11.519989013671875,0.0,1740481179.6982489,11.519989013671875,0.0,, -1740481179.7186706,11.539988994598389,5.001914059077752,1740481179.718672,11.539988994598389,0.0,1740481179.7186742,11.539988994598389,0.0,1740481179.7186763,11.539988994598389,7.001914059077752,1740481179.718677,11.539988994598389,0.0,1740481179.7186782,11.539988994598389,0.0,1740481179.7186792,11.539988994598389,0.0,1740481179.7186801,11.539988994598389,0.0,1740481179.718681,11.539988994598389,0.0,1740481179.718682,11.539988994598389,-2.0,1740481179.7186828,11.539988994598389,-2.0,1740481179.718684,11.539988994598389,0.0,1740481179.718685,11.539988994598389,0.0,, -1740481179.738015,11.559988975524902,5.001914059077752,1740481179.7380166,11.559988975524902,0.0,1740481179.7380183,11.559988975524902,0.0,1740481179.7380207,11.559988975524902,7.001914059077752,1740481179.7380216,11.559988975524902,0.0,1740481179.7380228,11.559988975524902,0.0,1740481179.738024,11.559988975524902,0.0,1740481179.738025,11.559988975524902,0.0,1740481179.738026,11.559988975524902,0.0,1740481179.7380273,11.559988975524902,-2.0,1740481179.7380283,11.559988975524902,-2.0,1740481179.738029,11.559988975524902,0.0,1740481179.7380302,11.559988975524902,0.0,, -1740481179.7577639,11.579988956451416,5.001914059077752,1740481179.7577653,11.579988956451416,0.0,1740481179.7577677,11.579988956451416,0.0,1740481179.7577698,11.579988956451416,7.001914059077752,1740481179.7577708,11.579988956451416,0.0,1740481179.7577722,11.579988956451416,0.0,1740481179.7577734,11.579988956451416,0.0,1740481179.757774,11.579988956451416,0.0,1740481179.757775,11.579988956451416,0.0,1740481179.7577765,11.579988956451416,-2.0,1740481179.7577775,11.579988956451416,-2.0,1740481179.7577782,11.579988956451416,0.0,1740481179.7577791,11.579988956451416,0.0,, -1740481179.779371,11.59998893737793,5.001914059077752,1740481179.7793734,11.59998893737793,0.0,1740481179.7793772,11.59998893737793,0.0,1740481179.7793796,11.59998893737793,7.001914059077752,1740481179.7793813,11.59998893737793,0.0,1740481179.7793827,11.59998893737793,0.0,1740481179.7793844,11.59998893737793,0.0,1740481179.7793856,11.59998893737793,0.0,1740481179.7793872,11.59998893737793,0.0,1740481179.779389,11.59998893737793,-2.0,1740481179.77939,11.59998893737793,-2.0,1740481179.7793913,11.59998893737793,0.0,1740481179.7793922,11.59998893737793,0.0,, -1740481179.7989485,11.619988918304443,5.001914059077752,1740481179.7989502,11.619988918304443,0.0,1740481179.7989652,11.619988918304443,0.0,1740481179.798968,11.619988918304443,7.001914059077752,1740481179.798969,11.619988918304443,0.0,1740481179.7989705,11.619988918304443,0.0,1740481179.7989714,11.619988918304443,0.0,1740481179.7989724,11.619988918304443,0.0,1740481179.7989733,11.619988918304443,0.0,1740481179.7989745,11.619988918304443,-2.0,1740481179.7989757,11.619988918304443,-2.0,1740481179.7989764,11.619988918304443,0.0,1740481179.7989776,11.619988918304443,0.0,, -1740481179.8181958,11.639988899230957,5.001914059077752,1740481179.8181973,11.639988899230957,0.0,1740481179.8181992,11.639988899230957,0.0,1740481179.818201,11.639988899230957,7.001914059077752,1740481179.8182018,11.639988899230957,0.0,1740481179.8182032,11.639988899230957,0.0,1740481179.8182042,11.639988899230957,0.0,1740481179.8182049,11.639988899230957,0.0,1740481179.8182058,11.639988899230957,0.0,1740481179.818207,11.639988899230957,-2.0,1740481179.8182077,11.639988899230957,-2.0,1740481179.8182085,11.639988899230957,0.0,1740481179.8182096,11.639988899230957,0.0,, -1740481179.838566,11.65998888015747,5.001914059077752,1740481179.8385677,11.65998888015747,0.0,1740481179.8385696,11.65998888015747,0.0,1740481179.8385718,11.65998888015747,7.001914059077752,1740481179.8385727,11.65998888015747,0.0,1740481179.8385742,11.65998888015747,0.0,1740481179.8385754,11.65998888015747,0.0,1740481179.8385763,11.65998888015747,0.0,1740481179.8385775,11.65998888015747,0.0,1740481179.8385785,11.65998888015747,-2.0,1740481179.8385792,11.65998888015747,-2.0,1740481179.8385801,11.65998888015747,0.0,1740481179.8385813,11.65998888015747,0.0,, -1740481179.8595781,11.679988861083984,5.001914059077752,1740481179.8595796,11.679988861083984,0.0,1740481179.8595822,11.679988861083984,0.0,1740481179.8595846,11.679988861083984,7.001914059077752,1740481179.8595855,11.679988861083984,0.0,1740481179.859587,11.679988861083984,0.0,1740481179.8595884,11.679988861083984,0.0,1740481179.8595898,11.679988861083984,0.0,1740481179.8595912,11.679988861083984,0.0,1740481179.8595924,11.679988861083984,-2.0,1740481179.8595934,11.679988861083984,-2.0,1740481179.8595946,11.679988861083984,0.0,1740481179.8595955,11.679988861083984,0.0,, -1740481179.8806603,11.699988842010498,5.001914059077752,1740481179.880662,11.699988842010498,0.0,1740481179.8806646,11.699988842010498,0.0,1740481179.8806672,11.699988842010498,7.001914059077752,1740481179.8806684,11.699988842010498,0.0,1740481179.8806703,11.699988842010498,0.0,1740481179.8806715,11.699988842010498,0.0,1740481179.880673,11.699988842010498,0.0,1740481179.8806746,11.699988842010498,0.0,1740481179.8806767,11.699988842010498,-2.0,1740481179.8806784,11.699988842010498,-2.0,1740481179.8806963,11.699988842010498,0.0,1740481179.8806992,11.699988842010498,0.0,, -1740481179.8979137,11.719988822937012,5.001914059077752,1740481179.8979151,11.719988822937012,0.0,1740481179.8979175,11.719988822937012,0.0,1740481179.8979192,11.719988822937012,7.001914059077752,1740481179.8979204,11.719988822937012,0.0,1740481179.8979218,11.719988822937012,0.0,1740481179.8979228,11.719988822937012,0.0,1740481179.8979242,11.719988822937012,0.0,1740481179.897925,11.719988822937012,0.0,1740481179.897926,11.719988822937012,-2.0,1740481179.8979268,11.719988822937012,-2.0,1740481179.897928,11.719988822937012,0.0,1740481179.897929,11.719988822937012,0.0,, -1740481179.9186502,11.739988803863525,5.001914059077752,1740481179.9186513,11.739988803863525,0.0,1740481179.9186535,11.739988803863525,0.0,1740481179.9186552,11.739988803863525,7.001914059077752,1740481179.9186563,11.739988803863525,0.0,1740481179.9186575,11.739988803863525,0.0,1740481179.9186585,11.739988803863525,0.0,1740481179.9186597,11.739988803863525,0.0,1740481179.9186606,11.739988803863525,0.0,1740481179.9186614,11.739988803863525,-2.0,1740481179.9186623,11.739988803863525,-2.0,1740481179.9186633,11.739988803863525,0.0,1740481179.9186642,11.739988803863525,0.0,, -1740481179.9389234,11.759988784790039,5.001914059077752,1740481179.9389248,11.759988784790039,0.0,1740481179.938927,11.759988784790039,0.0,1740481179.9389288,11.759988784790039,7.001914059077752,1740481179.9389305,11.759988784790039,0.0,1740481179.9389317,11.759988784790039,0.0,1740481179.9389327,11.759988784790039,0.0,1740481179.9389338,11.759988784790039,0.0,1740481179.9389348,11.759988784790039,0.0,1740481179.9389358,11.759988784790039,-2.0,1740481179.9389365,11.759988784790039,-2.0,1740481179.9389377,11.759988784790039,0.0,1740481179.9389384,11.759988784790039,0.0,, -1740481179.9597747,11.779988765716553,5.001914059077752,1740481179.959776,11.779988765716553,0.0,1740481179.9597778,11.779988765716553,0.0,1740481179.9597797,11.779988765716553,7.001914059077752,1740481179.9597812,11.779988765716553,0.0,1740481179.9597824,11.779988765716553,0.0,1740481179.9597833,11.779988765716553,0.0,1740481179.9597843,11.779988765716553,0.0,1740481179.9597852,11.779988765716553,0.0,1740481179.9597862,11.779988765716553,-2.0,1740481179.959787,11.779988765716553,-2.0,1740481179.959788,11.779988765716553,0.0,1740481179.9597888,11.779988765716553,0.0,, -1740481179.9777527,11.799988746643066,5.001914059077752,1740481179.977754,11.799988746643066,0.0,1740481179.9777558,11.799988746643066,0.0,1740481179.977758,11.799988746643066,7.001914059077752,1740481179.977759,11.799988746643066,0.0,1740481179.9777603,11.799988746643066,0.0,1740481179.9777613,11.799988746643066,0.0,1740481179.9777622,11.799988746643066,0.0,1740481179.9777632,11.799988746643066,0.0,1740481179.9777641,11.799988746643066,-2.0,1740481179.977765,11.799988746643066,-2.0,1740481179.9777658,11.799988746643066,0.0,1740481179.977767,11.799988746643066,0.0,, -1740481179.9980574,11.81998872756958,5.001914059077752,1740481179.998059,11.81998872756958,0.0,1740481179.998061,11.81998872756958,0.0,1740481179.9980772,11.81998872756958,7.001914059077752,1740481179.9980783,11.81998872756958,0.0,1740481179.9980805,11.81998872756958,0.0,1740481179.9980817,11.81998872756958,0.0,1740481179.9980829,11.81998872756958,0.0,1740481179.9980838,11.81998872756958,0.0,1740481179.998085,11.81998872756958,-2.0,1740481179.998086,11.81998872756958,-2.0,1740481179.998087,11.81998872756958,0.0,1740481179.998088,11.81998872756958,0.0,, -1740481180.0204206,11.839988708496094,5.001914059077752,1740481180.0204222,11.839988708496094,0.0,1740481180.0204244,11.839988708496094,0.0,1740481180.0204265,11.839988708496094,7.001914059077752,1740481180.0204272,11.839988708496094,0.0,1740481180.0204287,11.839988708496094,0.0,1740481180.0204298,11.839988708496094,0.0,1740481180.0204306,11.839988708496094,0.0,1740481180.0204315,11.839988708496094,0.061237243569578145,1740481180.0204327,11.839988708496094,0.0,1740481180.0204334,11.839988708496094,0.061237243569578145,1740481180.0204341,11.839988708496094,0.0,1740481180.020435,11.839988708496094,0.0,, -1740481180.0379238,11.859988689422607,5.00192018280211,1740481180.037926,11.859988689422607,0.0,1740481180.0379276,11.859988689422607,6.123724357820362e-08,1740481180.0379298,11.859988689422607,7.004362997610343,1740481180.0379305,11.859988689422607,0.0,1740481180.037932,11.859988689422607,0.0,1740481180.037933,11.859988689422607,0.0,1740481180.037934,11.859988689422607,0.0,1740481180.037935,11.859988689422607,0.061237243569578145,1740481180.0379362,11.859988689422607,1.0,1740481180.0379372,11.859988689422607,1.0594562413694542,1740481180.037938,11.859988689422607,0.0,1740481180.0379388,11.859988689422607,0.001224438647673715,, -1740481180.0601723,11.879988670349121,5.00192018280211,1740481180.0601747,11.879988670349121,0.0,1740481180.0601766,11.879988670349121,6.123724357820362e-08,1740481180.060179,11.879988670349121,7.004362997610343,1740481180.06018,11.879988670349121,0.0,1740481180.0601811,11.879988670349121,0.0,1740481180.0601826,11.879988670349121,0.0,1740481180.0601835,11.879988670349121,0.0,1740481180.0601842,11.879988670349121,0.061237243569578145,1740481180.0601857,11.879988670349121,1.0,1740481180.0601866,11.879988670349121,1.0600128049219044,1740481180.0601873,11.879988670349121,0.0,1740481180.060188,11.879988670349121,0.001224438647673715,, -1740481180.078867,11.899988651275635,5.00192018280211,1740481180.0788686,11.899988651275635,0.0,1740481180.0788708,11.899988651275635,6.123724357820362e-08,1740481180.0788727,11.899988651275635,7.004362997610343,1740481180.0788736,11.899988651275635,0.0,1740481180.0788755,11.899988651275635,0.0,1740481180.0788765,11.899988651275635,0.0,1740481180.0788774,11.899988651275635,0.0,1740481180.0788782,11.899988651275635,0.061237243569578145,1740481180.0788796,11.899988651275635,1.0,1740481180.0788803,11.899988651275635,1.0600128049219044,1740481180.0788813,11.899988651275635,0.0,1740481180.078882,11.899988651275635,0.001224438647673715,, -1740481180.1001308,11.919988632202148,5.00192018280211,1740481180.1001327,11.919988632202148,0.0,1740481180.1001346,11.919988632202148,6.123724357820362e-08,1740481180.1001368,11.919988632202148,7.004362997610343,1740481180.1001377,11.919988632202148,0.0,1740481180.100139,11.919988632202148,0.0,1740481180.1001406,11.919988632202148,0.0,1740481180.1001415,11.919988632202148,0.0,1740481180.1001425,11.919988632202148,0.061237243569578145,1740481180.1001437,11.919988632202148,1.0,1740481180.1001444,11.919988632202148,1.0600128049219044,1740481180.1001453,11.919988632202148,0.0,1740481180.1001463,11.919988632202148,0.001224438647673715,, -1740481180.1220446,11.939988613128662,5.00192018280211,1740481180.1220465,11.939988613128662,0.0,1740481180.1220486,11.939988613128662,0.0,1740481180.1220503,11.939988613128662,7.004369060097456,1740481180.1220512,11.939988613128662,0.0,1740481180.1220527,11.939988613128662,0.0,1740481180.1220536,11.939988613128662,0.0,1740481180.1220543,11.939988613128662,0.0,1740481180.1220555,11.939988613128662,0.062461682217254705,1740481180.1220565,11.939988613128662,0.0,1740481180.1220572,11.939988613128662,0.06123724356958099,1740481180.122058,11.939988613128662,0.0,1740481180.122059,11.939988613128662,0.001224438647673715,, -1740481180.1381142,11.959988594055176,5.00192018280211,1740481180.1381276,11.959988594055176,0.0,1740481180.138131,11.959988594055176,0.0,1740481180.1381335,11.959988594055176,7.004369060097456,1740481180.1381347,11.959988594055176,0.0,1740481180.1381361,11.959988594055176,0.0,1740481180.138137,11.959988594055176,0.0,1740481180.138138,11.959988594055176,0.0,1740481180.1381388,11.959988594055176,0.062461682217254705,1740481180.13814,11.959988594055176,0.0,1740481180.1381407,11.959988594055176,0.06123724356958099,1740481180.1381416,11.959988594055176,0.0,1740481180.1381428,11.959988594055176,0.001224438647673715,, -1740481180.1594496,11.97998857498169,5.007452330469965,1740481180.159452,11.97998857498169,0.0,1740481180.1594543,11.97998857498169,5.642762957086539e-05,1740481180.1594565,11.97998857498169,7.186314179630248,1740481180.1594574,11.97998857498169,0.0,1740481180.1594589,11.97998857498169,0.0,1740481180.15946,11.97998857498169,0.0,1740481180.159461,11.97998857498169,0.0,1740481180.159462,11.97998857498169,0.062461682217254705,1740481180.1594632,11.97998857498169,1.0,1740481180.159464,11.97998857498169,0.9289545191257074,1740481180.159465,11.97998857498169,0.0,1740481180.1594658,11.97998857498169,0.09216878459928386,, -1740481180.178171,11.999988555908203,5.007452330469965,1740481180.1781726,11.999988555908203,0.0,1740481180.1781745,11.999988555908203,5.642762957086539e-05,1740481180.1781769,11.999988555908203,7.186314179630248,1740481180.1781778,11.999988555908203,0.0,1740481180.1781793,11.999988555908203,0.0,1740481180.1781807,11.999988555908203,0.0,1740481180.1781816,11.999988555908203,0.0,1740481180.1781824,11.999988555908203,0.062461682217254705,1740481180.1781838,11.999988555908203,1.0,1740481180.1781845,11.999988555908203,0.9702928976179709,1740481180.1781855,11.999988555908203,0.0,1740481180.1781862,11.999988555908203,0.09216878459928386,, -1740481180.1990712,12.019988536834717,5.007452330469965,1740481180.1990733,12.019988536834717,0.0,1740481180.1990752,12.019988536834717,5.642762957086539e-05,1740481180.1990774,12.019988536834717,7.186314179630248,1740481180.1990786,12.019988536834717,0.0,1740481180.19908,12.019988536834717,0.0,1740481180.199081,12.019988536834717,0.0,1740481180.199082,12.019988536834717,0.0,1740481180.199083,12.019988536834717,0.062461682217254705,1740481180.199084,12.019988536834717,1.0,1740481180.199085,12.019988536834717,0.9702928976179709,1740481180.1990857,12.019988536834717,0.0,1740481180.1990871,12.019988536834717,0.09216878459928386,, -1740481180.220615,12.03998851776123,5.007452330469965,1740481180.2206163,12.03998851776123,0.0,1740481180.2206187,12.03998851776123,0.0,1740481180.220621,12.03998851776123,7.1917898996685325,1740481180.220622,12.03998851776123,0.0,1740481180.2206237,12.03998851776123,0.0,1740481180.220625,12.03998851776123,0.0,1740481180.2206259,12.03998851776123,0.0,1740481180.2206268,12.03998851776123,0.15340602816886606,1740481180.2206283,12.03998851776123,0.0,1740481180.2206292,12.03998851776123,0.0612372435695822,1740481180.2206302,12.03998851776123,0.0,1740481180.2206314,12.03998851776123,0.09216878459928386,, -1740481180.2393374,12.059988498687744,5.007452330469965,1740481180.2393396,12.059988498687744,0.0,1740481180.2393415,12.059988498687744,0.0,1740481180.239344,12.059988498687744,7.1917898996685325,1740481180.2393446,12.059988498687744,0.0,1740481180.239346,12.059988498687744,0.0,1740481180.239347,12.059988498687744,0.0,1740481180.239348,12.059988498687744,0.0,1740481180.239349,12.059988498687744,0.15340602816886606,1740481180.23935,12.059988498687744,0.0,1740481180.2393508,12.059988498687744,0.0612372435695822,1740481180.2393515,12.059988498687744,0.0,1740481180.2393525,12.059988498687744,0.09216878459928386,, -1740481180.260268,12.079988479614258,5.0213710768713025,1740481180.2602706,12.079988479614258,0.0,1740481180.2602727,12.079988479614258,0.0003486799009973053,1740481180.2602746,12.079988479614258,7.311615676629449,1740481180.2602756,12.079988479614258,0.0,1740481180.2602773,12.079988479614258,0.0,1740481180.2602782,12.079988479614258,0.0,1740481180.2602792,12.079988479614258,0.0,1740481180.2602804,12.079988479614258,0.15340602816886606,1740481180.2602813,12.079988479614258,1.0,1740481180.2602823,12.079988479614258,0.9743447834481982,1740481180.2602835,12.079988479614258,0.0,1740481180.2602844,12.079988479614258,0.15190733312924354,, -1740481180.2781234,12.099988460540771,5.0213710768713025,1740481180.278125,12.099988460540771,0.0,1740481180.2781272,12.099988460540771,0.0003486799009973053,1740481180.2781289,12.099988460540771,7.311615676629449,1740481180.2781298,12.099988460540771,0.0,1740481180.2781312,12.099988460540771,0.0,1740481180.2781322,12.099988460540771,0.0,1740481180.278133,12.099988460540771,0.0,1740481180.278134,12.099988460540771,0.15340602816886606,1740481180.278135,12.099988460540771,1.0,1740481180.2781358,12.099988460540771,1.0014986950396225,1740481180.2781367,12.099988460540771,0.0,1740481180.2781377,12.099988460540771,0.15190733312924354,, -1740481180.3000617,12.119988441467285,5.0213710768713025,1740481180.3000638,12.119988441467285,0.0,1740481180.3000662,12.119988441467285,0.0003486799009973053,1740481180.3000684,12.119988441467285,7.311615676629449,1740481180.3000693,12.119988441467285,0.0,1740481180.3000708,12.119988441467285,0.0,1740481180.300072,12.119988441467285,0.0,1740481180.300073,12.119988441467285,0.0,1740481180.3000736,12.119988441467285,0.15340602816886606,1740481180.300096,12.119988441467285,1.0,1740481180.300097,12.119988441467285,1.0014986950396225,1740481180.3000977,12.119988441467285,0.0,1740481180.300099,12.119988441467285,0.15190733312924354,, -1740481180.320104,12.139988422393799,5.0213710768713025,1740481180.3201184,12.139988422393799,0.0,1740481180.3201218,12.139988422393799,0.0,1740481180.320124,12.139988422393799,7.32518574312979,1740481180.3201249,12.139988422393799,0.0,1740481180.3201263,12.139988422393799,0.0,1740481180.320127,12.139988422393799,0.0,1740481180.320128,12.139988422393799,0.0,1740481180.3201287,12.139988422393799,0.21314457669882347,1740481180.3201299,12.139988422393799,0.0,1740481180.3201306,12.139988422393799,0.061237243569579936,1740481180.3201313,12.139988422393799,0.0,1740481180.3201323,12.139988422393799,0.15190733312924354,, -1740481180.3380485,12.159988403320312,5.0213710768713025,1740481180.3380506,12.159988403320312,0.0,1740481180.3380647,12.159988403320312,0.0,1740481180.338069,12.159988403320312,7.32518574312979,1740481180.33807,12.159988403320312,0.0,1740481180.3380716,12.159988403320312,0.0,1740481180.3380725,12.159988403320312,0.0,1740481180.3380735,12.159988403320312,0.0,1740481180.3380747,12.159988403320312,0.21314457669882347,1740481180.3380756,12.159988403320312,0.0,1740481180.3380766,12.159988403320312,0.061237243569579936,1740481180.3380775,12.159988403320312,0.0,1740481180.3380785,12.159988403320312,0.15190733312924354,, -1740481180.3593473,12.179988384246826,5.0213710768713025,1740481180.35935,12.179988384246826,0.0,1740481180.3593526,12.179988384246826,0.0,1740481180.359355,12.179988384246826,7.32518574312979,1740481180.359356,12.179988384246826,0.0,1740481180.359357,12.179988384246826,0.0,1740481180.3593585,12.179988384246826,0.0,1740481180.3593595,12.179988384246826,0.0,1740481180.3593605,12.179988384246826,0.21314457669882347,1740481180.3593616,12.179988384246826,0.0,1740481180.3593626,12.179988384246826,0.061237243569579936,1740481180.3593636,12.179988384246826,0.0,1740481180.3593645,12.179988384246826,0.15190733312924354,, -1740481180.3780887,12.19998836517334,5.042542200091958,1740481180.3780904,12.19998836517334,0.0,1740481180.3780928,12.19998836517334,0.0007368898131376633,1740481180.378095,12.19998836517334,7.448820515642424,1740481180.3780959,12.19998836517334,0.0,1740481180.378097,12.19998836517334,0.0,1740481180.3780982,12.19998836517334,0.0,1740481180.378099,12.19998836517334,0.0,1740481180.3781,12.19998836517334,0.21314457669882347,1740481180.378101,12.19998836517334,1.0,1740481180.378102,12.19998836517334,0.9718569386052489,1740481180.3781028,12.19998836517334,0.0,1740481180.3781037,12.19998836517334,0.21335627447899205,, -1740481180.3986154,12.219988346099854,5.042542200091958,1740481180.3986187,12.219988346099854,0.0,1740481180.398621,12.219988346099854,0.0007368898131376633,1740481180.3986242,12.219988346099854,7.448820515642424,1740481180.3986266,12.219988346099854,0.0,1740481180.3986282,12.219988346099854,0.0,1740481180.3986301,12.219988346099854,0.0,1740481180.3986323,12.219988346099854,0.0,1740481180.398644,12.219988346099854,0.21314457669882347,1740481180.3986454,12.219988346099854,1.0,1740481180.3986473,12.219988346099854,0.9997883022198314,1740481180.3986487,12.219988346099854,0.0,1740481180.3986502,12.219988346099854,0.21335627447899205,, -1740481180.4209282,12.239988327026367,5.042542200091958,1740481180.4209301,12.239988327026367,0.0,1740481180.420932,12.239988327026367,0.0,1740481180.4209342,12.239988327026367,7.469254749049942,1740481180.4209352,12.239988327026367,0.0,1740481180.4209363,12.239988327026367,0.0,1740481180.4209375,12.239988327026367,0.0,1740481180.4209383,12.239988327026367,0.0,1740481180.4209392,12.239988327026367,0.27459351804857035,1740481180.4209404,12.239988327026367,0.0,1740481180.420941,12.239988327026367,0.0612372435695783,1740481180.420942,12.239988327026367,0.0,1740481180.4209428,12.239988327026367,0.21335627447899205,, -1740481180.4392996,12.25998830795288,5.042542200091958,1740481180.4393015,12.25998830795288,0.0,1740481180.4393034,12.25998830795288,0.0,1740481180.4393055,12.25998830795288,7.469254749049942,1740481180.4393067,12.25998830795288,0.0,1740481180.439308,12.25998830795288,0.0,1740481180.4393091,12.25998830795288,0.0,1740481180.43931,12.25998830795288,0.0,1740481180.4393108,12.25998830795288,0.27459351804857035,1740481180.439312,12.25998830795288,0.0,1740481180.439313,12.25998830795288,0.0612372435695783,1740481180.4393137,12.25998830795288,0.0,1740481180.4393146,12.25998830795288,0.21335627447899205,, -1740481180.4599204,12.279988288879395,5.042542200091958,1740481180.4599223,12.279988288879395,0.0,1740481180.4599245,12.279988288879395,0.0,1740481180.4599266,12.279988288879395,7.469254749049942,1740481180.4599276,12.279988288879395,0.0,1740481180.4599285,12.279988288879395,0.0,1740481180.4599297,12.279988288879395,0.0,1740481180.4599304,12.279988288879395,0.0,1740481180.4599314,12.279988288879395,0.27459351804857035,1740481180.4599323,12.279988288879395,0.0,1740481180.4599333,12.279988288879395,0.0612372435695783,1740481180.4599345,12.279988288879395,0.0,1740481180.4599352,12.279988288879395,0.21335627447899205,, -1740481180.4780855,12.299988269805908,5.069049716268669,1740481180.4780872,12.299988269805908,0.0,1740481180.4780893,12.299988269805908,0.0011886217761291023,1740481180.4780912,12.299988269805908,7.555103309723497,1740481180.4780922,12.299988269805908,0.0,1740481180.4780936,12.299988269805908,0.0,1740481180.4780946,12.299988269805908,0.0,1740481180.4780955,12.299988269805908,0.0,1740481180.4780967,12.299988269805908,0.27459351804857035,1740481180.4780977,12.299988269805908,1.0,1740481180.4780986,12.299988269805908,0.9996663605673398,1740481180.4780993,12.299988269805908,0.0,1740481180.4781005,12.299988269805908,0.25568624392770506,, -1740481180.4985926,12.319988250732422,5.069049716268669,1740481180.4985976,12.319988250732422,0.0,1740481180.4986012,12.319988250732422,0.0011886217761291023,1740481180.4986045,12.319988250732422,7.555103309723497,1740481180.498606,12.319988250732422,0.0,1740481180.4986084,12.319988250732422,0.0,1740481180.4986103,12.319988250732422,0.0,1740481180.4986129,12.319988250732422,0.0,1740481180.498615,12.319988250732422,0.27459351804857035,1740481180.498617,12.319988250732422,1.0,1740481180.4986181,12.319988250732422,1.0189072741208653,1740481180.4986193,12.319988250732422,0.0,1740481180.4986217,12.319988250732422,0.25568624392770506,, -1740481180.5215201,12.339988231658936,5.069049716268669,1740481180.5215218,12.339988231658936,0.0,1740481180.5215242,12.339988231658936,0.0,1740481180.5215418,12.339988231658936,7.580422204124079,1740481180.5215433,12.339988231658936,0.0,1740481180.5215456,12.339988231658936,0.0,1740481180.5215468,12.339988231658936,0.0,1740481180.5215478,12.339988231658936,0.0,1740481180.521549,12.339988231658936,0.31692348749728594,1740481180.5215502,12.339988231658936,0.0,1740481180.5215511,12.339988231658936,0.06123724356958088,1740481180.5215518,12.339988231658936,0.0,1740481180.521553,12.339988231658936,0.25568624392770506,, -1740481180.5408585,12.35998821258545,5.069049716268669,1740481180.5408607,12.35998821258545,0.0,1740481180.5408633,12.35998821258545,0.0,1740481180.540865,12.35998821258545,7.580422204124079,1740481180.5408661,12.35998821258545,0.0,1740481180.5408673,12.35998821258545,0.0,1740481180.5408683,12.35998821258545,0.0,1740481180.5408697,12.35998821258545,0.0,1740481180.5408704,12.35998821258545,0.31692348749728594,1740481180.5408714,12.35998821258545,0.0,1740481180.5408723,12.35998821258545,0.06123724356958088,1740481180.5408733,12.35998821258545,0.0,1740481180.5408742,12.35998821258545,0.25568624392770506,, -1740481180.5600405,12.379988193511963,5.069049716268669,1740481180.5600429,12.379988193511963,0.0,1740481180.560045,12.379988193511963,0.0,1740481180.5600474,12.379988193511963,7.580422204124079,1740481180.5600483,12.379988193511963,0.0,1740481180.5600498,12.379988193511963,0.0,1740481180.5600507,12.379988193511963,0.0,1740481180.5600514,12.379988193511963,0.0,1740481180.5600524,12.379988193511963,0.31692348749728594,1740481180.5600536,12.379988193511963,0.0,1740481180.5600543,12.379988193511963,0.06123724356958088,1740481180.5600555,12.379988193511963,0.0,1740481180.5600562,12.379988193511963,0.25568624392770506,, -1740481180.580196,12.399988174438477,5.069049716268669,1740481180.5801988,12.399988174438477,0.0,1740481180.580201,12.399988174438477,0.0,1740481180.5802033,12.399988174438477,7.580422204124079,1740481180.5802042,12.399988174438477,0.0,1740481180.580206,12.399988174438477,0.0,1740481180.580207,12.399988174438477,0.0,1740481180.5802085,12.399988174438477,0.0,1740481180.58021,12.399988174438477,0.31692348749728594,1740481180.580212,12.399988174438477,0.0,1740481180.5802138,12.399988174438477,0.06123724356958088,1740481180.5802155,12.399988174438477,0.0,1740481180.5802171,12.399988174438477,0.25568624392770506,, -1740481180.5990236,12.41998815536499,5.101184533156012,1740481180.5990257,12.41998815536499,0.0,1740481180.5990276,12.41998815536499,0.0016630856721125417,1740481180.5990298,12.41998815536499,7.686018469567536,1740481180.5990307,12.41998815536499,0.0,1740481180.5990322,12.41998815536499,0.0,1740481180.599033,12.41998815536499,0.0,1740481180.599034,12.41998815536499,0.0,1740481180.599035,12.41998815536499,0.31692348749728594,1740481180.5990362,12.41998815536499,1.0,1740481180.5990372,12.41998815536499,0.9856494539362171,1740481180.5990381,12.41998815536499,0.0,1740481180.599039,12.41998815536499,0.30765283381337716,, -1740481180.680607,12.439988136291504,5.101184533156012,1740481180.680609,12.439988136291504,0.0,1740481180.6806111,12.439988136291504,0.0,1740481180.680613,12.439988136291504,7.716490200782766,1740481180.6806142,12.439988136291504,0.0,1740481180.6806154,12.439988136291504,0.0,1740481180.6806164,12.439988136291504,0.0,1740481180.6806176,12.439988136291504,0.0,1740481180.6806185,12.439988136291504,0.36889007738295815,1740481180.6806195,12.439988136291504,0.0,1740481180.6806202,12.439988136291504,0.06123724356958099,1740481180.6806214,12.439988136291504,0.0,1740481180.680622,12.439988136291504,0.30765283381337716,, -1740481180.6835814,12.459988117218018,5.101184533156012,1740481180.6835833,12.459988117218018,0.0,1740481180.6835852,12.459988117218018,0.0,1740481180.6835873,12.459988117218018,7.716490200782766,1740481180.6835883,12.459988117218018,0.0,1740481180.6835897,12.459988117218018,0.0,1740481180.6835907,12.459988117218018,0.0,1740481180.6835914,12.459988117218018,0.0,1740481180.6835926,12.459988117218018,0.36889007738295815,1740481180.6835933,12.459988117218018,0.0,1740481180.683594,12.459988117218018,0.06123724356958099,1740481180.683595,12.459988117218018,0.0,1740481180.6835957,12.459988117218018,0.30765283381337716,, -1740481180.7056513,12.479988098144531,5.101184533156012,1740481180.7056532,12.479988098144531,0.0,1740481180.7056553,12.479988098144531,0.0,1740481180.7056572,12.479988098144531,7.716490200782766,1740481180.7056584,12.479988098144531,0.0,1740481180.7056596,12.479988098144531,0.0,1740481180.7056603,12.479988098144531,0.0,1740481180.7056615,12.479988098144531,0.0,1740481180.7056625,12.479988098144531,0.36889007738295815,1740481180.7056632,12.479988098144531,0.0,1740481180.7056642,12.479988098144531,0.06123724356958099,1740481180.705665,12.479988098144531,0.0,1740481180.705666,12.479988098144531,0.30765283381337716,, -1740481180.7269907,12.499988079071045,5.101184533156012,1740481180.7269928,12.499988079071045,0.0,1740481180.7269955,12.499988079071045,0.0,1740481180.7269976,12.499988079071045,7.716490200782766,1740481180.7269988,12.499988079071045,0.0,1740481180.7270002,12.499988079071045,0.0,1740481180.7270014,12.499988079071045,0.0,1740481180.7270024,12.499988079071045,0.0,1740481180.727003,12.499988079071045,0.36889007738295815,1740481180.7270048,12.499988079071045,0.0,1740481180.7270055,12.499988079071045,0.06123724356958099,1740481180.7270064,12.499988079071045,0.0,1740481180.7270072,12.499988079071045,0.30765283381337716,, -1740481180.7479312,12.519988059997559,5.138040942771699,1740481180.7479334,12.519988059997559,0.0,1740481180.7479358,12.519988059997559,0.00222021159063778,1740481180.7479374,12.519988059997559,7.802202394660881,1740481180.7479386,12.519988059997559,0.0,1740481180.7479396,12.519988059997559,0.0,1740481180.7479405,12.519988059997559,0.0,1740481180.7479415,12.519988059997559,0.0,1740481180.7479424,12.519988059997559,0.36889007738295815,1740481180.7479436,12.519988059997559,1.0,1740481180.7479446,12.519988059997559,1.0005157838095442,1740481180.7479455,12.519988059997559,0.0,1740481180.7479465,12.519988059997559,0.34939882495711583,, -1740481180.7664402,12.539988040924072,5.138040942771699,1740481180.766442,12.539988040924072,0.0,1740481180.7664576,12.539988040924072,0.0,1740481180.7664611,12.539988040924072,7.836838592685931,1740481180.7664623,12.539988040924072,0.0,1740481180.7664635,12.539988040924072,0.0,1740481180.7664645,12.539988040924072,0.0,1740481180.7664652,12.539988040924072,0.0,1740481180.7664664,12.539988040924072,0.4106360685266966,1740481180.766467,12.539988040924072,0.0,1740481180.766468,12.539988040924072,0.06123724356958077,1740481180.7664688,12.539988040924072,0.0,1740481180.76647,12.539988040924072,0.34939882495711583,, -1740481180.7843246,12.559988021850586,5.138040942771699,1740481180.7843263,12.559988021850586,0.0,1740481180.7843287,12.559988021850586,0.0,1740481180.7843306,12.559988021850586,7.836838592685931,1740481180.7843316,12.559988021850586,0.0,1740481180.784333,12.559988021850586,0.0,1740481180.7843342,12.559988021850586,0.0,1740481180.7843351,12.559988021850586,0.0,1740481180.7843359,12.559988021850586,0.4106360685266966,1740481180.784337,12.559988021850586,0.0,1740481180.7843382,12.559988021850586,0.06123724356958077,1740481180.784339,12.559988021850586,0.0,1740481180.7843397,12.559988021850586,0.34939882495711583,, -1740481180.80722,12.5799880027771,5.138040942771699,1740481180.8072217,12.5799880027771,0.0,1740481180.8072367,12.5799880027771,0.0,1740481180.80724,12.5799880027771,7.836838592685931,1740481180.807241,12.5799880027771,0.0,1740481180.8072422,12.5799880027771,0.0,1740481180.8072433,12.5799880027771,0.0,1740481180.8072443,12.5799880027771,0.0,1740481180.8072453,12.5799880027771,0.4106360685266966,1740481180.8072464,12.5799880027771,0.0,1740481180.8072472,12.5799880027771,0.06123724356958077,1740481180.8072479,12.5799880027771,0.0,1740481180.8072488,12.5799880027771,0.34939882495711583,, -1740481180.829262,12.599987983703613,5.138040942771699,1740481180.8292642,12.599987983703613,0.0,1740481180.8292668,12.599987983703613,0.0,1740481180.8292685,12.599987983703613,7.836838592685931,1740481180.8292694,12.599987983703613,0.0,1740481180.829271,12.599987983703613,0.0,1740481180.8292718,12.599987983703613,0.0,1740481180.8292727,12.599987983703613,0.0,1740481180.8292737,12.599987983703613,0.4106360685266966,1740481180.8292747,12.599987983703613,0.0,1740481180.8292754,12.599987983703613,0.06123724356958077,1740481180.8292763,12.599987983703613,0.0,1740481180.8292773,12.599987983703613,0.34939882495711583,, -1740481180.8446515,12.619987964630127,5.138040942771699,1740481180.8446536,12.619987964630127,0.0,1740481180.844656,12.619987964630127,0.0,1740481180.8446577,12.619987964630127,7.836838592685931,1740481180.8446584,12.619987964630127,0.0,1740481180.84466,12.619987964630127,0.0,1740481180.8446612,12.619987964630127,0.0,1740481180.844662,12.619987964630127,0.0,1740481180.8446631,12.619987964630127,0.4106360685266966,1740481180.8446639,12.619987964630127,0.0,1740481180.8446646,12.619987964630127,0.06123724356958077,1740481180.8446655,12.619987964630127,0.0,1740481180.8446667,12.619987964630127,0.34939882495711583,, -1740481180.868065,12.63998794555664,5.178487725666972,1740481180.8680668,12.63998794555664,0.0,1740481180.868069,12.63998794555664,0.0,1740481180.8680708,12.63998794555664,7.923965857720077,1740481180.868072,12.63998794555664,0.0,1740481180.8680732,12.63998794555664,0.0,1740481180.868074,12.63998794555664,0.0,1740481180.868075,12.63998794555664,0.0,1740481180.8680758,12.63998794555664,0.43397630959612915,1740481180.868077,12.63998794555664,1.0,1740481180.8680778,12.63998794555664,1.061237243569575,1740481180.868079,12.63998794555664,0.0,1740481180.8680797,12.63998794555664,0.37273906602655243,, -1740481180.8841748,12.659987926483154,5.178487725666972,1740481180.8841767,12.659987926483154,0.0,1740481180.8841786,12.659987926483154,0.0,1740481180.8841808,12.659987926483154,7.923965857720077,1740481180.8841817,12.659987926483154,0.0,1740481180.8841827,12.659987926483154,0.0,1740481180.8841841,12.659987926483154,0.0,1740481180.884185,12.659987926483154,0.0,1740481180.884186,12.659987926483154,0.43397630959612915,1740481180.8841872,12.659987926483154,1.0,1740481180.8841882,12.659987926483154,1.0612372435695767,1740481180.884189,12.659987926483154,0.0,1740481180.8841903,12.659987926483154,0.37273906602655243,, -1740481180.9050875,12.679987907409668,5.178487725666972,1740481180.9050899,12.679987907409668,0.0,1740481180.9050927,12.679987907409668,0.0,1740481180.9050946,12.679987907409668,7.923965857720077,1740481180.9050956,12.679987907409668,0.0,1740481180.905097,12.679987907409668,0.0,1740481180.905098,12.679987907409668,0.0,1740481180.9050992,12.679987907409668,0.0,1740481180.9051,12.679987907409668,0.43397630959612915,1740481180.9051013,12.679987907409668,1.0,1740481180.9051023,12.679987907409668,1.0612372435695767,1740481180.9051034,12.679987907409668,0.0,1740481180.9051044,12.679987907409668,0.37273906602655243,, -1740481180.9277186,12.699987888336182,5.178487725666972,1740481180.927721,12.699987888336182,0.0,1740481180.9277232,12.699987888336182,0.0,1740481180.9277253,12.699987888336182,7.923965857720077,1740481180.9277265,12.699987888336182,0.0,1740481180.9277465,12.699987888336182,0.0,1740481180.9277475,12.699987888336182,0.0,1740481180.927749,12.699987888336182,0.0,1740481180.9277496,12.699987888336182,0.43397630959612915,1740481180.9277508,12.699987888336182,1.0,1740481180.9277518,12.699987888336182,1.0612372435695767,1740481180.9277527,12.699987888336182,0.0,1740481180.9277537,12.699987888336182,0.37273906602655243,, -1740481180.9440837,12.719987869262695,5.178487725666972,1740481180.9440868,12.719987869262695,0.0,1740481180.9440897,12.719987869262695,0.0,1740481180.9440925,12.719987869262695,7.923965857720077,1740481180.944094,12.719987869262695,0.0,1740481180.9440963,12.719987869262695,0.0,1740481180.944098,12.719987869262695,0.0,1740481180.9440997,12.719987869262695,0.0,1740481180.9441018,12.719987869262695,0.43397630959612915,1740481180.9441037,12.719987869262695,1.0,1740481180.944105,12.719987869262695,1.0612372435695767,1740481180.9441063,12.719987869262695,0.0,1740481180.9441075,12.719987869262695,0.37273906602655243,, -1740481180.9697506,12.739987850189209,5.223933206777517,1740481180.9697528,12.739987850189209,0.0,1740481180.9697552,12.739987850189209,0.0,1740481180.969757,12.739987850189209,8.165714091726372,1740481180.9697585,12.739987850189209,0.0,1740481180.9697602,12.739987850189209,0.0,1740481180.9697616,12.739987850189209,0.0,1740481180.9697626,12.739987850189209,0.0,1740481180.9697635,12.739987850189209,0.5321276860440062,1740481180.9697647,12.739987850189209,1.0,1740481180.9697657,12.739987850189209,1.0612372435695796,1740481180.9697666,12.739987850189209,0.0,1740481180.9697676,12.739987850189209,0.4708904424744274,, -1740481180.9846766,12.759987831115723,5.223933206777517,1740481180.9846785,12.759987831115723,0.0,1740481180.984681,12.759987831115723,0.0,1740481180.9846828,12.759987831115723,8.165714091726372,1740481180.9846838,12.759987831115723,0.0,1740481180.984685,12.759987831115723,0.0,1740481180.9846861,12.759987831115723,0.0,1740481180.9846869,12.759987831115723,0.0,1740481180.9846878,12.759987831115723,0.5321276860440062,1740481180.9846888,12.759987831115723,1.0,1740481180.9846897,12.759987831115723,1.0612372435695787,1740481180.9846904,12.759987831115723,0.0,1740481180.9846914,12.759987831115723,0.4708904424744274,, -1740481181.003739,12.779987812042236,5.223933206777517,1740481181.003741,12.779987812042236,0.0,1740481181.0037432,12.779987812042236,0.0,1740481181.003745,12.779987812042236,8.165714091726372,1740481181.003746,12.779987812042236,0.0,1740481181.0037472,12.779987812042236,0.0,1740481181.0037484,12.779987812042236,0.0,1740481181.0037494,12.779987812042236,0.0,1740481181.0037503,12.779987812042236,0.5321276860440062,1740481181.0037515,12.779987812042236,1.0,1740481181.0037522,12.779987812042236,1.0612372435695787,1740481181.0037532,12.779987812042236,0.0,1740481181.003754,12.779987812042236,0.4708904424744274,, -1740481181.0238867,12.79998779296875,5.223933206777517,1740481181.0238883,12.79998779296875,0.0,1740481181.0238907,12.79998779296875,0.0,1740481181.0238929,12.79998779296875,8.165714091726372,1740481181.023894,12.79998779296875,0.0,1740481181.0238953,12.79998779296875,0.0,1740481181.0238962,12.79998779296875,0.0,1740481181.0238974,12.79998779296875,0.0,1740481181.0238986,12.79998779296875,0.5321276860440062,1740481181.0238996,12.79998779296875,1.0,1740481181.0239007,12.79998779296875,1.0612372435695787,1740481181.0239015,12.79998779296875,0.0,1740481181.0239024,12.79998779296875,0.4708904424744274,, -1740481181.0435474,12.819987773895264,5.223933206777517,1740481181.04355,12.819987773895264,0.0,1740481181.0435543,12.819987773895264,0.0,1740481181.0435567,12.819987773895264,8.165714091726372,1740481181.043558,12.819987773895264,0.0,1740481181.0435598,12.819987773895264,0.0,1740481181.0435612,12.819987773895264,0.0,1740481181.0435627,12.819987773895264,0.0,1740481181.0435638,12.819987773895264,0.5321276860440062,1740481181.0435658,12.819987773895264,1.0,1740481181.0435672,12.819987773895264,1.0612372435695787,1740481181.0435686,12.819987773895264,0.0,1740481181.0435703,12.819987773895264,0.4708904424744274,, -1740481181.066799,12.839987754821777,5.223933206777517,1740481181.0668006,12.839987754821777,0.0,1740481181.0668027,12.839987754821777,0.0,1740481181.0668044,12.839987754821777,8.165714091726372,1740481181.0668056,12.839987754821777,0.0,1740481181.0668068,12.839987754821777,0.0,1740481181.0668077,12.839987754821777,0.0,1740481181.066809,12.839987754821777,0.0,1740481181.0668097,12.839987754821777,0.5321276860440062,1740481181.0668106,12.839987754821777,1.0,1740481181.0668116,12.839987754821777,1.0612372435695787,1740481181.0668128,12.839987754821777,0.0,1740481181.0668137,12.839987754821777,0.4708904424744274,, -1740481181.0837624,12.859987735748291,5.281079846967561,1740481181.083764,12.859987735748291,0.0,1740481181.0837662,12.859987735748291,0.004965819432248915,1740481181.0837681,12.859987735748291,8.384369399637807,1740481181.083769,12.859987735748291,0.0,1740481181.0837703,12.859987735748291,0.0,1740481181.0837717,12.859987735748291,0.0,1740481181.0837727,12.859987735748291,0.0,1740481181.0837736,12.859987735748291,0.6546021731831678,1740481181.0837748,12.859987735748291,0.0,1740481181.0837755,12.859987735748291,0.08397142183517822,1740481181.0837765,12.859987735748291,0.0,1740481181.0837772,12.859987735748291,0.5777351867140202,, -1740481181.1048238,12.879987716674805,5.281079846967561,1740481181.1048255,12.879987716674805,0.0,1740481181.104828,12.879987716674805,0.004965819432248915,1740481181.1048298,12.879987716674805,8.384369399637807,1740481181.1048307,12.879987716674805,0.0,1740481181.104832,12.879987716674805,0.0,1740481181.1048331,12.879987716674805,0.0,1740481181.104834,12.879987716674805,0.0,1740481181.1048348,12.879987716674805,0.6546021731831678,1740481181.1048357,12.879987716674805,0.0,1740481181.1048367,12.879987716674805,0.07686698646914758,1740481181.1048377,12.879987716674805,0.0,1740481181.1048386,12.879987716674805,0.5777351867140202,, -1740481181.1240883,12.899987697601318,5.281079846967561,1740481181.1240907,12.899987697601318,0.0,1740481181.1240926,12.899987697601318,0.004965819432248915,1740481181.1240947,12.899987697601318,8.384369399637807,1740481181.1240957,12.899987697601318,0.0,1740481181.124097,12.899987697601318,0.0,1740481181.124098,12.899987697601318,0.0,1740481181.124099,12.899987697601318,0.0,1740481181.1241002,12.899987697601318,0.6546021731831678,1740481181.1241012,12.899987697601318,0.0,1740481181.1241019,12.899987697601318,0.07686698646914758,1740481181.1241028,12.899987697601318,0.0,1740481181.1241038,12.899987697601318,0.5777351867140202,, -1740481181.1454885,12.919987678527832,5.281079846967561,1740481181.1454902,12.919987678527832,0.0,1740481181.1454926,12.919987678527832,0.004965819432248915,1740481181.1454945,12.919987678527832,8.384369399637807,1740481181.145496,12.919987678527832,0.0,1740481181.145497,12.919987678527832,0.0,1740481181.145498,12.919987678527832,0.0,1740481181.1454992,12.919987678527832,0.0,1740481181.1455002,12.919987678527832,0.6546021731831678,1740481181.1455011,12.919987678527832,0.0,1740481181.145502,12.919987678527832,0.07686698646914758,1740481181.1455033,12.919987678527832,0.0,1740481181.1455042,12.919987678527832,0.5777351867140202,, -1740481181.166621,12.939987659454346,5.281079846967561,1740481181.1666224,12.939987659454346,0.0,1740481181.1666245,12.939987659454346,0.0,1740481181.1666265,12.939987659454346,8.436550220395603,1740481181.1666276,12.939987659454346,0.0,1740481181.166629,12.939987659454346,0.0,1740481181.16663,12.939987659454346,0.0,1740481181.1666312,12.939987659454346,0.0,1740481181.166632,12.939987659454346,0.6389724302836005,1740481181.166633,12.939987659454346,0.0,1740481181.1666338,12.939987659454346,0.06123724356958027,1740481181.1666348,12.939987659454346,0.0,1740481181.1666358,12.939987659454346,0.5777351867140202,, -1740481181.1839092,12.95998764038086,5.345806859456825,1740481181.1839132,12.95998764038086,0.0,1740481181.1839166,12.95998764038086,0.0067538599166811234,1740481181.183919,12.95998764038086,8.471101992745144,1740481181.18392,12.95998764038086,0.0,1740481181.183921,12.95998764038086,0.0,1740481181.1839223,12.95998764038086,0.0,1740481181.1839232,12.95998764038086,0.0,1740481181.1839242,12.95998764038086,0.6389724302836005,1740481181.183925,12.95998764038086,1.0,1740481181.183926,12.95998764038086,1.0410205739570033,1740481181.183927,12.95998764038086,0.0,1740481181.183928,12.95998764038086,0.5916341429304511,, -1740481181.203452,12.979987621307373,5.345806859456825,1740481181.203454,12.979987621307373,0.0,1740481181.203456,12.979987621307373,0.0067538599166811234,1740481181.2034578,12.979987621307373,8.471101992745144,1740481181.2034588,12.979987621307373,0.0,1740481181.20346,12.979987621307373,0.0,1740481181.2034612,12.979987621307373,0.0,1740481181.2034621,12.979987621307373,0.0,1740481181.203463,12.979987621307373,0.6389724302836005,1740481181.2034643,12.979987621307373,1.0,1740481181.2034652,12.979987621307373,1.0473382873531494,1740481181.203466,12.979987621307373,0.0,1740481181.203467,12.979987621307373,0.5916341429304511,, -1740481181.22535,12.999987602233887,5.345806859456825,1740481181.2253551,12.999987602233887,0.0,1740481181.2253604,12.999987602233887,0.0067538599166811234,1740481181.225363,12.999987602233887,8.471101992745144,1740481181.225364,12.999987602233887,0.0,1740481181.2253654,12.999987602233887,0.0,1740481181.2253666,12.999987602233887,0.0,1740481181.2253678,12.999987602233887,0.0,1740481181.2253687,12.999987602233887,0.6389724302836005,1740481181.22537,12.999987602233887,1.0,1740481181.225371,12.999987602233887,1.0473382873531494,1740481181.2253718,12.999987602233887,0.0,1740481181.225373,12.999987602233887,0.5916341429304511,, -1740481181.2450511,13.0199875831604,5.345806859456825,1740481181.2450533,13.0199875831604,0.0,1740481181.2450552,13.0199875831604,0.0067538599166811234,1740481181.245057,13.0199875831604,8.471101992745144,1740481181.245058,13.0199875831604,0.0,1740481181.2450595,13.0199875831604,0.0,1740481181.2450607,13.0199875831604,0.0,1740481181.2450616,13.0199875831604,0.0,1740481181.2450626,13.0199875831604,0.6389724302836005,1740481181.245064,13.0199875831604,1.0,1740481181.245065,13.0199875831604,1.0473382873531494,1740481181.2450657,13.0199875831604,0.0,1740481181.2450666,13.0199875831604,0.5916341429304511,, -1740481181.2673166,13.039987564086914,5.345806859456825,1740481181.2673187,13.039987564086914,0.0,1740481181.267321,13.039987564086914,0.0,1740481181.267323,13.039987564086914,8.529075145317726,1740481181.2673242,13.039987564086914,0.0,1740481181.2673254,13.039987564086914,0.0,1740481181.2673268,13.039987564086914,0.0,1740481181.2673278,13.039987564086914,0.0,1740481181.2673287,13.039987564086914,0.6528713865000293,1740481181.2673297,13.039987564086914,0.0,1740481181.267331,13.039987564086914,0.06123724356957816,1740481181.2673318,13.039987564086914,0.0,1740481181.2673326,13.039987564086914,0.5916341429304511,, -1740481181.2839003,13.059987545013428,5.345806859456825,1740481181.2839017,13.059987545013428,0.0,1740481181.2839043,13.059987545013428,0.0,1740481181.2839062,13.059987545013428,8.529075145317726,1740481181.2839072,13.059987545013428,0.0,1740481181.2839084,13.059987545013428,0.0,1740481181.2839093,13.059987545013428,0.0,1740481181.2839105,13.059987545013428,0.0,1740481181.2839112,13.059987545013428,0.6528713865000293,1740481181.2839122,13.059987545013428,0.0,1740481181.283913,13.059987545013428,0.06123724356957816,1740481181.283914,13.059987545013428,0.0,1740481181.283915,13.059987545013428,0.5916341429304511,, -1740481181.3037357,13.079987525939941,5.415913165338189,1740481181.3037376,13.079987525939941,0.0,1740481181.3038213,13.079987525939941,0.007474275204950325,1740481181.3038454,13.079987525939941,8.692317794801673,1740481181.3038473,13.079987525939941,0.0,1740481181.3038497,13.079987525939941,0.0,1740481181.3038516,13.079987525939941,0.0,1740481181.3038533,13.079987525939941,0.0,1740481181.3038552,13.079987525939941,0.6528713865000293,1740481181.303857,13.079987525939941,1.0,1740481181.3038588,13.079987525939941,0.9479511194229369,1740481181.3038607,13.079987525939941,0.0,1740481181.3038628,13.079987525939941,0.6695183300699483,, -1740481181.324158,13.099987506866455,5.415913165338189,1740481181.3241599,13.099987506866455,0.0,1740481181.3241618,13.099987506866455,0.007474275204950325,1740481181.324164,13.099987506866455,8.692317794801673,1740481181.3241649,13.099987506866455,0.0,1740481181.324166,13.099987506866455,0.0,1740481181.3241673,13.099987506866455,0.0,1740481181.3241682,13.099987506866455,0.0,1740481181.3241692,13.099987506866455,0.6528713865000293,1740481181.3241704,13.099987506866455,1.0,1740481181.3241713,13.099987506866455,0.983353056430081,1740481181.3241723,13.099987506866455,0.0,1740481181.324173,13.099987506866455,0.6695183300699483,, -1740481181.3440688,13.119987487792969,5.415913165338189,1740481181.344071,13.119987487792969,0.0,1740481181.344073,13.119987487792969,0.007474275204950325,1740481181.344075,13.119987487792969,8.692317794801673,1740481181.344076,13.119987487792969,0.0,1740481181.3440776,13.119987487792969,0.0,1740481181.3440785,13.119987487792969,0.0,1740481181.3440797,13.119987487792969,0.0,1740481181.3440807,13.119987487792969,0.6528713865000293,1740481181.3440819,13.119987487792969,1.0,1740481181.3440826,13.119987487792969,0.983353056430081,1740481181.344084,13.119987487792969,0.0,1740481181.344085,13.119987487792969,0.6695183300699483,, -1740481181.3673885,13.139987468719482,5.415913165338189,1740481181.3673902,13.139987468719482,0.0,1740481181.3673925,13.139987468719482,0.0,1740481181.3673942,13.139987468719482,8.754949825478086,1740481181.3673954,13.139987468719482,0.0,1740481181.3673966,13.139987468719482,0.0,1740481181.3673975,13.139987468719482,0.0,1740481181.3673987,13.139987468719482,0.0,1740481181.3673995,13.139987468719482,0.7307555736395281,1740481181.3674002,13.139987468719482,0.0,1740481181.3674011,13.139987468719482,0.061237243569579825,1740481181.367402,13.139987468719482,0.0,1740481181.367403,13.139987468719482,0.6695183300699483,, -1740481181.3836367,13.159987449645996,5.415913165338189,1740481181.3836384,13.159987449645996,0.0,1740481181.3836405,13.159987449645996,0.0,1740481181.3836427,13.159987449645996,8.754949825478086,1740481181.3836436,13.159987449645996,0.0,1740481181.3836448,13.159987449645996,0.0,1740481181.383646,13.159987449645996,0.0,1740481181.383647,13.159987449645996,0.0,1740481181.3836477,13.159987449645996,0.7307555736395281,1740481181.3836489,13.159987449645996,0.0,1740481181.3836498,13.159987449645996,0.061237243569579825,1740481181.3836505,13.159987449645996,0.0,1740481181.3836515,13.159987449645996,0.6695183300699483,, -1740481181.4038584,13.17998743057251,5.493217368318382,1740481181.403861,13.17998743057251,0.0,1740481181.403863,13.17998743057251,0.009224856296699741,1740481181.403865,13.17998743057251,8.878066666875243,1740481181.403866,13.17998743057251,0.0,1740481181.403868,13.17998743057251,0.0,1740481181.4038687,13.17998743057251,0.0,1740481181.4038696,13.17998743057251,0.0,1740481181.4038708,13.17998743057251,0.7307555736395281,1740481181.4038718,13.17998743057251,1.0,1740481181.4038727,13.17998743057251,0.9784066842656188,1740481181.4038737,13.17998743057251,0.0,1740481181.4038746,13.17998743057251,0.726464322620177,, -1740481181.4238591,13.199987411499023,5.493217368318382,1740481181.4238615,13.199987411499023,0.0,1740481181.4238641,13.199987411499023,0.009224856296699741,1740481181.423866,13.199987411499023,8.878066666875243,1740481181.4238672,13.199987411499023,0.0,1740481181.4238682,13.199987411499023,0.0,1740481181.4238691,13.199987411499023,0.0,1740481181.4238703,13.199987411499023,0.0,1740481181.4238713,13.199987411499023,0.7307555736395281,1740481181.4238722,13.199987411499023,1.0,1740481181.423873,13.199987411499023,1.0042912510193511,1740481181.4238744,13.199987411499023,0.0,1740481181.423875,13.199987411499023,0.726464322620177,, -1740481181.44476,13.219987392425537,5.493217368318382,1740481181.4447849,13.219987392425537,0.0,1740481181.4447873,13.219987392425537,0.009224856296699741,1740481181.4447894,13.219987392425537,8.878066666875243,1740481181.4447908,13.219987392425537,0.0,1740481181.4448164,13.219987392425537,0.0,1740481181.4448173,13.219987392425537,0.0,1740481181.4448185,13.219987392425537,0.0,1740481181.4448195,13.219987392425537,0.7307555736395281,1740481181.4448216,13.219987392425537,1.0,1740481181.4448225,13.219987392425537,1.0042912510193511,1740481181.4448235,13.219987392425537,0.0,1740481181.444842,13.219987392425537,0.726464322620177,, -1740481181.4669876,13.23998737335205,5.493217368318382,1740481181.4669893,13.23998737335205,0.0,1740481181.4669914,13.23998737335205,0.0,1740481181.4669933,13.23998737335205,8.946146013558735,1740481181.4669945,13.23998737335205,0.0,1740481181.4670062,13.23998737335205,0.0,1740481181.4670086,13.23998737335205,0.0,1740481181.4670095,13.23998737335205,0.0,1740481181.4670103,13.23998737335205,0.7877015661897561,1740481181.4670112,13.23998737335205,0.0,1740481181.4670122,13.23998737335205,0.06123724356957905,1740481181.4670131,13.23998737335205,0.0,1740481181.4670138,13.23998737335205,0.726464322620177,, -1740481181.4840307,13.259987354278564,5.493217368318382,1740481181.4840326,13.259987354278564,0.0,1740481181.4840345,13.259987354278564,0.0,1740481181.4840367,13.259987354278564,8.946146013558735,1740481181.4840376,13.259987354278564,0.0,1740481181.4840388,13.259987354278564,0.0,1740481181.4840403,13.259987354278564,0.0,1740481181.4840412,13.259987354278564,0.0,1740481181.4840422,13.259987354278564,0.7877015661897561,1740481181.4840434,13.259987354278564,0.0,1740481181.484044,13.259987354278564,0.06123724356957905,1740481181.484045,13.259987354278564,0.0,1740481181.484046,13.259987354278564,0.726464322620177,, -1740481181.5050364,13.279987335205078,5.493217368318382,1740481181.5050387,13.279987335205078,0.0,1740481181.5050414,13.279987335205078,0.0,1740481181.505044,13.279987335205078,8.946146013558735,1740481181.5050452,13.279987335205078,0.0,1740481181.5050468,13.279987335205078,0.0,1740481181.5050483,13.279987335205078,0.0,1740481181.5050492,13.279987335205078,0.0,1740481181.5050507,13.279987335205078,0.7877015661897561,1740481181.5050523,13.279987335205078,0.0,1740481181.5050538,13.279987335205078,0.06123724356957905,1740481181.5050547,13.279987335205078,0.0,1740481181.505056,13.279987335205078,0.726464322620177,, -1740481181.523896,13.299987316131592,5.577410315180376,1740481181.523899,13.299987316131592,0.0,1740481181.5239022,13.299987316131592,0.010829833650165993,1740481181.5239043,13.299987316131592,9.072526800533833,1740481181.5239053,13.299987316131592,0.0,1740481181.5239065,13.299987316131592,0.0,1740481181.5239077,13.299987316131592,0.0,1740481181.5239086,13.299987316131592,0.0,1740481181.5239093,13.299987316131592,0.7877015661897561,1740481181.52391,13.299987316131592,1.0,1740481181.5239112,13.299987316131592,0.9772001615609737,1740481181.523912,13.299987316131592,0.0,1740481181.523913,13.299987316131592,0.7842397992826429,, -1740481181.5445962,13.319987297058105,5.577410315180376,1740481181.5445986,13.319987297058105,0.0,1740481181.5446005,13.319987297058105,0.010829833650165993,1740481181.5446026,13.319987297058105,9.072526800533833,1740481181.5446038,13.319987297058105,0.0,1740481181.5446053,13.319987297058105,0.0,1740481181.5446064,13.319987297058105,0.0,1740481181.5446076,13.319987297058105,0.0,1740481181.5446086,13.319987297058105,0.7877015661897561,1740481181.5446098,13.319987297058105,1.0,1740481181.5446107,13.319987297058105,1.003461766907113,1740481181.544612,13.319987297058105,0.0,1740481181.544613,13.319987297058105,0.7842397992826429,, -1740481181.5669894,13.33998727798462,5.577410315180376,1740481181.566991,13.33998727798462,0.0,1740481181.5669935,13.33998727798462,0.0,1740481181.5669959,13.33998727798462,9.145889913745663,1740481181.566997,13.33998727798462,0.0,1740481181.5669982,13.33998727798462,0.0,1740481181.566999,13.33998727798462,0.0,1740481181.5670002,13.33998727798462,0.0,1740481181.5670009,13.33998727798462,0.8454770428522242,1740481181.5670018,13.33998727798462,0.0,1740481181.5670025,13.33998727798462,0.06123724356958138,1740481181.5670037,13.33998727798462,0.0,1740481181.5670044,13.33998727798462,0.7842397992826429,, -1740481181.5839179,13.359987258911133,5.577410315180376,1740481181.5839195,13.359987258911133,0.0,1740481181.5839217,13.359987258911133,0.0,1740481181.5839238,13.359987258911133,9.145889913745663,1740481181.5839245,13.359987258911133,0.0,1740481181.583926,13.359987258911133,0.0,1740481181.5839274,13.359987258911133,0.0,1740481181.5839283,13.359987258911133,0.0,1740481181.5839293,13.359987258911133,0.8454770428522242,1740481181.5839303,13.359987258911133,0.0,1740481181.5839312,13.359987258911133,0.06123724356958138,1740481181.5839322,13.359987258911133,0.0,1740481181.5839329,13.359987258911133,0.7842397992826429,, -1740481181.604953,13.379987239837646,5.577410315180376,1740481181.6049552,13.379987239837646,0.0,1740481181.604957,13.379987239837646,0.0,1740481181.6049595,13.379987239837646,9.145889913745663,1740481181.6049604,13.379987239837646,0.0,1740481181.6049619,13.379987239837646,0.0,1740481181.6049628,13.379987239837646,0.0,1740481181.6049638,13.379987239837646,0.0,1740481181.6049645,13.379987239837646,0.8454770428522242,1740481181.6049662,13.379987239837646,0.0,1740481181.6049669,13.379987239837646,0.06123724356958138,1740481181.6049678,13.379987239837646,0.0,1740481181.604969,13.379987239837646,0.7842397992826429,, -1740481181.623981,13.39998722076416,5.66653526964325,1740481181.6239827,13.39998722076416,0.0,1740481181.6239848,13.39998722076416,0.012305110183150367,1740481181.6239867,13.39998722076416,9.235499007343524,1740481181.6239877,13.39998722076416,0.0,1740481181.623989,13.39998722076416,0.0,1740481181.62399,13.39998722076416,0.0,1740481181.623991,13.39998722076416,0.0,1740481181.623992,13.39998722076416,0.8454770428522242,1740481181.623993,13.39998722076416,1.0,1740481181.6239939,13.39998722076416,1.0050161479673159,1740481181.6239946,13.39998722076416,0.0,1740481181.623996,13.39998722076416,0.8228917909899981,, -1740481181.643693,13.419987201690674,5.66653526964325,1740481181.6436949,13.419987201690674,0.0,1740481181.6436968,13.419987201690674,0.012305110183150367,1740481181.643699,13.419987201690674,9.235499007343524,1740481181.6437,13.419987201690674,0.0,1740481181.643701,13.419987201690674,0.0,1740481181.643702,13.419987201690674,0.0,1740481181.643703,13.419987201690674,0.0,1740481181.6437042,13.419987201690674,0.8454770428522242,1740481181.643705,13.419987201690674,1.0,1740481181.6437056,13.419987201690674,1.022585251862226,1740481181.643707,13.419987201690674,0.0,1740481181.643708,13.419987201690674,0.8228917909899981,, -1740481181.6666584,13.439987182617188,5.66653526964325,1740481181.66666,13.439987182617188,0.0,1740481181.6666625,13.439987182617188,0.0,1740481181.6666644,13.439987182617188,9.312318851623246,1740481181.6666653,13.439987182617188,0.0,1740481181.6666665,13.439987182617188,0.0,1740481181.6666675,13.439987182617188,0.0,1740481181.6666687,13.439987182617188,0.0,1740481181.6666696,13.439987182617188,0.8841290345595755,1740481181.6666703,13.439987182617188,0.0,1740481181.6666713,13.439987182617188,0.06123724356957738,1740481181.6666725,13.439987182617188,0.0,1740481181.6666732,13.439987182617188,0.8228917909899981,, -1740481181.685005,13.459987163543701,5.66653526964325,1740481181.6850097,13.459987163543701,0.0,1740481181.6850138,13.459987163543701,0.0,1740481181.685016,13.459987163543701,9.312318851623246,1740481181.685017,13.459987163543701,0.0,1740481181.6850195,13.459987163543701,0.0,1740481181.6850204,13.459987163543701,0.0,1740481181.6850214,13.459987163543701,0.0,1740481181.6850228,13.459987163543701,0.8841290345595755,1740481181.685024,13.459987163543701,0.0,1740481181.685025,13.459987163543701,0.06123724356957738,1740481181.6850264,13.459987163543701,0.0,1740481181.6850274,13.459987163543701,0.8228917909899981,, -1740481181.7037246,13.479987144470215,5.66653526964325,1740481181.7037263,13.479987144470215,0.0,1740481181.7037284,13.479987144470215,0.0,1740481181.7037432,13.479987144470215,9.312318851623246,1740481181.7037444,13.479987144470215,0.0,1740481181.7037468,13.479987144470215,0.0,1740481181.703748,13.479987144470215,0.0,1740481181.7037492,13.479987144470215,0.0,1740481181.7037501,13.479987144470215,0.8841290345595755,1740481181.703751,13.479987144470215,0.0,1740481181.703752,13.479987144470215,0.06123724356957738,1740481181.703753,13.479987144470215,0.0,1740481181.7037537,13.479987144470215,0.8228917909899981,, -1740481181.7248585,13.499987125396729,5.66653526964325,1740481181.7248604,13.499987125396729,0.0,1740481181.7248633,13.499987125396729,0.0,1740481181.7248654,13.499987125396729,9.312318851623246,1740481181.7248666,13.499987125396729,0.0,1740481181.7248678,13.499987125396729,0.0,1740481181.7248688,13.499987125396729,0.0,1740481181.7248697,13.499987125396729,0.0,1740481181.7248707,13.499987125396729,0.8841290345595755,1740481181.7248714,13.499987125396729,0.0,1740481181.7248724,13.499987125396729,0.06123724356957738,1740481181.7248735,13.499987125396729,0.0,1740481181.7248743,13.499987125396729,0.8228917909899981,, -1740481181.7451797,13.519987106323242,5.760310142154793,1740481181.7451825,13.519987106323242,0.0,1740481181.7451851,13.519987106323242,0.013538997294248688,1740481181.745187,13.519987106323242,9.403454330250991,1740481181.7451882,13.519987106323242,0.0,1740481181.7451906,13.519987106323242,0.0,1740481181.7451925,13.519987106323242,0.0,1740481181.7451937,13.519987106323242,0.0,1740481181.7451952,13.519987106323242,0.8841290345595755,1740481181.7451966,13.519987106323242,1.0,1740481181.7451975,13.519987106323242,1.0048034221447981,1740481181.7451985,13.519987106323242,0.0,1740481181.7451997,13.519987106323242,0.8616900316567461,, -1740481181.7697563,13.539987087249756,5.760310142154793,1740481181.7697616,13.539987087249756,0.0,1740481181.7697973,13.539987087249756,0.0,1740481181.7698064,13.539987087249756,9.483690205468285,1740481181.76981,13.539987087249756,0.0,1740481181.769816,13.539987087249756,0.0,1740481181.7698195,13.539987087249756,0.0,1740481181.7698228,13.539987087249756,0.0,1740481181.769826,13.539987087249756,0.9229272752263241,1740481181.769861,13.539987087249756,0.0,1740481181.7698648,13.539987087249756,0.06123724356957805,1740481181.7698684,13.539987087249756,0.0,1740481181.7698717,13.539987087249756,0.8616900316567461,, -1740481181.7835677,13.55998706817627,5.760310142154793,1740481181.783569,13.55998706817627,0.0,1740481181.7835712,13.55998706817627,0.0,1740481181.783573,13.55998706817627,9.483690205468285,1740481181.783574,13.55998706817627,0.0,1740481181.7835753,13.55998706817627,0.0,1740481181.7835763,13.55998706817627,0.0,1740481181.7835772,13.55998706817627,0.0,1740481181.783578,13.55998706817627,0.9229272752263241,1740481181.7835789,13.55998706817627,0.0,1740481181.7835796,13.55998706817627,0.06123724356957805,1740481181.7835803,13.55998706817627,0.0,1740481181.7835815,13.55998706817627,0.8616900316567461,, -1740481181.804323,13.579987049102783,5.760310142154793,1740481181.8043249,13.579987049102783,0.0,1740481181.8043516,13.579987049102783,0.0,1740481181.8043532,13.579987049102783,9.483690205468285,1740481181.8043542,13.579987049102783,0.0,1740481181.8043556,13.579987049102783,0.0,1740481181.8043568,13.579987049102783,0.0,1740481181.804358,13.579987049102783,0.0,1740481181.8043587,13.579987049102783,0.9229272752263241,1740481181.8043833,13.579987049102783,0.0,1740481181.8043842,13.579987049102783,0.06123724356957805,1740481181.804385,13.579987049102783,0.0,1740481181.8043861,13.579987049102783,0.8616900316567461,, -1740481181.8253825,13.599987030029297,5.760310142154793,1740481181.8253841,13.599987030029297,0.0,1740481181.8253863,13.599987030029297,0.0,1740481181.8253882,13.599987030029297,9.483690205468285,1740481181.8253894,13.599987030029297,0.0,1740481181.8253903,13.599987030029297,0.0,1740481181.8253913,13.599987030029297,0.0,1740481181.8253925,13.599987030029297,0.0,1740481181.8254042,13.599987030029297,0.9229272752263241,1740481181.8254056,13.599987030029297,0.0,1740481181.8254066,13.599987030029297,0.06123724356957805,1740481181.8254075,13.599987030029297,0.0,1740481181.8254082,13.599987030029297,0.8616900316567461,, -1740481181.8444629,13.61998701095581,5.857402581377343,1740481181.8444653,13.61998701095581,0.0,1740481181.8444676,13.61998701095581,0.014633130943414997,1740481181.8444695,13.61998701095581,9.556697773827736,1740481181.8444705,13.61998701095581,0.0,1740481181.8444717,13.61998701095581,0.0,1740481181.844473,13.61998701095581,0.0,1740481181.8444736,13.61998701095581,0.0,1740481181.8444748,13.61998701095581,0.9229272752263241,1740481181.8444767,13.61998701095581,0.76048991297329,1740481181.844478,13.61998701095581,0.779273007587967,1740481181.8444793,13.61998701095581,0.0,1740481181.8444803,13.61998701095581,0.8908772503647633,, -1740481181.8681438,13.639986991882324,5.857402581377343,1740481181.868146,13.639986991882324,0.0,1740481181.8681483,13.639986991882324,0.0,1740481181.8681502,13.639986991882324,9.63915708210687,1740481181.868151,13.639986991882324,0.0,1740481181.8681526,13.639986991882324,0.0,1740481181.8681533,13.639986991882324,0.0,1740481181.8681543,13.639986991882324,0.0,1740481181.8681552,13.639986991882324,0.9513867142206324,1740481181.868156,13.639986991882324,0.0,1740481181.868157,13.639986991882324,0.06050946385586908,1740481181.8681579,13.639986991882324,0.0,1740481181.8681588,13.639986991882324,0.8908772503647633,, -1740481181.8846438,13.659986972808838,5.857402581377343,1740481181.8846457,13.659986972808838,0.0,1740481181.8846478,13.659986972808838,0.0,1740481181.8846498,13.659986972808838,9.63915708210687,1740481181.8846507,13.659986972808838,0.0,1740481181.8846521,13.659986972808838,0.0,1740481181.884653,13.659986972808838,0.0,1740481181.884654,13.659986972808838,0.0,1740481181.8846548,13.659986972808838,0.9513867142206324,1740481181.884656,13.659986972808838,0.0,1740481181.884657,13.659986972808838,0.06050946385586908,1740481181.8846576,13.659986972808838,0.0,1740481181.8846586,13.659986972808838,0.8908772503647633,, -1740481181.9095962,13.679986953735352,5.857402581377343,1740481181.909598,13.679986953735352,0.0,1740481181.9096005,13.679986953735352,0.0,1740481181.9096026,13.679986953735352,9.63915708210687,1740481181.9096036,13.679986953735352,0.0,1740481181.9096048,13.679986953735352,0.0,1740481181.909606,13.679986953735352,0.0,1740481181.9096067,13.679986953735352,0.0,1740481181.9096076,13.679986953735352,0.9513867142206324,1740481181.9096084,13.679986953735352,0.0,1740481181.9096093,13.679986953735352,0.06050946385586908,1740481181.90961,13.679986953735352,0.0,1740481181.9096117,13.679986953735352,0.8908772503647633,, -1740481181.924972,13.699986934661865,5.857402581377343,1740481181.9249737,13.699986934661865,0.0,1740481181.924976,13.699986934661865,0.0,1740481181.924978,13.699986934661865,9.63915708210687,1740481181.9249787,13.699986934661865,0.0,1740481181.9249802,13.699986934661865,0.0,1740481181.9249814,13.699986934661865,0.0,1740481181.924982,13.699986934661865,0.0,1740481181.924983,13.699986934661865,0.9513867142206324,1740481181.9249837,13.699986934661865,0.0,1740481181.9249847,13.699986934661865,0.06050946385586908,1740481181.9249856,13.699986934661865,0.0,1740481181.9249864,13.699986934661865,0.8908772503647633,, -1740481181.945264,13.719986915588379,5.857402581377343,1740481181.9452684,13.719986915588379,0.0,1740481181.9452727,13.719986915588379,0.0,1740481181.945276,13.719986915588379,9.63915708210687,1740481181.9452775,13.719986915588379,0.0,1740481181.945279,13.719986915588379,0.0,1740481181.9452803,13.719986915588379,0.0,1740481181.9452817,13.719986915588379,0.0,1740481181.9452837,13.719986915588379,0.9513867142206324,1740481181.9452848,13.719986915588379,0.0,1740481181.945286,13.719986915588379,0.06050946385586908,1740481181.9452884,13.719986915588379,0.0,1740481181.9452908,13.719986915588379,0.8908772503647633,, -1740481181.9708145,13.739986896514893,5.9568048494835875,1740481181.970816,13.739986896514893,0.0,1740481181.9708183,13.739986896514893,0.0,1740481181.9708204,13.739986896514893,9.768885189891838,1740481181.9708214,13.739986896514893,0.0,1740481181.9708226,13.739986896514893,0.0,1740481181.9708235,13.739986896514893,0.0,1740481181.9708245,13.739986896514893,0.0,1740481181.9708254,13.739986896514893,0.9639580053711966,1740481181.9708261,13.739986896514893,0.36041994628808305,1740481181.970827,13.739986896514893,0.41715976729134985,1740481181.9708278,13.739986896514893,0.0,1740481181.9708288,13.739986896514893,0.9060401702041253,, -1740481181.9840388,13.759986877441406,5.9568048494835875,1740481181.9840405,13.759986877441406,0.0,1740481181.9840424,13.759986877441406,0.0,1740481181.9840446,13.759986877441406,9.768885189891838,1740481181.9840457,13.759986877441406,0.0,1740481181.9840472,13.759986877441406,0.0,1740481181.9840481,13.759986877441406,0.0,1740481181.984049,13.759986877441406,0.0,1740481181.9840503,13.759986877441406,0.9639580053711966,1740481181.9840515,13.759986877441406,0.36041994628808305,1740481181.9840522,13.759986877441406,0.4183377814551543,1740481181.9840531,13.759986877441406,0.0,1740481181.984054,13.759986877441406,0.9060401702041253,, -1740481182.004445,13.77998685836792,5.9568048494835875,1740481182.0044475,13.77998685836792,0.0,1740481182.0044503,13.77998685836792,0.0,1740481182.0044525,13.77998685836792,9.768885189891838,1740481182.0044537,13.77998685836792,0.0,1740481182.004455,13.77998685836792,0.0,1740481182.0044563,13.77998685836792,0.0,1740481182.0044572,13.77998685836792,0.0,1740481182.0044582,13.77998685836792,0.9639580053711966,1740481182.0044596,13.77998685836792,0.36041994628808305,1740481182.0044606,13.77998685836792,0.4183377814551543,1740481182.0044618,13.77998685836792,0.0,1740481182.004463,13.77998685836792,0.9060401702041253,, -1740481182.0236325,13.799986839294434,5.9568048494835875,1740481182.0236344,13.799986839294434,0.0,1740481182.0236366,13.799986839294434,0.0,1740481182.0236382,13.799986839294434,9.768885189891838,1740481182.0236392,13.799986839294434,0.0,1740481182.0236406,13.799986839294434,0.0,1740481182.0236416,13.799986839294434,0.0,1740481182.0236425,13.799986839294434,0.0,1740481182.0236435,13.799986839294434,0.9639580053711966,1740481182.0236444,13.799986839294434,0.36041994628808305,1740481182.0236452,13.799986839294434,0.4183377814551543,1740481182.023646,13.799986839294434,0.0,1740481182.0236473,13.799986839294434,0.9060401702041253,, -1740481182.0444348,13.819986820220947,5.9568048494835875,1740481182.0444367,13.819986820220947,0.0,1740481182.0444396,13.819986820220947,0.0,1740481182.0444417,13.819986820220947,9.768885189891838,1740481182.0444427,13.819986820220947,0.0,1740481182.044444,13.819986820220947,0.0,1740481182.0444453,13.819986820220947,0.0,1740481182.0444462,13.819986820220947,0.0,1740481182.0444472,13.819986820220947,0.9639580053711966,1740481182.0444481,13.819986820220947,0.36041994628808305,1740481182.0444493,13.819986820220947,0.4183377814551543,1740481182.0444503,13.819986820220947,0.0,1740481182.0444512,13.819986820220947,0.9060401702041253,, -1740481182.0671172,13.839986801147461,6.057792872457066,1740481182.0671196,13.839986801147461,0.0,1740481182.0671232,13.839986801147461,0.0,1740481182.0671256,13.839986801147461,9.935617512830827,1740481182.0671327,13.839986801147461,0.0,1740481182.067136,13.839986801147461,0.0,1740481182.0671382,13.839986801147461,0.0,1740481182.0671396,13.839986801147461,0.0,1740481182.067141,13.839986801147461,0.9847653796634791,1740481182.0671427,13.839986801147461,0.15234620336525784,1740481182.067144,13.839986801147461,0.1927152686616968,1740481182.0671458,13.839986801147461,0.0,1740481182.0671487,13.839986801147461,0.9389123201868808,, -1740481182.0839403,13.859986782073975,6.057792872457066,1740481182.0839422,13.859986782073975,0.0,1740481182.083944,13.859986782073975,0.0,1740481182.0839465,13.859986782073975,9.935617512830827,1740481182.0839474,13.859986782073975,0.0,1740481182.0839489,13.859986782073975,0.0,1740481182.0839498,13.859986782073975,0.0,1740481182.083951,13.859986782073975,0.0,1740481182.083952,13.859986782073975,0.9847653796634791,1740481182.0839531,13.859986782073975,0.15234620336525784,1740481182.083954,13.859986782073975,0.19819926284185618,1740481182.0839553,13.859986782073975,0.0,1740481182.0839562,13.859986782073975,0.9389123201868808,, -1740481182.1039217,13.879986763000488,6.057792872457066,1740481182.1039238,13.879986763000488,0.0,1740481182.1039262,13.879986763000488,0.0,1740481182.1039283,13.879986763000488,9.935617512830827,1740481182.1039295,13.879986763000488,0.0,1740481182.103931,13.879986763000488,0.0,1740481182.1039317,13.879986763000488,0.0,1740481182.1039326,13.879986763000488,0.0,1740481182.1039338,13.879986763000488,0.9847653796634791,1740481182.103935,13.879986763000488,0.15234620336525784,1740481182.103936,13.879986763000488,0.19819926284185618,1740481182.103937,13.879986763000488,0.0,1740481182.103938,13.879986763000488,0.9389123201868808,, -1740481182.124321,13.899986743927002,6.057792872457066,1740481182.124323,13.899986743927002,0.0,1740481182.124325,13.899986743927002,0.0,1740481182.124327,13.899986743927002,9.935617512830827,1740481182.124328,13.899986743927002,0.0,1740481182.1243293,13.899986743927002,0.0,1740481182.1243303,13.899986743927002,0.0,1740481182.124331,13.899986743927002,0.0,1740481182.1243317,13.899986743927002,0.9847653796634791,1740481182.124333,13.899986743927002,0.15234620336525784,1740481182.1243339,13.899986743927002,0.19819926284185618,1740481182.124335,13.899986743927002,0.0,1740481182.1243362,13.899986743927002,0.9389123201868808,, -1740481182.143814,13.919986724853516,6.057792872457066,1740481182.143816,13.919986724853516,0.0,1740481182.143818,13.919986724853516,0.0,1740481182.14382,13.919986724853516,9.935617512830827,1740481182.143821,13.919986724853516,0.0,1740481182.1438224,13.919986724853516,0.0,1740481182.1438234,13.919986724853516,0.0,1740481182.1438367,13.919986724853516,0.0,1740481182.1438396,13.919986724853516,0.9847653796634791,1740481182.1438408,13.919986724853516,0.15234620336525784,1740481182.1438417,13.919986724853516,0.19819926284185618,1740481182.1438425,13.919986724853516,0.0,1740481182.1438437,13.919986724853516,0.9389123201868808,, -1740481182.1664793,13.93998670578003,6.057792872457066,1740481182.1664813,13.93998670578003,0.0,1740481182.1664832,13.93998670578003,0.0,1740481182.166485,13.93998670578003,9.935617512830827,1740481182.166486,13.93998670578003,0.0,1740481182.1664872,13.93998670578003,0.0,1740481182.1664884,13.93998670578003,0.0,1740481182.1664891,13.93998670578003,0.0,1740481182.1664898,13.93998670578003,0.9847653796634791,1740481182.1664908,13.93998670578003,0.15234620336525784,1740481182.1664917,13.93998670578003,0.19819926284185618,1740481182.1664927,13.93998670578003,0.0,1740481182.1664934,13.93998670578003,0.9389123201868808,, -1740481182.1844523,13.959986686706543,6.161844632204554,1740481182.1844542,13.959986686706543,0.0,1740481182.1844563,13.959986686706543,0.016732720925944834,1740481182.1844585,13.959986686706543,9.983360988509261,1740481182.1844594,13.959986686706543,0.0,1740481182.1844609,13.959986686706543,0.0,1740481182.1844792,13.959986686706543,0.0,1740481182.1844802,13.959986686706543,0.0,1740481182.1844814,13.959986686706543,1.0000000000000049,1740481182.1844823,13.959986686706543,-8.215650382226158e-14,1740481182.1844833,13.959986686706543,0.045459230937736746,1740481182.184484,13.959986686706543,0.0,1740481182.1844854,13.959986686706543,0.9544176975631254,, -1740481182.2051914,13.979986667633057,6.161844632204554,1740481182.2051954,13.979986667633057,0.0,1740481182.2051983,13.979986667633057,0.016732720925944834,1740481182.2052016,13.979986667633057,9.983360988509261,1740481182.205203,13.979986667633057,0.0,1740481182.2052042,13.979986667633057,0.0,1740481182.2052054,13.979986667633057,0.0,1740481182.2052076,13.979986667633057,0.0,1740481182.205209,13.979986667633057,1.0000000000000049,1740481182.2052107,13.979986667633057,-8.215650382226158e-14,1740481182.2052119,13.979986667633057,0.045582302436797284,1740481182.2052138,13.979986667633057,0.0,1740481182.2052152,13.979986667633057,0.9544176975631254,, -1740481182.2241313,13.99998664855957,6.161844632204554,1740481182.2241335,13.99998664855957,0.0,1740481182.2241352,13.99998664855957,0.016732720925944834,1740481182.2241373,13.99998664855957,9.983360988509261,1740481182.2241383,13.99998664855957,0.0,1740481182.2241395,13.99998664855957,0.0,1740481182.2241404,13.99998664855957,0.0,1740481182.2241414,13.99998664855957,0.0,1740481182.224142,13.99998664855957,1.0000000000000049,1740481182.224143,13.99998664855957,-8.215650382226158e-14,1740481182.2241442,13.99998664855957,0.045582302436797284,1740481182.2241452,13.99998664855957,0.0,1740481182.224146,13.99998664855957,0.9544176975631254,, -1740481182.2449832,14.019986629486084,6.161844632204554,1740481182.2449865,14.019986629486084,0.0,1740481182.2449915,14.019986629486084,0.016732720925944834,1740481182.2449946,14.019986629486084,9.983360988509261,1740481182.2449963,14.019986629486084,0.0,1740481182.2449985,14.019986629486084,0.0,1740481182.2450001,14.019986629486084,0.0,1740481182.245002,14.019986629486084,0.0,1740481182.2450037,14.019986629486084,1.0000000000000049,1740481182.2450054,14.019986629486084,-8.215650382226158e-14,1740481182.245007,14.019986629486084,0.045582302436797284,1740481182.2450087,14.019986629486084,0.0,1740481182.2450101,14.019986629486084,0.9544176975631254,, -1740481182.2678702,14.039986610412598,6.161844632204554,1740481182.267872,14.039986610412598,0.0,1740481182.267874,14.039986610412598,0.0,1740481182.2678761,14.039986610412598,10.070680027330805,1740481182.267877,14.039986610412598,0.0,1740481182.2678783,14.039986610412598,0.0,1740481182.2678792,14.039986610412598,0.0,1740481182.2678802,14.039986610412598,0.0,1740481182.267881,14.039986610412598,0.9915176362686652,1740481182.2678819,14.039986610412598,0.0,1740481182.2678828,14.039986610412598,0.03709993870553974,1740481182.2678835,14.039986610412598,0.0,1740481182.2678845,14.039986610412598,0.9544176975631254,, -1740481182.2839196,14.059986591339111,6.266919930930852,1740481182.2839217,14.059986591339111,0.0,1740481182.2839234,14.059986591339111,0.017013177888215412,1740481182.2839258,14.059986591339111,10.087914481778029,1740481182.2839267,14.059986591339111,0.0,1740481182.283928,14.059986591339111,0.0,1740481182.2839289,14.059986591339111,0.0,1740481182.2839298,14.059986591339111,0.0,1740481182.2839305,14.059986591339111,0.9915176362686652,1740481182.2839317,14.059986591339111,0.08482363731330933,1740481182.2839327,14.059986591339111,0.12176264756433658,1740481182.2839336,14.059986591339111,0.0,1740481182.2839344,14.059986591339111,0.95452833584263,, -1740481182.303965,14.079986572265625,6.266919930930852,1740481182.303967,14.079986572265625,0.0,1740481182.303969,14.079986572265625,0.017013177888215412,1740481182.3039713,14.079986572265625,10.087914481778029,1740481182.3039727,14.079986572265625,0.0,1740481182.303974,14.079986572265625,0.0,1740481182.3039749,14.079986572265625,0.0,1740481182.3039758,14.079986572265625,0.0,1740481182.3039768,14.079986572265625,0.9915176362686652,1740481182.3039777,14.079986572265625,0.08482363731330933,1740481182.3039787,14.079986572265625,0.12181293773934454,1740481182.3039799,14.079986572265625,0.0,1740481182.3039808,14.079986572265625,0.95452833584263,, -1740481182.3246064,14.099986553192139,6.266919930930852,1740481182.324608,14.099986553192139,0.0,1740481182.32461,14.099986553192139,0.017013177888215412,1740481182.3246348,14.099986553192139,10.087914481778029,1740481182.324636,14.099986553192139,0.0,1740481182.3246372,14.099986553192139,0.0,1740481182.3246381,14.099986553192139,0.0,1740481182.3246393,14.099986553192139,0.0,1740481182.32464,14.099986553192139,0.9915176362686652,1740481182.324641,14.099986553192139,0.08482363731330933,1740481182.324642,14.099986553192139,0.12181293773934454,1740481182.3246434,14.099986553192139,0.0,1740481182.3246608,14.099986553192139,0.95452833584263,, -1740481182.3436775,14.119986534118652,6.266919930930852,1740481182.3436794,14.119986534118652,0.0,1740481182.3436816,14.119986534118652,0.017013177888215412,1740481182.3436835,14.119986534118652,10.087914481778029,1740481182.3436847,14.119986534118652,0.0,1740481182.3436859,14.119986534118652,0.0,1740481182.3436866,14.119986534118652,0.0,1740481182.3436882,14.119986534118652,0.0,1740481182.343689,14.119986534118652,0.9915176362686652,1740481182.34369,14.119986534118652,0.08482363731330933,1740481182.343691,14.119986534118652,0.12181293773934454,1740481182.3436918,14.119986534118652,0.0,1740481182.3436928,14.119986534118652,0.95452833584263,, -1740481182.3665466,14.139986515045166,6.266919930930852,1740481182.3665488,14.139986515045166,0.0,1740481182.3665524,14.139986515045166,0.0,1740481182.3665543,14.139986515045166,10.175976602616112,1740481182.3665555,14.139986515045166,0.0,1740481182.3665566,14.139986515045166,0.0,1740481182.3665576,14.139986515045166,0.0,1740481182.3665588,14.139986515045166,0.0,1740481182.3665595,14.139986515045166,0.9915587634227395,1740481182.3665607,14.139986515045166,0.0,1740481182.366562,14.139986515045166,0.03703042758010955,1740481182.3665626,14.139986515045166,0.0,1740481182.3665636,14.139986515045166,0.95452833584263,, -1740481182.3850095,14.15998649597168,6.266919930930852,1740481182.385012,14.15998649597168,0.0,1740481182.3850155,14.15998649597168,0.0,1740481182.3850176,14.15998649597168,10.175976602616112,1740481182.3850183,14.15998649597168,0.0,1740481182.3850195,14.15998649597168,0.0,1740481182.385021,14.15998649597168,0.0,1740481182.385022,14.15998649597168,0.0,1740481182.3850229,14.15998649597168,0.9915587634227395,1740481182.385024,14.15998649597168,0.0,1740481182.385025,14.15998649597168,0.03703042758010955,1740481182.385026,14.15998649597168,0.0,1740481182.385027,14.15998649597168,0.95452833584263,, -1740481182.4038305,14.179986476898193,6.3722491477047605,1740481182.4038324,14.179986476898193,0.0,1740481182.4038343,14.179986476898193,0.017054998208394952,1740481182.4038365,14.179986476898193,10.20219142121987,1740481182.4038374,14.179986476898193,0.0,1740481182.4038386,14.179986476898193,0.0,1740481182.4038398,14.179986476898193,0.0,1740481182.403841,14.179986476898193,0.0,1740481182.403842,14.179986476898193,0.9915587634227395,1740481182.403843,14.179986476898193,0.08441236577256594,1740481182.4038439,14.179986476898193,0.11478110380707159,1740481182.4038448,14.179986476898193,0.0,1740481182.4038458,14.179986476898193,0.9591082460403118,, -1740481182.4242606,14.199986457824707,6.3722491477047605,1740481182.424264,14.199986457824707,0.0,1740481182.424267,14.199986457824707,0.017054998208394952,1740481182.4242692,14.199986457824707,10.20219142121987,1740481182.424271,14.199986457824707,0.0,1740481182.4242723,14.199986457824707,0.0,1740481182.4242744,14.199986457824707,0.0,1740481182.424277,14.199986457824707,0.0,1740481182.4242783,14.199986457824707,0.9915587634227395,1740481182.4242802,14.199986457824707,0.08441236577256594,1740481182.4242816,14.199986457824707,0.11686288315499371,1740481182.4242837,14.199986457824707,0.0,1740481182.4242857,14.199986457824707,0.9591082460403118,, -1740481182.4439096,14.21998643875122,6.3722491477047605,1740481182.443911,14.21998643875122,0.0,1740481182.4439132,14.21998643875122,0.017054998208394952,1740481182.4439154,14.21998643875122,10.20219142121987,1740481182.4439163,14.21998643875122,0.0,1740481182.4439175,14.21998643875122,0.0,1740481182.4439187,14.21998643875122,0.0,1740481182.4439197,14.21998643875122,0.0,1740481182.4439204,14.21998643875122,0.9915587634227395,1740481182.4439213,14.21998643875122,0.08441236577256594,1740481182.4439225,14.21998643875122,0.11686288315499371,1740481182.4439235,14.21998643875122,0.0,1740481182.4439244,14.21998643875122,0.9591082460403118,, -1740481182.4672546,14.239986419677734,6.3722491477047605,1740481182.4672563,14.239986419677734,0.0,1740481182.4672797,14.239986419677734,0.0,1740481182.4672818,14.239986419677734,10.290465639785385,1740481182.4672828,14.239986419677734,0.0,1740481182.467284,14.239986419677734,0.0,1740481182.467285,14.239986419677734,0.0,1740481182.467286,14.239986419677734,0.0,1740481182.4672868,14.239986419677734,0.9931735352359532,1740481182.4672878,14.239986419677734,0.0,1740481182.4672885,14.239986419677734,0.034065289195641446,1740481182.4672897,14.239986419677734,0.0,1740481182.4672906,14.239986419677734,0.9591082460403118,, -1740481182.4836433,14.259986400604248,6.3722491477047605,1740481182.483645,14.259986400604248,0.0,1740481182.4836473,14.259986400604248,0.0,1740481182.4836493,14.259986400604248,10.290465639785385,1740481182.4836502,14.259986400604248,0.0,1740481182.4836516,14.259986400604248,0.0,1740481182.4836526,14.259986400604248,0.0,1740481182.4836533,14.259986400604248,0.0,1740481182.4836545,14.259986400604248,0.9931735352359532,1740481182.4836555,14.259986400604248,0.0,1740481182.4836564,14.259986400604248,0.034065289195641446,1740481182.4836571,14.259986400604248,0.0,1740481182.4836583,14.259986400604248,0.9591082460403118,, -1740481182.5036323,14.279986381530762,6.477946001365115,1740481182.5036342,14.279986381530762,0.0,1740481182.5036366,14.279986381530762,0.017142397615251246,1740481182.5036383,14.279986381530762,10.312413214252938,1740481182.5036395,14.279986381530762,0.0,1740481182.503641,14.279986381530762,0.0,1740481182.5036418,14.279986381530762,0.0,1740481182.5036428,14.279986381530762,0.0,1740481182.5036438,14.279986381530762,0.9931735352359532,1740481182.5036447,14.279986381530762,0.06826464764051687,1740481182.5036457,14.279986381530762,0.09883526172026129,1740481182.5036464,14.279986381530762,0.0,1740481182.5036476,14.279986381530762,0.9615108344664631,, -1740481182.526981,14.299986362457275,6.477946001365115,1740481182.5269835,14.299986362457275,0.0,1740481182.5269856,14.299986362457275,0.017142397615251246,1740481182.5269878,14.299986362457275,10.312413214252938,1740481182.5269887,14.299986362457275,0.0,1740481182.5269904,14.299986362457275,0.0,1740481182.5269911,14.299986362457275,0.0,1740481182.5269923,14.299986362457275,0.0,1740481182.526993,14.299986362457275,0.9931735352359532,1740481182.5269942,14.299986362457275,0.06826464764051687,1740481182.526995,14.299986362457275,0.09992734841000694,1740481182.526996,14.299986362457275,0.0,1740481182.5269973,14.299986362457275,0.9615108344664631,, -1740481182.5451622,14.319986343383789,6.477946001365115,1740481182.5451639,14.319986343383789,0.0,1740481182.5451658,14.319986343383789,0.017142397615251246,1740481182.545168,14.319986343383789,10.312413214252938,1740481182.5451689,14.319986343383789,0.0,1740481182.54517,14.319986343383789,0.0,1740481182.5451713,14.319986343383789,0.0,1740481182.5451722,14.319986343383789,0.0,1740481182.545173,14.319986343383789,0.9931735352359532,1740481182.5451741,14.319986343383789,0.06826464764051687,1740481182.5451748,14.319986343383789,0.09992734841000694,1740481182.5451758,14.319986343383789,0.0,1740481182.5451765,14.319986343383789,0.9615108344664631,, -1740481182.5693192,14.339986324310303,6.477946001365115,1740481182.569321,14.339986324310303,0.0,1740481182.569323,14.339986324310303,0.0,1740481182.5693247,14.339986324310303,10.40096767029804,1740481182.569326,14.339986324310303,0.0,1740481182.569327,14.339986324310303,0.0,1740481182.569328,14.339986324310303,0.0,1740481182.5693288,14.339986324310303,0.0,1740481182.56933,14.339986324310303,0.9939521450627331,1740481182.5693307,14.339986324310303,0.0,1740481182.5693316,14.339986324310303,0.03244131059626998,1740481182.5693324,14.339986324310303,0.0,1740481182.5693336,14.339986324310303,0.9615108344664631,, -1740481182.5868127,14.359986305236816,6.477946001365115,1740481182.5868142,14.359986305236816,0.0,1740481182.5868165,14.359986305236816,0.0,1740481182.5868185,14.359986305236816,10.40096767029804,1740481182.5868196,14.359986305236816,0.0,1740481182.5868208,14.359986305236816,0.0,1740481182.5868216,14.359986305236816,0.0,1740481182.5868227,14.359986305236816,0.0,1740481182.5868235,14.359986305236816,0.9939521450627331,1740481182.5868244,14.359986305236816,0.0,1740481182.5868251,14.359986305236816,0.03244131059626998,1740481182.5868263,14.359986305236816,0.0,1740481182.586827,14.359986305236816,0.9615108344664631,, -1740481182.604713,14.37998628616333,6.477946001365115,1740481182.6047156,14.37998628616333,0.0,1740481182.604718,14.37998628616333,0.0,1740481182.6047206,14.37998628616333,10.40096767029804,1740481182.6047215,14.37998628616333,0.0,1740481182.6047232,14.37998628616333,0.0,1740481182.6047242,14.37998628616333,0.0,1740481182.6047256,14.37998628616333,0.0,1740481182.6047268,14.37998628616333,0.9939521450627331,1740481182.604728,14.37998628616333,0.0,1740481182.604729,14.37998628616333,0.03244131059626998,1740481182.60473,14.37998628616333,0.0,1740481182.6047308,14.37998628616333,0.9615108344664631,, -1740481182.6244116,14.399986267089844,6.583903502481709,1740481182.6244135,14.399986267089844,0.0,1740481182.6244156,14.399986267089844,0.017198142728397214,1740481182.6244175,14.399986267089844,10.422070239845095,1740481182.6244185,14.399986267089844,0.0,1740481182.62442,14.399986267089844,0.0,1740481182.624421,14.399986267089844,0.0,1740481182.6244216,14.399986267089844,0.0,1740481182.6244226,14.399986267089844,0.9939521450627331,1740481182.6244235,14.399986267089844,0.060478549372630086,1740481182.6244245,14.399986267089844,0.09008027598179755,1740481182.6244252,14.399986267089844,0.0,1740481182.6244261,14.399986267089844,0.9634630478757906,, -1740481182.6442099,14.419986248016357,6.583903502481709,1740481182.6442118,14.419986248016357,0.0,1740481182.644214,14.419986248016357,0.017198142728397214,1740481182.6442158,14.419986248016357,10.422070239845095,1740481182.6442168,14.419986248016357,0.0,1740481182.6442182,14.419986248016357,0.0,1740481182.6442194,14.419986248016357,0.0,1740481182.6442204,14.419986248016357,0.0,1740481182.6442215,14.419986248016357,0.9939521450627331,1740481182.6442225,14.419986248016357,0.060478549372630086,1740481182.6442237,14.419986248016357,0.09096764655957257,1740481182.644225,14.419986248016357,0.0,1740481182.6442258,14.419986248016357,0.9634630478757906,, -1740481182.6669223,14.439986228942871,6.583903502481709,1740481182.6669242,14.439986228942871,0.0,1740481182.6669264,14.439986228942871,0.0,1740481182.6669283,14.439986228942871,10.51082959823329,1740481182.6669292,14.439986228942871,0.0,1740481182.6669304,14.439986228942871,0.0,1740481182.6669316,14.439986228942871,0.0,1740481182.6669328,14.439986228942871,0.0,1740481182.6669335,14.439986228942871,0.9945500940575076,1740481182.6669347,14.439986228942871,0.0,1740481182.6669354,14.439986228942871,0.031087046181716982,1740481182.6669369,14.439986228942871,0.0,1740481182.6669378,14.439986228942871,0.9634630478757906,, -1740481182.6856015,14.459986209869385,6.583903502481709,1740481182.6856034,14.459986209869385,0.0,1740481182.6856053,14.459986209869385,0.0,1740481182.6856077,14.459986209869385,10.51082959823329,1740481182.6856086,14.459986209869385,0.0,1740481182.68561,14.459986209869385,0.0,1740481182.685611,14.459986209869385,0.0,1740481182.685612,14.459986209869385,0.0,1740481182.685613,14.459986209869385,0.9945500940575076,1740481182.6856139,14.459986209869385,0.0,1740481182.6856146,14.459986209869385,0.031087046181716982,1740481182.6856155,14.459986209869385,0.0,1740481182.6856165,14.459986209869385,0.9634630478757906,, -1740481182.7054434,14.479986190795898,6.583903502481709,1740481182.7054465,14.479986190795898,0.0,1740481182.7054498,14.479986190795898,0.0,1740481182.7054522,14.479986190795898,10.51082959823329,1740481182.7054534,14.479986190795898,0.0,1740481182.7054555,14.479986190795898,0.0,1740481182.7054572,14.479986190795898,0.0,1740481182.7054713,14.479986190795898,0.0,1740481182.7054746,14.479986190795898,0.9945500940575076,1740481182.7054768,14.479986190795898,0.0,1740481182.7054787,14.479986190795898,0.031087046181716982,1740481182.7054803,14.479986190795898,0.0,1740481182.7054822,14.479986190795898,0.9634630478757906,, -1740481182.724045,14.499986171722412,6.689918783775488,1740481182.7240474,14.499986171722412,0.0,1740481182.7240496,14.499986171722412,0.01721787295381114,1740481182.7240515,14.499986171722412,10.527023633167808,1740481182.7240524,14.499986171722412,0.0,1740481182.7240539,14.499986171722412,0.0,1740481182.7240548,14.499986171722412,0.0,1740481182.7240558,14.499986171722412,0.0,1740481182.7240572,14.499986171722412,0.9945500940575076,1740481182.7240582,14.499986171722412,0.054499059424972796,1740481182.7240589,14.499986171722412,0.08633071529717735,1740481182.7240598,14.499986171722412,0.0,1740481182.724061,14.499986171722412,0.9629511288661443,, -1740481182.7441602,14.519986152648926,6.689918783775488,1740481182.7442513,14.519986152648926,0.0,1740481182.7442558,14.519986152648926,0.01721787295381114,1740481182.7442808,14.519986152648926,10.527023633167808,1740481182.7442825,14.519986152648926,0.0,1740481182.744284,14.519986152648926,0.0,1740481182.7442849,14.519986152648926,0.0,1740481182.7442863,14.519986152648926,0.0,1740481182.7442873,14.519986152648926,0.9945500940575076,1740481182.7442884,14.519986152648926,0.054499059424972796,1740481182.7442896,14.519986152648926,0.08609802461633609,1740481182.7442906,14.519986152648926,0.0,1740481182.7442915,14.519986152648926,0.9629511288661443,, -1740481182.765964,14.53998613357544,6.689918783775488,1740481182.765966,14.53998613357544,0.0,1740481182.7659678,14.53998613357544,0.0,1740481182.76597,14.53998613357544,10.615821041507775,1740481182.765971,14.53998613357544,0.0,1740481182.7659721,14.53998613357544,0.0,1740481182.7659733,14.53998613357544,0.0,1740481182.765974,14.53998613357544,0.0,1740481182.765975,14.53998613357544,0.9943963070009302,1740481182.7659757,14.53998613357544,0.0,1740481182.7659767,14.53998613357544,0.03144517813478587,1740481182.7659776,14.53998613357544,0.0,1740481182.7659783,14.53998613357544,0.9629511288661443,, -1740481182.7842677,14.559986114501953,6.689918783775488,1740481182.7842696,14.559986114501953,0.0,1740481182.7842724,14.559986114501953,0.0,1740481182.784274,14.559986114501953,10.615821041507775,1740481182.7842753,14.559986114501953,0.0,1740481182.7842765,14.559986114501953,0.0,1740481182.7842774,14.559986114501953,0.0,1740481182.7842782,14.559986114501953,0.0,1740481182.7842796,14.559986114501953,0.9943963070009302,1740481182.7842803,14.559986114501953,0.0,1740481182.7842813,14.559986114501953,0.03144517813478587,1740481182.7842824,14.559986114501953,0.0,1740481182.7842834,14.559986114501953,0.9629511288661443,, -1740481182.8034785,14.579986095428467,6.689918783775488,1740481182.8034804,14.579986095428467,0.0,1740481182.8034823,14.579986095428467,0.0,1740481182.8034844,14.579986095428467,10.615821041507775,1740481182.8034854,14.579986095428467,0.0,1740481182.8034863,14.579986095428467,0.0,1740481182.8034875,14.579986095428467,0.0,1740481182.8034885,14.579986095428467,0.0,1740481182.8034894,14.579986095428467,0.9943963070009302,1740481182.8034904,14.579986095428467,0.0,1740481182.8034914,14.579986095428467,0.03144517813478587,1740481182.803492,14.579986095428467,0.0,1740481182.803493,14.579986095428467,0.9629511288661443,, -1740481182.8241558,14.59998607635498,6.689918783775488,1740481182.8241577,14.59998607635498,0.0,1740481182.8241603,14.59998607635498,0.0,1740481182.8241622,14.59998607635498,10.615821041507775,1740481182.8241637,14.59998607635498,0.0,1740481182.8241649,14.59998607635498,0.0,1740481182.824166,14.59998607635498,0.0,1740481182.8241673,14.59998607635498,0.0,1740481182.8241682,14.59998607635498,0.9943963070009302,1740481182.8241692,14.59998607635498,0.0,1740481182.8241704,14.59998607635498,0.03144517813478587,1740481182.8241713,14.59998607635498,0.0,1740481182.824172,14.59998607635498,0.9629511288661443,, -1740481182.8435836,14.619986057281494,6.795886610338917,1740481182.8435853,14.619986057281494,0.0,1740481182.8435874,14.619986057281494,0.01720750465782477,1740481182.8435893,14.619986057281494,10.63168956844136,1740481182.8435905,14.619986057281494,0.0,1740481182.8435917,14.619986057281494,0.0,1740481182.8435926,14.619986057281494,0.0,1740481182.8435938,14.619986057281494,0.0,1740481182.8435948,14.619986057281494,0.9943963070009302,1740481182.8435957,14.619986057281494,0.056036929990659345,1740481182.8435965,14.619986057281494,0.08845591039692709,1740481182.8435977,14.619986057281494,0.0,1740481182.8435984,14.619986057281494,0.9622816400040239,, -1740481182.8674262,14.639986038208008,6.795886610338917,1740481182.8674278,14.639986038208008,0.0,1740481182.8674302,14.639986038208008,0.0,1740481182.8674319,14.639986038208008,10.720449890346964,1740481182.867433,14.639986038208008,0.0,1740481182.8674343,14.639986038208008,0.0,1740481182.8674352,14.639986038208008,0.0,1740481182.867436,14.639986038208008,0.0,1740481182.867437,14.639986038208008,0.9941919549368307,1740481182.8674378,14.639986038208008,0.0,1740481182.8674388,14.639986038208008,0.031910314932806716,1740481182.8674395,14.639986038208008,0.0,1740481182.867441,14.639986038208008,0.9622816400040239,, -1740481182.8838902,14.659986019134521,6.795886610338917,1740481182.8838923,14.659986019134521,0.0,1740481182.8838944,14.659986019134521,0.0,1740481182.8838966,14.659986019134521,10.720449890346964,1740481182.8838975,14.659986019134521,0.0,1740481182.883899,14.659986019134521,0.0,1740481182.8839,14.659986019134521,0.0,1740481182.883901,14.659986019134521,0.0,1740481182.8839016,14.659986019134521,0.9941919549368307,1740481182.8839028,14.659986019134521,0.0,1740481182.8839037,14.659986019134521,0.031910314932806716,1740481182.8839047,14.659986019134521,0.0,1740481182.883906,14.659986019134521,0.9622816400040239,, -1740481182.904197,14.679986000061035,6.795886610338917,1740481182.9041986,14.679986000061035,0.0,1740481182.9042013,14.679986000061035,0.0,1740481182.9042032,14.679986000061035,10.720449890346964,1740481182.9042044,14.679986000061035,0.0,1740481182.9042056,14.679986000061035,0.0,1740481182.9042063,14.679986000061035,0.0,1740481182.9042077,14.679986000061035,0.0,1740481182.9042087,14.679986000061035,0.9941919549368307,1740481182.9042096,14.679986000061035,0.0,1740481182.9042108,14.679986000061035,0.031910314932806716,1740481182.9042115,14.679986000061035,0.0,1740481182.9042273,14.679986000061035,0.9622816400040239,, -1740481182.9238398,14.699985980987549,6.795886610338917,1740481182.9238412,14.699985980987549,0.0,1740481182.9238434,14.699985980987549,0.0,1740481182.9238453,14.699985980987549,10.720449890346964,1740481182.9238467,14.699985980987549,0.0,1740481182.923848,14.699985980987549,0.0,1740481182.9238486,14.699985980987549,0.0,1740481182.9238498,14.699985980987549,0.0,1740481182.9238508,14.699985980987549,0.9941919549368307,1740481182.9238515,14.699985980987549,0.0,1740481182.9238524,14.699985980987549,0.031910314932806716,1740481182.9238534,14.699985980987549,0.0,1740481182.9238546,14.699985980987549,0.9622816400040239,, -1740481182.9442127,14.719985961914062,6.901693244926349,1740481182.9442148,14.719985961914062,0.0,1740481182.9442167,14.719985961914062,0.01717779879596383,1740481182.9442189,14.719985961914062,10.734284352874024,1740481182.9442198,14.719985961914062,0.0,1740481182.9442213,14.719985961914062,0.0,1740481182.9442222,14.719985961914062,0.0,1740481182.9442232,14.719985961914062,0.0,1740481182.944224,14.719985961914062,0.9941919549368307,1740481182.944225,14.719985961914062,0.05808045063165457,1740481182.9442263,14.719985961914062,0.09242228357558731,1740481182.944227,14.719985961914062,0.0,1740481182.944228,14.719985961914062,0.9606099718695712,, -1740481182.965683,14.739985942840576,6.901693244926349,1740481182.9656847,14.739985942840576,0.0,1740481182.9656868,14.739985942840576,0.0,1740481182.965689,14.739985942840576,10.822913188665492,1740481182.9656897,14.739985942840576,0.0,1740481182.9656909,14.739985942840576,0.0,1740481182.9656916,14.739985942840576,0.0,1740481182.9656928,14.739985942840576,0.0,1740481182.9656935,14.739985942840576,0.9936657243791785,1740481182.9656944,14.739985942840576,0.0,1740481182.9656954,14.739985942840576,0.03305575250960735,1740481182.9656963,14.739985942840576,0.0,1740481182.965697,14.739985942840576,0.9606099718695712,, -1740481182.9849348,14.75998592376709,6.901693244926349,1740481182.984937,14.75998592376709,0.0,1740481182.9849393,14.75998592376709,0.0,1740481182.984941,14.75998592376709,10.822913188665492,1740481182.9849422,14.75998592376709,0.0,1740481182.9849434,14.75998592376709,0.0,1740481182.9849443,14.75998592376709,0.0,1740481182.9849453,14.75998592376709,0.0,1740481182.9849463,14.75998592376709,0.9936657243791785,1740481182.9849474,14.75998592376709,0.0,1740481182.9849484,14.75998592376709,0.03305575250960735,1740481182.9849494,14.75998592376709,0.0,1740481182.9849503,14.75998592376709,0.9606099718695712,, -1740481183.0034075,14.779985904693604,6.901693244926349,1740481183.003409,14.779985904693604,0.0,1740481183.0034106,14.779985904693604,0.0,1740481183.0034127,14.779985904693604,10.822913188665492,1740481183.0034137,14.779985904693604,0.0,1740481183.0034149,14.779985904693604,0.0,1740481183.0034158,14.779985904693604,0.0,1740481183.0034168,14.779985904693604,0.0,1740481183.003418,14.779985904693604,0.9936657243791785,1740481183.0034187,14.779985904693604,0.0,1740481183.0034199,14.779985904693604,0.03305575250960735,1740481183.0034206,14.779985904693604,0.0,1740481183.0034218,14.779985904693604,0.9606099718695712,, -1740481183.0234256,14.799985885620117,6.901693244926349,1740481183.023427,14.799985885620117,0.0,1740481183.0234294,14.799985885620117,0.0,1740481183.0234315,14.799985885620117,10.822913188665492,1740481183.0234325,14.799985885620117,0.0,1740481183.0234337,14.799985885620117,0.0,1740481183.0234346,14.799985885620117,0.0,1740481183.0234356,14.799985885620117,0.0,1740481183.0234365,14.799985885620117,0.9936657243791785,1740481183.0234373,14.799985885620117,0.0,1740481183.023438,14.799985885620117,0.03305575250960735,1740481183.023439,14.799985885620117,0.0,1740481183.02344,14.799985885620117,0.9606099718695712,, -1740481183.045695,14.81998586654663,6.901693244926349,1740481183.045697,14.81998586654663,0.0,1740481183.0456994,14.81998586654663,0.0,1740481183.0457013,14.81998586654663,10.822913188665492,1740481183.0457025,14.81998586654663,0.0,1740481183.0457034,14.81998586654663,0.0,1740481183.0457044,14.81998586654663,0.0,1740481183.0457056,14.81998586654663,0.0,1740481183.0457063,14.81998586654663,0.9936657243791785,1740481183.0457072,14.81998586654663,0.0,1740481183.045708,14.81998586654663,0.03305575250960735,1740481183.0457091,14.81998586654663,0.0,1740481183.0457215,14.81998586654663,0.9606099718695712,, -1740481183.0707984,14.839985847473145,7.0073399684638265,1740481183.0708,14.839985847473145,0.0,1740481183.0708022,14.839985847473145,0.0,1740481183.070804,14.839985847473145,10.92561285128479,1740481183.0708053,14.839985847473145,0.0,1740481183.0708065,14.839985847473145,0.0,1740481183.0708072,14.839985847473145,0.0,1740481183.0708084,14.839985847473145,0.0,1740481183.0708091,14.839985847473145,0.9931829458542611,1740481183.07081,14.839985847473145,0.06817054145734969,1740481183.0708108,14.839985847473145,0.10266738811886848,1740481183.0708117,14.839985847473145,0.0,1740481183.0708127,14.839985847473145,0.959136441410482,, -1740481183.0859134,14.859985828399658,7.0073399684638265,1740481183.0859149,14.859985828399658,0.0,1740481183.0859172,14.859985828399658,0.0,1740481183.085919,14.859985828399658,10.92561285128479,1740481183.08592,14.859985828399658,0.0,1740481183.0859213,14.859985828399658,0.0,1740481183.085922,14.859985828399658,0.0,1740481183.0859234,14.859985828399658,0.0,1740481183.0859241,14.859985828399658,0.9931829458542611,1740481183.085925,14.859985828399658,0.06817054145734969,1740481183.0859258,14.859985828399658,0.10221704590112879,1740481183.085927,14.859985828399658,0.0,1740481183.0859277,14.859985828399658,0.959136441410482,, -1740481183.103705,14.879985809326172,7.0073399684638265,1740481183.1037066,14.879985809326172,0.0,1740481183.1037087,14.879985809326172,0.0,1740481183.1037107,14.879985809326172,10.92561285128479,1740481183.1037118,14.879985809326172,0.0,1740481183.1037128,14.879985809326172,0.0,1740481183.1037138,14.879985809326172,0.0,1740481183.1037147,14.879985809326172,0.0,1740481183.103716,14.879985809326172,0.9931829458542611,1740481183.1037166,14.879985809326172,0.06817054145734969,1740481183.1037173,14.879985809326172,0.10221704590112879,1740481183.1037188,14.879985809326172,0.0,1740481183.1037197,14.879985809326172,0.959136441410482,, -1740481183.1260521,14.899985790252686,7.0073399684638265,1740481183.1260543,14.899985790252686,0.0,1740481183.1260567,14.899985790252686,0.0,1740481183.1260588,14.899985790252686,10.92561285128479,1740481183.1260598,14.899985790252686,0.0,1740481183.126061,14.899985790252686,0.0,1740481183.126062,14.899985790252686,0.0,1740481183.126063,14.899985790252686,0.0,1740481183.126064,14.899985790252686,0.9931829458542611,1740481183.1260648,14.899985790252686,0.06817054145734969,1740481183.126066,14.899985790252686,0.10221704590112879,1740481183.1260667,14.899985790252686,0.0,1740481183.1260679,14.899985790252686,0.959136441410482,, -1740481183.144791,14.9199857711792,7.0073399684638265,1740481183.144793,14.9199857711792,0.0,1740481183.1447957,14.9199857711792,0.0,1740481183.1447978,14.9199857711792,10.92561285128479,1740481183.1447985,14.9199857711792,0.0,1740481183.1448,14.9199857711792,0.0,1740481183.1448011,14.9199857711792,0.0,1740481183.144802,14.9199857711792,0.0,1740481183.144803,14.9199857711792,0.9931829458542611,1740481183.144804,14.9199857711792,0.06817054145734969,1740481183.1448052,14.9199857711792,0.10221704590112879,1740481183.1448061,14.9199857711792,0.0,1740481183.1448069,14.9199857711792,0.959136441410482,, -1740481183.1660097,14.939985752105713,7.112961637532111,1740481183.1660113,14.939985752105713,0.0,1740481183.1660135,14.939985752105713,0.0,1740481183.1660154,14.939985752105713,11.038374303356237,1740481183.1660166,14.939985752105713,0.0,1740481183.1660178,14.939985752105713,0.0,1740481183.1660187,14.939985752105713,0.0,1740481183.1660197,14.939985752105713,0.0,1740481183.1660206,14.939985752105713,0.9943220109046655,1740481183.1660213,14.939985752105713,0.05677989095330571,1740481183.1660223,14.939985752105713,0.08729064677800075,1740481183.1660235,14.939985752105713,0.0,1740481183.1660242,14.939985752105713,0.9627063329120633,, -1740481183.1837943,14.959985733032227,7.112961637532111,1740481183.1837976,14.959985733032227,0.0,1740481183.1838005,14.959985733032227,0.0,1740481183.1838033,14.959985733032227,11.038374303356237,1740481183.183805,14.959985733032227,0.0,1740481183.1838064,14.959985733032227,0.0,1740481183.183808,14.959985733032227,0.0,1740481183.18381,14.959985733032227,0.0,1740481183.183812,14.959985733032227,0.9943220109046655,1740481183.1838133,14.959985733032227,0.05677989095330571,1740481183.1838148,14.959985733032227,0.08839556894590794,1740481183.1838162,14.959985733032227,0.0,1740481183.1838174,14.959985733032227,0.9627063329120633,, -1740481183.2040248,14.97998571395874,7.112961637532111,1740481183.2040272,14.97998571395874,0.0,1740481183.2040293,14.97998571395874,0.0,1740481183.2040315,14.97998571395874,11.038374303356237,1740481183.2040324,14.97998571395874,0.0,1740481183.2040336,14.97998571395874,0.0,1740481183.2040348,14.97998571395874,0.0,1740481183.2040355,14.97998571395874,0.0,1740481183.204037,14.97998571395874,0.9943220109046655,1740481183.204038,14.97998571395874,0.05677989095330571,1740481183.2040389,14.97998571395874,0.08839556894590794,1740481183.20404,14.97998571395874,0.0,1740481183.204041,14.97998571395874,0.9627063329120633,, -1740481183.224252,14.999985694885254,7.112961637532111,1740481183.224254,14.999985694885254,0.0,1740481183.224256,14.999985694885254,0.0,1740481183.2242584,14.999985694885254,11.038374303356237,1740481183.2242594,14.999985694885254,0.0,1740481183.2242603,14.999985694885254,0.0,1740481183.2242613,14.999985694885254,0.0,1740481183.2242625,14.999985694885254,0.0,1740481183.2242634,14.999985694885254,0.9943220109046655,1740481183.2242644,14.999985694885254,0.05677989095330571,1740481183.2242656,14.999985694885254,0.08839556894590794,1740481183.2242668,14.999985694885254,0.0,1740481183.2242675,14.999985694885254,0.9627063329120633,, -1740481183.2444644,15.019985675811768,7.112961637532111,1740481183.244467,15.019985675811768,0.0,1740481183.2444701,15.019985675811768,0.0,1740481183.244472,15.019985675811768,11.038374303356237,1740481183.2444735,15.019985675811768,0.0,1740481183.2444754,15.019985675811768,0.0,1740481183.2444777,15.019985675811768,0.0,1740481183.2444794,15.019985675811768,0.0,1740481183.244481,15.019985675811768,0.9943220109046655,1740481183.2444825,15.019985675811768,0.05677989095330571,1740481183.244484,15.019985675811768,0.08839556894590794,1740481183.2444856,15.019985675811768,0.0,1740481183.2445004,15.019985675811768,0.9627063329120633,, -1740481183.2671514,15.039985656738281,7.112961637532111,1740481183.2671533,15.039985656738281,0.0,1740481183.2671552,15.039985656738281,0.0,1740481183.2671573,15.039985656738281,11.038374303356237,1740481183.267158,15.039985656738281,0.0,1740481183.2671592,15.039985656738281,0.0,1740481183.2671604,15.039985656738281,0.0,1740481183.2671614,15.039985656738281,0.0,1740481183.267162,15.039985656738281,0.9943220109046655,1740481183.2671628,15.039985656738281,0.05677989095330571,1740481183.267164,15.039985656738281,0.08839556894590794,1740481183.2671647,15.039985656738281,0.0,1740481183.2671657,15.039985656738281,0.9627063329120633,, -1740481183.2842221,15.059985637664795,7.219027344451137,1740481183.2842238,15.059985637664795,0.0,1740481183.2842257,15.059985637664795,0.017222112042309667,1740481183.2842278,15.059985637664795,11.062347228327912,1740481183.2842288,15.059985637664795,0.0,1740481183.28423,15.059985637664795,0.0,1740481183.284231,15.059985637664795,0.0,1740481183.2842317,15.059985637664795,0.0,1740481183.2842326,15.059985637664795,0.9999999999999961,1740481183.2842338,15.059985637664795,9.43689570931383e-14,1740481183.2842345,15.059985637664795,0.03496489008996554,1740481183.2842352,15.059985637664795,0.0,1740481183.284236,15.059985637664795,0.9660817393767452,, -1740481183.303911,15.079985618591309,7.219027344451137,1740481183.303913,15.079985618591309,0.0,1740481183.3039153,15.079985618591309,0.017222112042309667,1740481183.3039172,15.079985618591309,11.062347228327912,1740481183.3039186,15.079985618591309,0.0,1740481183.30392,15.079985618591309,0.0,1740481183.3039212,15.079985618591309,0.0,1740481183.3039222,15.079985618591309,0.0,1740481183.303923,15.079985618591309,0.9999999999999961,1740481183.303924,15.079985618591309,9.43689570931383e-14,1740481183.303925,15.079985618591309,0.03391826062334524,1740481183.3039262,15.079985618591309,0.0,1740481183.3039277,15.079985618591309,0.9660817393767452,, -1740481183.323864,15.099985599517822,7.219027344451137,1740481183.3238657,15.099985599517822,0.0,1740481183.3238816,15.099985599517822,0.017222112042309667,1740481183.3238845,15.099985599517822,11.062347228327912,1740481183.3238857,15.099985599517822,0.0,1740481183.3238869,15.099985599517822,0.0,1740481183.3238878,15.099985599517822,0.0,1740481183.3238885,15.099985599517822,0.0,1740481183.3238897,15.099985599517822,0.9999999999999961,1740481183.3238907,15.099985599517822,9.43689570931383e-14,1740481183.3238914,15.099985599517822,0.03391826062334524,1740481183.3238926,15.099985599517822,0.0,1740481183.3238935,15.099985599517822,0.9660817393767452,, -1740481183.343732,15.119985580444336,7.219027344451137,1740481183.343734,15.119985580444336,0.0,1740481183.3437362,15.119985580444336,0.017222112042309667,1740481183.3437386,15.119985580444336,11.062347228327912,1740481183.3437397,15.119985580444336,0.0,1740481183.343741,15.119985580444336,0.0,1740481183.343742,15.119985580444336,0.0,1740481183.3437426,15.119985580444336,0.0,1740481183.3437438,15.119985580444336,0.9999999999999961,1740481183.3437445,15.119985580444336,9.43689570931383e-14,1740481183.3437455,15.119985580444336,0.03391826062334524,1740481183.3437467,15.119985580444336,0.0,1740481183.3437479,15.119985580444336,0.9660817393767452,, -1740481183.3664496,15.13998556137085,7.219027344451137,1740481183.3664513,15.13998556137085,0.0,1740481183.3664534,15.13998556137085,0.0,1740481183.3664556,15.13998556137085,11.151190823204626,1740481183.3664565,15.13998556137085,0.0,1740481183.3664577,15.13998556137085,0.0,1740481183.3664587,15.13998556137085,0.0,1740481183.3664596,15.13998556137085,0.0,1740481183.3664603,15.13998556137085,0.9953033140591997,1740481183.3664615,15.13998556137085,0.0,1740481183.3664622,15.13998556137085,0.029221574682454454,1740481183.3664632,15.13998556137085,0.0,1740481183.3664641,15.13998556137085,0.9660817393767452,, -1740481183.3851955,15.159985542297363,7.3252217650253755,1740481183.3851998,15.159985542297363,0.0,1740481183.3852031,15.159985542297363,0.01726002879473863,1740481183.385206,15.159985542297363,11.164186560159598,1740481183.385207,15.159985542297363,0.0,1740481183.3852086,15.159985542297363,0.0,1740481183.3852096,15.159985542297363,0.0,1740481183.3852112,15.159985542297363,0.0,1740481183.3852131,15.159985542297363,0.9953033140591997,1740481183.385215,15.159985542297363,0.04696685940796419,1740481183.385216,15.159985542297363,0.07928973817087477,1740481183.385217,15.159985542297363,0.0,1740481183.3852184,15.159985542297363,0.9639495934568613,, -1740481183.4039547,15.179985523223877,7.3252217650253755,1740481183.4039564,15.179985523223877,0.0,1740481183.4039586,15.179985523223877,0.01726002879473863,1740481183.4039605,15.179985523223877,11.164186560159598,1740481183.4039614,15.179985523223877,0.0,1740481183.4039626,15.179985523223877,0.0,1740481183.4039636,15.179985523223877,0.0,1740481183.4039648,15.179985523223877,0.0,1740481183.4039655,15.179985523223877,0.9953033140591997,1740481183.4039664,15.179985523223877,0.04696685940796419,1740481183.4039674,15.179985523223877,0.07832058001030262,1740481183.4039686,15.179985523223877,0.0,1740481183.4039695,15.179985523223877,0.9639495934568613,, -1740481183.4251766,15.19998550415039,7.3252217650253755,1740481183.4251788,15.19998550415039,0.0,1740481183.4251816,15.19998550415039,0.01726002879473863,1740481183.4251842,15.19998550415039,11.164186560159598,1740481183.4251857,15.19998550415039,0.0,1740481183.4251876,15.19998550415039,0.0,1740481183.4251888,15.19998550415039,0.0,1740481183.4251902,15.19998550415039,0.0,1740481183.4251912,15.19998550415039,0.9953033140591997,1740481183.4251924,15.19998550415039,0.04696685940796419,1740481183.4251935,15.19998550415039,0.07832058001030262,1740481183.4251945,15.19998550415039,0.0,1740481183.4251957,15.19998550415039,0.9639495934568613,, -1740481183.443668,15.219985485076904,7.3252217650253755,1740481183.4436698,15.219985485076904,0.0,1740481183.4436717,15.219985485076904,0.01726002879473863,1740481183.443674,15.219985485076904,11.164186560159598,1740481183.443675,15.219985485076904,0.0,1740481183.4436765,15.219985485076904,0.0,1740481183.4436774,15.219985485076904,0.0,1740481183.4436786,15.219985485076904,0.0,1740481183.4436796,15.219985485076904,0.9953033140591997,1740481183.4436805,15.219985485076904,0.04696685940796419,1740481183.4436812,15.219985485076904,0.07832058001030262,1740481183.4436827,15.219985485076904,0.0,1740481183.4436839,15.219985485076904,0.9639495934568613,, -1740481183.4677296,15.239985466003418,7.3252217650253755,1740481183.4677327,15.239985466003418,0.0,1740481183.467736,15.239985466003418,0.0,1740481183.4677384,15.239985466003418,11.2531209519391,1740481183.467739,15.239985466003418,0.0,1740481183.4677403,15.239985466003418,0.0,1740481183.4677415,15.239985466003418,0.0,1740481183.4677424,15.239985466003418,0.0,1740481183.4677434,15.239985466003418,0.9946942753454907,1740481183.4677444,15.239985466003418,0.0,1740481183.467745,15.239985466003418,0.030744681888629444,1740481183.4677458,15.239985466003418,0.0,1740481183.4677567,15.239985466003418,0.9639495934568613,, -1740481183.48371,15.259985446929932,7.3252217650253755,1740481183.4837117,15.259985446929932,0.0,1740481183.483714,15.259985446929932,0.0,1740481183.4837158,15.259985446929932,11.2531209519391,1740481183.483717,15.259985446929932,0.0,1740481183.4837182,15.259985446929932,0.0,1740481183.4837189,15.259985446929932,0.0,1740481183.4837203,15.259985446929932,0.0,1740481183.483721,15.259985446929932,0.9946942753454907,1740481183.483722,15.259985446929932,0.0,1740481183.483723,15.259985446929932,0.030744681888629444,1740481183.483724,15.259985446929932,0.0,1740481183.483725,15.259985446929932,0.9639495934568613,, -1740481183.5039093,15.279985427856445,7.431358120093588,1740481183.5039115,15.279985427856445,0.0,1740481183.5039134,15.279985427856445,0.017240035416099683,1740481183.5039158,15.279985427856445,11.27211392295522,1740481183.5039167,15.279985427856445,0.0,1740481183.5039182,15.279985427856445,0.0,1740481183.503919,15.279985427856445,0.0,1740481183.5039198,15.279985427856445,0.0,1740481183.5039208,15.279985427856445,0.9946942753454907,1740481183.503922,15.279985427856445,0.05305724654505406,1740481183.5039227,15.279985427856445,0.08252706579918241,1740481183.5039237,15.279985427856445,0.0,1740481183.5039248,15.279985427856445,0.9648260612568728,, -1740481183.5236702,15.299985408782959,7.431358120093588,1740481183.5236723,15.299985408782959,0.0,1740481183.5236742,15.299985408782959,0.017240035416099683,1740481183.5236764,15.299985408782959,11.27211392295522,1740481183.5236773,15.299985408782959,0.0,1740481183.5236788,15.299985408782959,0.0,1740481183.5236795,15.299985408782959,0.0,1740481183.523681,15.299985408782959,0.0,1740481183.523682,15.299985408782959,0.9946942753454907,1740481183.5236828,15.299985408782959,0.05305724654505406,1740481183.5236838,15.299985408782959,0.08292546063367201,1740481183.5236845,15.299985408782959,0.0,1740481183.5236857,15.299985408782959,0.9648260612568728,, -1740481183.544224,15.319985389709473,7.431358120093588,1740481183.544226,15.319985389709473,0.0,1740481183.5442283,15.319985389709473,0.017240035416099683,1740481183.5442305,15.319985389709473,11.27211392295522,1740481183.5442317,15.319985389709473,0.0,1740481183.5442328,15.319985389709473,0.0,1740481183.544234,15.319985389709473,0.0,1740481183.544235,15.319985389709473,0.0,1740481183.544236,15.319985389709473,0.9946942753454907,1740481183.5442371,15.319985389709473,0.05305724654505406,1740481183.5442379,15.319985389709473,0.08292546063367201,1740481183.5442388,15.319985389709473,0.0,1740481183.5442398,15.319985389709473,0.9648260612568728,, -1740481183.5662422,15.339985370635986,7.431358120093588,1740481183.566244,15.339985370635986,0.0,1740481183.5662458,15.339985370635986,0.0,1740481183.566248,15.339985370635986,11.361010242607334,1740481183.566249,15.339985370635986,0.0,1740481183.5662503,15.339985370635986,0.0,1740481183.566251,15.339985370635986,0.0,1740481183.566252,15.339985370635986,0.0,1740481183.566253,15.339985370635986,0.994949127791408,1740481183.566254,15.339985370635986,0.0,1740481183.5662549,15.339985370635986,0.030123066534535226,1740481183.5662556,15.339985370635986,0.0,1740481183.566257,15.339985370635986,0.9648260612568728,, -1740481183.5838606,15.3599853515625,7.431358120093588,1740481183.5838625,15.3599853515625,0.0,1740481183.5838652,15.3599853515625,0.0,1740481183.583867,15.3599853515625,11.361010242607334,1740481183.5838683,15.3599853515625,0.0,1740481183.5838692,15.3599853515625,0.0,1740481183.5838702,15.3599853515625,0.0,1740481183.5838711,15.3599853515625,0.0,1740481183.5838723,15.3599853515625,0.994949127791408,1740481183.583873,15.3599853515625,0.0,1740481183.583874,15.3599853515625,0.030123066534535226,1740481183.5838747,15.3599853515625,0.0,1740481183.583876,15.3599853515625,0.9648260612568728,, -1740481183.6041532,15.379985332489014,7.537543900360738,1740481183.604156,15.379985332489014,0.0,1740481183.6041586,15.379985332489014,0.017252482852303692,1740481183.6041613,15.379985332489014,11.378553929065106,1740481183.6041625,15.379985332489014,0.0,1740481183.6041644,15.379985332489014,0.0,1740481183.6041656,15.379985332489014,0.0,1740481183.604167,15.379985332489014,0.0,1740481183.6041682,15.379985332489014,0.994949127791408,1740481183.6041694,15.379985332489014,0.050508722085969016,1740481183.6041706,15.379985332489014,0.08042000411704675,1740481183.6041718,15.379985332489014,0.0,1740481183.6041727,15.379985332489014,0.964971663059607,, -1740481183.6241055,15.399985313415527,7.537543900360738,1740481183.6241074,15.399985313415527,0.0,1740481183.6241093,15.399985313415527,0.017252482852303692,1740481183.6241114,15.399985313415527,11.378553929065106,1740481183.6241124,15.399985313415527,0.0,1740481183.6241133,15.399985313415527,0.0,1740481183.6241145,15.399985313415527,0.0,1740481183.6241155,15.399985313415527,0.0,1740481183.6241164,15.399985313415527,0.994949127791408,1740481183.6241176,15.399985313415527,0.050508722085969016,1740481183.6241186,15.399985313415527,0.08048618681776998,1740481183.6241193,15.399985313415527,0.0,1740481183.6241202,15.399985313415527,0.964971663059607,, -1740481183.6436422,15.419985294342041,7.537543900360738,1740481183.6436436,15.419985294342041,0.0,1740481183.6436465,15.419985294342041,0.017252482852303692,1740481183.6436489,15.419985294342041,11.378553929065106,1740481183.6436498,15.419985294342041,0.0,1740481183.643651,15.419985294342041,0.0,1740481183.6436522,15.419985294342041,0.0,1740481183.6436532,15.419985294342041,0.0,1740481183.643654,15.419985294342041,0.994949127791408,1740481183.643655,15.419985294342041,0.050508722085969016,1740481183.643656,15.419985294342041,0.08048618681776998,1740481183.643657,15.419985294342041,0.0,1740481183.6436577,15.419985294342041,0.964971663059607,, -1740481183.6681788,15.439985275268555,7.537543900360738,1740481183.668181,15.439985275268555,0.0,1740481183.6681833,15.439985275268555,0.0,1740481183.6681857,15.439985275268555,11.467487226479953,1740481183.6681864,15.439985275268555,0.0,1740481183.6681876,15.439985275268555,0.0,1740481183.6681886,15.439985275268555,0.0,1740481183.6681898,15.439985275268555,0.0,1740481183.6681907,15.439985275268555,0.9949908572084273,1740481183.6681914,15.439985275268555,0.0,1740481183.6681921,15.439985275268555,0.03001919414882026,1740481183.6681933,15.439985275268555,0.0,1740481183.668194,15.439985275268555,0.964971663059607,, -1740481183.6838841,15.459985256195068,7.537543900360738,1740481183.6838858,15.459985256195068,0.0,1740481183.683889,15.459985256195068,0.0,1740481183.683891,15.459985256195068,11.467487226479953,1740481183.683892,15.459985256195068,0.0,1740481183.6838934,15.459985256195068,0.0,1740481183.6838949,15.459985256195068,0.0,1740481183.6838958,15.459985256195068,0.0,1740481183.6838968,15.459985256195068,0.9949908572084273,1740481183.683898,15.459985256195068,0.0,1740481183.683899,15.459985256195068,0.03001919414882026,1740481183.6838996,15.459985256195068,0.0,1740481183.6839006,15.459985256195068,0.964971663059607,, -1740481183.7038958,15.479985237121582,7.537543900360738,1740481183.7038972,15.479985237121582,0.0,1740481183.7038996,15.479985237121582,0.0,1740481183.7039015,15.479985237121582,11.467487226479953,1740481183.7039025,15.479985237121582,0.0,1740481183.703904,15.479985237121582,0.0,1740481183.703905,15.479985237121582,0.0,1740481183.703906,15.479985237121582,0.0,1740481183.703907,15.479985237121582,0.9949908572084273,1740481183.7039082,15.479985237121582,0.0,1740481183.703909,15.479985237121582,0.03001919414882026,1740481183.7039099,15.479985237121582,0.0,1740481183.7039108,15.479985237121582,0.964971663059607,, -1740481183.7238822,15.499985218048096,7.64376605653184,1740481183.7238843,15.499985218048096,0.0,1740481183.7238863,15.499985218048096,0.017259116848250013,1740481183.7238882,15.499985218048096,11.484730260692226,1740481183.723889,15.499985218048096,0.0,1740481183.72389,15.499985218048096,0.0,1740481183.7238915,15.499985218048096,0.0,1740481183.7238927,15.499985218048096,0.0,1740481183.7238941,15.499985218048096,0.9949908572084273,1740481183.7238948,15.499985218048096,0.050091427915688325,1740481183.7238955,15.499985218048096,0.08012231853052279,1740481183.7238965,15.499985218048096,0.0,1740481183.7238977,15.499985218048096,0.9649636217416188,, -1740481183.7440896,15.51998519897461,7.64376605653184,1740481183.7440917,15.51998519897461,0.0,1740481183.744094,15.51998519897461,0.017259116848250013,1740481183.7440958,15.51998519897461,11.484730260692226,1740481183.744097,15.51998519897461,0.0,1740481183.744098,15.51998519897461,0.0,1740481183.7440991,15.51998519897461,0.0,1740481183.7441,15.51998519897461,0.0,1740481183.7441008,15.51998519897461,0.9949908572084273,1740481183.7441015,15.51998519897461,0.050091427915688325,1740481183.7441027,15.51998519897461,0.08011866338249685,1740481183.7441037,15.51998519897461,0.0,1740481183.7441049,15.51998519897461,0.9649636217416188,, -1740481183.7652707,15.539985179901123,7.64376605653184,1740481183.7652726,15.539985179901123,0.0,1740481183.7652745,15.539985179901123,0.0,1740481183.7652767,15.539985179901123,11.573693300015076,1740481183.7652774,15.539985179901123,0.0,1740481183.7652788,15.539985179901123,0.0,1740481183.7652795,15.539985179901123,0.0,1740481183.7652805,15.539985179901123,0.0,1740481183.7652812,15.539985179901123,0.9949885570858942,1740481183.7652824,15.539985179901123,0.0,1740481183.765283,15.539985179901123,0.030024935344275416,1740481183.7652838,15.539985179901123,0.0,1740481183.7652848,15.539985179901123,0.9649636217416188,, -1740481183.7839804,15.559985160827637,7.64376605653184,1740481183.783982,15.559985160827637,0.0,1740481183.7839842,15.559985160827637,0.0,1740481183.783986,15.559985160827637,11.573693300015076,1740481183.7839873,15.559985160827637,0.0,1740481183.7839885,15.559985160827637,0.0,1740481183.7839894,15.559985160827637,0.0,1740481183.7839909,15.559985160827637,0.0,1740481183.7839918,15.559985160827637,0.9949885570858942,1740481183.7839925,15.559985160827637,0.0,1740481183.7839935,15.559985160827637,0.030024935344275416,1740481183.7839947,15.559985160827637,0.0,1740481183.7839954,15.559985160827637,0.9649636217416188,, -1740481183.8054621,15.57998514175415,7.64376605653184,1740481183.8054638,15.57998514175415,0.0,1740481183.8054664,15.57998514175415,0.0,1740481183.8054686,15.57998514175415,11.573693300015076,1740481183.8054698,15.57998514175415,0.0,1740481183.8054707,15.57998514175415,0.0,1740481183.8054717,15.57998514175415,0.0,1740481183.805473,15.57998514175415,0.0,1740481183.805474,15.57998514175415,0.9949885570858942,1740481183.805475,15.57998514175415,0.0,1740481183.8054762,15.57998514175415,0.030024935344275416,1740481183.8054771,15.57998514175415,0.0,1740481183.805478,15.57998514175415,0.9649636217416188,, -1740481183.8236613,15.599985122680664,7.749910862942164,1740481183.8236628,15.599985122680664,0.0,1740481183.8236802,15.599985122680664,0.017246509087622378,1740481183.8236835,15.599985122680664,11.588889849006218,1740481183.8236847,15.599985122680664,0.0,1740481183.823686,15.599985122680664,0.0,1740481183.823687,15.599985122680664,0.0,1740481183.8236883,15.599985122680664,0.0,1740481183.823689,15.599985122680664,0.9949885570858942,1740481183.8236897,15.599985122680664,0.050114429141107086,1740481183.823691,15.599985122680664,0.08163024499986875,1740481183.823692,15.599985122680664,0.0,1740481183.823693,15.599985122680664,0.9639386416933776,, -1740481183.8457994,15.619985103607178,7.749910862942164,1740481183.8458538,15.619985103607178,0.0,1740481183.8458583,15.619985103607178,0.017246509087622378,1740481183.8458838,15.619985103607178,11.588889849006218,1740481183.845885,15.619985103607178,0.0,1740481183.8458865,15.619985103607178,0.0,1740481183.8458874,15.619985103607178,0.0,1740481183.8458889,15.619985103607178,0.0,1740481183.8458898,15.619985103607178,0.9949885570858942,1740481183.8458908,15.619985103607178,0.050114429141107086,1740481183.8458915,15.619985103607178,0.08116434453362364,1740481183.8458927,15.619985103607178,0.0,1740481183.8458936,15.619985103607178,0.9639386416933776,, -1740481183.86856,15.639985084533691,7.749910862942164,1740481183.868562,15.639985084533691,0.0,1740481183.8685641,15.639985084533691,0.0,1740481183.8685665,15.639985084533691,11.677788146328918,1740481183.8685675,15.639985084533691,0.0,1740481183.8685687,15.639985084533691,0.0,1740481183.8685696,15.639985084533691,0.0,1740481183.8685706,15.639985084533691,0.0,1740481183.8685718,15.639985084533691,0.994691051200559,1740481183.8685725,15.639985084533691,0.0,1740481183.8685734,15.639985084533691,0.03075240950718139,1740481183.8685741,15.639985084533691,0.0,1740481183.8685753,15.639985084533691,0.9639386416933776,, -1740481183.8839326,15.659985065460205,7.749910862942164,1740481183.8839343,15.659985065460205,0.0,1740481183.8839364,15.659985065460205,0.0,1740481183.8839386,15.659985065460205,11.677788146328918,1740481183.8839397,15.659985065460205,0.0,1740481183.883941,15.659985065460205,0.0,1740481183.883942,15.659985065460205,0.0,1740481183.8839426,15.659985065460205,0.0,1740481183.8839438,15.659985065460205,0.994691051200559,1740481183.8839447,15.659985065460205,0.0,1740481183.8839457,15.659985065460205,0.03075240950718139,1740481183.8839464,15.659985065460205,0.0,1740481183.8839476,15.659985065460205,0.9639386416933776,, -1740481183.903542,15.679985046386719,7.749910862942164,1740481183.9035444,15.679985046386719,0.0,1740481183.9035468,15.679985046386719,0.0,1740481183.9035509,15.679985046386719,11.677788146328918,1740481183.9035552,15.679985046386719,0.0,1740481183.9035618,15.679985046386719,0.0,1740481183.9035635,15.679985046386719,0.0,1740481183.9035654,15.679985046386719,0.0,1740481183.9035687,15.679985046386719,0.994691051200559,1740481183.903572,15.679985046386719,0.0,1740481183.9035735,15.679985046386719,0.03075240950718139,1740481183.903576,15.679985046386719,0.0,1740481183.9035773,15.679985046386719,0.9639386416933776,, -1740481183.9236648,15.699985027313232,7.749910862942164,1740481183.9236667,15.699985027313232,0.0,1740481183.9236686,15.699985027313232,0.0,1740481183.9236708,15.699985027313232,11.677788146328918,1740481183.9236717,15.699985027313232,0.0,1740481183.9236732,15.699985027313232,0.0,1740481183.923674,15.699985027313232,0.0,1740481183.923675,15.699985027313232,0.0,1740481183.923676,15.699985027313232,0.994691051200559,1740481183.923677,15.699985027313232,0.0,1740481183.923678,15.699985027313232,0.03075240950718139,1740481183.9236786,15.699985027313232,0.0,1740481183.9236798,15.699985027313232,0.9639386416933776,, -1740481183.9438567,15.719985008239746,7.855969198936354,1740481183.9438581,15.719985008239746,0.0,1740481183.9438605,15.719985008239746,0.01722730671225854,1740481183.9438622,15.719985008239746,11.693181581576459,1740481183.9438634,15.719985008239746,0.0,1740481183.9438646,15.719985008239746,0.0,1740481183.9438655,15.719985008239746,0.0,1740481183.9438663,15.719985008239746,0.0,1740481183.9438674,15.719985008239746,0.994691051200559,1740481183.9438682,15.719985008239746,0.053089487994458784,1740481183.943869,15.719985008239746,0.08517562260073468,1740481183.9438703,15.719985008239746,0.0,1740481183.9438713,15.719985008239746,0.9630217059610185,, -1740481183.9669354,15.73998498916626,7.855969198936354,1740481183.9669397,15.73998498916626,0.0,1740481183.966945,15.73998498916626,0.0,1740481183.9669487,15.73998498916626,11.782012610858391,1740481183.9669516,15.73998498916626,0.0,1740481183.966954,15.73998498916626,0.0,1740481183.9669554,15.73998498916626,0.0,1740481183.966957,15.73998498916626,0.0,1740481183.9669597,15.73998498916626,0.994417636431985,1740481183.966962,15.73998498916626,0.0,1740481183.9669635,15.73998498916626,0.03139593047096645,1740481183.9669664,15.73998498916626,0.0,1740481183.966969,15.73998498916626,0.9630217059610185,, -1740481183.9838066,15.759984970092773,7.855969198936354,1740481183.9838083,15.759984970092773,0.0,1740481183.9838107,15.759984970092773,0.0,1740481183.9838123,15.759984970092773,11.782012610858391,1740481183.9838133,15.759984970092773,0.0,1740481183.983815,15.759984970092773,0.0,1740481183.983816,15.759984970092773,0.0,1740481183.9838169,15.759984970092773,0.0,1740481183.9838178,15.759984970092773,0.994417636431985,1740481183.9838185,15.759984970092773,0.0,1740481183.9838195,15.759984970092773,0.03139593047096645,1740481183.9838204,15.759984970092773,0.0,1740481183.9838216,15.759984970092773,0.9630217059610185,, -1740481184.003502,15.779984951019287,7.855969198936354,1740481184.0035033,15.779984951019287,0.0,1740481184.0035057,15.779984951019287,0.0,1740481184.0035076,15.779984951019287,11.782012610858391,1740481184.0035088,15.779984951019287,0.0,1740481184.00351,15.779984951019287,0.0,1740481184.003511,15.779984951019287,0.0,1740481184.003512,15.779984951019287,0.0,1740481184.0035129,15.779984951019287,0.994417636431985,1740481184.0035136,15.779984951019287,0.0,1740481184.0035143,15.779984951019287,0.03139593047096645,1740481184.0035155,15.779984951019287,0.0,1740481184.0035164,15.779984951019287,0.9630217059610185,, -1740481184.0234916,15.7999849319458,7.855969198936354,1740481184.0234933,15.7999849319458,0.0,1740481184.0234957,15.7999849319458,0.0,1740481184.0234978,15.7999849319458,11.782012610858391,1740481184.0234988,15.7999849319458,0.0,1740481184.0235,15.7999849319458,0.0,1740481184.0235012,15.7999849319458,0.0,1740481184.023502,15.7999849319458,0.0,1740481184.0235028,15.7999849319458,0.994417636431985,1740481184.0235038,15.7999849319458,0.0,1740481184.023505,15.7999849319458,0.03139593047096645,1740481184.0235057,15.7999849319458,0.0,1740481184.0235066,15.7999849319458,0.9630217059610185,, -1740481184.043809,15.819984912872314,7.96184926861933,1740481184.043811,15.819984912872314,0.0,1740481184.0438135,15.819984912872314,0.01719362311266791,1740481184.0438151,15.819984912872314,11.795625359331584,1740481184.043816,15.819984912872314,0.0,1740481184.0438175,15.819984912872314,0.0,1740481184.0438187,15.819984912872314,0.0,1740481184.0438194,15.819984912872314,0.0,1740481184.0438206,15.819984912872314,0.994417636431985,1740481184.0438218,15.819984912872314,0.05582363568011117,1740481184.0438225,15.819984912872314,0.08982383939228443,1740481184.043824,15.819984912872314,0.0,1740481184.043825,15.819984912872314,0.9612312686412813,, -1740481184.06916,15.839984893798828,7.96184926861933,1740481184.0691617,15.839984893798828,0.0,1740481184.069164,15.839984893798828,0.0,1740481184.0691662,15.839984893798828,11.884311805901893,1740481184.0691671,15.839984893798828,0.0,1740481184.0691683,15.839984893798828,0.0,1740481184.0691695,15.839984893798828,0.0,1740481184.0691702,15.839984893798828,0.0,1740481184.0691712,15.839984893798828,0.9938639688710971,1740481184.069172,15.839984893798828,0.0,1740481184.0691726,15.839984893798828,0.03263270022981579,1740481184.0691738,15.839984893798828,0.0,1740481184.0691748,15.839984893798828,0.9612312686412813,, -1740481184.0839884,15.859984874725342,7.96184926861933,1740481184.0839903,15.859984874725342,0.0,1740481184.0839922,15.859984874725342,0.0,1740481184.0839946,15.859984874725342,11.884311805901893,1740481184.0839956,15.859984874725342,0.0,1740481184.083997,15.859984874725342,0.0,1740481184.083998,15.859984874725342,0.0,1740481184.0839987,15.859984874725342,0.0,1740481184.0839996,15.859984874725342,0.9938639688710971,1740481184.0840008,15.859984874725342,0.0,1740481184.0840015,15.859984874725342,0.03263270022981579,1740481184.0840025,15.859984874725342,0.0,1740481184.0840032,15.859984874725342,0.9612312686412813,, -1740481184.1037815,15.879984855651855,7.96184926861933,1740481184.1037831,15.879984855651855,0.0,1740481184.1037855,15.879984855651855,0.0,1740481184.1037874,15.879984855651855,11.884311805901893,1740481184.1037889,15.879984855651855,0.0,1740481184.10379,15.879984855651855,0.0,1740481184.1037908,15.879984855651855,0.0,1740481184.1037922,15.879984855651855,0.0,1740481184.103793,15.879984855651855,0.9938639688710971,1740481184.1037939,15.879984855651855,0.0,1740481184.103795,15.879984855651855,0.03263270022981579,1740481184.103796,15.879984855651855,0.0,1740481184.103797,15.879984855651855,0.9612312686412813,, -1740481184.1240425,15.89998483657837,7.96184926861933,1740481184.1240451,15.89998483657837,0.0,1740481184.1240473,15.89998483657837,0.0,1740481184.1240497,15.89998483657837,11.884311805901893,1740481184.1240509,15.89998483657837,0.0,1740481184.1240525,15.89998483657837,0.0,1740481184.1240537,15.89998483657837,0.0,1740481184.1240547,15.89998483657837,0.0,1740481184.1240563,15.89998483657837,0.9938639688710971,1740481184.1240573,15.89998483657837,0.0,1740481184.1240587,15.89998483657837,0.03263270022981579,1740481184.1240597,15.89998483657837,0.0,1740481184.1240606,15.89998483657837,0.9612312686412813,, -1740481184.1436696,15.919984817504883,7.96184926861933,1740481184.1436713,15.919984817504883,0.0,1740481184.143674,15.919984817504883,0.0,1740481184.1436758,15.919984817504883,11.884311805901893,1740481184.143677,15.919984817504883,0.0,1740481184.1436782,15.919984817504883,0.0,1740481184.1436794,15.919984817504883,0.0,1740481184.1436806,15.919984817504883,0.0,1740481184.1436818,15.919984817504883,0.9938639688710971,1740481184.1436827,15.919984817504883,0.0,1740481184.143684,15.919984817504883,0.03263270022981579,1740481184.1436849,15.919984817504883,0.0,1740481184.1436858,15.919984817504883,0.9612312686412813,, -1740481184.1654892,15.939984798431396,8.067603297929363,1740481184.165492,15.939984798431396,0.0,1740481184.1654944,15.939984798431396,0.0,1740481184.165508,15.939984798431396,11.988067655067846,1740481184.1655104,15.939984798431396,0.0,1740481184.165513,15.939984798431396,0.0,1740481184.1657388,15.939984798431396,0.0,1740481184.16574,15.939984798431396,0.0,1740481184.1657572,15.939984798431396,0.9935436364818048,1740481184.1657581,15.939984798431396,0.06456363518208996,1740481184.1657593,15.939984798431396,0.09818361960831774,1740481184.1657603,15.939984798431396,0.0,1740481184.1657612,15.939984798431396,0.9602321785692415,, -1740481184.18417,15.95998477935791,8.067603297929363,1740481184.184172,15.95998477935791,0.0,1740481184.1841745,15.95998477935791,0.0,1740481184.1841767,15.95998477935791,11.988067655067846,1740481184.1841779,15.95998477935791,0.0,1740481184.1841795,15.95998477935791,0.0,1740481184.1841807,15.95998477935791,0.0,1740481184.184182,15.95998477935791,0.0,1740481184.1841834,15.95998477935791,0.9935436364818048,1740481184.1841843,15.95998477935791,0.06456363518208996,1740481184.1841855,15.95998477935791,0.09787509309465325,1740481184.1841867,15.95998477935791,0.0,1740481184.1841877,15.95998477935791,0.9602321785692415,, -1740481184.2038589,15.979984760284424,8.067603297929363,1740481184.2038608,15.979984760284424,0.0,1740481184.2038631,15.979984760284424,0.0,1740481184.203865,15.979984760284424,11.988067655067846,1740481184.203866,15.979984760284424,0.0,1740481184.2038674,15.979984760284424,0.0,1740481184.2038686,15.979984760284424,0.0,1740481184.2038696,15.979984760284424,0.0,1740481184.2038705,15.979984760284424,0.9935436364818048,1740481184.2038717,15.979984760284424,0.06456363518208996,1740481184.2038727,15.979984760284424,0.09787509309465325,1740481184.2038739,15.979984760284424,0.0,1740481184.2038746,15.979984760284424,0.9602321785692415,, -1740481184.2254028,15.999984741210938,8.067603297929363,1740481184.2254055,15.999984741210938,0.0,1740481184.2254078,15.999984741210938,0.0,1740481184.2254097,15.999984741210938,11.988067655067846,1740481184.2254112,15.999984741210938,0.0,1740481184.2254124,15.999984741210938,0.0,1740481184.2254133,15.999984741210938,0.0,1740481184.2254145,15.999984741210938,0.0,1740481184.2254155,15.999984741210938,0.9935436364818048,1740481184.2254162,15.999984741210938,0.06456363518208996,1740481184.2254171,15.999984741210938,0.09787509309465325,1740481184.2254186,15.999984741210938,0.0,1740481184.2254195,15.999984741210938,0.9602321785692415,, -1740481184.2439463,16.01998472213745,8.067603297929363,1740481184.2439482,16.01998472213745,0.0,1740481184.2439666,16.01998472213745,0.0,1740481184.2439685,16.01998472213745,11.988067655067846,1740481184.2439697,16.01998472213745,0.0,1740481184.2439709,16.01998472213745,0.0,1740481184.2439718,16.01998472213745,0.0,1740481184.2439728,16.01998472213745,0.0,1740481184.243974,16.01998472213745,0.9935436364818048,1740481184.2439747,16.01998472213745,0.06456363518208996,1740481184.2439756,16.01998472213745,0.09787509309465325,1740481184.2439766,16.01998472213745,0.0,1740481184.2439778,16.01998472213745,0.9602321785692415,, -1740481184.270517,16.039984703063965,8.173387394235935,1740481184.270519,16.039984703063965,0.0,1740481184.2705214,16.039984703063965,0.0,1740481184.2705233,16.039984703063965,12.101478756791485,1740481184.2705245,16.039984703063965,0.0,1740481184.2705257,16.039984703063965,0.0,1740481184.2705266,16.039984703063965,0.0,1740481184.2705278,16.039984703063965,0.0,1740481184.2705288,16.039984703063965,0.9947225211349098,1740481184.2705297,16.039984703063965,0.05277478865086338,1740481184.2705307,16.039984703063965,0.08225407370436262,1740481184.270532,16.039984703063965,0.0,1740481184.2705326,16.039984703063965,0.9640456812777749,, -1740481184.2835634,16.05998468399048,8.173387394235935,1740481184.2835648,16.05998468399048,0.0,1740481184.283567,16.05998468399048,0.0,1740481184.2835689,16.05998468399048,12.101478756791485,1740481184.2835698,16.05998468399048,0.0,1740481184.2835712,16.05998468399048,0.0,1740481184.2835722,16.05998468399048,0.0,1740481184.283573,16.05998468399048,0.0,1740481184.283574,16.05998468399048,0.9947225211349098,1740481184.283575,16.05998468399048,0.05277478865086338,1740481184.2835758,16.05998468399048,0.08345162850799825,1740481184.2835765,16.05998468399048,0.0,1740481184.2835777,16.05998468399048,0.9640456812777749,, -1740481184.3039687,16.079984664916992,8.173387394235935,1740481184.3039706,16.079984664916992,0.0,1740481184.303973,16.079984664916992,0.0,1740481184.3039749,16.079984664916992,12.101478756791485,1740481184.3039758,16.079984664916992,0.0,1740481184.3039773,16.079984664916992,0.0,1740481184.3039782,16.079984664916992,0.0,1740481184.3039792,16.079984664916992,0.0,1740481184.30398,16.079984664916992,0.9947225211349098,1740481184.303981,16.079984664916992,0.05277478865086338,1740481184.303982,16.079984664916992,0.08345162850799825,1740481184.3039827,16.079984664916992,0.0,1740481184.303984,16.079984664916992,0.9640456812777749,, -1740481184.3236508,16.099984645843506,8.173387394235935,1740481184.3236525,16.099984645843506,0.0,1740481184.3236547,16.099984645843506,0.0,1740481184.323657,16.099984645843506,12.101478756791485,1740481184.3236578,16.099984645843506,0.0,1740481184.323659,16.099984645843506,0.0,1740481184.3236601,16.099984645843506,0.0,1740481184.3236609,16.099984645843506,0.0,1740481184.3236616,16.099984645843506,0.9947225211349098,1740481184.3236625,16.099984645843506,0.05277478865086338,1740481184.3236637,16.099984645843506,0.08345162850799825,1740481184.3236644,16.099984645843506,0.0,1740481184.3236654,16.099984645843506,0.9640456812777749,, -1740481184.343997,16.11998462677002,8.173387394235935,1740481184.3439987,16.11998462677002,0.0,1740481184.344001,16.11998462677002,0.0,1740481184.344003,16.11998462677002,12.101478756791485,1740481184.3440042,16.11998462677002,0.0,1740481184.3440053,16.11998462677002,0.0,1740481184.3440063,16.11998462677002,0.0,1740481184.3440075,16.11998462677002,0.0,1740481184.3440084,16.11998462677002,0.9947225211349098,1740481184.3440094,16.11998462677002,0.05277478865086338,1740481184.3440104,16.11998462677002,0.08345162850799825,1740481184.3440113,16.11998462677002,0.0,1740481184.344012,16.11998462677002,0.9640456812777749,, -1740481184.367072,16.139984607696533,8.173387394235935,1740481184.3670743,16.139984607696533,0.0,1740481184.3670766,16.139984607696533,0.0,1740481184.367133,16.139984607696533,12.101478756791485,1740481184.367134,16.139984607696533,0.0,1740481184.3671355,16.139984607696533,0.0,1740481184.3671365,16.139984607696533,0.0,1740481184.3671374,16.139984607696533,0.0,1740481184.3671386,16.139984607696533,0.9947225211349098,1740481184.3671398,16.139984607696533,0.05277478865086338,1740481184.3671618,16.139984607696533,0.08345162850799825,1740481184.367163,16.139984607696533,0.0,1740481184.367164,16.139984607696533,0.9640456812777749,, -1740481184.384567,16.159984588623047,8.279588181846634,1740481184.3845716,16.159984588623047,0.0,1740481184.3845763,16.159984588623047,0.017250991233561445,1740481184.384581,16.159984588623047,12.124682888321944,1740481184.3845835,16.159984588623047,0.0,1740481184.3845856,16.159984588623047,0.0,1740481184.3845873,16.159984588623047,0.0,1740481184.3845887,16.159984588623047,0.0,1740481184.3845904,16.159984588623047,0.9999999999999961,1740481184.384592,16.159984588623047,5.551115123125783e-15,1740481184.3845935,16.159984588623047,0.034023617169667154,1740481184.384595,16.159984588623047,0.0,1740481184.3845966,16.159984588623047,0.967022251426224,, -1740481184.4049273,16.17998456954956,8.279588181846634,1740481184.4049287,16.17998456954956,0.0,1740481184.4049313,16.17998456954956,0.017250991233561445,1740481184.4049332,16.17998456954956,12.124682888321944,1740481184.4049342,16.17998456954956,0.0,1740481184.4049354,16.17998456954956,0.0,1740481184.4049366,16.17998456954956,0.0,1740481184.4049375,16.17998456954956,0.0,1740481184.4049382,16.17998456954956,0.9999999999999961,1740481184.40494,16.17998456954956,5.551115123125783e-15,1740481184.4049406,16.17998456954956,0.032977748573777665,1740481184.4049416,16.17998456954956,0.0,1740481184.4049423,16.17998456954956,0.967022251426224,, -1740481184.4238462,16.199984550476074,8.279588181846634,1740481184.423851,16.199984550476074,0.0,1740481184.423855,16.199984550476074,0.017250991233561445,1740481184.4238577,16.199984550476074,12.124682888321944,1740481184.423859,16.199984550476074,0.0,1740481184.4238603,16.199984550476074,0.0,1740481184.4238617,16.199984550476074,0.0,1740481184.4238627,16.199984550476074,0.0,1740481184.423864,16.199984550476074,0.9999999999999961,1740481184.4238648,16.199984550476074,5.551115123125783e-15,1740481184.4238663,16.199984550476074,0.032977748573777665,1740481184.4238675,16.199984550476074,0.0,1740481184.4238687,16.199984550476074,0.967022251426224,, -1740481184.4442825,16.219984531402588,8.279588181846634,1740481184.4442844,16.219984531402588,0.0,1740481184.4442863,16.219984531402588,0.017250991233561445,1740481184.4442885,16.219984531402588,12.124682888321944,1740481184.4442894,16.219984531402588,0.0,1740481184.4442909,16.219984531402588,0.0,1740481184.4442918,16.219984531402588,0.0,1740481184.4442928,16.219984531402588,0.0,1740481184.444294,16.219984531402588,0.9999999999999961,1740481184.4442947,16.219984531402588,5.551115123125783e-15,1740481184.4442954,16.219984531402588,0.032977748573777665,1740481184.4442964,16.219984531402588,0.0,1740481184.4442976,16.219984531402588,0.967022251426224,, -1740481184.4665623,16.2399845123291,8.279588181846634,1740481184.4665647,16.2399845123291,0.0,1740481184.4665668,16.2399845123291,0.0,1740481184.4665701,16.2399845123291,12.213632684699082,1740481184.466572,16.2399845123291,0.0,1740481184.4665742,16.2399845123291,0.0,1740481184.4665754,16.2399845123291,0.0,1740481184.4665763,16.2399845123291,0.0,1740481184.4665773,16.2399845123291,0.99556016960594,1740481184.4665785,16.2399845123291,0.0,1740481184.4665794,16.2399845123291,0.02853791817971596,1740481184.4665804,16.2399845123291,0.0,1740481184.4665816,16.2399845123291,0.967022251426224,, -1740481184.4842525,16.259984493255615,8.385876572242696,1740481184.484254,16.259984493255615,0.0,1740481184.4842565,16.259984493255615,0.017279760126631703,1740481184.4842587,16.259984493255615,12.226358388107364,1740481184.4842596,16.259984493255615,0.0,1740481184.4842608,16.259984493255615,0.0,1740481184.484262,16.259984493255615,0.0,1740481184.4842627,16.259984493255615,0.0,1740481184.4842637,16.259984493255615,0.99556016960594,1740481184.4842646,16.259984493255615,0.044398303940561545,1740481184.4842656,16.259984493255615,0.0762482643570532,1740481184.4842665,16.259984493255615,0.0,1740481184.4842675,16.259984493255615,0.9647452230670487,, -1740481184.5039654,16.27998447418213,8.385876572242696,1740481184.503967,16.27998447418213,0.0,1740481184.5039692,16.27998447418213,0.017279760126631703,1740481184.503971,16.27998447418213,12.226358388107364,1740481184.503972,16.27998447418213,0.0,1740481184.5039735,16.27998447418213,0.0,1740481184.5039744,16.27998447418213,0.0,1740481184.5039752,16.27998447418213,0.0,1740481184.503976,16.27998447418213,0.99556016960594,1740481184.5039773,16.27998447418213,0.044398303940561545,1740481184.503978,16.27998447418213,0.07521325047945282,1740481184.503979,16.27998447418213,0.0,1740481184.50398,16.27998447418213,0.9647452230670487,, -1740481184.5235274,16.299984455108643,8.385876572242696,1740481184.523529,16.299984455108643,0.0,1740481184.5235312,16.299984455108643,0.017279760126631703,1740481184.5235333,16.299984455108643,12.226358388107364,1740481184.5235343,16.299984455108643,0.0,1740481184.5235357,16.299984455108643,0.0,1740481184.5235367,16.299984455108643,0.0,1740481184.5235376,16.299984455108643,0.0,1740481184.5235384,16.299984455108643,0.99556016960594,1740481184.5235398,16.299984455108643,0.044398303940561545,1740481184.5235405,16.299984455108643,0.07521325047945282,1740481184.5235415,16.299984455108643,0.0,1740481184.5235426,16.299984455108643,0.9647452230670487,, -1740481184.545763,16.319984436035156,8.385876572242696,1740481184.5457697,16.319984436035156,0.0,1740481184.5457733,16.319984436035156,0.017279760126631703,1740481184.5457766,16.319984436035156,12.226358388107364,1740481184.545779,16.319984436035156,0.0,1740481184.5457816,16.319984436035156,0.0,1740481184.5457838,16.319984436035156,0.0,1740481184.545786,16.319984436035156,0.0,1740481184.5457888,16.319984436035156,0.99556016960594,1740481184.5457914,16.319984436035156,0.044398303940561545,1740481184.5457942,16.319984436035156,0.07521325047945282,1740481184.5457969,16.319984436035156,0.0,1740481184.5457995,16.319984436035156,0.9647452230670487,, -1740481184.5652034,16.33998441696167,8.385876572242696,1740481184.565205,16.33998441696167,0.0,1740481184.5652072,16.33998441696167,0.0,1740481184.5652096,16.33998441696167,12.315367018376794,1740481184.5652106,16.33998441696167,0.0,1740481184.565212,16.33998441696167,0.0,1740481184.565213,16.33998441696167,0.0,1740481184.565214,16.33998441696167,0.0,1740481184.5652146,16.33998441696167,0.9949258848694771,1740481184.5652158,16.33998441696167,0.0,1740481184.5652165,16.33998441696167,0.0301806618024284,1740481184.5652175,16.33998441696167,0.0,1740481184.5652182,16.33998441696167,0.9647452230670487,, -1740481184.5841286,16.359984397888184,8.385876572242696,1740481184.5841305,16.359984397888184,0.0,1740481184.584133,16.359984397888184,0.0,1740481184.5841348,16.359984397888184,12.315367018376794,1740481184.584136,16.359984397888184,0.0,1740481184.5841374,16.359984397888184,0.0,1740481184.5841384,16.359984397888184,0.0,1740481184.5841396,16.359984397888184,0.0,1740481184.5841403,16.359984397888184,0.9949258848694771,1740481184.5841413,16.359984397888184,0.0,1740481184.584142,16.359984397888184,0.0301806618024284,1740481184.5841432,16.359984397888184,0.0,1740481184.584144,16.359984397888184,0.9647452230670487,, -1740481184.607188,16.379984378814697,8.4920839766951,1740481184.6071906,16.379984378814697,0.0,1740481184.6071944,16.379984378814697,0.017255593115394933,1740481184.6071978,16.379984378814697,12.333837319558828,1740481184.6071994,16.379984378814697,0.0,1740481184.6072025,16.379984378814697,0.0,1740481184.6072037,16.379984378814697,0.0,1740481184.6072052,16.379984378814697,0.0,1740481184.6072063,16.379984378814697,0.9949258848694771,1740481184.6072078,16.379984378814697,0.0507411513051903,1740481184.607209,16.379984378814697,0.08003838879587144,1740481184.6072102,16.379984378814697,0.0,1740481184.6072118,16.379984378814697,0.9653525771003691,, -1740481184.6262903,16.39998435974121,8.4920839766951,1740481184.6262953,16.39998435974121,0.0,1740481184.6262982,16.39998435974121,0.017255593115394933,1740481184.6263008,16.39998435974121,12.333837319558828,1740481184.6263032,16.39998435974121,0.0,1740481184.6263056,16.39998435974121,0.0,1740481184.626307,16.39998435974121,0.0,1740481184.6263087,16.39998435974121,0.0,1740481184.6263094,16.39998435974121,0.9949258848694771,1740481184.6263115,16.39998435974121,0.0507411513051903,1740481184.626313,16.39998435974121,0.08031445907429824,1740481184.626314,16.39998435974121,0.0,1740481184.6263158,16.39998435974121,0.9653525771003691,, -1740481184.6444757,16.419984340667725,8.4920839766951,1740481184.6444795,16.419984340667725,0.0,1740481184.644484,16.419984340667725,0.017255593115394933,1740481184.6444876,16.419984340667725,12.333837319558828,1740481184.6444895,16.419984340667725,0.0,1740481184.6444921,16.419984340667725,0.0,1740481184.644494,16.419984340667725,0.0,1740481184.6444962,16.419984340667725,0.0,1740481184.6444983,16.419984340667725,0.9949258848694771,1740481184.6445005,16.419984340667725,0.0507411513051903,1740481184.644503,16.419984340667725,0.08031445907429824,1740481184.644505,16.419984340667725,0.0,1740481184.644508,16.419984340667725,0.9653525771003691,, -1740481184.665617,16.43998432159424,8.4920839766951,1740481184.6656187,16.43998432159424,0.0,1740481184.6656208,16.43998432159424,0.0,1740481184.6656353,16.43998432159424,12.42278913089584,1740481184.665638,16.43998432159424,0.0,1740481184.66564,16.43998432159424,0.0,1740481184.6656413,16.43998432159424,0.0,1740481184.6656423,16.43998432159424,0.0,1740481184.665643,16.43998432159424,0.9950992082448111,1740481184.6656442,16.43998432159424,0.0,1740481184.6656451,16.43998432159424,0.029746631144441982,1740481184.665646,16.43998432159424,0.0,1740481184.665647,16.43998432159424,0.9653525771003691,, -1740481184.6839917,16.459984302520752,8.4920839766951,1740481184.6839938,16.459984302520752,0.0,1740481184.683997,16.459984302520752,0.0,1740481184.6839993,16.459984302520752,12.42278913089584,1740481184.6840005,16.459984302520752,0.0,1740481184.6840022,16.459984302520752,0.0,1740481184.684003,16.459984302520752,0.0,1740481184.6840043,16.459984302520752,0.0,1740481184.684005,16.459984302520752,0.9950992082448111,1740481184.6840065,16.459984302520752,0.0,1740481184.6840072,16.459984302520752,0.029746631144441982,1740481184.6840084,16.459984302520752,0.0,1740481184.6840093,16.459984302520752,0.9653525771003691,, -1740481184.7034178,16.479984283447266,8.598316730870444,1740481184.7034209,16.479984283447266,0.0,1740481184.703424,16.479984283447266,0.017262718471225173,1740481184.7034261,16.479984283447266,12.43998671903938,1740481184.703427,16.479984283447266,0.0,1740481184.7034283,16.479984283447266,0.0,1740481184.7034295,16.479984283447266,0.0,1740481184.7034304,16.479984283447266,0.0,1740481184.7034311,16.479984283447266,0.9950992082448111,1740481184.703432,16.479984283447266,0.049007917551849856,1740481184.703433,16.479984283447266,0.07880191622145119,1740481184.7034338,16.479984283447266,0.0,1740481184.7034347,16.479984283447266,0.9653200119365273,, -1740481184.7246869,16.49998426437378,8.598316730870444,1740481184.724689,16.49998426437378,0.0,1740481184.7246912,16.49998426437378,0.017262718471225173,1740481184.724693,16.49998426437378,12.43998671903938,1740481184.724694,16.49998426437378,0.0,1740481184.7246954,16.49998426437378,0.0,1740481184.7246966,16.49998426437378,0.0,1740481184.7246976,16.49998426437378,0.0,1740481184.7246985,16.49998426437378,0.9950992082448111,1740481184.7246995,16.49998426437378,0.049007917551849856,1740481184.7247005,16.49998426437378,0.0787871138601337,1740481184.7247014,16.49998426437378,0.0,1740481184.7247024,16.49998426437378,0.9653200119365273,, -1740481184.7440403,16.519984245300293,8.598316730870444,1740481184.744043,16.519984245300293,0.0,1740481184.7440457,16.519984245300293,0.017262718471225173,1740481184.7440479,16.519984245300293,12.43998671903938,1740481184.7440493,16.519984245300293,0.0,1740481184.744051,16.519984245300293,0.0,1740481184.7440524,16.519984245300293,0.0,1740481184.7440536,16.519984245300293,0.0,1740481184.7440548,16.519984245300293,0.9950992082448111,1740481184.744056,16.519984245300293,0.049007917551849856,1740481184.7440577,16.519984245300293,0.0787871138601337,1740481184.7440588,16.519984245300293,0.0,1740481184.7440598,16.519984245300293,0.9653200119365273,, -1740481184.767452,16.539984226226807,8.598316730870444,1740481184.7674544,16.539984226226807,0.0,1740481184.7674582,16.539984226226807,0.0,1740481184.7674606,16.539984226226807,12.528956754743499,1740481184.7674623,16.539984226226807,0.0,1740481184.767464,16.539984226226807,0.0,1740481184.7674649,16.539984226226807,0.0,1740481184.767467,16.539984226226807,0.0,1740481184.7674682,16.539984226226807,0.9950899913925906,1740481184.76747,16.539984226226807,0.0,1740481184.7674706,16.539984226226807,0.0297699794560633,1740481184.7674716,16.539984226226807,0.0,1740481184.767474,16.539984226226807,0.9653200119365273,, -1740481184.7836432,16.55998420715332,8.598316730870444,1740481184.783645,16.55998420715332,0.0,1740481184.783647,16.55998420715332,0.0,1740481184.783649,16.55998420715332,12.528956754743499,1740481184.7836502,16.55998420715332,0.0,1740481184.7836514,16.55998420715332,0.0,1740481184.7836525,16.55998420715332,0.0,1740481184.7836533,16.55998420715332,0.0,1740481184.7836545,16.55998420715332,0.9950899913925906,1740481184.7836554,16.55998420715332,0.0,1740481184.7836561,16.55998420715332,0.0297699794560633,1740481184.7836573,16.55998420715332,0.0,1740481184.783658,16.55998420715332,0.9653200119365273,, -1740481184.803673,16.579984188079834,8.598316730870444,1740481184.8036747,16.579984188079834,0.0,1740481184.8036768,16.579984188079834,0.0,1740481184.8036792,16.579984188079834,12.528956754743499,1740481184.8036802,16.579984188079834,0.0,1740481184.8036816,16.579984188079834,0.0,1740481184.8036826,16.579984188079834,0.0,1740481184.8036835,16.579984188079834,0.0,1740481184.8036842,16.579984188079834,0.9950899913925906,1740481184.8036854,16.579984188079834,0.0,1740481184.8036864,16.579984188079834,0.0297699794560633,1740481184.8036876,16.579984188079834,0.0,1740481184.8036885,16.579984188079834,0.9653200119365273,, -1740481184.8236978,16.599984169006348,8.704569349669976,1740481184.8236997,16.599984169006348,0.0,1740481184.8237028,16.599984169006348,0.017265786531774928,1740481184.8237047,16.599984169006348,12.545976664767675,1740481184.823706,16.599984169006348,0.0,1740481184.8237073,16.599984169006348,0.0,1740481184.8237085,16.599984169006348,0.0,1740481184.8237092,16.599984169006348,0.0,1740481184.82371,16.599984169006348,0.9950899913925906,1740481184.823711,16.599984169006348,0.04910008607405536,1740481184.823712,16.599984169006348,0.07904888486166482,1740481184.8237128,16.599984169006348,0.0,1740481184.8237138,16.599984169006348,0.9651970736827278,, -1740481184.844431,16.61998414993286,8.704569349669976,1740481184.8444324,16.61998414993286,0.0,1740481184.8444345,16.61998414993286,0.017265786531774928,1740481184.8444364,16.61998414993286,12.545976664767675,1740481184.8444376,16.61998414993286,0.0,1740481184.844439,16.61998414993286,0.0,1740481184.84444,16.61998414993286,0.0,1740481184.8444412,16.61998414993286,0.0,1740481184.8444421,16.61998414993286,0.9950899913925906,1740481184.8444428,16.61998414993286,0.04910008607405536,1740481184.8444438,16.61998414993286,0.07899300378391816,1740481184.844445,16.61998414993286,0.0,1740481184.844446,16.61998414993286,0.9651970736827278,, -1740481184.8664424,16.639984130859375,8.704569349669976,1740481184.8664446,16.639984130859375,0.0,1740481184.8664467,16.639984130859375,0.0,1740481184.8664489,16.639984130859375,12.634963497035432,1740481184.8664496,16.639984130859375,0.0,1740481184.8664513,16.639984130859375,0.0,1740481184.866452,16.639984130859375,0.0,1740481184.866453,16.639984130859375,0.0,1740481184.8664536,16.639984130859375,0.9950551183820491,1740481184.8664546,16.639984130859375,0.0,1740481184.8664556,16.639984130859375,0.029858044699321296,1740481184.8664565,16.639984130859375,0.0,1740481184.8664575,16.639984130859375,0.9651970736827278,, -1740481184.8837838,16.65998411178589,8.704569349669976,1740481184.8837855,16.65998411178589,0.0,1740481184.8837879,16.65998411178589,0.0,1740481184.8837898,16.65998411178589,12.634963497035432,1740481184.8837907,16.65998411178589,0.0,1740481184.8837922,16.65998411178589,0.0,1740481184.8837934,16.65998411178589,0.0,1740481184.8837945,16.65998411178589,0.0,1740481184.8837953,16.65998411178589,0.9950551183820491,1740481184.8837962,16.65998411178589,0.0,1740481184.8837972,16.65998411178589,0.029858044699321296,1740481184.8837984,16.65998411178589,0.0,1740481184.8838136,16.65998411178589,0.9651970736827278,, -1740481184.9038281,16.679984092712402,8.704569349669976,1740481184.9038308,16.679984092712402,0.0,1740481184.9038336,16.679984092712402,0.0,1740481184.9038355,16.679984092712402,12.634963497035432,1740481184.9038367,16.679984092712402,0.0,1740481184.903838,16.679984092712402,0.0,1740481184.9038389,16.679984092712402,0.0,1740481184.90384,16.679984092712402,0.0,1740481184.9038408,16.679984092712402,0.9950551183820491,1740481184.9038417,16.679984092712402,0.0,1740481184.9038424,16.679984092712402,0.029858044699321296,1740481184.9038436,16.679984092712402,0.0,1740481184.9038446,16.679984092712402,0.9651970736827278,, -1740481184.9237876,16.699984073638916,8.810735967815697,1740481184.923789,16.699984073638916,0.0,1740481184.923791,16.699984073638916,0.017251207048073532,1740481184.9237928,16.699984073638916,12.650048745929766,1740481184.923794,16.699984073638916,0.0,1740481184.9237952,16.699984073638916,0.0,1740481184.9237962,16.699984073638916,0.0,1740481184.9237971,16.699984073638916,0.0,1740481184.923798,16.699984073638916,0.9950551183820491,1740481184.923799,16.699984073638916,0.04944881617947039,1740481184.9238,16.699984073638916,0.0808821036418796,1740481184.923801,16.699984073638916,0.0,1740481184.923802,16.699984073638916,0.9641140946058581,, -1740481184.9438019,16.71998405456543,8.810735967815697,1740481184.9438035,16.71998405456543,0.0,1740481184.9438057,16.71998405456543,0.017251207048073532,1740481184.9438078,16.71998405456543,12.650048745929766,1740481184.9438088,16.71998405456543,0.0,1740481184.94381,16.71998405456543,0.0,1740481184.9438112,16.71998405456543,0.0,1740481184.9438121,16.71998405456543,0.0,1740481184.9438128,16.71998405456543,0.9950551183820491,1740481184.9438138,16.71998405456543,0.04944881617947039,1740481184.943815,16.71998405456543,0.0803898399556614,1740481184.9438157,16.71998405456543,0.0,1740481184.9438167,16.71998405456543,0.9641140946058581,, -1740481184.9663813,16.739984035491943,8.810735967815697,1740481184.9663837,16.739984035491943,0.0,1740481184.9663863,16.739984035491943,0.0,1740481184.9663885,16.739984035491943,12.738964157027414,1740481184.966406,16.739984035491943,0.0,1740481184.9664078,16.739984035491943,0.0,1740481184.966409,16.739984035491943,0.0,1740481184.96641,16.739984035491943,0.0,1740481184.966411,16.739984035491943,0.9947425858395518,1740481184.966412,16.739984035491943,0.0,1740481184.966413,16.739984035491943,0.03062849123369371,1740481184.966414,16.739984035491943,0.0,1740481184.966415,16.739984035491943,0.9641140946058581,, -1740481184.9840121,16.759984016418457,8.810735967815697,1740481184.9840164,16.759984016418457,0.0,1740481184.9840195,16.759984016418457,0.0,1740481184.9840217,16.759984016418457,12.738964157027414,1740481184.9840229,16.759984016418457,0.0,1740481184.984024,16.759984016418457,0.0,1740481184.984025,16.759984016418457,0.0,1740481184.984026,16.759984016418457,0.0,1740481184.984027,16.759984016418457,0.9947425858395518,1740481184.9840276,16.759984016418457,0.0,1740481184.9840286,16.759984016418457,0.03062849123369371,1740481184.9840295,16.759984016418457,0.0,1740481184.9840305,16.759984016418457,0.9641140946058581,, -1740481185.0034347,16.77998399734497,8.810735967815697,1740481185.0034366,16.77998399734497,0.0,1740481185.0034387,16.77998399734497,0.0,1740481185.0034409,16.77998399734497,12.738964157027414,1740481185.0034418,16.77998399734497,0.0,1740481185.0034435,16.77998399734497,0.0,1740481185.0034442,16.77998399734497,0.0,1740481185.0034451,16.77998399734497,0.0,1740481185.0034463,16.77998399734497,0.9947425858395518,1740481185.003447,16.77998399734497,0.0,1740481185.003448,16.77998399734497,0.03062849123369371,1740481185.0034487,16.77998399734497,0.0,1740481185.00345,16.77998399734497,0.9641140946058581,, -1740481185.0235472,16.799983978271484,8.810735967815697,1740481185.023549,16.799983978271484,0.0,1740481185.0235515,16.799983978271484,0.0,1740481185.0235534,16.799983978271484,12.738964157027414,1740481185.0235543,16.799983978271484,0.0,1740481185.0235558,16.799983978271484,0.0,1740481185.023557,16.799983978271484,0.0,1740481185.023558,16.799983978271484,0.0,1740481185.0235586,16.799983978271484,0.9947425858395518,1740481185.0235596,16.799983978271484,0.0,1740481185.0235605,16.799983978271484,0.03062849123369371,1740481185.0235615,16.799983978271484,0.0,1740481185.0235622,16.799983978271484,0.9641140946058581,, -1740481185.0444603,16.819983959197998,8.916810700570888,1740481185.0444617,16.819983959197998,0.0,1740481185.044464,16.819983959197998,0.01723086275646076,1740481185.044466,16.819983959197998,12.75428062182436,1740481185.044467,16.819983959197998,0.0,1740481185.044468,16.819983959197998,0.0,1740481185.0444694,16.819983959197998,0.0,1740481185.04447,16.819983959197998,0.0,1740481185.044471,16.819983959197998,0.9947425858395518,1740481185.044472,16.819983959197998,0.05257414160461993,1740481185.044473,16.819983959197998,0.08459492267834937,1740481185.044474,16.819983959197998,0.0,1740481185.0444748,16.819983959197998,0.9631568956261013,, -1740481185.067491,16.83998394012451,8.916810700570888,1740481185.067493,16.83998394012451,0.0,1740481185.067495,16.83998394012451,0.0,1740481185.0674973,16.83998394012451,12.84312449182309,1740481185.0674982,16.83998394012451,0.0,1740481185.0674996,16.83998394012451,0.0,1740481185.0675006,16.83998394012451,0.0,1740481185.0675013,16.83998394012451,0.0,1740481185.0675023,16.83998394012451,0.9944583791628212,1740481185.0675037,16.83998394012451,0.0,1740481185.0675046,16.83998394012451,0.03130148353671991,1740481185.0675054,16.83998394012451,0.0,1740481185.0675063,16.83998394012451,0.9631568956261013,, -1740481185.08352,16.859983921051025,8.916810700570888,1740481185.0835216,16.859983921051025,0.0,1740481185.0835238,16.859983921051025,0.0,1740481185.083526,16.859983921051025,12.84312449182309,1740481185.0835268,16.859983921051025,0.0,1740481185.0835283,16.859983921051025,0.0,1740481185.0835295,16.859983921051025,0.0,1740481185.0835307,16.859983921051025,0.0,1740481185.0835319,16.859983921051025,0.9944583791628212,1740481185.0835328,16.859983921051025,0.0,1740481185.0835335,16.859983921051025,0.03130148353671991,1740481185.0835342,16.859983921051025,0.0,1740481185.0835354,16.859983921051025,0.9631568956261013,, -1740481185.104139,16.87998390197754,8.916810700570888,1740481185.1041405,16.87998390197754,0.0,1740481185.104143,16.87998390197754,0.0,1740481185.1041448,16.87998390197754,12.84312449182309,1740481185.104146,16.87998390197754,0.0,1740481185.1041472,16.87998390197754,0.0,1740481185.104148,16.87998390197754,0.0,1740481185.1041493,16.87998390197754,0.0,1740481185.10415,16.87998390197754,0.9944583791628212,1740481185.104151,16.87998390197754,0.0,1740481185.1041517,16.87998390197754,0.03130148353671991,1740481185.104153,16.87998390197754,0.0,1740481185.1041539,16.87998390197754,0.9631568956261013,, -1740481185.1243625,16.899983882904053,8.916810700570888,1740481185.1243687,16.899983882904053,0.0,1740481185.1243722,16.899983882904053,0.0,1740481185.1243753,16.899983882904053,12.84312449182309,1740481185.124377,16.899983882904053,0.0,1740481185.1243796,16.899983882904053,0.0,1740481185.124382,16.899983882904053,0.0,1740481185.1243837,16.899983882904053,0.0,1740481185.1243863,16.899983882904053,0.9944583791628212,1740481185.124388,16.899983882904053,0.0,1740481185.12439,16.899983882904053,0.03130148353671991,1740481185.1244135,16.899983882904053,0.0,1740481185.1244164,16.899983882904053,0.9631568956261013,, -1740481185.1449168,16.919983863830566,9.022704217489116,1740481185.1449192,16.919983863830566,0.0,1740481185.1449215,16.919983863830566,0.017196511315650382,1740481185.1449234,16.919983863830566,12.856697448116773,1740481185.1449244,16.919983863830566,0.0,1740481185.1449256,16.919983863830566,0.0,1740481185.144927,16.919983863830566,0.0,1740481185.144928,16.919983863830566,0.0,1740481185.1449287,16.919983863830566,0.9944583791628212,1740481185.14493,16.919983863830566,0.0554162083717491,1740481185.1449308,16.919983863830566,0.08935300543710416,1740481185.1449316,16.919983863830566,0.0,1740481185.1449325,16.919983863830566,0.9613451181151169,, -1740481185.16779,16.93998384475708,9.022704217489116,1740481185.1678133,16.93998384475708,0.0,1740481185.167818,16.93998384475708,0.0,1740481185.1678226,16.93998384475708,12.945394453719349,1740481185.1678255,16.93998384475708,0.0,1740481185.1678283,16.93998384475708,0.0,1740481185.1678305,16.93998384475708,0.0,1740481185.1678338,16.93998384475708,0.0,1740481185.167836,16.93998384475708,0.9938999544785341,1740481185.1678379,16.93998384475708,0.0,1740481185.1678407,16.93998384475708,0.03255483636341716,1740481185.167843,16.93998384475708,0.0,1740481185.1678455,16.93998384475708,0.9613451181151169,, -1740481185.1834831,16.959983825683594,9.022704217489116,1740481185.183485,16.959983825683594,0.0,1740481185.183487,16.959983825683594,0.0,1740481185.183489,16.959983825683594,12.945394453719349,1740481185.18349,16.959983825683594,0.0,1740481185.1834912,16.959983825683594,0.0,1740481185.1834924,16.959983825683594,0.0,1740481185.1834934,16.959983825683594,0.0,1740481185.1834943,16.959983825683594,0.9938999544785341,1740481185.1834953,16.959983825683594,0.0,1740481185.1834962,16.959983825683594,0.03255483636341716,1740481185.183497,16.959983825683594,0.0,1740481185.183498,16.959983825683594,0.9613451181151169,, -1740481185.2034278,16.979983806610107,9.022704217489116,1740481185.2034295,16.979983806610107,0.0,1740481185.2034316,16.979983806610107,0.0,1740481185.2034338,16.979983806610107,12.945394453719349,1740481185.2034347,16.979983806610107,0.0,1740481185.2034364,16.979983806610107,0.0,1740481185.2034373,16.979983806610107,0.0,1740481185.203438,16.979983806610107,0.0,1740481185.2034395,16.979983806610107,0.9938999544785341,1740481185.2034402,16.979983806610107,0.0,1740481185.2034411,16.979983806610107,0.03255483636341716,1740481185.203442,16.979983806610107,0.0,1740481185.2034433,16.979983806610107,0.9613451181151169,, -1740481185.2256553,16.99998378753662,9.022704217489116,1740481185.225657,16.99998378753662,0.0,1740481185.2256594,16.99998378753662,0.0,1740481185.2256613,16.99998378753662,12.945394453719349,1740481185.2256622,16.99998378753662,0.0,1740481185.2256637,16.99998378753662,0.0,1740481185.2256649,16.99998378753662,0.0,1740481185.2256658,16.99998378753662,0.0,1740481185.2256665,16.99998378753662,0.9938999544785341,1740481185.2256675,16.99998378753662,0.0,1740481185.2256687,16.99998378753662,0.03255483636341716,1740481185.2256694,16.99998378753662,0.0,1740481185.22567,16.99998378753662,0.9613451181151169,, -1740481185.2447307,17.019983768463135,9.022704217489116,1740481185.2447324,17.019983768463135,0.0,1740481185.244735,17.019983768463135,0.0,1740481185.2447367,17.019983768463135,12.945394453719349,1740481185.2447379,17.019983768463135,0.0,1740481185.244739,17.019983768463135,0.0,1740481185.24474,17.019983768463135,0.0,1740481185.244741,17.019983768463135,0.0,1740481185.244742,17.019983768463135,0.9938999544785341,1740481185.2447426,17.019983768463135,0.0,1740481185.2447433,17.019983768463135,0.03255483636341716,1740481185.2447445,17.019983768463135,0.0,1740481185.2447455,17.019983768463135,0.9613451181151169,, -1740481185.2650235,17.03998374938965,9.128423912970664,1740481185.2650254,17.03998374938965,0.0,1740481185.2650282,17.03998374938965,0.0,1740481185.2650301,17.03998374938965,13.04794405067448,1740481185.265031,17.03998374938965,0.0,1740481185.2650325,17.03998374938965,0.0,1740481185.2650335,17.03998374938965,0.0,1740481185.2650344,17.03998374938965,0.0,1740481185.2650352,17.03998374938965,0.9933894311516384,1740481185.2650363,17.03998374938965,0.06610568848357756,1740481185.265037,17.03998374938965,0.10022347212924484,1740481185.265038,17.03998374938965,0.0,1740481185.265039,17.03998374938965,0.9597600688519082,, -1740481185.284057,17.059983730316162,9.128423912970664,1740481185.2840583,17.059983730316162,0.0,1740481185.2840607,17.059983730316162,0.0,1740481185.2840626,17.059983730316162,13.04794405067448,1740481185.2840638,17.059983730316162,0.0,1740481185.284065,17.059983730316162,0.0,1740481185.284066,17.059983730316162,0.0,1740481185.284067,17.059983730316162,0.0,1740481185.2840676,17.059983730316162,0.9933894311516384,1740481185.2840686,17.059983730316162,0.06610568848357756,1740481185.2840693,17.059983730316162,0.09973505078330769,1740481185.2840703,17.059983730316162,0.0,1740481185.2840712,17.059983730316162,0.9597600688519082,, -1740481185.3061411,17.079983711242676,9.128423912970664,1740481185.3061433,17.079983711242676,0.0,1740481185.3061464,17.079983711242676,0.0,1740481185.3061483,17.079983711242676,13.04794405067448,1740481185.3061495,17.079983711242676,0.0,1740481185.3061507,17.079983711242676,0.0,1740481185.3061516,17.079983711242676,0.0,1740481185.3061528,17.079983711242676,0.0,1740481185.3061535,17.079983711242676,0.9933894311516384,1740481185.3061545,17.079983711242676,0.06610568848357756,1740481185.3061554,17.079983711242676,0.09973505078330769,1740481185.3061564,17.079983711242676,0.0,1740481185.3061574,17.079983711242676,0.9597600688519082,, -1740481185.32652,17.09998369216919,9.128423912970664,1740481185.326546,17.09998369216919,0.0,1740481185.3265495,17.09998369216919,0.0,1740481185.3265514,17.09998369216919,13.04794405067448,1740481185.3265529,17.09998369216919,0.0,1740481185.3265538,17.09998369216919,0.0,1740481185.3265548,17.09998369216919,0.0,1740481185.326556,17.09998369216919,0.0,1740481185.3265567,17.09998369216919,0.9933894311516384,1740481185.3265576,17.09998369216919,0.06610568848357756,1740481185.3265584,17.09998369216919,0.09973505078330769,1740481185.3265595,17.09998369216919,0.0,1740481185.3265603,17.09998369216919,0.9597600688519082,, -1740481185.3450909,17.119983673095703,9.128423912970664,1740481185.345093,17.119983673095703,0.0,1740481185.3450956,17.119983673095703,0.0,1740481185.345098,17.119983673095703,13.04794405067448,1740481185.345099,17.119983673095703,0.0,1740481185.3451006,17.119983673095703,0.0,1740481185.3451018,17.119983673095703,0.0,1740481185.345103,17.119983673095703,0.0,1740481185.3451042,17.119983673095703,0.9933894311516384,1740481185.3451052,17.119983673095703,0.06610568848357756,1740481185.3451061,17.119983673095703,0.09973505078330769,1740481185.3451073,17.119983673095703,0.0,1740481185.3451083,17.119983673095703,0.9597600688519082,, -1740481185.3676796,17.139983654022217,9.234164838336826,1740481185.3676815,17.139983654022217,0.0,1740481185.3676836,17.139983654022217,0.0,1740481185.3676856,17.139983654022217,13.161695588606307,1740481185.3676867,17.139983654022217,0.0,1740481185.367688,17.139983654022217,0.0,1740481185.367689,17.139983654022217,0.0,1740481185.36769,17.139983654022217,0.0,1740481185.3676908,17.139983654022217,0.9946399120755887,1740481185.3676918,17.139983654022217,0.05360087924407453,1740481185.3676925,17.139983654022217,0.08322322164579125,1740481185.3676937,17.139983654022217,0.0,1740481185.3676944,17.139983654022217,0.96376537513474,, -1740481185.3851306,17.15998363494873,9.234164838336826,1740481185.385134,17.15998363494873,0.0,1740481185.3851366,17.15998363494873,0.0,1740481185.385139,17.15998363494873,13.161695588606307,1740481185.3851402,17.15998363494873,0.0,1740481185.3851418,17.15998363494873,0.0,1740481185.3851428,17.15998363494873,0.0,1740481185.385144,17.15998363494873,0.0,1740481185.3851452,17.15998363494873,0.9946399120755887,1740481185.3851461,17.15998363494873,0.05360087924407453,1740481185.3851476,17.15998363494873,0.08447541618492316,1740481185.3851488,17.15998363494873,0.0,1740481185.3851497,17.15998363494873,0.96376537513474,, -1740481185.4055455,17.179983615875244,9.234164838336826,1740481185.40555,17.179983615875244,0.0,1740481185.4055536,17.179983615875244,0.0,1740481185.4055698,17.179983615875244,13.161695588606307,1740481185.405571,17.179983615875244,0.0,1740481185.4055727,17.179983615875244,0.0,1740481185.4055736,17.179983615875244,0.0,1740481185.4055746,17.179983615875244,0.0,1740481185.4055758,17.179983615875244,0.9946399120755887,1740481185.4055767,17.179983615875244,0.05360087924407453,1740481185.4055777,17.179983615875244,0.08447541618492316,1740481185.4055786,17.179983615875244,0.0,1740481185.405592,17.179983615875244,0.96376537513474,, -1740481185.4235687,17.199983596801758,9.234164838336826,1740481185.4235704,17.199983596801758,0.0,1740481185.4235725,17.199983596801758,0.0,1740481185.4235744,17.199983596801758,13.161695588606307,1740481185.4235756,17.199983596801758,0.0,1740481185.4235768,17.199983596801758,0.0,1740481185.4235778,17.199983596801758,0.0,1740481185.4235787,17.199983596801758,0.0,1740481185.4235797,17.199983596801758,0.9946399120755887,1740481185.4235804,17.199983596801758,0.05360087924407453,1740481185.4235814,17.199983596801758,0.08447541618492316,1740481185.4235823,17.199983596801758,0.0,1740481185.4235833,17.199983596801758,0.96376537513474,, -1740481185.44482,17.21998357772827,9.234164838336826,1740481185.444822,17.21998357772827,0.0,1740481185.4448242,17.21998357772827,0.0,1740481185.4448266,17.21998357772827,13.161695588606307,1740481185.4448276,17.21998357772827,0.0,1740481185.444829,17.21998357772827,0.0,1740481185.44483,17.21998357772827,0.0,1740481185.4448311,17.21998357772827,0.0,1740481185.4448323,17.21998357772827,0.9946399120755887,1740481185.4448333,17.21998357772827,0.05360087924407453,1740481185.444834,17.21998357772827,0.08447541618492316,1740481185.4448352,17.21998357772827,0.0,1740481185.4448361,17.21998357772827,0.96376537513474,, -1740481185.4655285,17.239983558654785,9.234164838336826,1740481185.4655437,17.239983558654785,0.0,1740481185.4655476,17.239983558654785,0.0,1740481185.4655497,17.239983558654785,13.161695588606307,1740481185.465551,17.239983558654785,0.0,1740481185.465552,17.239983558654785,0.0,1740481185.4655535,17.239983558654785,0.0,1740481185.4655542,17.239983558654785,0.0,1740481185.4655552,17.239983558654785,0.9946399120755887,1740481185.4655561,17.239983558654785,0.05360087924407453,1740481185.465557,17.239983558654785,0.08447541618492316,1740481185.465558,17.239983558654785,0.0,1740481185.465559,17.239983558654785,0.96376537513474,, -1740481185.4843736,17.2599835395813,9.340324842116338,1740481185.4843752,17.2599835395813,0.0,1740481185.4843774,17.2599835395813,0.017242934310918702,1740481185.4843793,17.2599835395813,13.184807943579198,1740481185.4843805,17.2599835395813,0.0,1740481185.4843817,17.2599835395813,0.0,1740481185.4843824,17.2599835395813,0.0,1740481185.4843836,17.2599835395813,0.0,1740481185.4843843,17.2599835395813,0.9999999999999961,1740481185.4843853,17.2599835395813,5.551115123125783e-15,1740481185.484386,17.2599835395813,0.034402359946293815,1740481185.4843872,17.2599835395813,0.0,1740481185.4843879,17.2599835395813,0.9667000854657273,, -1740481185.503899,17.279983520507812,9.340324842116338,1740481185.503901,17.279983520507812,0.0,1740481185.503903,17.279983520507812,0.017242934310918702,1740481185.503905,17.279983520507812,13.184807943579198,1740481185.503906,17.279983520507812,0.0,1740481185.5039074,17.279983520507812,0.0,1740481185.5039084,17.279983520507812,0.0,1740481185.503909,17.279983520507812,0.0,1740481185.50391,17.279983520507812,0.9999999999999961,1740481185.503911,17.279983520507812,5.551115123125783e-15,1740481185.503912,17.279983520507812,0.03329991453427439,1740481185.5039127,17.279983520507812,0.0,1740481185.5039136,17.279983520507812,0.9667000854657273,, -1740481185.5238984,17.299983501434326,9.340324842116338,1740481185.5239003,17.299983501434326,0.0,1740481185.5239024,17.299983501434326,0.017242934310918702,1740481185.5239046,17.299983501434326,13.184807943579198,1740481185.5239058,17.299983501434326,0.0,1740481185.5239074,17.299983501434326,0.0,1740481185.5239084,17.299983501434326,0.0,1740481185.5239096,17.299983501434326,0.0,1740481185.5239108,17.299983501434326,0.9999999999999961,1740481185.523912,17.299983501434326,5.551115123125783e-15,1740481185.523913,17.299983501434326,0.03329991453427439,1740481185.523914,17.299983501434326,0.0,1740481185.523915,17.299983501434326,0.9667000854657273,, -1740481185.5444143,17.31998348236084,9.340324842116338,1740481185.54442,17.31998348236084,0.0,1740481185.5444243,17.31998348236084,0.017242934310918702,1740481185.5444267,17.31998348236084,13.184807943579198,1740481185.5444283,17.31998348236084,0.0,1740481185.5444298,17.31998348236084,0.0,1740481185.5444314,17.31998348236084,0.0,1740481185.5444336,17.31998348236084,0.0,1740481185.5444546,17.31998348236084,0.9999999999999961,1740481185.5444567,17.31998348236084,5.551115123125783e-15,1740481185.544458,17.31998348236084,0.03329991453427439,1740481185.544459,17.31998348236084,0.0,1740481185.54446,17.31998348236084,0.9667000854657273,, -1740481185.566287,17.339983463287354,9.340324842116338,1740481185.566289,17.339983463287354,0.0,1740481185.5662909,17.339983463287354,0.0,1740481185.5662932,17.339983463287354,13.273725013047793,1740481185.5662942,17.339983463287354,0.0,1740481185.5662956,17.339983463287354,0.0,1740481185.5662968,17.339983463287354,0.0,1740481185.56631,17.339983463287354,0.0,1740481185.5663111,17.339983463287354,0.9954729987694119,1740481185.566312,17.339983463287354,0.0,1740481185.566313,17.339983463287354,0.02877291330368459,1740481185.5663145,17.339983463287354,0.0,1740481185.566316,17.339983463287354,0.9667000854657273,, -1740481185.584655,17.359983444213867,9.446580471732716,1740481185.5846574,17.359983444213867,0.0,1740481185.5846598,17.359983444213867,0.0172729215236743,1740481185.5846617,17.359983444213867,13.286532105171661,1740481185.5846627,17.359983444213867,0.0,1740481185.584664,17.359983444213867,0.0,1740481185.584665,17.359983444213867,0.0,1740481185.584666,17.359983444213867,0.0,1740481185.584667,17.359983444213867,0.9954729987694119,1740481185.5846682,17.359983444213867,0.04527001230584249,1740481185.5846689,17.359983444213867,0.07729080250460266,1740481185.58467,17.359983444213867,0.0,1740481185.5846708,17.359983444213867,0.9644671707658239,, -1740481185.6040154,17.37998342514038,9.446580471732716,1740481185.6040173,17.37998342514038,0.0,1740481185.6040194,17.37998342514038,0.0172729215236743,1740481185.6040213,17.37998342514038,13.286532105171661,1740481185.6040225,17.37998342514038,0.0,1740481185.6040237,17.37998342514038,0.0,1740481185.604025,17.37998342514038,0.0,1740481185.6040258,17.37998342514038,0.0,1740481185.6040266,17.37998342514038,0.9954729987694119,1740481185.6040277,17.37998342514038,0.04527001230584249,1740481185.6040287,17.37998342514038,0.07627584030943046,1740481185.60403,17.37998342514038,0.0,1740481185.604031,17.37998342514038,0.9644671707658239,, -1740481185.6235387,17.399983406066895,9.446580471732716,1740481185.6235404,17.399983406066895,0.0,1740481185.623543,17.399983406066895,0.0172729215236743,1740481185.6235454,17.399983406066895,13.286532105171661,1740481185.6235464,17.399983406066895,0.0,1740481185.6235476,17.399983406066895,0.0,1740481185.6235487,17.399983406066895,0.0,1740481185.6235495,17.399983406066895,0.0,1740481185.6235504,17.399983406066895,0.9954729987694119,1740481185.6235523,17.399983406066895,0.04527001230584249,1740481185.6235535,17.399983406066895,0.07627584030943046,1740481185.6235547,17.399983406066895,0.0,1740481185.6235566,17.399983406066895,0.9644671707658239,, -1740481185.6455703,17.419983386993408,9.446580471732716,1740481185.6455762,17.419983386993408,0.0,1740481185.6455812,17.419983386993408,0.0172729215236743,1740481185.6455843,17.419983386993408,13.286532105171661,1740481185.6455867,17.419983386993408,0.0,1740481185.6455886,17.419983386993408,0.0,1740481185.6455915,17.419983386993408,0.0,1740481185.645594,17.419983386993408,0.0,1740481185.6456175,17.419983386993408,0.9954729987694119,1740481185.6456192,17.419983386993408,0.04527001230584249,1740481185.6456227,17.419983386993408,0.07627584030943046,1740481185.645625,17.419983386993408,0.0,1740481185.645627,17.419983386993408,0.9644671707658239,, -1740481185.6664293,17.439983367919922,9.446580471732716,1740481185.666431,17.439983367919922,0.0,1740481185.666433,17.439983367919922,0.0,1740481185.666435,17.439983367919922,13.375514813264363,1740481185.6664364,17.439983367919922,0.0,1740481185.6664376,17.439983367919922,0.0,1740481185.6664386,17.439983367919922,0.0,1740481185.6664395,17.439983367919922,0.0,1740481185.6664405,17.439983367919922,0.9948455307596042,1740481185.6664414,17.439983367919922,0.0,1740481185.6664422,17.439983367919922,0.030378359993780357,1740481185.666443,17.439983367919922,0.0,1740481185.666444,17.439983367919922,0.9644671707658239,, -1740481185.6841104,17.459983348846436,9.446580471732716,1740481185.6841123,17.459983348846436,0.0,1740481185.6841147,17.459983348846436,0.0,1740481185.6841168,17.459983348846436,13.375514813264363,1740481185.6841178,17.459983348846436,0.0,1740481185.684119,17.459983348846436,0.0,1740481185.6841202,17.459983348846436,0.0,1740481185.6841211,17.459983348846436,0.0,1740481185.6841218,17.459983348846436,0.9948455307596042,1740481185.684123,17.459983348846436,0.0,1740481185.684124,17.459983348846436,0.030378359993780357,1740481185.684125,17.459983348846436,0.0,1740481185.6841257,17.459983348846436,0.9644671707658239,, -1740481185.7039576,17.47998332977295,9.55276293091197,1740481185.7039592,17.47998332977295,0.0,1740481185.7039614,17.47998332977295,0.017250146937054518,1740481185.7039638,17.47998332977295,13.394164200230561,1740481185.7039645,17.47998332977295,0.0,1740481185.703966,17.47998332977295,0.0,1740481185.703967,17.47998332977295,0.0,1740481185.7039678,17.47998332977295,0.0,1740481185.7039688,17.47998332977295,0.9948455307596042,1740481185.7039697,17.47998332977295,0.05154469240391868,1740481185.7039707,17.47998332977295,0.08090542298231818,1740481185.7039716,17.47998332977295,0.0,1740481185.7039723,17.47998332977295,0.965166790780395,, -1740481185.7236257,17.499983310699463,9.55276293091197,1740481185.7236276,17.499983310699463,0.0,1740481185.7236295,17.499983310699463,0.017250146937054518,1740481185.7236316,17.499983310699463,13.394164200230561,1740481185.7236326,17.499983310699463,0.0,1740481185.723634,17.499983310699463,0.0,1740481185.7236352,17.499983310699463,0.0,1740481185.723636,17.499983310699463,0.0,1740481185.723637,17.499983310699463,0.9948455307596042,1740481185.723638,17.499983310699463,0.05154469240391868,1740481185.723639,17.499983310699463,0.0812234323831279,1740481185.7236397,17.499983310699463,0.0,1740481185.723641,17.499983310699463,0.965166790780395,, -1740481185.7457528,17.519983291625977,9.55276293091197,1740481185.7457557,17.519983291625977,0.0,1740481185.7457583,17.519983291625977,0.017250146937054518,1740481185.7457607,17.519983291625977,13.394164200230561,1740481185.7457619,17.519983291625977,0.0,1740481185.7457633,17.519983291625977,0.0,1740481185.7457645,17.519983291625977,0.0,1740481185.745766,17.519983291625977,0.0,1740481185.745767,17.519983291625977,0.9948455307596042,1740481185.7457685,17.519983291625977,0.05154469240391868,1740481185.7457697,17.519983291625977,0.0812234323831279,1740481185.745771,17.519983291625977,0.0,1740481185.7457724,17.519983291625977,0.965166790780395,, -1740481185.7671733,17.53998327255249,9.55276293091197,1740481185.7671752,17.53998327255249,0.0,1740481185.7671776,17.53998327255249,0.0,1740481185.7671797,17.53998327255249,13.483096512472759,1740481185.7671807,17.53998327255249,0.0,1740481185.767182,17.53998327255249,0.0,1740481185.767183,17.53998327255249,0.0,1740481185.767184,17.53998327255249,0.0,1740481185.767185,17.53998327255249,0.9950465093062307,1740481185.767186,17.53998327255249,0.0,1740481185.7671869,17.53998327255249,0.029879718525835708,1740481185.7671876,17.53998327255249,0.0,1740481185.7671888,17.53998327255249,0.965166790780395,, -1740481185.7836154,17.559983253479004,9.55276293091197,1740481185.7836175,17.559983253479004,0.0,1740481185.78362,17.559983253479004,0.0,1740481185.7836225,17.559983253479004,13.483096512472759,1740481185.7836235,17.559983253479004,0.0,1740481185.7836246,17.559983253479004,0.0,1740481185.7836258,17.559983253479004,0.0,1740481185.7836268,17.559983253479004,0.0,1740481185.7836277,17.559983253479004,0.9950465093062307,1740481185.7836294,17.559983253479004,0.0,1740481185.7836304,17.559983253479004,0.029879718525835708,1740481185.7836316,17.559983253479004,0.0,1740481185.7836323,17.559983253479004,0.965166790780395,, -1740481185.804513,17.579983234405518,9.658979062751342,1740481185.8045151,17.579983234405518,0.0,1740481185.804518,17.579983234405518,0.017259103293682816,1740481185.80452,17.579983234405518,13.500414789897995,1740481185.8045208,17.579983234405518,0.0,1740481185.8045223,17.579983234405518,0.0,1740481185.8045232,17.579983234405518,0.0,1740481185.8045242,17.579983234405518,0.0,1740481185.8045254,17.579983234405518,0.9950465093062307,1740481185.8045263,17.579983234405518,0.04953490693765383,1740481185.804527,17.579983234405518,0.07937158971862518,1740481185.8045282,17.579983234405518,0.0,1740481185.804529,17.579983234405518,0.9651963778461716,, -1740481185.8249288,17.59998321533203,9.658979062751342,1740481185.8249316,17.59998321533203,0.0,1740481185.8249347,17.59998321533203,0.017259103293682816,1740481185.8249369,17.59998321533203,13.500414789897995,1740481185.824938,17.59998321533203,0.0,1740481185.8249393,17.59998321533203,0.0,1740481185.8249402,17.59998321533203,0.0,1740481185.8249419,17.59998321533203,0.0,1740481185.8249426,17.59998321533203,0.9950465093062307,1740481185.824944,17.59998321533203,0.04953490693765383,1740481185.8249452,17.59998321533203,0.07938503839771294,1740481185.8249464,17.59998321533203,0.0,1740481185.8249476,17.59998321533203,0.9651963778461716,, -1740481185.8462698,17.619983196258545,9.658979062751342,1740481185.8462722,17.619983196258545,0.0,1740481185.8462746,17.619983196258545,0.017259103293682816,1740481185.8462765,17.619983196258545,13.500414789897995,1740481185.8462777,17.619983196258545,0.0,1740481185.846279,17.619983196258545,0.0,1740481185.8462799,17.619983196258545,0.0,1740481185.846281,17.619983196258545,0.0,1740481185.8462818,17.619983196258545,0.9950465093062307,1740481185.8463,17.619983196258545,0.04953490693765383,1740481185.846301,17.619983196258545,0.07938503839771294,1740481185.8463123,17.619983196258545,0.0,1740481185.8463159,17.619983196258545,0.9651963778461716,, -1740481185.8678372,17.63998317718506,9.658979062751342,1740481185.8678389,17.63998317718506,0.0,1740481185.8678412,17.63998317718506,0.0,1740481185.8678434,17.63998317718506,13.589371818443686,1740481185.8678443,17.63998317718506,0.0,1740481185.8678455,17.63998317718506,0.0,1740481185.867847,17.63998317718506,0.0,1740481185.867848,17.63998317718506,0.0,1740481185.8678486,17.63998317718506,0.9950549206478815,1740481185.86785,17.63998317718506,0.0,1740481185.8678508,17.63998317718506,0.029858542801709853,1740481185.8678515,17.63998317718506,0.0,1740481185.8678524,17.63998317718506,0.9651963778461716,, -1740481185.8840127,17.659983158111572,9.658979062751342,1740481185.8840153,17.659983158111572,0.0,1740481185.8840196,17.659983158111572,0.0,1740481185.8840218,17.659983158111572,13.589371818443686,1740481185.8840232,17.659983158111572,0.0,1740481185.8840246,17.659983158111572,0.0,1740481185.8840253,17.659983158111572,0.0,1740481185.8840265,17.659983158111572,0.0,1740481185.8840284,17.659983158111572,0.9950549206478815,1740481185.8840296,17.659983158111572,0.0,1740481185.8840318,17.659983158111572,0.029858542801709853,1740481185.884033,17.659983158111572,0.0,1740481185.8840342,17.659983158111572,0.9651963778461716,, -1740481185.9034276,17.679983139038086,9.658979062751342,1740481185.903429,17.679983139038086,0.0,1740481185.9034314,17.679983139038086,0.0,1740481185.9034336,17.679983139038086,13.589371818443686,1740481185.9034345,17.679983139038086,0.0,1740481185.9034357,17.679983139038086,0.0,1740481185.903437,17.679983139038086,0.0,1740481185.9034376,17.679983139038086,0.0,1740481185.9034383,17.679983139038086,0.9950549206478815,1740481185.9034393,17.679983139038086,0.0,1740481185.9034402,17.679983139038086,0.029858542801709853,1740481185.903441,17.679983139038086,0.0,1740481185.903442,17.679983139038086,0.9651963778461716,, -1740481185.92353,17.6999831199646,9.765220848065695,1740481185.9235315,17.6999831199646,0.0,1740481185.9235332,17.6999831199646,0.017263417667606935,1740481185.9235353,17.6999831199646,13.606470338732366,1740481185.923536,17.6999831199646,0.0,1740481185.9235375,17.6999831199646,0.0,1740481185.9235384,17.6999831199646,0.0,1740481185.9235392,17.6999831199646,0.0,1740481185.9235399,17.6999831199646,0.9950549206478815,1740481185.923541,17.6999831199646,0.04945079352114634,1740481185.9235418,17.6999831199646,0.07942926172508881,1740481185.9235425,17.6999831199646,0.0,1740481185.9235435,17.6999831199646,0.9651139291567084,, -1740481185.9442055,17.719983100891113,9.765220848065695,1740481185.9442093,17.719983100891113,0.0,1740481185.9442399,17.719983100891113,0.017263417667606935,1740481185.9442434,17.719983100891113,13.606470338732366,1740481185.944245,17.719983100891113,0.0,1740481185.944247,17.719983100891113,0.0,1740481185.9442503,17.719983100891113,0.0,1740481185.9442537,17.719983100891113,0.0,1740481185.9442556,17.719983100891113,0.9950549206478815,1740481185.944257,17.719983100891113,0.04945079352114634,1740481185.9442585,17.719983100891113,0.07939178501231947,1740481185.94426,17.719983100891113,0.0,1740481185.9442618,17.719983100891113,0.9651139291567084,, -1740481185.9698703,17.739983081817627,9.765220848065695,1740481185.9698758,17.739983081817627,0.0,1740481185.9698818,17.739983081817627,0.0,1740481185.9698849,17.739983081817627,13.695448706379112,1740481185.9698985,17.739983081817627,0.0,1740481185.9699016,17.739983081817627,0.0,1740481185.969904,17.739983081817627,0.0,1740481185.9699068,17.739983081817627,0.0,1740481185.9699113,17.739983081817627,0.9950314634202134,1740481185.9699135,17.739983081817627,0.0,1740481185.969918,17.739983081817627,0.029917534263505074,1740481185.9699223,17.739983081817627,0.0,1740481185.9699237,17.739983081817627,0.9651139291567084,, -1740481185.9863057,17.75998306274414,9.765220848065695,1740481185.9863076,17.75998306274414,0.0,1740481185.98631,17.75998306274414,0.0,1740481185.986312,17.75998306274414,13.695448706379112,1740481185.9863129,17.75998306274414,0.0,1740481185.986314,17.75998306274414,0.0,1740481185.9863155,17.75998306274414,0.0,1740481185.9863164,17.75998306274414,0.0,1740481185.9863174,17.75998306274414,0.9950314634202134,1740481185.9863183,17.75998306274414,0.0,1740481185.986319,17.75998306274414,0.029917534263505074,1740481185.98632,17.75998306274414,0.0,1740481185.986321,17.75998306274414,0.9651139291567084,, -1740481186.0049915,17.779983043670654,9.765220848065695,1740481186.0049953,17.779983043670654,0.0,1740481186.0050142,17.779983043670654,0.0,1740481186.005019,17.779983043670654,13.695448706379112,1740481186.00502,17.779983043670654,0.0,1740481186.005021,17.779983043670654,0.0,1740481186.0050223,17.779983043670654,0.0,1740481186.0050237,17.779983043670654,0.0,1740481186.0050259,17.779983043670654,0.9950314634202134,1740481186.0050273,17.779983043670654,0.0,1740481186.005029,17.779983043670654,0.029917534263505074,1740481186.0050306,17.779983043670654,0.0,1740481186.0050323,17.779983043670654,0.9651139291567084,, -1740481186.0240731,17.799983024597168,9.871404394617036,1740481186.024075,17.799983024597168,0.0,1740481186.024077,17.799983024597168,0.017253547605564534,1740481186.024079,17.799983024597168,13.711563510818493,1740481186.0240798,17.799983024597168,0.0,1740481186.0240812,17.799983024597168,0.0,1740481186.0240822,17.799983024597168,0.0,1740481186.0240831,17.799983024597168,0.0,1740481186.0240843,17.799983024597168,0.9950314634202134,1740481186.0240853,17.799983024597168,0.0496853657978269,1740481186.024086,17.799983024597168,0.08043107715628213,1740481186.024087,17.799983024597168,0.0,1740481186.0240881,17.799983024597168,0.9645445575736162,, -1740481186.0440319,17.81998300552368,9.871404394617036,1740481186.0440335,17.81998300552368,0.0,1740481186.0440357,17.81998300552368,0.017253547605564534,1740481186.0440376,17.81998300552368,13.711563510818493,1740481186.0440383,17.81998300552368,0.0,1740481186.0440397,17.81998300552368,0.0,1740481186.044041,17.81998300552368,0.0,1740481186.0440416,17.81998300552368,0.0,1740481186.0440433,17.81998300552368,0.9950314634202134,1740481186.044044,17.81998300552368,0.0496853657978269,1740481186.044045,17.81998300552368,0.08017227164442409,1740481186.0440462,17.81998300552368,0.0,1740481186.044047,17.81998300552368,0.9645445575736162,, -1740481186.066615,17.839982986450195,9.871404394617036,1740481186.0666168,17.839982986450195,0.0,1740481186.0666192,17.839982986450195,0.0,1740481186.066621,17.839982986450195,13.80049350976427,1740481186.0666223,17.839982986450195,0.0,1740481186.0666232,17.839982986450195,0.0,1740481186.0666242,17.839982986450195,0.0,1740481186.0666254,17.839982986450195,0.0,1740481186.0666263,17.839982986450195,0.9948679581069698,1740481186.066627,17.839982986450195,0.0,1740481186.0666287,17.839982986450195,0.030323400533353584,1740481186.0666294,17.839982986450195,0.0,1740481186.0666301,17.839982986450195,0.9645445575736162,, -1740481186.0865884,17.85998296737671,9.871404394617036,1740481186.086591,17.85998296737671,0.0,1740481186.0865934,17.85998296737671,0.0,1740481186.086595,17.85998296737671,13.80049350976427,1740481186.086596,17.85998296737671,0.0,1740481186.0865974,17.85998296737671,0.0,1740481186.0865989,17.85998296737671,0.0,1740481186.0865998,17.85998296737671,0.0,1740481186.0866008,17.85998296737671,0.9948679581069698,1740481186.0866017,17.85998296737671,0.0,1740481186.0866027,17.85998296737671,0.030323400533353584,1740481186.0866034,17.85998296737671,0.0,1740481186.0866046,17.85998296737671,0.9645445575736162,, -1740481186.104246,17.879982948303223,9.871404394617036,1740481186.104248,17.879982948303223,0.0,1740481186.104252,17.879982948303223,0.0,1740481186.1042542,17.879982948303223,13.80049350976427,1740481186.1042552,17.879982948303223,0.0,1740481186.1042566,17.879982948303223,0.0,1740481186.1042743,17.879982948303223,0.0,1740481186.1042752,17.879982948303223,0.0,1740481186.1042764,17.879982948303223,0.9948679581069698,1740481186.1042776,17.879982948303223,0.0,1740481186.1042783,17.879982948303223,0.030323400533353584,1740481186.1042793,17.879982948303223,0.0,1740481186.1042802,17.879982948303223,0.9645445575736162,, -1740481186.1243026,17.899982929229736,9.871404394617036,1740481186.1243043,17.899982929229736,0.0,1740481186.124307,17.899982929229736,0.0,1740481186.124309,17.899982929229736,13.80049350976427,1740481186.12431,17.899982929229736,0.0,1740481186.1243112,17.899982929229736,0.0,1740481186.1243126,17.899982929229736,0.0,1740481186.1243134,17.899982929229736,0.0,1740481186.124314,17.899982929229736,0.9948679581069698,1740481186.124315,17.899982929229736,0.0,1740481186.1243162,17.899982929229736,0.030323400533353584,1740481186.124317,17.899982929229736,0.0,1740481186.124318,17.899982929229736,0.9645445575736162,, -1740481186.144739,17.91998291015625,9.977524494593599,1740481186.1447408,17.91998291015625,0.0,1740481186.1447434,17.91998291015625,0.017240404862088988,1740481186.1447456,17.91998291015625,13.815743773134912,1740481186.1447465,17.91998291015625,0.0,1740481186.1447475,17.91998291015625,0.0,1740481186.1447484,17.91998291015625,0.0,1740481186.1447496,17.91998291015625,0.0,1740481186.1447508,17.91998291015625,0.9948679581069698,1740481186.1447515,17.91998291015625,0.05132041893026296,1740481186.1447527,17.91998291015625,0.08309119552511028,1740481186.1447537,17.91998291015625,0.0,1740481186.1447544,17.91998291015625,0.9635494868278938,, -1740481186.1678925,17.939982891082764,9.977524494593599,1740481186.1678944,17.939982891082764,0.0,1740481186.1678963,17.939982891082764,0.0,1740481186.1678984,17.939982891082764,13.904623468249387,1740481186.1678994,17.939982891082764,0.0,1740481186.1679006,17.939982891082764,0.0,1740481186.1679018,17.939982891082764,0.0,1740481186.1679027,17.939982891082764,0.0,1740481186.1679034,17.939982891082764,0.9945758502789234,1740481186.1679046,17.939982891082764,0.0,1740481186.1679053,17.939982891082764,0.031026363451029604,1740481186.1679063,17.939982891082764,0.0,1740481186.167907,17.939982891082764,0.9635494868278938,, -1740481186.184318,17.959982872009277,9.977524494593599,1740481186.184331,17.959982872009277,0.0,1740481186.1843343,17.959982872009277,0.0,1740481186.1843364,17.959982872009277,13.904623468249387,1740481186.1843374,17.959982872009277,0.0,1740481186.1843386,17.959982872009277,0.0,1740481186.1843398,17.959982872009277,0.0,1740481186.1843407,17.959982872009277,0.0,1740481186.1843414,17.959982872009277,0.9945758502789234,1740481186.1843426,17.959982872009277,0.0,1740481186.1843436,17.959982872009277,0.031026363451029604,1740481186.1843443,17.959982872009277,0.0,1740481186.1843452,17.959982872009277,0.9635494868278938,, -1740481186.2035723,17.97998285293579,9.977524494593599,1740481186.2035744,17.97998285293579,0.0,1740481186.2035768,17.97998285293579,0.0,1740481186.203579,17.97998285293579,13.904623468249387,1740481186.20358,17.97998285293579,0.0,1740481186.203581,17.97998285293579,0.0,1740481186.2035823,17.97998285293579,0.0,1740481186.2035835,17.97998285293579,0.0,1740481186.2035844,17.97998285293579,0.9945758502789234,1740481186.2035854,17.97998285293579,0.0,1740481186.203586,17.97998285293579,0.031026363451029604,1740481186.2035873,17.97998285293579,0.0,1740481186.2035882,17.97998285293579,0.9635494868278938,, -1740481186.2237372,17.999982833862305,9.977524494593599,1740481186.2237391,17.999982833862305,0.0,1740481186.2237415,17.999982833862305,0.0,1740481186.2237434,17.999982833862305,13.904623468249387,1740481186.2237446,17.999982833862305,0.0,1740481186.2237458,17.999982833862305,0.0,1740481186.2237468,17.999982833862305,0.0,1740481186.2237477,17.999982833862305,0.0,1740481186.223749,17.999982833862305,0.9945758502789234,1740481186.2237499,17.999982833862305,0.0,1740481186.2237506,17.999982833862305,0.031026363451029604,1740481186.2237518,17.999982833862305,0.0,1740481186.2237525,17.999982833862305,0.9635494868278938,, -1740481186.2456453,18.01998281478882,10.083457424204878,1740481186.2456474,18.01998281478882,0.0,1740481186.2456498,18.01998281478882,0.01720494382164095,1740481186.245652,18.01998281478882,13.918089127698194,1740481186.2456532,18.01998281478882,0.0,1740481186.2456546,18.01998281478882,0.0,1740481186.2456558,18.01998281478882,0.0,1740481186.2456572,18.01998281478882,0.0,1740481186.2456582,18.01998281478882,0.9945758502789234,1740481186.245659,18.01998281478882,0.05424149721072746,1740481186.24566,18.01998281478882,0.0879873410161046,1740481186.2456613,18.01998281478882,0.0,1740481186.2456622,18.01998281478882,0.9616798446414772,, -1740481186.2653143,18.039982795715332,10.083457424204878,1740481186.265316,18.039982795715332,0.0,1740481186.2653184,18.039982795715332,0.0,1740481186.2653208,18.039982795715332,14.006817113487832,1740481186.2653215,18.039982795715332,0.0,1740481186.2653227,18.039982795715332,0.0,1740481186.2653239,18.039982795715332,0.0,1740481186.2653248,18.039982795715332,0.0,1740481186.2653258,18.039982795715332,0.9940051420463041,1740481186.2653265,18.039982795715332,0.0,1740481186.2653275,18.039982795715332,0.032325297404826925,1740481186.2653284,18.039982795715332,0.0,1740481186.2653291,18.039982795715332,0.9616798446414772,, -1740481186.2839475,18.059982776641846,10.083457424204878,1740481186.2839499,18.059982776641846,0.0,1740481186.2839522,18.059982776641846,0.0,1740481186.2839541,18.059982776641846,14.006817113487832,1740481186.283955,18.059982776641846,0.0,1740481186.2839565,18.059982776641846,0.0,1740481186.2839575,18.059982776641846,0.0,1740481186.2839587,18.059982776641846,0.0,1740481186.2839599,18.059982776641846,0.9940051420463041,1740481186.2839608,18.059982776641846,0.0,1740481186.2839618,18.059982776641846,0.032325297404826925,1740481186.2839627,18.059982776641846,0.0,1740481186.2839637,18.059982776641846,0.9616798446414772,, -1740481186.3069644,18.07998275756836,10.083457424204878,1740481186.3069668,18.07998275756836,0.0,1740481186.3069696,18.07998275756836,0.0,1740481186.3069723,18.07998275756836,14.006817113487832,1740481186.3069735,18.07998275756836,0.0,1740481186.3069746,18.07998275756836,0.0,1740481186.3069763,18.07998275756836,0.0,1740481186.3069773,18.07998275756836,0.0,1740481186.3069785,18.07998275756836,0.9940051420463041,1740481186.3069797,18.07998275756836,0.0,1740481186.3069806,18.07998275756836,0.032325297404826925,1740481186.306982,18.07998275756836,0.0,1740481186.3069832,18.07998275756836,0.9616798446414772,, -1740481186.323836,18.099982738494873,10.083457424204878,1740481186.323838,18.099982738494873,0.0,1740481186.32384,18.099982738494873,0.0,1740481186.323842,18.099982738494873,14.006817113487832,1740481186.323843,18.099982738494873,0.0,1740481186.3238444,18.099982738494873,0.0,1740481186.3238456,18.099982738494873,0.0,1740481186.3238466,18.099982738494873,0.0,1740481186.323848,18.099982738494873,0.9940051420463041,1740481186.323849,18.099982738494873,0.0,1740481186.3238606,18.099982738494873,0.032325297404826925,1740481186.323863,18.099982738494873,0.0,1740481186.323864,18.099982738494873,0.9616798446414772,, -1740481186.3447142,18.119982719421387,10.083457424204878,1740481186.3447163,18.119982719421387,0.0,1740481186.3447187,18.119982719421387,0.0,1740481186.3447206,18.119982719421387,14.006817113487832,1740481186.3447213,18.119982719421387,0.0,1740481186.3447227,18.119982719421387,0.0,1740481186.3447237,18.119982719421387,0.0,1740481186.3447247,18.119982719421387,0.0,1740481186.344726,18.119982719421387,0.9940051420463041,1740481186.344727,18.119982719421387,0.0,1740481186.3447282,18.119982719421387,0.032325297404826925,1740481186.3447292,18.119982719421387,0.0,1740481186.3447304,18.119982719421387,0.9616798446414772,, -1740481186.3706157,18.1399827003479,10.189210400288738,1740481186.3706174,18.1399827003479,0.0,1740481186.3706195,18.1399827003479,0.0,1740481186.3706214,18.1399827003479,14.109299439745927,1740481186.3706224,18.1399827003479,0.0,1740481186.3706238,18.1399827003479,0.0,1740481186.3706248,18.1399827003479,0.0,1740481186.3706255,18.1399827003479,0.0,1740481186.3706264,18.1399827003479,0.9934825593435489,1740481186.3706274,18.1399827003479,0.06517440656447215,1740481186.3706284,18.1399827003479,0.09911823857548305,1740481186.370629,18.1399827003479,0.0,1740481186.3706298,18.1399827003479,0.9600445197285938,, -1740481186.3865602,18.159982681274414,10.189210400288738,1740481186.3865633,18.159982681274414,0.0,1740481186.3865666,18.159982681274414,0.0,1740481186.3865688,18.159982681274414,14.109299439745927,1740481186.3865697,18.159982681274414,0.0,1740481186.3865707,18.159982681274414,0.0,1740481186.386572,18.159982681274414,0.0,1740481186.3865728,18.159982681274414,0.0,1740481186.3865738,18.159982681274414,0.9934825593435489,1740481186.3865745,18.159982681274414,0.06517440656447215,1740481186.3865757,18.159982681274414,0.09861244617942722,1740481186.3865764,18.159982681274414,0.0,1740481186.3865771,18.159982681274414,0.9600445197285938,, -1740481186.4047318,18.179982662200928,10.189210400288738,1740481186.4047334,18.179982662200928,0.0,1740481186.4047358,18.179982662200928,0.0,1740481186.4047375,18.179982662200928,14.109299439745927,1740481186.4047387,18.179982662200928,0.0,1740481186.4047399,18.179982662200928,0.0,1740481186.4047408,18.179982662200928,0.0,1740481186.404742,18.179982662200928,0.0,1740481186.404743,18.179982662200928,0.9934825593435489,1740481186.404744,18.179982662200928,0.06517440656447215,1740481186.4047446,18.179982662200928,0.09861244617942722,1740481186.4047456,18.179982662200928,0.0,1740481186.4047465,18.179982662200928,0.9600445197285938,, -1740481186.4259036,18.19998264312744,10.189210400288738,1740481186.4259074,18.19998264312744,0.0,1740481186.4259098,18.19998264312744,0.0,1740481186.4259121,18.19998264312744,14.109299439745927,1740481186.425913,18.19998264312744,0.0,1740481186.4259143,18.19998264312744,0.0,1740481186.425916,18.19998264312744,0.0,1740481186.4259171,18.19998264312744,0.0,1740481186.4259179,18.19998264312744,0.9934825593435489,1740481186.4259198,18.19998264312744,0.06517440656447215,1740481186.4259207,18.19998264312744,0.09861244617942722,1740481186.4259217,18.19998264312744,0.0,1740481186.4259229,18.19998264312744,0.9600445197285938,, -1740481186.4446785,18.219982624053955,10.189210400288738,1740481186.444702,18.219982624053955,0.0,1740481186.4447043,18.219982624053955,0.0,1740481186.444707,18.219982624053955,14.109299439745927,1740481186.4447079,18.219982624053955,0.0,1740481186.444709,18.219982624053955,0.0,1740481186.4447103,18.219982624053955,0.0,1740481186.4447112,18.219982624053955,0.0,1740481186.4447122,18.219982624053955,0.9934825593435489,1740481186.444713,18.219982624053955,0.06517440656447215,1740481186.4447143,18.219982624053955,0.09861244617942722,1740481186.444715,18.219982624053955,0.0,1740481186.4447598,18.219982624053955,0.9600445197285938,, -1740481186.4694004,18.23998260498047,10.2949173179372,1740481186.469402,18.23998260498047,0.0,1740481186.4694042,18.23998260498047,0.0,1740481186.469406,18.23998260498047,14.221457403369758,1740481186.469407,18.23998260498047,0.0,1740481186.4694083,18.23998260498047,0.0,1740481186.469409,18.23998260498047,0.0,1740481186.46941,18.23998260498047,0.0,1740481186.4694111,18.23998260498047,0.9944923641095539,1740481186.469412,18.23998260498047,0.05507635890442231,1740481186.4694128,18.23998260498047,0.08529153469099048,1740481186.4694135,18.23998260498047,0.0,1740481186.4694145,18.23998260498047,0.9632700427162787,, -1740481186.4845397,18.259982585906982,10.2949173179372,1740481186.4845433,18.259982585906982,0.0,1740481186.484548,18.259982585906982,0.0,1740481186.4845505,18.259982585906982,14.221457403369758,1740481186.4845514,18.259982585906982,0.0,1740481186.4845526,18.259982585906982,0.0,1740481186.484554,18.259982585906982,0.0,1740481186.4845552,18.259982585906982,0.0,1740481186.4845564,18.259982585906982,0.9944923641095539,1740481186.4845583,18.259982585906982,0.05507635890442231,1740481186.4845598,18.259982585906982,0.0862986802976975,1740481186.4845612,18.259982585906982,0.0,1740481186.4845629,18.259982585906982,0.9632700427162787,, -1740481186.5038788,18.279982566833496,10.2949173179372,1740481186.5038812,18.279982566833496,0.0,1740481186.5038838,18.279982566833496,0.0,1740481186.5038857,18.279982566833496,14.221457403369758,1740481186.503887,18.279982566833496,0.0,1740481186.5038881,18.279982566833496,0.0,1740481186.503889,18.279982566833496,0.0,1740481186.5038905,18.279982566833496,0.0,1740481186.5038915,18.279982566833496,0.9944923641095539,1740481186.5038924,18.279982566833496,0.05507635890442231,1740481186.5038936,18.279982566833496,0.0862986802976975,1740481186.5038943,18.279982566833496,0.0,1740481186.503895,18.279982566833496,0.9632700427162787,, -1740481186.525964,18.29998254776001,10.2949173179372,1740481186.5259664,18.29998254776001,0.0,1740481186.5259686,18.29998254776001,0.0,1740481186.5259707,18.29998254776001,14.221457403369758,1740481186.5259717,18.29998254776001,0.0,1740481186.525973,18.29998254776001,0.0,1740481186.525974,18.29998254776001,0.0,1740481186.5259748,18.29998254776001,0.0,1740481186.5259762,18.29998254776001,0.9944923641095539,1740481186.5259774,18.29998254776001,0.05507635890442231,1740481186.525978,18.29998254776001,0.0862986802976975,1740481186.525979,18.29998254776001,0.0,1740481186.5259802,18.29998254776001,0.9632700427162787,, -1740481186.5455716,18.319982528686523,10.2949173179372,1740481186.5455735,18.319982528686523,0.0,1740481186.5455754,18.319982528686523,0.0,1740481186.5455775,18.319982528686523,14.221457403369758,1740481186.5455785,18.319982528686523,0.0,1740481186.5455794,18.319982528686523,0.0,1740481186.5455806,18.319982528686523,0.0,1740481186.5455816,18.319982528686523,0.0,1740481186.5455825,18.319982528686523,0.9944923641095539,1740481186.5455832,18.319982528686523,0.05507635890442231,1740481186.5455844,18.319982528686523,0.0862986802976975,1740481186.5455852,18.319982528686523,0.0,1740481186.5455863,18.319982528686523,0.9632700427162787,, -1740481186.5685804,18.339982509613037,10.2949173179372,1740481186.5685823,18.339982509613037,0.0,1740481186.5685844,18.339982509613037,0.0,1740481186.5685866,18.339982509613037,14.221457403369758,1740481186.5685875,18.339982509613037,0.0,1740481186.5685887,18.339982509613037,0.0,1740481186.56859,18.339982509613037,0.0,1740481186.5685909,18.339982509613037,0.0,1740481186.5685916,18.339982509613037,0.9944923641095539,1740481186.5685925,18.339982509613037,0.05507635890442231,1740481186.5685937,18.339982509613037,0.0862986802976975,1740481186.5685947,18.339982509613037,0.0,1740481186.5685954,18.339982509613037,0.9632700427162787,, -1740481186.5848248,18.35998249053955,10.40104677432711,1740481186.584827,18.35998249053955,0.0,1740481186.5848289,18.35998249053955,0.017235415546903304,1740481186.584831,18.35998249053955,14.245243811372855,1740481186.5848317,18.35998249053955,0.0,1740481186.584833,18.35998249053955,0.0,1740481186.584834,18.35998249053955,0.0,1740481186.584835,18.35998249053955,0.0,1740481186.584836,18.35998249053955,0.9999999999999961,1740481186.584837,18.35998249053955,5.551115123125783e-15,1740481186.5848377,18.35998249053955,0.034469070960662096,1740481186.5848389,18.35998249053955,0.0,1740481186.5848396,18.35998249053955,0.9665455389443763,, -1740481186.6058142,18.379982471466064,10.40104677432711,1740481186.6058168,18.379982471466064,0.0,1740481186.6058192,18.379982471466064,0.017235415546903304,1740481186.6058214,18.379982471466064,14.245243811372855,1740481186.6058226,18.379982471466064,0.0,1740481186.605824,18.379982471466064,0.0,1740481186.6058252,18.379982471466064,0.0,1740481186.6058266,18.379982471466064,0.0,1740481186.6058276,18.379982471466064,0.9999999999999961,1740481186.6058288,18.379982471466064,5.551115123125783e-15,1740481186.60583,18.379982471466064,0.03345446105562533,1740481186.6058311,18.379982471466064,0.0,1740481186.605832,18.379982471466064,0.9665455389443763,, -1740481186.6265132,18.399982452392578,10.40104677432711,1740481186.6265152,18.399982452392578,0.0,1740481186.626518,18.399982452392578,0.017235415546903304,1740481186.6265204,18.399982452392578,14.245243811372855,1740481186.6265213,18.399982452392578,0.0,1740481186.6265225,18.399982452392578,0.0,1740481186.6265237,18.399982452392578,0.0,1740481186.6265247,18.399982452392578,0.0,1740481186.6265256,18.399982452392578,0.9999999999999961,1740481186.626527,18.399982452392578,5.551115123125783e-15,1740481186.626528,18.399982452392578,0.03345446105562533,1740481186.6265287,18.399982452392578,0.0,1740481186.6265297,18.399982452392578,0.9665455389443763,, -1740481186.6450808,18.419982433319092,10.40104677432711,1740481186.6450849,18.419982433319092,0.0,1740481186.6450882,18.419982433319092,0.017235415546903304,1740481186.6450903,18.419982433319092,14.245243811372855,1740481186.6450918,18.419982433319092,0.0,1740481186.6450937,18.419982433319092,0.0,1740481186.6450958,18.419982433319092,0.0,1740481186.6450975,18.419982433319092,0.0,1740481186.6450992,18.419982433319092,0.9999999999999961,1740481186.6451015,18.419982433319092,5.551115123125783e-15,1740481186.6451037,18.419982433319092,0.03345446105562533,1740481186.6451051,18.419982433319092,0.0,1740481186.6451073,18.419982433319092,0.9665455389443763,, -1740481186.6673524,18.439982414245605,10.40104677432711,1740481186.6673543,18.439982414245605,0.0,1740481186.6673565,18.439982414245605,0.0,1740481186.6673584,18.439982414245605,14.334137852215862,1740481186.6673596,18.439982414245605,0.0,1740481186.6673608,18.439982414245605,0.0,1740481186.6673617,18.439982414245605,0.0,1740481186.667363,18.439982414245605,0.0,1740481186.6673636,18.439982414245605,0.9954308811954881,1740481186.6673646,18.439982414245605,0.0,1740481186.6673656,18.439982414245605,0.028885342251111723,1740481186.6673665,18.439982414245605,0.0,1740481186.6673672,18.439982414245605,0.9665455389443763,, -1740481186.6836257,18.45998239517212,10.507287821250857,1740481186.6836276,18.45998239517212,0.0,1740481186.6836295,18.45998239517212,0.017269820258691847,1740481186.6836314,18.45998239517212,14.347006041239649,1740481186.6836324,18.45998239517212,0.0,1740481186.6836336,18.45998239517212,0.0,1740481186.6836348,18.45998239517212,0.0,1740481186.6836357,18.45998239517212,0.0,1740481186.6836367,18.45998239517212,0.9954308811954881,1740481186.6836376,18.45998239517212,0.045691188045080544,1740481186.6836386,18.45998239517212,0.07777771760287931,1740481186.6836395,18.45998239517212,0.0,1740481186.6836402,18.45998239517212,0.9643447233269238,, -1740481186.7043273,18.479982376098633,10.507287821250857,1740481186.7043293,18.479982376098633,0.0,1740481186.7043316,18.479982376098633,0.017269820258691847,1740481186.7043335,18.479982376098633,14.347006041239649,1740481186.7043345,18.479982376098633,0.0,1740481186.7043357,18.479982376098633,0.0,1740481186.7043366,18.479982376098633,0.0,1740481186.7043376,18.479982376098633,0.0,1740481186.7043393,18.479982376098633,0.9954308811954881,1740481186.7043402,18.479982376098633,0.045691188045080544,1740481186.7043412,18.479982376098633,0.07677734591364482,1740481186.7043424,18.479982376098633,0.0,1740481186.704343,18.479982376098633,0.9643447233269238,, -1740481186.7237387,18.499982357025146,10.507287821250857,1740481186.7237408,18.499982357025146,0.0,1740481186.723743,18.499982357025146,0.017269820258691847,1740481186.7237453,18.499982357025146,14.347006041239649,1740481186.7237465,18.499982357025146,0.0,1740481186.7237477,18.499982357025146,0.0,1740481186.723749,18.499982357025146,0.0,1740481186.7237499,18.499982357025146,0.0,1740481186.7237506,18.499982357025146,0.9954308811954881,1740481186.723752,18.499982357025146,0.045691188045080544,1740481186.723753,18.499982357025146,0.07677734591364482,1740481186.723754,18.499982357025146,0.0,1740481186.7237546,18.499982357025146,0.9643447233269238,, -1740481186.7440987,18.51998233795166,10.507287821250857,1740481186.7441003,18.51998233795166,0.0,1740481186.7441027,18.51998233795166,0.017269820258691847,1740481186.7441046,18.51998233795166,14.347006041239649,1740481186.7441056,18.51998233795166,0.0,1740481186.7441068,18.51998233795166,0.0,1740481186.744108,18.51998233795166,0.0,1740481186.7441092,18.51998233795166,0.0,1740481186.7441103,18.51998233795166,0.9954308811954881,1740481186.7441113,18.51998233795166,0.045691188045080544,1740481186.7441125,18.51998233795166,0.07677734591364482,1740481186.7441134,18.51998233795166,0.0,1740481186.7441144,18.51998233795166,0.9643447233269238,, -1740481186.7670758,18.539982318878174,10.507287821250857,1740481186.7670798,18.539982318878174,0.0,1740481186.7670848,18.539982318878174,0.0,1740481186.767089,18.539982318878174,14.435977267904704,1740481186.767091,18.539982318878174,0.0,1740481186.7670934,18.539982318878174,0.0,1740481186.7670958,18.539982318878174,0.0,1740481186.767098,18.539982318878174,0.0,1740481186.7671003,18.539982318878174,0.9948099445675228,1740481186.7671025,18.539982318878174,0.0,1740481186.7671046,18.539982318878174,0.030465221240599027,1740481186.7671068,18.539982318878174,0.0,1740481186.7671094,18.539982318878174,0.9643447233269238,, -1740481186.7835572,18.559982299804688,10.507287821250857,1740481186.7835588,18.559982299804688,0.0,1740481186.7835612,18.559982299804688,0.0,1740481186.7835634,18.559982299804688,14.435977267904704,1740481186.7835643,18.559982299804688,0.0,1740481186.7835653,18.559982299804688,0.0,1740481186.7835662,18.559982299804688,0.0,1740481186.7835674,18.559982299804688,0.0,1740481186.7835684,18.559982299804688,0.9948099445675228,1740481186.7835693,18.559982299804688,0.0,1740481186.7835703,18.559982299804688,0.030465221240599027,1740481186.7835712,18.559982299804688,0.0,1740481186.783572,18.559982299804688,0.9643447233269238,, -1740481186.8034077,18.5799822807312,10.613459458334486,1740481186.8034093,18.5799822807312,0.0,1740481186.8034115,18.5799822807312,0.017247771820721874,1740481186.8034134,18.5799822807312,14.454710648726502,1740481186.8034143,18.5799822807312,0.0,1740481186.8034155,18.5799822807312,0.0,1740481186.8034165,18.5799822807312,0.0,1740481186.8034174,18.5799822807312,0.0,1740481186.8034184,18.5799822807312,0.9948099445675228,1740481186.8034196,18.5799822807312,0.05190055432473306,1740481186.8034203,18.5799822807312,0.08128533233346176,1740481186.8034215,18.5799822807312,0.0,1740481186.8034225,18.5799822807312,0.9650875278274614,, -1740481186.8233912,18.599982261657715,10.613459458334486,1740481186.823393,18.599982261657715,0.0,1740481186.823395,18.599982261657715,0.017247771820721874,1740481186.823397,18.599982261657715,14.454710648726502,1740481186.8233979,18.599982261657715,0.0,1740481186.823399,18.599982261657715,0.0,1740481186.8234,18.599982261657715,0.0,1740481186.823401,18.599982261657715,0.0,1740481186.8234017,18.599982261657715,0.9948099445675228,1740481186.8234026,18.599982261657715,0.05190055432473306,1740481186.8234038,18.599982261657715,0.08162297106479444,1740481186.8234046,18.599982261657715,0.0,1740481186.8234055,18.599982261657715,0.9650875278274614,, -1740481186.845877,18.61998224258423,10.613459458334486,1740481186.845879,18.61998224258423,0.0,1740481186.845881,18.61998224258423,0.017247771820721874,1740481186.845883,18.61998224258423,14.454710648726502,1740481186.8458838,18.61998224258423,0.0,1740481186.8458853,18.61998224258423,0.0,1740481186.8458865,18.61998224258423,0.0,1740481186.8458874,18.61998224258423,0.0,1740481186.8458886,18.61998224258423,0.9948099445675228,1740481186.8458896,18.61998224258423,0.05190055432473306,1740481186.8458903,18.61998224258423,0.08162297106479444,1740481186.845891,18.61998224258423,0.0,1740481186.8458922,18.61998224258423,0.9650875278274614,, -1740481186.8667853,18.639982223510742,10.613459458334486,1740481186.8667867,18.639982223510742,0.0,1740481186.866789,18.639982223510742,0.0,1740481186.8667912,18.639982223510742,14.543634513989408,1740481186.866792,18.639982223510742,0.0,1740481186.8667932,18.639982223510742,0.0,1740481186.8667943,18.639982223510742,0.0,1740481186.8667953,18.639982223510742,0.0,1740481186.8667963,18.639982223510742,0.9950239403255775,1740481186.8667972,18.639982223510742,0.0,1740481186.8667982,18.639982223510742,0.029936412498116072,1740481186.866799,18.639982223510742,0.0,1740481186.8667998,18.639982223510742,0.9650875278274614,, -1740481186.88587,18.659982204437256,10.613459458334486,1740481186.885872,18.659982204437256,0.0,1740481186.8858743,18.659982204437256,0.0,1740481186.885876,18.659982204437256,14.543634513989408,1740481186.885877,18.659982204437256,0.0,1740481186.8858783,18.659982204437256,0.0,1740481186.8858793,18.659982204437256,0.0,1740481186.8858802,18.659982204437256,0.0,1740481186.8858814,18.659982204437256,0.9950239403255775,1740481186.885896,18.659982204437256,0.0,1740481186.8858979,18.659982204437256,0.029936412498116072,1740481186.885899,18.659982204437256,0.0,1740481186.8859,18.659982204437256,0.9650875278274614,, -1740481186.9039137,18.67998218536377,10.719668543701626,1740481186.903916,18.67998218536377,0.0,1740481186.9039183,18.67998218536377,0.01725756687599937,1740481186.9039202,18.67998218536377,14.56100566399455,1740481186.9039211,18.67998218536377,0.0,1740481186.9039223,18.67998218536377,0.0,1740481186.9039235,18.67998218536377,0.0,1740481186.9039245,18.67998218536377,0.0,1740481186.9039254,18.67998218536377,0.9950239403255775,1740481186.9039264,18.67998218536377,0.04976059674418609,1740481186.9039273,18.67998218536377,0.07961440330558063,1740481186.9039283,18.67998218536377,0.0,1740481186.9039292,18.67998218536377,0.9651443193920323,, -1740481186.9262974,18.699982166290283,10.719668543701626,1740481186.9262993,18.699982166290283,0.0,1740481186.9263015,18.699982166290283,0.01725756687599937,1740481186.9263031,18.699982166290283,14.56100566399455,1740481186.9263043,18.699982166290283,0.0,1740481186.9263055,18.699982166290283,0.0,1740481186.9263065,18.699982166290283,0.0,1740481186.9263077,18.699982166290283,0.0,1740481186.9263086,18.699982166290283,0.9950239403255775,1740481186.9264796,18.699982166290283,0.04976059674418609,1740481186.9264839,18.699982166290283,0.07964021767773133,1740481186.926485,18.699982166290283,0.0,1740481186.9264858,18.699982166290283,0.9651443193920323,, -1740481186.9449685,18.719982147216797,10.719668543701626,1740481186.9449701,18.719982147216797,0.0,1740481186.9449723,18.719982147216797,0.01725756687599937,1740481186.9449744,18.719982147216797,14.56100566399455,1740481186.9449756,18.719982147216797,0.0,1740481186.9449766,18.719982147216797,0.0,1740481186.9449778,18.719982147216797,0.0,1740481186.944979,18.719982147216797,0.0,1740481186.94498,18.719982147216797,0.9950239403255775,1740481186.9449806,18.719982147216797,0.04976059674418609,1740481186.9449816,18.719982147216797,0.07964021767773133,1740481186.9449825,18.719982147216797,0.0,1740481186.9449835,18.719982147216797,0.9651443193920323,, -1740481186.9701383,18.73998212814331,10.719668543701626,1740481186.9701402,18.73998212814331,0.0,1740481186.9701424,18.73998212814331,0.0,1740481186.9701443,18.73998212814331,14.649957182485691,1740481186.9701452,18.73998212814331,0.0,1740481186.9701467,18.73998212814331,0.0,1740481186.9701478,18.73998212814331,0.0,1740481186.970149,18.73998212814331,0.0,1740481186.9701502,18.73998212814331,0.995040116113063,1740481186.9701512,18.73998212814331,0.0,1740481186.970152,18.73998212814331,0.02989579672103071,1740481186.9701526,18.73998212814331,0.0,1740481186.9701538,18.73998212814331,0.9651443193920323,, -1740481186.9846973,18.759982109069824,10.719668543701626,1740481186.9846992,18.759982109069824,0.0,1740481186.9847014,18.759982109069824,0.0,1740481186.9847033,18.759982109069824,14.649957182485691,1740481186.9847043,18.759982109069824,0.0,1740481186.9847054,18.759982109069824,0.0,1740481186.9847064,18.759982109069824,0.0,1740481186.9847074,18.759982109069824,0.0,1740481186.9847083,18.759982109069824,0.995040116113063,1740481186.984709,18.759982109069824,0.0,1740481186.9847102,18.759982109069824,0.02989579672103071,1740481186.984711,18.759982109069824,0.0,1740481186.984712,18.759982109069824,0.9651443193920323,, -1740481187.0060513,18.779982089996338,10.719668543701626,1740481187.0060534,18.779982089996338,0.0,1740481187.0060565,18.779982089996338,0.0,1740481187.0060585,18.779982089996338,14.649957182485691,1740481187.0060594,18.779982089996338,0.0,1740481187.0060608,18.779982089996338,0.0,1740481187.0060618,18.779982089996338,0.0,1740481187.0060632,18.779982089996338,0.0,1740481187.0060642,18.779982089996338,0.995040116113063,1740481187.006065,18.779982089996338,0.0,1740481187.0060658,18.779982089996338,0.02989579672103071,1740481187.006067,18.779982089996338,0.0,1740481187.0060678,18.779982089996338,0.9651443193920323,, -1740481187.0239363,18.79998207092285,10.825925658849366,1740481187.0239384,18.79998207092285,0.0,1740481187.0239403,18.79998207092285,0.017265651755587672,1740481187.0239425,18.79998207092285,14.668084552175264,1740481187.0239434,18.79998207092285,0.0,1740481187.0239444,18.79998207092285,0.0,1740481187.0239456,18.79998207092285,0.0,1740481187.0239468,18.79998207092285,0.0,1740481187.0239477,18.79998207092285,0.995040116113063,1740481187.0239484,18.79998207092285,0.04959883886933136,1740481187.0239496,18.79998207092285,0.07886793145159987,1740481187.0239506,18.79998207092285,0.0,1740481187.0239513,18.79998207092285,0.9655751783590252,, -1740481187.0437365,18.819982051849365,10.825925658849366,1740481187.0437384,18.819982051849365,0.0,1740481187.0437407,18.819982051849365,0.017265651755587672,1740481187.0437427,18.819982051849365,14.668084552175264,1740481187.0437438,18.819982051849365,0.0,1740481187.0437448,18.819982051849365,0.0,1740481187.0437458,18.819982051849365,0.0,1740481187.0437467,18.819982051849365,0.0,1740481187.0437481,18.819982051849365,0.995040116113063,1740481187.043749,18.819982051849365,0.04959883886933136,1740481187.0437498,18.819982051849365,0.07906377662336916,1740481187.043751,18.819982051849365,0.0,1740481187.043752,18.819982051849365,0.9655751783590252,, -1740481187.0649254,18.83998203277588,10.825925658849366,1740481187.0649276,18.83998203277588,0.0,1740481187.0649297,18.83998203277588,0.0,1740481187.0649319,18.83998203277588,14.757076015567417,1740481187.0649328,18.83998203277588,0.0,1740481187.0649345,18.83998203277588,0.0,1740481187.0649354,18.83998203277588,0.0,1740481187.0649364,18.83998203277588,0.0,1740481187.0649374,18.83998203277588,0.9951619787406595,1740481187.0649385,18.83998203277588,0.0,1740481187.0649393,18.83998203277588,0.029586800381634304,1740481187.0649402,18.83998203277588,0.0,1740481187.0649414,18.83998203277588,0.9655751783590252,, -1740481187.084891,18.859982013702393,10.825925658849366,1740481187.084893,18.859982013702393,0.0,1740481187.0848958,18.859982013702393,0.0,1740481187.0848978,18.859982013702393,14.757076015567417,1740481187.0848987,18.859982013702393,0.0,1740481187.0849001,18.859982013702393,0.0,1740481187.084901,18.859982013702393,0.0,1740481187.084902,18.859982013702393,0.0,1740481187.084903,18.859982013702393,0.9951619787406595,1740481187.084904,18.859982013702393,0.0,1740481187.0849047,18.859982013702393,0.029586800381634304,1740481187.0849056,18.859982013702393,0.0,1740481187.0849066,18.859982013702393,0.9655751783590252,, -1740481187.1039379,18.879981994628906,10.825925658849366,1740481187.1039393,18.879981994628906,0.0,1740481187.1039414,18.879981994628906,0.0,1740481187.1039433,18.879981994628906,14.757076015567417,1740481187.1039445,18.879981994628906,0.0,1740481187.1039455,18.879981994628906,0.0,1740481187.1039464,18.879981994628906,0.0,1740481187.1039479,18.879981994628906,0.0,1740481187.1039488,18.879981994628906,0.9951619787406595,1740481187.1039495,18.879981994628906,0.0,1740481187.1039505,18.879981994628906,0.029586800381634304,1740481187.1039515,18.879981994628906,0.0,1740481187.1039524,18.879981994628906,0.9655751783590252,, -1740481187.1235642,18.89998197555542,10.932133228619435,1740481187.1235673,18.89998197555542,0.0,1740481187.123571,18.89998197555542,0.017259714697890706,1740481187.1235733,18.89998197555542,14.772129655461775,1740481187.1235745,18.89998197555542,0.0,1740481187.1235754,18.89998197555542,0.0,1740481187.1235769,18.89998197555542,0.0,1740481187.1235778,18.89998197555542,0.0,1740481187.123591,18.89998197555542,0.9951619787406595,1740481187.1235933,18.89998197555542,0.048380212593366334,1740481187.1235943,18.89998197555542,0.07957143149208776,1740481187.1235952,18.89998197555542,0.0,1740481187.123596,18.89998197555542,0.9644721409572589,, -1740481187.1436777,18.919981956481934,10.932133228619435,1740481187.1436803,18.919981956481934,0.0,1740481187.1436825,18.919981956481934,0.017259714697890706,1740481187.1436846,18.919981956481934,14.772129655461775,1740481187.1436856,18.919981956481934,0.0,1740481187.143687,18.919981956481934,0.0,1740481187.1436882,18.919981956481934,0.0,1740481187.1436892,18.919981956481934,0.0,1740481187.1436903,18.919981956481934,0.9951619787406595,1740481187.1436913,18.919981956481934,0.048380212593366334,1740481187.143692,18.919981956481934,0.07907005037676695,1740481187.143693,18.919981956481934,0.0,1740481187.143694,18.919981956481934,0.9644721409572589,, -1740481187.1667068,18.939981937408447,10.932133228619435,1740481187.1667085,18.939981937408447,0.0,1740481187.1667109,18.939981937408447,0.0,1740481187.1667128,18.939981937408447,14.861077510533953,1740481187.166714,18.939981937408447,0.0,1740481187.166715,18.939981937408447,0.0,1740481187.1667159,18.939981937408447,0.0,1740481187.1667168,18.939981937408447,0.0,1740481187.166718,18.939981937408447,0.9948469726322369,1740481187.1667187,18.939981937408447,0.0,1740481187.166732,18.939981937408447,0.03037483167497801,1740481187.1667335,18.939981937408447,0.0,1740481187.1667342,18.939981937408447,0.9644721409572589,, -1740481187.1842113,18.95998191833496,10.932133228619435,1740481187.1842127,18.95998191833496,0.0,1740481187.184215,18.95998191833496,0.0,1740481187.184217,18.95998191833496,14.861077510533953,1740481187.1842182,18.95998191833496,0.0,1740481187.1842194,18.95998191833496,0.0,1740481187.1842208,18.95998191833496,0.0,1740481187.1842217,18.95998191833496,0.0,1740481187.1842225,18.95998191833496,0.9948469726322369,1740481187.1842234,18.95998191833496,0.0,1740481187.1842246,18.95998191833496,0.03037483167497801,1740481187.1842256,18.95998191833496,0.0,1740481187.1842263,18.95998191833496,0.9644721409572589,, -1740481187.2040532,18.979981899261475,10.932133228619435,1740481187.204055,18.979981899261475,0.0,1740481187.2040575,18.979981899261475,0.0,1740481187.2040594,18.979981899261475,14.861077510533953,1740481187.2040603,18.979981899261475,0.0,1740481187.2040617,18.979981899261475,0.0,1740481187.2040627,18.979981899261475,0.0,1740481187.2040637,18.979981899261475,0.0,1740481187.2040648,18.979981899261475,0.9948469726322369,1740481187.2040658,18.979981899261475,0.0,1740481187.2040668,18.979981899261475,0.03037483167497801,1740481187.2040682,18.979981899261475,0.0,1740481187.204069,18.979981899261475,0.9644721409572589,, -1740481187.2253335,18.99998188018799,10.932133228619435,1740481187.2253354,18.99998188018799,0.0,1740481187.2253373,18.99998188018799,0.0,1740481187.2253392,18.99998188018799,14.861077510533953,1740481187.2253401,18.99998188018799,0.0,1740481187.2253418,18.99998188018799,0.0,1740481187.2253428,18.99998188018799,0.0,1740481187.2253437,18.99998188018799,0.0,1740481187.2253447,18.99998188018799,0.9948469726322369,1740481187.2253458,18.99998188018799,0.0,1740481187.2253594,18.99998188018799,0.03037483167497801,1740481187.2253616,18.99998188018799,0.0,1740481187.225363,18.99998188018799,0.9644721409572589,, -1740481187.2437696,19.019981861114502,11.03824222008845,1740481187.2437716,19.019981861114502,0.0,1740481187.2437737,19.019981861114502,0.01723823653363268,1740481187.2437758,19.019981861114502,14.876255870754214,1740481187.2437768,19.019981861114502,0.0,1740481187.243778,19.019981861114502,0.0,1740481187.2437792,19.019981861114502,0.0,1740481187.2437804,19.019981861114502,0.0,1740481187.2437813,19.019981861114502,0.9948469726322369,1740481187.2437823,19.019981861114502,0.05153027367776897,1740481187.2437832,19.019981861114502,0.08340319766348324,1740481187.2437842,19.019981861114502,0.0,1740481187.2437854,19.019981861114502,0.9634422028005735,, -1740481187.2654252,19.039981842041016,11.03824222008845,1740481187.2654295,19.039981842041016,0.0,1740481187.2654328,19.039981842041016,0.0,1740481187.2654357,19.039981842041016,14.965126625689596,1740481187.265437,19.039981842041016,0.0,1740481187.265439,19.039981842041016,0.0,1740481187.2654405,19.039981842041016,0.0,1740481187.26546,19.039981842041016,0.0,1740481187.2654643,19.039981842041016,0.9945438737189592,1740481187.265466,19.039981842041016,0.0,1740481187.2654672,19.039981842041016,0.031101670918385782,1740481187.265469,19.039981842041016,0.0,1740481187.265472,19.039981842041016,0.9634422028005735,, -1740481187.28419,19.05998182296753,11.03824222008845,1740481187.284193,19.05998182296753,0.0,1740481187.2841964,19.05998182296753,0.0,1740481187.2841992,19.05998182296753,14.965126625689596,1740481187.2842004,19.05998182296753,0.0,1740481187.284202,19.05998182296753,0.0,1740481187.2842033,19.05998182296753,0.0,1740481187.2842045,19.05998182296753,0.0,1740481187.284206,19.05998182296753,0.9945438737189592,1740481187.2842073,19.05998182296753,0.0,1740481187.2842083,19.05998182296753,0.031101670918385782,1740481187.2842097,19.05998182296753,0.0,1740481187.284211,19.05998182296753,0.9634422028005735,, -1740481187.3043385,19.079981803894043,11.03824222008845,1740481187.3043408,19.079981803894043,0.0,1740481187.3043432,19.079981803894043,0.0,1740481187.3043458,19.079981803894043,14.965126625689596,1740481187.3043468,19.079981803894043,0.0,1740481187.3043485,19.079981803894043,0.0,1740481187.3043497,19.079981803894043,0.0,1740481187.304351,19.079981803894043,0.0,1740481187.3043523,19.079981803894043,0.9945438737189592,1740481187.3043535,19.079981803894043,0.0,1740481187.3043547,19.079981803894043,0.031101670918385782,1740481187.3043556,19.079981803894043,0.0,1740481187.3043566,19.079981803894043,0.9634422028005735,, -1740481187.323753,19.099981784820557,11.03824222008845,1740481187.3237553,19.099981784820557,0.0,1740481187.3237581,19.099981784820557,0.0,1740481187.32376,19.099981784820557,14.965126625689596,1740481187.3237612,19.099981784820557,0.0,1740481187.3237624,19.099981784820557,0.0,1740481187.3237636,19.099981784820557,0.0,1740481187.3237648,19.099981784820557,0.0,1740481187.3237658,19.099981784820557,0.9945438737189592,1740481187.3237667,19.099981784820557,0.0,1740481187.323768,19.099981784820557,0.031101670918385782,1740481187.3237686,19.099981784820557,0.0,1740481187.3237696,19.099981784820557,0.9634422028005735,, -1740481187.3436203,19.11998176574707,11.144164180106086,1740481187.3436222,19.11998176574707,0.0,1740481187.343625,19.11998176574707,0.017202609112892373,1740481187.343627,19.11998176574707,14.978617027838546,1740481187.343628,19.11998176574707,0.0,1740481187.3436296,19.11998176574707,0.0,1740481187.3436306,19.11998176574707,0.0,1740481187.343632,19.11998176574707,0.0,1740481187.343633,19.11998176574707,0.9945438737189592,1740481187.343634,19.11998176574707,0.05456126281036866,1740481187.3436348,19.11998176574707,0.08836272141622223,1740481187.3436363,19.11998176574707,0.0,1740481187.3436375,19.11998176574707,0.9615860993186018,, -1740481187.3674242,19.139981746673584,11.144164180106086,1740481187.3674269,19.139981746673584,0.0,1740481187.3674297,19.139981746673584,0.0,1740481187.3674316,19.139981746673584,15.06733637874329,1740481187.367433,19.139981746673584,0.0,1740481187.3674345,19.139981746673584,0.0,1740481187.367436,19.139981746673584,0.0,1740481187.3674371,19.139981746673584,0.0,1740481187.367438,19.139981746673584,0.9939757748734914,1740481187.3674388,19.139981746673584,0.0,1740481187.36744,19.139981746673584,0.032389675554889585,1740481187.367441,19.139981746673584,0.0,1740481187.367442,19.139981746673584,0.9615860993186018,, -1740481187.383887,19.159981727600098,11.144164180106086,1740481187.383889,19.159981727600098,0.0,1740481187.383891,19.159981727600098,0.0,1740481187.3838935,19.159981727600098,15.06733637874329,1740481187.3838944,19.159981727600098,0.0,1740481187.3838959,19.159981727600098,0.0,1740481187.3838968,19.159981727600098,0.0,1740481187.3838978,19.159981727600098,0.0,1740481187.383899,19.159981727600098,0.9939757748734914,1740481187.3839,19.159981727600098,0.0,1740481187.383901,19.159981727600098,0.032389675554889585,1740481187.3839018,19.159981727600098,0.0,1740481187.3839028,19.159981727600098,0.9615860993186018,, -1740481187.4039562,19.17998170852661,11.144164180106086,1740481187.403958,19.17998170852661,0.0,1740481187.4039602,19.17998170852661,0.0,1740481187.4039624,19.17998170852661,15.06733637874329,1740481187.4039633,19.17998170852661,0.0,1740481187.4039648,19.17998170852661,0.0,1740481187.403966,19.17998170852661,0.0,1740481187.403967,19.17998170852661,0.0,1740481187.403968,19.17998170852661,0.9939757748734914,1740481187.403969,19.17998170852661,0.0,1740481187.4039698,19.17998170852661,0.032389675554889585,1740481187.4039707,19.17998170852661,0.0,1740481187.403972,19.17998170852661,0.9615860993186018,, -1740481187.423939,19.199981689453125,11.144164180106086,1740481187.423941,19.199981689453125,0.0,1740481187.4239435,19.199981689453125,0.0,1740481187.4239454,19.199981689453125,15.06733637874329,1740481187.4239464,19.199981689453125,0.0,1740481187.423948,19.199981689453125,0.0,1740481187.423949,19.199981689453125,0.0,1740481187.4239502,19.199981689453125,0.0,1740481187.4239511,19.199981689453125,0.9939757748734914,1740481187.4239519,19.199981689453125,0.0,1740481187.4239528,19.199981689453125,0.032389675554889585,1740481187.423954,19.199981689453125,0.0,1740481187.423955,19.199981689453125,0.9615860993186018,, -1740481187.4444535,19.21998167037964,11.144164180106086,1740481187.4444575,19.21998167037964,0.0,1740481187.444461,19.21998167037964,0.0,1740481187.4444633,19.21998167037964,15.06733637874329,1740481187.4444644,19.21998167037964,0.0,1740481187.4444664,19.21998167037964,0.0,1740481187.4444675,19.21998167037964,0.0,1740481187.444469,19.21998167037964,0.0,1740481187.4444706,19.21998167037964,0.9939757748734914,1740481187.4444885,19.21998167037964,0.0,1740481187.4444892,19.21998167037964,0.032389675554889585,1740481187.4444911,19.21998167037964,0.0,1740481187.4444935,19.21998167037964,0.9615860993186018,, -1740481187.4667,19.239981651306152,11.24990782233614,1740481187.466702,19.239981651306152,0.0,1740481187.4667046,19.239981651306152,0.0,1740481187.466707,19.239981651306152,15.169837266746306,1740481187.4667077,19.239981651306152,0.0,1740481187.466709,19.239981651306152,0.0,1740481187.46671,19.239981651306152,0.0,1740481187.466711,19.239981651306152,0.0,1740481187.4667118,19.239981651306152,0.9934565005922579,1740481187.4667127,19.239981651306152,0.06543499407755893,1740481187.4667137,19.239981651306152,0.09942772877534073,1740481187.4667146,19.239981651306152,0.0,1740481187.4667153,19.239981651306152,0.9599647222050824,, -1740481187.4846838,19.259981632232666,11.24990782233614,1740481187.4846866,19.259981632232666,0.0,1740481187.484689,19.259981632232666,0.0,1740481187.4846911,19.259981632232666,15.169837266746306,1740481187.4846923,19.259981632232666,0.0,1740481187.4846935,19.259981632232666,0.0,1740481187.4846945,19.259981632232666,0.0,1740481187.4846954,19.259981632232666,0.0,1740481187.4846966,19.259981632232666,0.9934565005922579,1740481187.4846976,19.259981632232666,0.06543499407755893,1740481187.4846983,19.259981632232666,0.09892677246473436,1740481187.4846995,19.259981632232666,0.0,1740481187.4847004,19.259981632232666,0.9599647222050824,, -1740481187.5047328,19.27998161315918,11.24990782233614,1740481187.504735,19.27998161315918,0.0,1740481187.5047376,19.27998161315918,0.0,1740481187.5047395,19.27998161315918,15.169837266746306,1740481187.5047407,19.27998161315918,0.0,1740481187.504742,19.27998161315918,0.0,1740481187.5047429,19.27998161315918,0.0,1740481187.504744,19.27998161315918,0.0,1740481187.504745,19.27998161315918,0.9934565005922579,1740481187.504746,19.27998161315918,0.06543499407755893,1740481187.504747,19.27998161315918,0.09892677246473436,1740481187.504748,19.27998161315918,0.0,1740481187.504749,19.27998161315918,0.9599647222050824,, -1740481187.5245132,19.299981594085693,11.24990782233614,1740481187.5245152,19.299981594085693,0.0,1740481187.5245173,19.299981594085693,0.0,1740481187.5245194,19.299981594085693,15.169837266746306,1740481187.5245204,19.299981594085693,0.0,1740481187.5245218,19.299981594085693,0.0,1740481187.5245225,19.299981594085693,0.0,1740481187.5245235,19.299981594085693,0.0,1740481187.5245245,19.299981594085693,0.9934565005922579,1740481187.5245256,19.299981594085693,0.06543499407755893,1740481187.5245266,19.299981594085693,0.09892677246473436,1740481187.5245273,19.299981594085693,0.0,1740481187.5245283,19.299981594085693,0.9599647222050824,, -1740481187.5447516,19.319981575012207,11.24990782233614,1740481187.5447552,19.319981575012207,0.0,1740481187.5447598,19.319981575012207,0.0,1740481187.5447628,19.319981575012207,15.169837266746306,1740481187.5447638,19.319981575012207,0.0,1740481187.5447657,19.319981575012207,0.0,1740481187.5447671,19.319981575012207,0.0,1740481187.544769,19.319981575012207,0.0,1740481187.544772,19.319981575012207,0.9934565005922579,1740481187.5447738,19.319981575012207,0.06543499407755893,1740481187.5447757,19.319981575012207,0.09892677246473436,1740481187.5447779,19.319981575012207,0.0,1740481187.5447795,19.319981575012207,0.9599647222050824,, -1740481187.5660923,19.33998155593872,11.355667407889465,1740481187.5660942,19.33998155593872,0.0,1740481187.5660963,19.33998155593872,0.0,1740481187.5660985,19.33998155593872,15.28344042393136,1740481187.5660992,19.33998155593872,0.0,1740481187.5661006,19.33998155593872,0.0,1740481187.5661016,19.33998155593872,0.0,1740481187.5661025,19.33998155593872,0.0,1740481187.5661035,19.33998155593872,0.9946756898788307,1740481187.5661044,19.33998155593872,0.0532431012116541,1740481187.5661054,19.33998155593872,0.08280382893013229,1740481187.566106,19.33998155593872,0.0,1740481187.566107,19.33998155593872,0.9638865080209473,, -1740481187.5836558,19.359981536865234,11.355667407889465,1740481187.5836577,19.359981536865234,0.0,1740481187.5836601,19.359981536865234,0.0,1740481187.583662,19.359981536865234,15.28344042393136,1740481187.583663,19.359981536865234,0.0,1740481187.5836644,19.359981536865234,0.0,1740481187.5836654,19.359981536865234,0.0,1740481187.5836668,19.359981536865234,0.0,1740481187.5836682,19.359981536865234,0.9946756898788307,1740481187.5836692,19.359981536865234,0.0532431012116541,1740481187.5836704,19.359981536865234,0.08403228306953747,1740481187.5836713,19.359981536865234,0.0,1740481187.583672,19.359981536865234,0.9638865080209473,, -1740481187.603855,19.379981517791748,11.355667407889465,1740481187.6038568,19.379981517791748,0.0,1740481187.6038592,19.379981517791748,0.0,1740481187.6038613,19.379981517791748,15.28344042393136,1740481187.6038623,19.379981517791748,0.0,1740481187.6038635,19.379981517791748,0.0,1740481187.6038647,19.379981517791748,0.0,1740481187.6038656,19.379981517791748,0.0,1740481187.6038666,19.379981517791748,0.9946756898788307,1740481187.6038675,19.379981517791748,0.0532431012116541,1740481187.6038685,19.379981517791748,0.08403228306953747,1740481187.6038694,19.379981517791748,0.0,1740481187.6038706,19.379981517791748,0.9638865080209473,, -1740481187.625284,19.39998149871826,11.355667407889465,1740481187.6252859,19.39998149871826,0.0,1740481187.6252887,19.39998149871826,0.0,1740481187.6252909,19.39998149871826,15.28344042393136,1740481187.6252918,19.39998149871826,0.0,1740481187.625293,19.39998149871826,0.0,1740481187.625294,19.39998149871826,0.0,1740481187.6252952,19.39998149871826,0.0,1740481187.6252964,19.39998149871826,0.9946756898788307,1740481187.625297,19.39998149871826,0.0532431012116541,1740481187.6252983,19.39998149871826,0.08403228306953747,1740481187.6252992,19.39998149871826,0.0,1740481187.6253002,19.39998149871826,0.9638865080209473,, -1740481187.6450174,19.419981479644775,11.355667407889465,1740481187.6450222,19.419981479644775,0.0,1740481187.6450272,19.419981479644775,0.0,1740481187.6450293,19.419981479644775,15.28344042393136,1740481187.6450307,19.419981479644775,0.0,1740481187.645032,19.419981479644775,0.0,1740481187.645033,19.419981479644775,0.0,1740481187.645034,19.419981479644775,0.0,1740481187.645035,19.419981479644775,0.9946756898788307,1740481187.645036,19.419981479644775,0.0532431012116541,1740481187.6450372,19.419981479644775,0.08403228306953747,1740481187.6450381,19.419981479644775,0.0,1740481187.6450393,19.419981479644775,0.9638865080209473,, -1740481187.6678586,19.43998146057129,11.355667407889465,1740481187.667861,19.43998146057129,0.0,1740481187.6678634,19.43998146057129,0.0,1740481187.667865,19.43998146057129,15.28344042393136,1740481187.6678662,19.43998146057129,0.0,1740481187.6678677,19.43998146057129,0.0,1740481187.6678686,19.43998146057129,0.0,1740481187.6678698,19.43998146057129,0.0,1740481187.6678708,19.43998146057129,0.9946756898788307,1740481187.6678717,19.43998146057129,0.0532431012116541,1740481187.6678724,19.43998146057129,0.08403228306953747,1740481187.6678736,19.43998146057129,0.0,1740481187.6678743,19.43998146057129,0.9638865080209473,, -1740481187.6842358,19.459981441497803,11.46183830301949,1740481187.6842375,19.459981441497803,0.0,1740481187.6842396,19.459981441497803,0.017245323630303403,1740481187.6842418,19.459981441497803,15.306457119004076,1740481187.6842427,19.459981441497803,0.0,1740481187.684244,19.459981441497803,0.0,1740481187.684245,19.459981441497803,0.0,1740481187.684246,19.459981441497803,0.0,1740481187.684247,19.459981441497803,0.9999999999999961,1740481187.684248,19.459981441497803,5.551115123125783e-15,1740481187.6842492,19.459981441497803,0.034336272951309,1740481187.68425,19.459981441497803,0.0,1740481187.684251,19.459981441497803,0.9667721937421538,, -1740481187.7041419,19.479981422424316,11.46183830301949,1740481187.7041435,19.479981422424316,0.0,1740481187.704146,19.479981422424316,0.017245323630303403,1740481187.704148,19.479981422424316,15.306457119004076,1740481187.704149,19.479981422424316,0.0,1740481187.7041502,19.479981422424316,0.0,1740481187.7041514,19.479981422424316,0.0,1740481187.7041523,19.479981422424316,0.0,1740481187.704153,19.479981422424316,0.9999999999999961,1740481187.7041543,19.479981422424316,5.551115123125783e-15,1740481187.7041552,19.479981422424316,0.033227806257847825,1740481187.7041562,19.479981422424316,0.0,1740481187.7041569,19.479981422424316,0.9667721937421538,, -1740481187.7237208,19.49998140335083,11.46183830301949,1740481187.7237225,19.49998140335083,0.0,1740481187.7237248,19.49998140335083,0.017245323630303403,1740481187.7237265,19.49998140335083,15.306457119004076,1740481187.7237277,19.49998140335083,0.0,1740481187.723729,19.49998140335083,0.0,1740481187.7237298,19.49998140335083,0.0,1740481187.723731,19.49998140335083,0.0,1740481187.723732,19.49998140335083,0.9999999999999961,1740481187.723733,19.49998140335083,5.551115123125783e-15,1740481187.723734,19.49998140335083,0.033227806257847825,1740481187.723735,19.49998140335083,0.0,1740481187.7237358,19.49998140335083,0.9667721937421538,, -1740481187.744664,19.519981384277344,11.46183830301949,1740481187.7448947,19.519981384277344,0.0,1740481187.7449064,19.519981384277344,0.017245323630303403,1740481187.744933,19.519981384277344,15.306457119004076,1740481187.7449343,19.519981384277344,0.0,1740481187.7449365,19.519981384277344,0.0,1740481187.7449381,19.519981384277344,0.0,1740481187.7449393,19.519981384277344,0.0,1740481187.7449408,19.519981384277344,0.9999999999999961,1740481187.7449424,19.519981384277344,5.551115123125783e-15,1740481187.7449436,19.519981384277344,0.033227806257847825,1740481187.7449448,19.519981384277344,0.0,1740481187.7449465,19.519981384277344,0.9667721937421538,, -1740481187.7680128,19.539981365203857,11.46183830301949,1740481187.7680151,19.539981365203857,0.0,1740481187.7680178,19.539981365203857,0.0,1740481187.76802,19.539981365203857,15.395382690503798,1740481187.7680213,19.539981365203857,0.0,1740481187.7680228,19.539981365203857,0.0,1740481187.7680237,19.539981365203857,0.0,1740481187.7680252,19.539981365203857,0.0,1740481187.768026,19.539981365203857,0.9954925832534646,1740481187.768027,19.539981365203857,0.0,1740481187.7680283,19.539981365203857,0.02872038951131073,1740481187.7680295,19.539981365203857,0.0,1740481187.7680304,19.539981365203857,0.9667721937421538,, -1740481187.783701,19.55998134613037,11.56810108363452,1740481187.7837029,19.55998134613037,0.0,1740481187.7837048,19.55998134613037,0.017274423832933872,1740481187.783707,19.55998134613037,15.408168033429225,1740481187.7837076,19.55998134613037,0.0,1740481187.7837088,19.55998134613037,0.0,1740481187.78371,19.55998134613037,0.0,1740481187.7837114,19.55998134613037,0.0,1740481187.7837126,19.55998134613037,0.9954925832534646,1740481187.7837136,19.55998134613037,0.04507416746531545,1740481187.7837143,19.55998134613037,0.077059344064159,1740481187.7837152,19.55998134613037,0.0,1740481187.7837162,19.55998134613037,0.9645276532884008,, -1740481187.803967,19.579981327056885,11.56810108363452,1740481187.8039696,19.579981327056885,0.0,1740481187.8039715,19.579981327056885,0.017274423832933872,1740481187.8039737,19.579981327056885,15.408168033429225,1740481187.8039749,19.579981327056885,0.0,1740481187.8039763,19.579981327056885,0.0,1740481187.8039773,19.579981327056885,0.0,1740481187.8039782,19.579981327056885,0.0,1740481187.8039792,19.579981327056885,0.9954925832534646,1740481187.8039804,19.579981327056885,0.04507416746531545,1740481187.803981,19.579981327056885,0.07603909743037918,1740481187.803982,19.579981327056885,0.0,1740481187.8039832,19.579981327056885,0.9645276532884008,, -1740481187.8240774,19.5999813079834,11.56810108363452,1740481187.8240793,19.5999813079834,0.0,1740481187.8240814,19.5999813079834,0.017274423832933872,1740481187.8240836,19.5999813079834,15.408168033429225,1740481187.8240845,19.5999813079834,0.0,1740481187.8240855,19.5999813079834,0.0,1740481187.8240864,19.5999813079834,0.0,1740481187.8240879,19.5999813079834,0.0,1740481187.8240888,19.5999813079834,0.9954925832534646,1740481187.8240898,19.5999813079834,0.04507416746531545,1740481187.8240907,19.5999813079834,0.07603909743037918,1740481187.8240917,19.5999813079834,0.0,1740481187.8240924,19.5999813079834,0.9645276532884008,, -1740481187.843658,19.619981288909912,11.56810108363452,1740481187.8436599,19.619981288909912,0.0,1740481187.843662,19.619981288909912,0.017274423832933872,1740481187.8436642,19.619981288909912,15.408168033429225,1740481187.8436654,19.619981288909912,0.0,1740481187.8436668,19.619981288909912,0.0,1740481187.8436677,19.619981288909912,0.0,1740481187.843669,19.619981288909912,0.0,1740481187.8436701,19.619981288909912,0.9954925832534646,1740481187.843671,19.619981288909912,0.04507416746531545,1740481187.8436718,19.619981288909912,0.07603909743037918,1740481187.8436728,19.619981288909912,0.0,1740481187.843674,19.619981288909912,0.9645276532884008,, -1740481187.864542,19.639981269836426,11.56810108363452,1740481187.864544,19.639981269836426,0.0,1740481187.8645463,19.639981269836426,0.0,1740481187.8645482,19.639981269836426,15.497156390211321,1740481187.8645494,19.639981269836426,0.0,1740481187.8645506,19.639981269836426,0.0,1740481187.8645518,19.639981269836426,0.0,1740481187.8645527,19.639981269836426,0.0,1740481187.8645535,19.639981269836426,0.9948630632770161,1740481187.8645544,19.639981269836426,0.0,1740481187.8645556,19.639981269836426,0.03033540998861528,1740481187.8645563,19.639981269836426,0.0,1740481187.8645573,19.639981269836426,0.9645276532884008,, -1740481187.8841548,19.65998125076294,11.56810108363452,1740481187.8841565,19.65998125076294,0.0,1740481187.884159,19.65998125076294,0.0,1740481187.8841612,19.65998125076294,15.497156390211321,1740481187.884162,19.65998125076294,0.0,1740481187.8841636,19.65998125076294,0.0,1740481187.8841646,19.65998125076294,0.0,1740481187.8841655,19.65998125076294,0.0,1740481187.8841667,19.65998125076294,0.9948630632770161,1740481187.8841677,19.65998125076294,0.0,1740481187.8841686,19.65998125076294,0.03033540998861528,1740481187.8841698,19.65998125076294,0.0,1740481187.8841705,19.65998125076294,0.9645276532884008,, -1740481187.9045138,19.679981231689453,11.674288941638826,1740481187.9045157,19.679981231689453,0.0,1740481187.904518,19.679981231689453,0.017251328038133357,1740481187.90452,19.679981231689453,15.515765965462034,1740481187.904521,19.679981231689453,0.0,1740481187.904522,19.679981231689453,0.0,1740481187.904523,19.679981231689453,0.0,1740481187.9045243,19.679981231689453,0.0,1740481187.904525,19.679981231689453,0.9948630632770161,1740481187.904526,19.679981231689453,0.0513693672297999,1740481187.9045272,19.679981231689453,0.08071696076941996,1740481187.9045281,19.679981231689453,0.0,1740481187.9045289,19.679981231689453,0.9652067768946903,, -1740481187.9237146,19.699981212615967,11.674288941638826,1740481187.9237163,19.699981212615967,0.0,1740481187.9237185,19.699981212615967,0.017251328038133357,1740481187.9237204,19.699981212615967,15.515765965462034,1740481187.9237218,19.699981212615967,0.0,1740481187.9237227,19.699981212615967,0.0,1740481187.923724,19.699981212615967,0.0,1740481187.9237254,19.699981212615967,0.0,1740481187.9237266,19.699981212615967,0.9948630632770161,1740481187.9237275,19.699981212615967,0.0513693672297999,1740481187.9237285,19.699981212615967,0.08102565361212577,1740481187.9237294,19.699981212615967,0.0,1740481187.9237304,19.699981212615967,0.9652067768946903,, -1740481187.9438865,19.71998119354248,11.674288941638826,1740481187.943889,19.71998119354248,0.0,1740481187.9438913,19.71998119354248,0.017251328038133357,1740481187.9438932,19.71998119354248,15.515765965462034,1740481187.9438944,19.71998119354248,0.0,1740481187.9438953,19.71998119354248,0.0,1740481187.9438965,19.71998119354248,0.0,1740481187.9438972,19.71998119354248,0.0,1740481187.9438984,19.71998119354248,0.9948630632770161,1740481187.9438996,19.71998119354248,0.0513693672297999,1740481187.9439003,19.71998119354248,0.08102565361212577,1740481187.9439015,19.71998119354248,0.0,1740481187.9439023,19.71998119354248,0.9652067768946903,, -1740481187.9650648,19.739981174468994,11.674288941638826,1740481187.9650667,19.739981174468994,0.0,1740481187.9650688,19.739981174468994,0.0,1740481187.965071,19.739981174468994,15.604702495428207,1740481187.965072,19.739981174468994,0.0,1740481187.9650729,19.739981174468994,0.0,1740481187.9650738,19.739981174468994,0.0,1740481187.965075,19.739981174468994,0.0,1740481187.965076,19.739981174468994,0.9950578753080236,1740481187.9650767,19.739981174468994,0.0,1740481187.9650774,19.739981174468994,0.029851098413333332,1740481187.9650784,19.739981174468994,0.0,1740481187.965079,19.739981174468994,0.9652067768946903,, -1740481187.9841545,19.759981155395508,11.674288941638826,1740481187.9841561,19.759981155395508,0.0,1740481187.9841585,19.759981155395508,0.0,1740481187.9841604,19.759981155395508,15.604702495428207,1740481187.9841616,19.759981155395508,0.0,1740481187.9841628,19.759981155395508,0.0,1740481187.9841638,19.759981155395508,0.0,1740481187.984165,19.759981155395508,0.0,1740481187.984166,19.759981155395508,0.9950578753080236,1740481187.9841669,19.759981155395508,0.0,1740481187.9841676,19.759981155395508,0.029851098413333332,1740481187.984169,19.759981155395508,0.0,1740481187.9841697,19.759981155395508,0.9652067768946903,, -1740481188.0045369,19.77998113632202,11.780508642807344,1740481188.0045385,19.77998113632202,0.0,1740481188.004541,19.77998113632202,0.017259880425627847,1740481188.0045428,19.77998113632202,15.621994545796284,1740481188.0045438,19.77998113632202,0.0,1740481188.004545,19.77998113632202,0.0,1740481188.0045462,19.77998113632202,0.0,1740481188.004547,19.77998113632202,0.0,1740481188.0045478,19.77998113632202,0.9950578753080236,1740481188.0045488,19.77998113632202,0.04942124691972527,1740481188.0045497,19.77998113632202,0.07924894900430532,1740481188.0045507,19.77998113632202,0.0,1740481188.0045516,19.77998113632202,0.9652228618659144,, -1740481188.0236309,19.799981117248535,11.780508642807344,1740481188.0236335,19.799981117248535,0.0,1740481188.0236359,19.799981117248535,0.017259880425627847,1740481188.0236385,19.799981117248535,15.621994545796284,1740481188.0236402,19.799981117248535,0.0,1740481188.0236416,19.799981117248535,0.0,1740481188.0236437,19.799981117248535,0.0,1740481188.023645,19.799981117248535,0.0,1740481188.0236468,19.799981117248535,0.9950578753080236,1740481188.023649,19.799981117248535,0.04942124691972527,1740481188.0236506,19.799981117248535,0.07925626036183442,1740481188.0236523,19.799981117248535,0.0,1740481188.023654,19.799981117248535,0.9652228618659144,, -1740481188.0458302,19.81998109817505,11.780508642807344,1740481188.0458636,19.81998109817505,0.0,1740481188.045867,19.81998109817505,0.017259880425627847,1740481188.045869,19.81998109817505,15.621994545796284,1740481188.04587,19.81998109817505,0.0,1740481188.045872,19.81998109817505,0.0,1740481188.0458732,19.81998109817505,0.0,1740481188.0458739,19.81998109817505,0.0,1740481188.0458753,19.81998109817505,0.9950578753080236,1740481188.0458763,19.81998109817505,0.04942124691972527,1740481188.045877,19.81998109817505,0.07925626036183442,1740481188.0458777,19.81998109817505,0.0,1740481188.0459034,19.81998109817505,0.9652228618659144,, -1740481188.0666685,19.839981079101562,11.780508642807344,1740481188.0666704,19.839981079101562,0.0,1740481188.0666726,19.839981079101562,0.0,1740481188.0666745,19.839981079101562,15.710954366539173,1740481188.0666754,19.839981079101562,0.0,1740481188.0666764,19.839981079101562,0.0,1740481188.0666776,19.839981079101562,0.0,1740481188.0666783,19.839981079101562,0.0,1740481188.0666792,19.839981079101562,0.9950624437584972,1740481188.06668,19.839981079101562,0.0,1740481188.0666811,19.839981079101562,0.029839581892582734,1740481188.0666819,19.839981079101562,0.0,1740481188.0666826,19.839981079101562,0.9652228618659144,, -1740481188.0844657,19.859981060028076,11.780508642807344,1740481188.0844684,19.859981060028076,0.0,1740481188.0844717,19.859981060028076,0.0,1740481188.084474,19.859981060028076,15.710954366539173,1740481188.084475,19.859981060028076,0.0,1740481188.0844767,19.859981060028076,0.0,1740481188.0844777,19.859981060028076,0.0,1740481188.0844793,19.859981060028076,0.0,1740481188.0844808,19.859981060028076,0.9950624437584972,1740481188.084482,19.859981060028076,0.0,1740481188.0844834,19.859981060028076,0.029839581892582734,1740481188.084485,19.859981060028076,0.0,1740481188.0844865,19.859981060028076,0.9652228618659144,, -1740481188.1034663,19.87998104095459,11.780508642807344,1740481188.103468,19.87998104095459,0.0,1740481188.10347,19.87998104095459,0.0,1740481188.1034722,19.87998104095459,15.710954366539173,1740481188.1034732,19.87998104095459,0.0,1740481188.1034741,19.87998104095459,0.0,1740481188.103475,19.87998104095459,0.0,1740481188.1034763,19.87998104095459,0.0,1740481188.1034772,19.87998104095459,0.9950624437584972,1740481188.103478,19.87998104095459,0.0,1740481188.1034787,19.87998104095459,0.029839581892582734,1740481188.1034799,19.87998104095459,0.0,1740481188.1034806,19.87998104095459,0.9652228618659144,, -1740481188.1258748,19.899981021881104,11.886752745847467,1740481188.1258764,19.899981021881104,0.0,1740481188.1258786,19.899981021881104,0.017263924801891574,1740481188.1258805,19.899981021881104,15.728035968687472,1740481188.1258817,19.899981021881104,0.0,1740481188.1258826,19.899981021881104,0.0,1740481188.1258836,19.899981021881104,0.0,1740481188.1258848,19.899981021881104,0.0,1740481188.1258855,19.899981021881104,0.9950624437584972,1740481188.1258864,19.899981021881104,0.049375562414989416,1740481188.1258872,19.899981021881104,0.07934774264061115,1740481188.125888,19.899981021881104,0.0,1740481188.125889,19.899981021881104,0.9651317005391183,, -1740481188.1447883,19.919981002807617,11.886752745847467,1740481188.14479,19.919981002807617,0.0,1740481188.1447923,19.919981002807617,0.017263924801891574,1740481188.1447942,19.919981002807617,15.728035968687472,1740481188.1447952,19.919981002807617,0.0,1740481188.1447964,19.919981002807617,0.0,1740481188.1447973,19.919981002807617,0.0,1740481188.1447985,19.919981002807617,0.0,1740481188.1447992,19.919981002807617,0.9950624437584972,1740481188.1448002,19.919981002807617,0.049375562414989416,1740481188.1448011,19.919981002807617,0.07930630563436825,1740481188.144802,19.919981002807617,0.0,1740481188.144803,19.919981002807617,0.9651317005391183,, -1740481188.1688526,19.93998098373413,11.886752745847467,1740481188.1688542,19.93998098373413,0.0,1740481188.1688569,19.93998098373413,0.0,1740481188.1688588,19.93998098373413,15.817016146925702,1740481188.16886,19.93998098373413,0.0,1740481188.1688612,19.93998098373413,0.0,1740481188.168862,19.93998098373413,0.0,1740481188.1688633,19.93998098373413,0.0,1740481188.168865,19.93998098373413,0.9950365241949851,1740481188.1688662,19.93998098373413,0.0,1740481188.1688669,19.93998098373413,0.029904823655866775,1740481188.1688678,19.93998098373413,0.0,1740481188.1688688,19.93998098373413,0.9651317005391183,, -1740481188.1845353,19.959980964660645,11.886752745847467,1740481188.1845372,19.959980964660645,0.0,1740481188.184539,19.959980964660645,0.0,1740481188.1845412,19.959980964660645,15.817016146925702,1740481188.1845422,19.959980964660645,0.0,1740481188.1845431,19.959980964660645,0.0,1740481188.1845446,19.959980964660645,0.0,1740481188.1845455,19.959980964660645,0.0,1740481188.1845465,19.959980964660645,0.9950365241949851,1740481188.1845474,19.959980964660645,0.0,1740481188.1845484,19.959980964660645,0.029904823655866775,1740481188.1845493,19.959980964660645,0.0,1740481188.18455,19.959980964660645,0.9651317005391183,, -1740481188.2073057,19.979980945587158,11.886752745847467,1740481188.2073078,19.979980945587158,0.0,1740481188.20731,19.979980945587158,0.0,1740481188.207312,19.979980945587158,15.817016146925702,1740481188.207313,19.979980945587158,0.0,1740481188.2073145,19.979980945587158,0.0,1740481188.2073154,19.979980945587158,0.0,1740481188.2073164,19.979980945587158,0.0,1740481188.2073176,19.979980945587158,0.9950365241949851,1740481188.2073185,19.979980945587158,0.0,1740481188.2073193,19.979980945587158,0.029904823655866775,1740481188.207334,19.979980945587158,0.0,1740481188.207336,19.979980945587158,0.9651317005391183,, -1740481188.2252505,19.999980926513672,11.992937917075146,1740481188.2252524,19.999980926513672,0.0,1740481188.2252548,19.999980926513672,0.017253899349566164,1740481188.2252564,19.999980926513672,15.833121038104762,1740481188.2252574,19.999980926513672,0.0,1740481188.2252588,19.999980926513672,0.0,1740481188.2252595,19.999980926513672,0.0,1740481188.2252605,19.999980926513672,0.0,1740481188.2252614,19.999980926513672,0.9950365241949851,1740481188.2252624,19.999980926513672,0.04963475805010997,1740481188.2252634,19.999980926513672,0.0803752242608414,1740481188.225264,19.999980926513672,0.0,1740481188.2252655,19.999980926513672,0.9645571964538646,, -1740481188.2450485,20.019980907440186,11.992937917075146,1740481188.2450502,20.019980907440186,0.0,1740481188.2450638,20.019980907440186,0.017253899349566164,1740481188.2450686,20.019980907440186,15.833121038104762,1740481188.2450697,20.019980907440186,0.0,1740481188.2450712,20.019980907440186,0.0,1740481188.2450721,20.019980907440186,0.0,1740481188.245073,20.019980907440186,0.0,1740481188.245074,20.019980907440186,0.9950365241949851,1740481188.245075,20.019980907440186,0.04963475805010997,1740481188.2450757,20.019980907440186,0.08011408579123047,1740481188.2450767,20.019980907440186,0.0,1740481188.2450778,20.019980907440186,0.9645571964538646,, -1740481188.2681901,20.0399808883667,11.992937917075146,1740481188.2681918,20.0399808883667,0.0,1740481188.2681947,20.0399808883667,0.0,1740481188.2681963,20.0399808883667,15.922052309982876,1740481188.2681973,20.0399808883667,0.0,1740481188.2681987,20.0399808883667,0.0,1740481188.2681997,20.0399808883667,0.0,1740481188.2682006,20.0399808883667,0.0,1740481188.2682016,20.0399808883667,0.9948716163155578,1740481188.2682025,20.0399808883667,0.0,1740481188.2682033,20.0399808883667,0.030314419861693143,1740481188.268204,20.0399808883667,0.0,1740481188.2682052,20.0399808883667,0.9645571964538646,, -1740481188.2840762,20.059980869293213,11.992937917075146,1740481188.2840798,20.059980869293213,0.0,1740481188.2840831,20.059980869293213,0.0,1740481188.2840865,20.059980869293213,15.922052309982876,1740481188.284089,20.059980869293213,0.0,1740481188.2840915,20.059980869293213,0.0,1740481188.284093,20.059980869293213,0.0,1740481188.2840946,20.059980869293213,0.0,1740481188.284096,20.059980869293213,0.9948716163155578,1740481188.2840974,20.059980869293213,0.0,1740481188.284099,20.059980869293213,0.030314419861693143,1740481188.2841005,20.059980869293213,0.0,1740481188.2841024,20.059980869293213,0.9645571964538646,, -1740481188.3067873,20.079980850219727,11.992937917075146,1740481188.306789,20.079980850219727,0.0,1740481188.3067913,20.079980850219727,0.0,1740481188.3067935,20.079980850219727,15.922052309982876,1740481188.3067944,20.079980850219727,0.0,1740481188.3067958,20.079980850219727,0.0,1740481188.3067968,20.079980850219727,0.0,1740481188.3067977,20.079980850219727,0.0,1740481188.306799,20.079980850219727,0.9948716163155578,1740481188.3067997,20.079980850219727,0.0,1740481188.3068006,20.079980850219727,0.030314419861693143,1740481188.3068016,20.079980850219727,0.0,1740481188.3068027,20.079980850219727,0.9645571964538646,, -1740481188.3236504,20.09998083114624,11.992937917075146,1740481188.3236518,20.09998083114624,0.0,1740481188.3236542,20.09998083114624,0.0,1740481188.3236566,20.09998083114624,15.922052309982876,1740481188.3236575,20.09998083114624,0.0,1740481188.3236587,20.09998083114624,0.0,1740481188.3236597,20.09998083114624,0.0,1740481188.3236609,20.09998083114624,0.0,1740481188.3236618,20.09998083114624,0.9948716163155578,1740481188.3236628,20.09998083114624,0.0,1740481188.3236637,20.09998083114624,0.030314419861693143,1740481188.3236647,20.09998083114624,0.0,1740481188.3236656,20.09998083114624,0.9645571964538646,, -1740481188.3474858,20.119980812072754,12.099059190794723,1740481188.3474889,20.119980812072754,0.0,1740481188.3474917,20.119980812072754,0.017240658944895425,1740481188.3474946,20.119980812072754,15.937296845923598,1740481188.3474963,20.119980812072754,0.0,1740481188.347498,20.119980812072754,0.0,1740481188.3474996,20.119980812072754,0.0,1740481188.3475006,20.119980812072754,0.0,1740481188.3475018,20.119980812072754,0.9948716163155578,1740481188.3475032,20.119980812072754,0.051283836844383535,1740481188.3475208,20.119980812072754,0.08304998295994227,1740481188.3475218,20.119980812072754,0.0,1740481188.3475227,20.119980812072754,0.9635591349517778,, -1740481188.3653593,20.139980792999268,12.099059190794723,1740481188.3653615,20.139980792999268,0.0,1740481188.365364,20.139980792999268,0.0,1740481188.3653665,20.139980792999268,16.02617746069828,1740481188.365368,20.139980792999268,0.0,1740481188.365369,20.139980792999268,0.0,1740481188.3653703,20.139980792999268,0.0,1740481188.3653715,20.139980792999268,0.0,1740481188.3653722,20.139980792999268,0.9945787213464519,1740481188.3653736,20.139980792999268,0.0,1740481188.3653748,20.139980792999268,0.03101958639467406,1740481188.3653758,20.139980792999268,0.0,1740481188.365377,20.139980792999268,0.9635591349517778,, -1740481188.3838818,20.15998077392578,12.099059190794723,1740481188.3838835,20.15998077392578,0.0,1740481188.3838859,20.15998077392578,0.0,1740481188.3838878,20.15998077392578,16.02617746069828,1740481188.383889,20.15998077392578,0.0,1740481188.3838902,20.15998077392578,0.0,1740481188.383891,20.15998077392578,0.0,1740481188.3838923,20.15998077392578,0.0,1740481188.383893,20.15998077392578,0.9945787213464519,1740481188.3838942,20.15998077392578,0.0,1740481188.3838954,20.15998077392578,0.03101958639467406,1740481188.383896,20.15998077392578,0.0,1740481188.3838968,20.15998077392578,0.9635591349517778,, -1740481188.4050536,20.179980754852295,12.099059190794723,1740481188.4050555,20.179980754852295,0.0,1740481188.4050581,20.179980754852295,0.0,1740481188.405061,20.179980754852295,16.02617746069828,1740481188.4050624,20.179980754852295,0.0,1740481188.4050648,20.179980754852295,0.0,1740481188.405067,20.179980754852295,0.0,1740481188.4050686,20.179980754852295,0.0,1740481188.40507,20.179980754852295,0.9945787213464519,1740481188.4050722,20.179980754852295,0.0,1740481188.4050736,20.179980754852295,0.03101958639467406,1740481188.4050746,20.179980754852295,0.0,1740481188.4050763,20.179980754852295,0.9635591349517778,, -1740481188.4234297,20.19998073577881,12.099059190794723,1740481188.4234316,20.19998073577881,0.0,1740481188.4234347,20.19998073577881,0.0,1740481188.4234374,20.19998073577881,16.02617746069828,1740481188.4234385,20.19998073577881,0.0,1740481188.423441,20.19998073577881,0.0,1740481188.4234421,20.19998073577881,0.0,1740481188.4234436,20.19998073577881,0.0,1740481188.4234455,20.19998073577881,0.9945787213464519,1740481188.4234471,20.19998073577881,0.0,1740481188.4234483,20.19998073577881,0.03101958639467406,1740481188.4234495,20.19998073577881,0.0,1740481188.4234512,20.19998073577881,0.9635591349517778,, -1740481188.4442017,20.219980716705322,12.204993080250453,1740481188.4442043,20.219980716705322,0.0,1740481188.4442065,20.219980716705322,0.01720514937979279,1740481188.4442084,20.219980716705322,16.039640280300514,1740481188.4442093,20.219980716705322,0.0,1740481188.4442108,20.219980716705322,0.0,1740481188.4442117,20.219980716705322,0.0,1740481188.444213,20.219980716705322,0.0,1740481188.4442139,20.219980716705322,0.9945787213464519,1740481188.444215,20.219980716705322,0.054212786535619006,1740481188.444216,20.219980716705322,0.08795406812509911,1740481188.4442167,20.219980716705322,0.0,1740481188.444218,20.219980716705322,0.9616879700629998,, -1740481188.4649096,20.239980697631836,12.204993080250453,1740481188.4649115,20.239980697631836,0.0,1740481188.4649136,20.239980697631836,0.0,1740481188.4649158,20.239980697631836,16.128369020376454,1740481188.4649165,20.239980697631836,0.0,1740481188.4649177,20.239980697631836,0.0,1740481188.4649189,20.239980697631836,0.0,1740481188.4649198,20.239980697631836,0.0,1740481188.4649205,20.239980697631836,0.9940076840810647,1740481188.464922,20.239980697631836,0.0,1740481188.4649227,20.239980697631836,0.03231971401806488,1740481188.4649236,20.239980697631836,0.0,1740481188.4649246,20.239980697631836,0.9616879700629998,, -1740481188.4837606,20.25998067855835,12.204993080250453,1740481188.4837625,20.25998067855835,0.0,1740481188.4837644,20.25998067855835,0.0,1740481188.4837668,20.25998067855835,16.128369020376454,1740481188.4837675,20.25998067855835,0.0,1740481188.483769,20.25998067855835,0.0,1740481188.48377,20.25998067855835,0.0,1740481188.4837708,20.25998067855835,0.0,1740481188.4837716,20.25998067855835,0.9940076840810647,1740481188.4837852,20.25998067855835,0.0,1740481188.4837887,20.25998067855835,0.03231971401806488,1740481188.4837897,20.25998067855835,0.0,1740481188.4837906,20.25998067855835,0.9616879700629998,, -1740481188.5041797,20.279980659484863,12.204993080250453,1740481188.5041811,20.279980659484863,0.0,1740481188.5041835,20.279980659484863,0.0,1740481188.5041857,20.279980659484863,16.128369020376454,1740481188.5041869,20.279980659484863,0.0,1740481188.5041888,20.279980659484863,0.0,1740481188.5041897,20.279980659484863,0.0,1740481188.5041904,20.279980659484863,0.0,1740481188.5041914,20.279980659484863,0.9940076840810647,1740481188.5041924,20.279980659484863,0.0,1740481188.5041933,20.279980659484863,0.03231971401806488,1740481188.504194,20.279980659484863,0.0,1740481188.5041947,20.279980659484863,0.9616879700629998,, -1740481188.5242913,20.299980640411377,12.204993080250453,1740481188.524293,20.299980640411377,0.0,1740481188.5242956,20.299980640411377,0.0,1740481188.5242977,20.299980640411377,16.128369020376454,1740481188.5242987,20.299980640411377,0.0,1740481188.5243,20.299980640411377,0.0,1740481188.5243013,20.299980640411377,0.0,1740481188.524302,20.299980640411377,0.0,1740481188.524303,20.299980640411377,0.9940076840810647,1740481188.5243042,20.299980640411377,0.0,1740481188.5243049,20.299980640411377,0.03231971401806488,1740481188.5243056,20.299980640411377,0.0,1740481188.5243068,20.299980640411377,0.9616879700629998,, -1740481188.5436728,20.31998062133789,12.204993080250453,1740481188.5436745,20.31998062133789,0.0,1740481188.5436769,20.31998062133789,0.0,1740481188.543679,20.31998062133789,16.128369020376454,1740481188.54368,20.31998062133789,0.0,1740481188.5436814,20.31998062133789,0.0,1740481188.5436823,20.31998062133789,0.0,1740481188.5436833,20.31998062133789,0.0,1740481188.543684,20.31998062133789,0.9940076840810647,1740481188.5436852,20.31998062133789,0.0,1740481188.5436862,20.31998062133789,0.03231971401806488,1740481188.543687,20.31998062133789,0.0,1740481188.5436878,20.31998062133789,0.9616879700629998,, -1740481188.564615,20.339980602264404,12.31074686394302,1740481188.5646164,20.339980602264404,0.0,1740481188.5646188,20.339980602264404,0.0,1740481188.5646205,20.339980602264404,16.2308497064993,1740481188.5646217,20.339980602264404,0.0,1740481188.5646229,20.339980602264404,0.0,1740481188.5646238,20.339980602264404,0.0,1740481188.5646248,20.339980602264404,0.0,1740481188.564626,20.339980602264404,0.9934848106770025,1740481188.5646274,20.339980602264404,0.06515189322993664,1740481188.5646281,20.339980602264404,0.09909149919374743,1740481188.5646293,20.339980602264404,0.0,1740481188.56463,20.339980602264404,0.9600514212781387,, -1740481188.5844414,20.359980583190918,12.31074686394302,1740481188.584443,20.359980583190918,0.0,1740481188.5844457,20.359980583190918,0.0,1740481188.5844474,20.359980583190918,16.2308497064993,1740481188.5844486,20.359980583190918,0.0,1740481188.5844498,20.359980583190918,0.0,1740481188.584451,20.359980583190918,0.0,1740481188.5844522,20.359980583190918,0.0,1740481188.584453,20.359980583190918,0.9934848106770025,1740481188.5844538,20.359980583190918,0.06515189322993664,1740481188.5844553,20.359980583190918,0.0985852826288004,1740481188.584456,20.359980583190918,0.0,1740481188.584457,20.359980583190918,0.9600514212781387,, -1740481188.6073682,20.37998056411743,12.31074686394302,1740481188.6073701,20.37998056411743,0.0,1740481188.6073725,20.37998056411743,0.0,1740481188.6073747,20.37998056411743,16.2308497064993,1740481188.6073756,20.37998056411743,0.0,1740481188.6073768,20.37998056411743,0.0,1740481188.607378,20.37998056411743,0.0,1740481188.607379,20.37998056411743,0.0,1740481188.60738,20.37998056411743,0.9934848106770025,1740481188.607381,20.37998056411743,0.06515189322993664,1740481188.607382,20.37998056411743,0.0985852826288004,1740481188.6073828,20.37998056411743,0.0,1740481188.6073837,20.37998056411743,0.9600514212781387,, -1740481188.623789,20.399980545043945,12.31074686394302,1740481188.6237905,20.399980545043945,0.0,1740481188.6237931,20.399980545043945,0.0,1740481188.6237953,20.399980545043945,16.2308497064993,1740481188.6237962,20.399980545043945,0.0,1740481188.6237974,20.399980545043945,0.0,1740481188.6237986,20.399980545043945,0.0,1740481188.6237996,20.399980545043945,0.0,1740481188.6238003,20.399980545043945,0.9934848106770025,1740481188.6238017,20.399980545043945,0.06515189322993664,1740481188.6238027,20.399980545043945,0.0985852826288004,1740481188.6238034,20.399980545043945,0.0,1740481188.6238043,20.399980545043945,0.9600514212781387,, -1740481188.6439867,20.41998052597046,12.31074686394302,1740481188.643991,20.41998052597046,0.0,1740481188.643998,20.41998052597046,0.0,1740481188.6440005,20.41998052597046,16.2308497064993,1740481188.644002,20.41998052597046,0.0,1740481188.6440039,20.41998052597046,0.0,1740481188.6440063,20.41998052597046,0.0,1740481188.644008,20.41998052597046,0.0,1740481188.6440105,20.41998052597046,0.9934848106770025,1740481188.6440122,20.41998052597046,0.06515189322993664,1740481188.6440141,20.41998052597046,0.0985852826288004,1740481188.6440156,20.41998052597046,0.0,1740481188.644018,20.41998052597046,0.9600514212781387,, -1740481188.6654434,20.439980506896973,12.41651435876285,1740481188.665445,20.439980506896973,0.0,1740481188.6654472,20.439980506896973,0.0,1740481188.6654491,20.439980506896973,16.344390191107255,1740481188.6654503,20.439980506896973,0.0,1740481188.6654515,20.439980506896973,0.0,1740481188.6654525,20.439980506896973,0.0,1740481188.665454,20.439980506896973,0.0,1740481188.6654546,20.439980506896973,0.9946908375761386,1740481188.6654556,20.439980506896973,0.05309162423857483,1740481188.6654563,20.439980506896973,0.08262614993740922,1740481188.6654575,20.439980506896973,0.0,1740481188.6654582,20.439980506896973,0.9639379161722026,, -1740481188.6846502,20.459980487823486,12.41651435876285,1740481188.684652,20.459980487823486,0.0,1740481188.6846542,20.459980487823486,0.0,1740481188.6846564,20.459980487823486,16.344390191107255,1740481188.6846573,20.459980487823486,0.0,1740481188.684659,20.459980487823486,0.0,1740481188.68466,20.459980487823486,0.0,1740481188.684661,20.459980487823486,0.0,1740481188.6846619,20.459980487823486,0.9946908375761386,1740481188.6846628,20.459980487823486,0.05309162423857483,1740481188.6846635,20.459980487823486,0.08384454564251087,1740481188.6846647,20.459980487823486,0.0,1740481188.6846662,20.459980487823486,0.9639379161722026,, -1740481188.7056332,20.47998046875,12.41651435876285,1740481188.7056513,20.47998046875,0.0,1740481188.705657,20.47998046875,0.0,1740481188.7056606,20.47998046875,16.344390191107255,1740481188.7056623,20.47998046875,0.0,1740481188.705664,20.47998046875,0.0,1740481188.7056658,20.47998046875,0.0,1740481188.7056668,20.47998046875,0.0,1740481188.7056684,20.47998046875,0.9946908375761386,1740481188.7056706,20.47998046875,0.05309162423857483,1740481188.7056723,20.47998046875,0.08384454564251087,1740481188.7056751,20.47998046875,0.0,1740481188.705677,20.47998046875,0.9639379161722026,, -1740481188.723929,20.499980449676514,12.41651435876285,1740481188.7239325,20.499980449676514,0.0,1740481188.7239358,20.499980449676514,0.0,1740481188.7239377,20.499980449676514,16.344390191107255,1740481188.7239387,20.499980449676514,0.0,1740481188.7239404,20.499980449676514,0.0,1740481188.7239413,20.499980449676514,0.0,1740481188.7239425,20.499980449676514,0.0,1740481188.7239435,20.499980449676514,0.9946908375761386,1740481188.7239444,20.499980449676514,0.05309162423857483,1740481188.7239451,20.499980449676514,0.08384454564251087,1740481188.723946,20.499980449676514,0.0,1740481188.723947,20.499980449676514,0.9639379161722026,, -1740481188.7451599,20.519980430603027,12.41651435876285,1740481188.7451625,20.519980430603027,0.0,1740481188.7451842,20.519980430603027,0.0,1740481188.7451866,20.519980430603027,16.344390191107255,1740481188.7451875,20.519980430603027,0.0,1740481188.7451892,20.519980430603027,0.0,1740481188.7451906,20.519980430603027,0.0,1740481188.7451916,20.519980430603027,0.0,1740481188.7451928,20.519980430603027,0.9946908375761386,1740481188.7453573,20.519980430603027,0.05309162423857483,1740481188.7453628,20.519980430603027,0.08384454564251087,1740481188.7453642,20.519980430603027,0.0,1740481188.7453656,20.519980430603027,0.9639379161722026,, -1740481188.765618,20.53998041152954,12.41651435876285,1740481188.76562,20.53998041152954,0.0,1740481188.765622,20.53998041152954,0.0,1740481188.765624,20.53998041152954,16.344390191107255,1740481188.765625,20.53998041152954,0.0,1740481188.7656264,20.53998041152954,0.0,1740481188.7656274,20.53998041152954,0.0,1740481188.7656283,20.53998041152954,0.0,1740481188.7656293,20.53998041152954,0.9946908375761386,1740481188.7656307,20.53998041152954,0.05309162423857483,1740481188.7656317,20.53998041152954,0.08384454564251087,1740481188.7656326,20.53998041152954,0.0,1740481188.7656336,20.53998041152954,0.9639379161722026,, -1740481188.7837327,20.559980392456055,12.522689877880403,1740481188.7837343,20.559980392456055,0.0,1740481188.7837365,20.559980392456055,0.017246337340628484,1740481188.7837384,20.559980392456055,16.367366359091882,1740481188.7837393,20.559980392456055,0.0,1740481188.7837408,20.559980392456055,0.0,1740481188.7837417,20.559980392456055,0.0,1740481188.7837424,20.559980392456055,0.0,1740481188.7837431,20.559980392456055,0.9999999999999961,1740481188.7837443,20.559980392456055,5.551115123125783e-15,1740481188.7837453,20.559980392456055,0.03430819097528861,1740481188.783746,20.559980392456055,0.0,1740481188.783747,20.559980392456055,0.9668028314942021,, -1740481188.8036923,20.57998037338257,12.522689877880403,1740481188.8036938,20.57998037338257,0.0,1740481188.803696,20.57998037338257,0.017246337340628484,1740481188.8036978,20.57998037338257,16.367366359091882,1740481188.803699,20.57998037338257,0.0,1740481188.8037002,20.57998037338257,0.0,1740481188.8037014,20.57998037338257,0.0,1740481188.8037024,20.57998037338257,0.0,1740481188.8037033,20.57998037338257,0.9999999999999961,1740481188.8037043,20.57998037338257,5.551115123125783e-15,1740481188.8037055,20.57998037338257,0.03319716850579957,1740481188.8037062,20.57998037338257,0.0,1740481188.8037071,20.57998037338257,0.9668028314942021,, -1740481188.8237102,20.599980354309082,12.522689877880403,1740481188.8237116,20.599980354309082,0.0,1740481188.8237138,20.599980354309082,0.017246337340628484,1740481188.823716,20.599980354309082,16.367366359091882,1740481188.8237169,20.599980354309082,0.0,1740481188.823718,20.599980354309082,0.0,1740481188.8237193,20.599980354309082,0.0,1740481188.8237202,20.599980354309082,0.0,1740481188.823721,20.599980354309082,0.9999999999999961,1740481188.823722,20.599980354309082,5.551115123125783e-15,1740481188.823723,20.599980354309082,0.03319716850579957,1740481188.8237238,20.599980354309082,0.0,1740481188.8237247,20.599980354309082,0.9668028314942021,, -1740481188.8437989,20.619980335235596,12.522689877880403,1740481188.8438008,20.619980335235596,0.0,1740481188.843803,20.619980335235596,0.017246337340628484,1740481188.8438046,20.619980335235596,16.367366359091882,1740481188.843806,20.619980335235596,0.0,1740481188.8438072,20.619980335235596,0.0,1740481188.8438082,20.619980335235596,0.0,1740481188.8438091,20.619980335235596,0.0,1740481188.8438098,20.619980335235596,0.9999999999999961,1740481188.8438108,20.619980335235596,5.551115123125783e-15,1740481188.843812,20.619980335235596,0.03319716850579957,1740481188.843813,20.619980335235596,0.0,1740481188.8438144,20.619980335235596,0.9668028314942021,, -1740481188.8661432,20.63998031616211,12.522689877880403,1740481188.8661451,20.63998031616211,0.0,1740481188.8661478,20.63998031616211,0.0,1740481188.8661501,20.63998031616211,16.45629554086881,1740481188.8661513,20.63998031616211,0.0,1740481188.866153,20.63998031616211,0.0,1740481188.8661542,20.63998031616211,0.0,1740481188.8661551,20.63998031616211,0.0,1740481188.8661563,20.63998031616211,0.9955008915630285,1740481188.8661575,20.63998031616211,0.0,1740481188.8661585,20.63998031616211,0.02869806006882636,1740481188.8661597,20.63998031616211,0.0,1740481188.8661606,20.63998031616211,0.9668028314942021,, -1740481188.8836489,20.659980297088623,12.62895569738603,1740481188.8836505,20.659980297088623,0.0,1740481188.8836527,20.659980297088623,0.01727506202011332,1740481188.8836546,20.659980297088623,16.46907165292579,1740481188.8836558,20.659980297088623,0.0,1740481188.883657,20.659980297088623,0.0,1740481188.8836582,20.659980297088623,0.0,1740481188.8836591,20.659980297088623,0.0,1740481188.88366,20.659980297088623,0.9955008915630285,1740481188.883661,20.659980297088623,0.04499108436985311,1740481188.883662,20.659980297088623,0.0769611090233513,1740481188.883663,20.659980297088623,0.0,1740481188.8836637,20.659980297088623,0.9645533565126366,, -1740481188.903431,20.679980278015137,12.62895569738603,1740481188.9034328,20.679980278015137,0.0,1740481188.9034352,20.679980278015137,0.01727506202011332,1740481188.9034374,20.679980278015137,16.46907165292579,1740481188.9034383,20.679980278015137,0.0,1740481188.9034395,20.679980278015137,0.0,1740481188.9034407,20.679980278015137,0.0,1740481188.9034417,20.679980278015137,0.0,1740481188.9034424,20.679980278015137,0.9955008915630285,1740481188.903444,20.679980278015137,0.04499108436985311,1740481188.9034448,20.679980278015137,0.07593861942024493,1740481188.9034457,20.679980278015137,0.0,1740481188.9034464,20.679980278015137,0.9645533565126366,, -1740481188.9236023,20.69998025894165,12.62895569738603,1740481188.923604,20.69998025894165,0.0,1740481188.9236062,20.69998025894165,0.01727506202011332,1740481188.923608,20.69998025894165,16.46907165292579,1740481188.923609,20.69998025894165,0.0,1740481188.9236104,20.69998025894165,0.0,1740481188.9236114,20.69998025894165,0.0,1740481188.923612,20.69998025894165,0.0,1740481188.923613,20.69998025894165,0.9955008915630285,1740481188.923614,20.69998025894165,0.04499108436985311,1740481188.923615,20.69998025894165,0.07593861942024493,1740481188.9236157,20.69998025894165,0.0,1740481188.923617,20.69998025894165,0.9645533565126366,, -1740481188.9438674,20.719980239868164,12.62895569738603,1740481188.943869,20.719980239868164,0.0,1740481188.9438715,20.719980239868164,0.01727506202011332,1740481188.9438732,20.719980239868164,16.46907165292579,1740481188.9438744,20.719980239868164,0.0,1740481188.9438756,20.719980239868164,0.0,1740481188.9438765,20.719980239868164,0.0,1740481188.9438777,20.719980239868164,0.0,1740481188.9438787,20.719980239868164,0.9955008915630285,1740481188.9438796,20.719980239868164,0.04499108436985311,1740481188.9438806,20.719980239868164,0.07593861942024493,1740481188.9438815,20.719980239868164,0.0,1740481188.9438825,20.719980239868164,0.9645533565126366,, -1740481188.9649084,20.739980220794678,12.62895569738603,1740481188.96491,20.739980220794678,0.0,1740481188.9649124,20.739980220794678,0.0,1740481188.9649143,20.739980220794678,16.558062410411303,1740481188.9649155,20.739980220794678,0.0,1740481188.964917,20.739980220794678,0.0,1740481188.9649184,20.739980220794678,0.0,1740481188.964919,20.739980220794678,0.0,1740481188.96492,20.739980220794678,0.9948705050175403,1740481188.964921,20.739980220794678,0.0,1740481188.9649222,20.739980220794678,0.030317148504903635,1740481188.9649231,20.739980220794678,0.0,1740481188.9649239,20.739980220794678,0.9645533565126366,, -1740481188.985889,20.75998020172119,12.62895569738603,1740481188.9858909,20.75998020172119,0.0,1740481188.9858944,20.75998020172119,0.0,1740481188.9858963,20.75998020172119,16.558062410411303,1740481188.9858975,20.75998020172119,0.0,1740481188.9858987,20.75998020172119,0.0,1740481188.9858997,20.75998020172119,0.0,1740481188.9859009,20.75998020172119,0.0,1740481188.9859016,20.75998020172119,0.9948705050175403,1740481188.9859025,20.75998020172119,0.0,1740481188.9859035,20.75998020172119,0.030317148504903635,1740481188.9859045,20.75998020172119,0.0,1740481188.9859054,20.75998020172119,0.9645533565126366,, -1740481189.0053704,20.779980182647705,12.735145850395028,1740481189.0053725,20.779980182647705,0.0,1740481189.0053744,20.779980182647705,0.017251829931227303,1740481189.0053766,20.779980182647705,16.576655086988502,1740481189.0053775,20.779980182647705,0.0,1740481189.005379,20.779980182647705,0.0,1740481189.0053802,20.779980182647705,0.0,1740481189.005381,20.779980182647705,0.0,1740481189.005382,20.779980182647705,0.9948705050175403,1740481189.005383,20.779980182647705,0.05129494982455851,1740481189.005384,20.779980182647705,0.08063693684177071,1740481189.005385,20.779980182647705,0.0,1740481189.0053859,20.779980182647705,0.9652237798356226,, -1740481189.025944,20.79998016357422,12.735145850395028,1740481189.025946,20.79998016357422,0.0,1740481189.0259478,20.79998016357422,0.017251829931227303,1740481189.02595,20.79998016357422,16.576655086988502,1740481189.025951,20.79998016357422,0.0,1740481189.0259526,20.79998016357422,0.0,1740481189.0259533,20.79998016357422,0.0,1740481189.0259542,20.79998016357422,0.0,1740481189.025955,20.79998016357422,0.9948705050175403,1740481189.0259562,20.79998016357422,0.05129494982455851,1740481189.025957,20.79998016357422,0.0809416750064762,1740481189.0259578,20.79998016357422,0.0,1740481189.025959,20.79998016357422,0.9652237798356226,, -1740481189.045534,20.819980144500732,12.735145850395028,1740481189.045536,20.819980144500732,0.0,1740481189.045539,20.819980144500732,0.017251829931227303,1740481189.0455408,20.819980144500732,16.576655086988502,1740481189.045542,20.819980144500732,0.0,1740481189.0455432,20.819980144500732,0.0,1740481189.0455441,20.819980144500732,0.0,1740481189.045545,20.819980144500732,0.0,1740481189.045546,20.819980144500732,0.9948705050175403,1740481189.045547,20.819980144500732,0.05129494982455851,1740481189.0455477,20.819980144500732,0.0809416750064762,1740481189.0455484,20.819980144500732,0.0,1740481189.0455496,20.819980144500732,0.9652237798356226,, -1740481189.064307,20.839980125427246,12.735145850395028,1740481189.0643086,20.839980125427246,0.0,1740481189.0643108,20.839980125427246,0.0,1740481189.064313,20.839980125427246,16.665593410066272,1740481189.064314,20.839980125427246,0.0,1740481189.0643148,20.839980125427246,0.0,1740481189.0643158,20.839980125427246,0.0,1740481189.064317,20.839980125427246,0.0,1740481189.0643177,20.839980125427246,0.9950627044163607,1740481189.0643187,20.839980125427246,0.0,1740481189.0643194,20.839980125427246,0.029838924580738113,1740481189.0643206,20.839980125427246,0.0,1740481189.0643213,20.839980125427246,0.9652237798356226,, -1740481189.0839179,20.85998010635376,12.735145850395028,1740481189.0839193,20.85998010635376,0.0,1740481189.0839217,20.85998010635376,0.0,1740481189.0839233,20.85998010635376,16.665593410066272,1740481189.0839245,20.85998010635376,0.0,1740481189.0839257,20.85998010635376,0.0,1740481189.0839267,20.85998010635376,0.0,1740481189.0839279,20.85998010635376,0.0,1740481189.0839286,20.85998010635376,0.9950627044163607,1740481189.0839293,20.85998010635376,0.0,1740481189.0839303,20.85998010635376,0.029838924580738113,1740481189.0839312,20.85998010635376,0.0,1740481189.0839324,20.85998010635376,0.9652237798356226,, -1740481189.11559,20.879980087280273,12.841367069776702,1740481189.1155927,20.879980087280273,0.0,1740481189.1155953,20.879980087280273,0.017260210888531566,1740481189.1155975,20.879980087280273,16.682874322055266,1740481189.115599,20.879980087280273,0.0,1740481189.1156003,20.879980087280273,0.0,1740481189.1156018,20.879980087280273,0.0,1740481189.1156027,20.879980087280273,0.0,1740481189.115604,20.879980087280273,0.9950627044163607,1740481189.1156049,20.879980087280273,0.04937295583635426,1740481189.115606,20.879980087280273,0.07919682506681527,1740481189.115607,20.879980087280273,0.0,1740481189.1156082,20.879980087280273,0.9652341303858534,, -1740481189.1242058,20.899980068206787,12.841367069776702,1740481189.1242085,20.899980068206787,0.0,1740481189.1242115,20.899980068206787,0.017260210888531566,1740481189.1242144,20.899980068206787,16.682874322055266,1740481189.1242158,20.899980068206787,0.0,1740481189.1242177,20.899980068206787,0.0,1740481189.1242194,20.899980068206787,0.0,1740481189.1242206,20.899980068206787,0.0,1740481189.124222,20.899980068206787,0.9950627044163607,1740481189.1242235,20.899980068206787,0.04937295583635426,1740481189.1242251,20.899980068206787,0.07920152986686158,1740481189.1242263,20.899980068206787,0.0,1740481189.1242275,20.899980068206787,0.9652341303858534,, -1740481189.1436598,20.9199800491333,12.841367069776702,1740481189.1436615,20.9199800491333,0.0,1740481189.143664,20.9199800491333,0.017260210888531566,1740481189.143666,20.9199800491333,16.682874322055266,1740481189.1436672,20.9199800491333,0.0,1740481189.1436687,20.9199800491333,0.0,1740481189.14367,20.9199800491333,0.0,1740481189.1436713,20.9199800491333,0.0,1740481189.1436725,20.9199800491333,0.9950627044163607,1740481189.1436749,20.9199800491333,0.04937295583635426,1740481189.1436765,20.9199800491333,0.07920152986686158,1740481189.1436777,20.9199800491333,0.0,1740481189.143679,20.9199800491333,0.9652341303858534,, -1740481189.1670263,20.939980030059814,12.841367069776702,1740481189.167028,20.939980030059814,0.0,1740481189.1670303,20.939980030059814,0.0,1740481189.167032,20.939980030059814,16.77183533054841,1740481189.1670332,20.939980030059814,0.0,1740481189.1670344,20.939980030059814,0.0,1740481189.1670353,20.939980030059814,0.0,1740481189.167036,20.939980030059814,0.0,1740481189.1670372,20.939980030059814,0.9950656429830341,1740481189.167038,20.939980030059814,0.0,1740481189.1670392,20.939980030059814,0.029831512597180754,1740481189.16704,20.939980030059814,0.0,1740481189.167041,20.939980030059814,0.9652341303858534,, -1740481189.184436,20.959980010986328,12.841367069776702,1740481189.1844378,20.959980010986328,0.0,1740481189.1844401,20.959980010986328,0.0,1740481189.184442,20.959980010986328,16.77183533054841,1740481189.184443,20.959980010986328,0.0,1740481189.1844442,20.959980010986328,0.0,1740481189.1844454,20.959980010986328,0.0,1740481189.1844466,20.959980010986328,0.0,1740481189.1844473,20.959980010986328,0.9950656429830341,1740481189.1844487,20.959980010986328,0.0,1740481189.1844494,20.959980010986328,0.029831512597180754,1740481189.1844506,20.959980010986328,0.0,1740481189.1844513,20.959980010986328,0.9652341303858534,, -1740481189.2057219,20.979979991912842,12.841367069776702,1740481189.2057245,20.979979991912842,0.0,1740481189.2057269,20.979979991912842,0.0,1740481189.2057292,20.979979991912842,16.77183533054841,1740481189.2057307,20.979979991912842,0.0,1740481189.2057319,20.979979991912842,0.0,1740481189.2057328,20.979979991912842,0.0,1740481189.2057338,20.979979991912842,0.0,1740481189.205735,20.979979991912842,0.9950656429830341,1740481189.205736,20.979979991912842,0.0,1740481189.205737,20.979979991912842,0.029831512597180754,1740481189.205738,20.979979991912842,0.0,1740481189.2057395,20.979979991912842,0.9652341303858534,, -1740481189.2235277,20.999979972839355,12.9476121592411,1740481189.22353,20.999979972839355,0.0,1740481189.2235324,20.999979972839355,0.017264140594695165,1740481189.2235346,20.999979972839355,16.78890974141172,1740481189.2235355,20.999979972839355,0.0,1740481189.223537,20.999979972839355,0.0,1740481189.223538,20.999979972839355,0.0,1740481189.2235389,20.999979972839355,0.0,1740481189.2235398,20.999979972839355,0.9950656429830341,1740481189.223541,20.999979972839355,0.0493435701697964,1740481189.223542,20.999979972839355,0.07931306806728594,1740481189.2235427,20.999979972839355,0.0,1740481189.223544,20.999979972839355,0.965139265520163,, -1740481189.24408,21.01997995376587,12.9476121592411,1740481189.244082,21.01997995376587,0.0,1740481189.244084,21.01997995376587,0.017264140594695165,1740481189.2440863,21.01997995376587,16.78890974141172,1740481189.2440872,21.01997995376587,0.0,1740481189.2440886,21.01997995376587,0.0,1740481189.2440896,21.01997995376587,0.0,1740481189.2440906,21.01997995376587,0.0,1740481189.2440915,21.01997995376587,0.9950656429830341,1740481189.244093,21.01997995376587,0.0493435701697964,1740481189.244094,21.01997995376587,0.07926994763266748,1740481189.2440946,21.01997995376587,0.0,1740481189.2440958,21.01997995376587,0.965139265520163,, -1740481189.2647705,21.039979934692383,12.9476121592411,1740481189.264773,21.039979934692383,0.0,1740481189.2647753,21.039979934692383,0.0,1740481189.2647774,21.039979934692383,16.877890690281426,1740481189.2647786,21.039979934692383,0.0,1740481189.2647798,21.039979934692383,0.0,1740481189.2647808,21.039979934692383,0.0,1740481189.2647824,21.039979934692383,0.0,1740481189.2647831,21.039979934692383,0.9950386776999025,1740481189.2647843,21.039979934692383,0.0,1740481189.264785,21.039979934692383,0.02989941217973946,1740481189.2647862,21.039979934692383,0.0,1740481189.264787,21.039979934692383,0.965139265520163,, -1740481189.2850077,21.059979915618896,12.9476121592411,1740481189.2850094,21.059979915618896,0.0,1740481189.2850118,21.059979915618896,0.0,1740481189.2850137,21.059979915618896,16.877890690281426,1740481189.2850153,21.059979915618896,0.0,1740481189.2850165,21.059979915618896,0.0,1740481189.2850175,21.059979915618896,0.0,1740481189.2850187,21.059979915618896,0.0,1740481189.2850196,21.059979915618896,0.9950386776999025,1740481189.2850206,21.059979915618896,0.0,1740481189.2850218,21.059979915618896,0.02989941217973946,1740481189.2850227,21.059979915618896,0.0,1740481189.2850237,21.059979915618896,0.965139265520163,, -1740481189.303421,21.07997989654541,12.9476121592411,1740481189.3034225,21.07997989654541,0.0,1740481189.3034246,21.07997989654541,0.0,1740481189.3034265,21.07997989654541,16.877890690281426,1740481189.3034277,21.07997989654541,0.0,1740481189.303429,21.07997989654541,0.0,1740481189.3034298,21.07997989654541,0.0,1740481189.3034308,21.07997989654541,0.0,1740481189.303432,21.07997989654541,0.9950386776999025,1740481189.303433,21.07997989654541,0.0,1740481189.303434,21.07997989654541,0.02989941217973946,1740481189.3034348,21.07997989654541,0.0,1740481189.3034358,21.07997989654541,0.965139265520163,, -1740481189.3236628,21.099979877471924,13.053773371091882,1740481189.3236644,21.099979877471924,0.0,1740481189.3236663,21.099979877471924,0.017250043552825316,1740481189.3236685,21.099979877471924,16.893003364864025,1740481189.3236692,21.099979877471924,0.0,1740481189.3236706,21.099979877471924,0.0,1740481189.3236716,21.099979877471924,0.0,1740481189.3236725,21.099979877471924,0.0,1740481189.3236735,21.099979877471924,0.9950386776999025,1740481189.3236744,21.099979877471924,0.04961322300093607,1740481189.3236756,21.099979877471924,0.0810670858041016,1740481189.3236763,21.099979877471924,0.0,1740481189.3236775,21.099979877471924,0.9640705810350507,, -1740481189.3445604,21.119979858398438,13.053773371091882,1740481189.3445654,21.119979858398438,0.0,1740481189.3445694,21.119979858398438,0.017250043552825316,1740481189.3445716,21.119979858398438,16.893003364864025,1740481189.3445733,21.119979858398438,0.0,1740481189.3445747,21.119979858398438,0.0,1740481189.3445776,21.119979858398438,0.0,1740481189.3445804,21.119979858398438,0.0,1740481189.3445818,21.119979858398438,0.9950386776999025,1740481189.344584,21.119979858398438,0.04961322300093607,1740481189.3445857,21.119979858398438,0.08058131966578785,1740481189.3445873,21.119979858398438,0.0,1740481189.3445888,21.119979858398438,0.9640705810350507,, -1740481189.3660145,21.13997983932495,13.053773371091882,1740481189.3660166,21.13997983932495,0.0,1740481189.3660188,21.13997983932495,0.0,1740481189.3660207,21.13997983932495,16.981914533161984,1740481189.3660216,21.13997983932495,0.0,1740481189.3660228,21.13997983932495,0.0,1740481189.366024,21.13997983932495,0.0,1740481189.366025,21.13997983932495,0.0,1740481189.366026,21.13997983932495,0.9947298283205174,1740481189.366027,21.13997983932495,0.0,1740481189.3660278,21.13997983932495,0.03065924728546665,1740481189.3660288,21.13997983932495,0.0,1740481189.3660297,21.13997983932495,0.9640705810350507,, -1740481189.3839371,21.159979820251465,13.053773371091882,1740481189.3839405,21.159979820251465,0.0,1740481189.3839447,21.159979820251465,0.0,1740481189.3839493,21.159979820251465,16.981914533161984,1740481189.3839514,21.159979820251465,0.0,1740481189.3839543,21.159979820251465,0.0,1740481189.3839562,21.159979820251465,0.0,1740481189.383958,21.159979820251465,0.0,1740481189.38396,21.159979820251465,0.9947298283205174,1740481189.3839622,21.159979820251465,0.0,1740481189.383964,21.159979820251465,0.03065924728546665,1740481189.383966,21.159979820251465,0.0,1740481189.383968,21.159979820251465,0.9640705810350507,, -1740481189.403632,21.17997980117798,13.053773371091882,1740481189.4036336,21.17997980117798,0.0,1740481189.4036362,21.17997980117798,0.0,1740481189.4036384,21.17997980117798,16.981914533161984,1740481189.4036396,21.17997980117798,0.0,1740481189.403641,21.17997980117798,0.0,1740481189.4036422,21.17997980117798,0.0,1740481189.4036431,21.17997980117798,0.0,1740481189.403644,21.17997980117798,0.9947298283205174,1740481189.4036455,21.17997980117798,0.0,1740481189.4036465,21.17997980117798,0.03065924728546665,1740481189.4036472,21.17997980117798,0.0,1740481189.4036481,21.17997980117798,0.9640705810350507,, -1740481189.4237146,21.199979782104492,13.053773371091882,1740481189.4237163,21.199979782104492,0.0,1740481189.4237185,21.199979782104492,0.0,1740481189.4237201,21.199979782104492,16.981914533161984,1740481189.4237216,21.199979782104492,0.0,1740481189.4237225,21.199979782104492,0.0,1740481189.4237237,21.199979782104492,0.0,1740481189.4237247,21.199979782104492,0.0,1740481189.4237256,21.199979782104492,0.9947298283205174,1740481189.4237266,21.199979782104492,0.0,1740481189.4237273,21.199979782104492,0.03065924728546665,1740481189.4237285,21.199979782104492,0.0,1740481189.4237292,21.199979782104492,0.9640705810350507,, -1740481189.443724,21.219979763031006,13.15984403541566,1740481189.4437258,21.219979763031006,0.0,1740481189.443728,21.219979763031006,0.017229980900879197,1740481189.4437304,21.219979763031006,16.99725004419719,1740481189.4437315,21.219979763031006,0.0,1740481189.4437327,21.219979763031006,0.0,1740481189.4437337,21.219979763031006,0.0,1740481189.4437346,21.219979763031006,0.0,1740481189.4437354,21.219979763031006,0.9947298283205174,1740481189.4437368,21.219979763031006,0.05270171679496394,1740481189.4437375,21.219979763031006,0.08473876075698905,1740481189.4437387,21.219979763031006,0.0,1740481189.4437394,21.219979763031006,0.9631233461022151,, -1740481189.464508,21.23997974395752,13.15984403541566,1740481189.4645102,21.23997974395752,0.0,1740481189.4645123,21.23997974395752,0.0,1740481189.4645143,21.23997974395752,17.08609072762009,1740481189.4645152,21.23997974395752,0.0,1740481189.4645166,21.23997974395752,0.0,1740481189.4645176,21.23997974395752,0.0,1740481189.4645185,21.23997974395752,0.0,1740481189.4645197,21.23997974395752,0.9944482821097547,1740481189.4645207,21.23997974395752,0.0,1740481189.4645216,21.23997974395752,0.031324936007539605,1740481189.4645226,21.23997974395752,0.0,1740481189.4645233,21.23997974395752,0.9631233461022151,, -1740481189.4859915,21.259979724884033,13.15984403541566,1740481189.4859934,21.259979724884033,0.0,1740481189.4859958,21.259979724884033,0.0,1740481189.4859982,21.259979724884033,17.08609072762009,1740481189.4859993,21.259979724884033,0.0,1740481189.486001,21.259979724884033,0.0,1740481189.486002,21.259979724884033,0.0,1740481189.486003,21.259979724884033,0.0,1740481189.4860039,21.259979724884033,0.9944482821097547,1740481189.486005,21.259979724884033,0.0,1740481189.4860058,21.259979724884033,0.031324936007539605,1740481189.4860067,21.259979724884033,0.0,1740481189.4860077,21.259979724884033,0.9631233461022151,, -1740481189.5042524,21.279979705810547,13.15984403541566,1740481189.5042548,21.279979705810547,0.0,1740481189.504257,21.279979705810547,0.0,1740481189.504259,21.279979705810547,17.08609072762009,1740481189.50426,21.279979705810547,0.0,1740481189.5042615,21.279979705810547,0.0,1740481189.5042627,21.279979705810547,0.0,1740481189.5042636,21.279979705810547,0.0,1740481189.5042646,21.279979705810547,0.9944482821097547,1740481189.504266,21.279979705810547,0.0,1740481189.5042667,21.279979705810547,0.031324936007539605,1740481189.5042677,21.279979705810547,0.0,1740481189.5042691,21.279979705810547,0.9631233461022151,, -1740481189.5237432,21.29997968673706,13.15984403541566,1740481189.523745,21.29997968673706,0.0,1740481189.5237474,21.29997968673706,0.0,1740481189.5237627,21.29997968673706,17.08609072762009,1740481189.5237641,21.29997968673706,0.0,1740481189.5237665,21.29997968673706,0.0,1740481189.5237675,21.29997968673706,0.0,1740481189.5237687,21.29997968673706,0.0,1740481189.5237694,21.29997968673706,0.9944482821097547,1740481189.5237703,21.29997968673706,0.0,1740481189.5237713,21.29997968673706,0.031324936007539605,1740481189.5237725,21.29997968673706,0.0,1740481189.5237732,21.29997968673706,0.9631233461022151,, -1740481189.5438273,21.319979667663574,13.265734214764212,1740481189.5438292,21.319979667663574,0.0,1740481189.5438323,21.319979667663574,0.01719579471695431,1740481189.5438354,21.319979667663574,17.09967355063116,1740481189.5438366,21.319979667663574,0.0,1740481189.5438385,21.319979667663574,0.0,1740481189.5438397,21.319979667663574,0.0,1740481189.543842,21.319979667663574,0.0,1740481189.5438437,21.319979667663574,0.9944482821097547,1740481189.543846,21.319979667663574,0.055517178902591,1740481189.5438476,21.319979667663574,0.0894697314793209,1740481189.5438492,21.319979667663574,0.0,1740481189.543851,21.319979667663574,0.961316860249272,, -1740481189.5651782,21.339979648590088,13.265734214764212,1740481189.5651796,21.339979648590088,0.0,1740481189.565182,21.339979648590088,0.0,1740481189.565184,21.339979648590088,17.188367935262754,1740481189.5651848,21.339979648590088,0.0,1740481189.565186,21.339979648590088,0.0,1740481189.565187,21.339979648590088,0.0,1740481189.5651882,21.339979648590088,0.0,1740481189.5651891,21.339979648590088,0.9938910325900246,1740481189.56519,21.339979648590088,0.0,1740481189.5651913,21.339979648590088,0.03257417234075266,1740481189.5651922,21.339979648590088,0.0,1740481189.565193,21.339979648590088,0.961316860249272,, -1740481189.586168,21.3599796295166,13.265734214764212,1740481189.5861704,21.3599796295166,0.0,1740481189.5861726,21.3599796295166,0.0,1740481189.5861747,21.3599796295166,17.188367935262754,1740481189.5861757,21.3599796295166,0.0,1740481189.586177,21.3599796295166,0.0,1740481189.586178,21.3599796295166,0.0,1740481189.586179,21.3599796295166,0.0,1740481189.5861802,21.3599796295166,0.9938910325900246,1740481189.5861812,21.3599796295166,0.0,1740481189.586182,21.3599796295166,0.03257417234075266,1740481189.586183,21.3599796295166,0.0,1740481189.5861843,21.3599796295166,0.961316860249272,, -1740481189.6054463,21.379979610443115,13.265734214764212,1740481189.6054487,21.379979610443115,0.0,1740481189.605451,21.379979610443115,0.0,1740481189.6054533,21.379979610443115,17.188367935262754,1740481189.6054544,21.379979610443115,0.0,1740481189.6054559,21.379979610443115,0.0,1740481189.605457,21.379979610443115,0.0,1740481189.6054583,21.379979610443115,0.0,1740481189.6054592,21.379979610443115,0.9938910325900246,1740481189.6054602,21.379979610443115,0.0,1740481189.6054614,21.379979610443115,0.03257417234075266,1740481189.6054623,21.379979610443115,0.0,1740481189.6054633,21.379979610443115,0.961316860249272,, -1740481189.6240041,21.39997959136963,13.265734214764212,1740481189.624006,21.39997959136963,0.0,1740481189.6240084,21.39997959136963,0.0,1740481189.6240106,21.39997959136963,17.188367935262754,1740481189.6240115,21.39997959136963,0.0,1740481189.6240127,21.39997959136963,0.0,1740481189.624014,21.39997959136963,0.0,1740481189.6240149,21.39997959136963,0.0,1740481189.6240156,21.39997959136963,0.9938910325900246,1740481189.6240165,21.39997959136963,0.0,1740481189.6240177,21.39997959136963,0.03257417234075266,1740481189.6240187,21.39997959136963,0.0,1740481189.6240196,21.39997959136963,0.961316860249272,, -1740481189.644828,21.419979572296143,13.265734214764212,1740481189.6448326,21.419979572296143,0.0,1740481189.6448376,21.419979572296143,0.0,1740481189.644843,21.419979572296143,17.188367935262754,1740481189.644845,21.419979572296143,0.0,1740481189.6448486,21.419979572296143,0.0,1740481189.6448507,21.419979572296143,0.0,1740481189.6448526,21.419979572296143,0.0,1740481189.6448548,21.419979572296143,0.9938910325900246,1740481189.644857,21.419979572296143,0.0,1740481189.6448588,21.419979572296143,0.03257417234075266,1740481189.644861,21.419979572296143,0.0,1740481189.644863,21.419979572296143,0.961316860249272,, -1740481189.6661403,21.439979553222656,13.371451103240858,1740481189.6661422,21.439979553222656,0.0,1740481189.6661444,21.439979553222656,0.0,1740481189.6661463,21.439979553222656,17.29092326334286,1740481189.6661472,21.439979553222656,0.0,1740481189.6661487,21.439979553222656,0.0,1740481189.6661496,21.439979553222656,0.0,1740481189.6661503,21.439979553222656,0.0,1740481189.6661515,21.439979553222656,0.9933815470979754,1740481189.6661522,21.439979553222656,0.0661845290203833,1740481189.6661532,21.439979553222656,0.10031694867094126,1740481189.666154,21.439979553222656,0.0,1740481189.666155,21.439979553222656,0.9597360800510026,, -1740481189.6836426,21.45997953414917,13.371451103240858,1740481189.6836455,21.45997953414917,0.0,1740481189.683648,21.45997953414917,0.0,1740481189.6836503,21.45997953414917,17.29092326334286,1740481189.6836512,21.45997953414917,0.0,1740481189.6836529,21.45997953414917,0.0,1740481189.6836538,21.45997953414917,0.0,1740481189.6836553,21.45997953414917,0.0,1740481189.6836565,21.45997953414917,0.9933815470979754,1740481189.6836572,21.45997953414917,0.0661845290203833,1740481189.6836586,21.45997953414917,0.0998299960673561,1740481189.6836596,21.45997953414917,0.0,1740481189.6836603,21.45997953414917,0.9597360800510026,, -1740481189.7035868,21.479979515075684,13.371451103240858,1740481189.70359,21.479979515075684,0.0,1740481189.7035923,21.479979515075684,0.0,1740481189.7035944,21.479979515075684,17.29092326334286,1740481189.7035956,21.479979515075684,0.0,1740481189.7035968,21.479979515075684,0.0,1740481189.7035983,21.479979515075684,0.0,1740481189.7035997,21.479979515075684,0.0,1740481189.7036006,21.479979515075684,0.9933815470979754,1740481189.703602,21.479979515075684,0.0661845290203833,1740481189.7036033,21.479979515075684,0.0998299960673561,1740481189.7036042,21.479979515075684,0.0,1740481189.7036052,21.479979515075684,0.9597360800510026,, -1740481189.7255397,21.499979496002197,13.371451103240858,1740481189.7255445,21.499979496002197,0.0,1740481189.725549,21.499979496002197,0.0,1740481189.7255526,21.499979496002197,17.29092326334286,1740481189.7255547,21.499979496002197,0.0,1740481189.7255569,21.499979496002197,0.0,1740481189.725559,21.499979496002197,0.0,1740481189.7255604,21.499979496002197,0.0,1740481189.7255619,21.499979496002197,0.9933815470979754,1740481189.7255647,21.499979496002197,0.0661845290203833,1740481189.7255657,21.499979496002197,0.0998299960673561,1740481189.7255673,21.499979496002197,0.0,1740481189.7255695,21.499979496002197,0.9597360800510026,, -1740481189.7441168,21.51997947692871,13.371451103240858,1740481189.7441204,21.51997947692871,0.0,1740481189.7441232,21.51997947692871,0.0,1740481189.7441256,21.51997947692871,17.29092326334286,1740481189.7441278,21.51997947692871,0.0,1740481189.7441294,21.51997947692871,0.0,1740481189.744131,21.51997947692871,0.0,1740481189.7441328,21.51997947692871,0.0,1740481189.744134,21.51997947692871,0.9933815470979754,1740481189.7441351,21.51997947692871,0.0661845290203833,1740481189.7441363,21.51997947692871,0.0998299960673561,1740481189.7441373,21.51997947692871,0.0,1740481189.7441382,21.51997947692871,0.9597360800510026,, -1740481189.7660928,21.539979457855225,13.477189842202876,1740481189.766113,21.539979457855225,0.0,1740481189.7661178,21.539979457855225,0.0,1740481189.7661204,21.539979457855225,17.404692234590463,1740481189.766122,21.539979457855225,0.0,1740481189.7661247,21.539979457855225,0.0,1740481189.7661266,21.539979457855225,0.0,1740481189.7661278,21.539979457855225,0.0,1740481189.7661297,21.539979457855225,0.9946357163517343,1740481189.7661319,21.539979457855225,0.05364283648261803,1740481189.766134,21.539979457855225,0.08327237958506878,1740481189.7661352,21.539979457855225,0.0,1740481189.7661366,21.539979457855225,0.9637511961937933,, -1740481189.7846231,21.55997943878174,13.477189842202876,1740481189.784625,21.55997943878174,0.0,1740481189.7846274,21.55997943878174,0.0,1740481189.7846296,21.55997943878174,17.404692234590463,1740481189.7846305,21.55997943878174,0.0,1740481189.784632,21.55997943878174,0.0,1740481189.7846332,21.55997943878174,0.0,1740481189.7846339,21.55997943878174,0.0,1740481189.7846348,21.55997943878174,0.9946357163517343,1740481189.7846482,21.55997943878174,0.05364283648261803,1740481189.7846494,21.55997943878174,0.08452735664055899,1740481189.7846506,21.55997943878174,0.0,1740481189.7846515,21.55997943878174,0.9637511961937933,, -1740481189.8058102,21.579979419708252,13.477189842202876,1740481189.805814,21.579979419708252,0.0,1740481189.8058188,21.579979419708252,0.0,1740481189.8058221,21.579979419708252,17.404692234590463,1740481189.805824,21.579979419708252,0.0,1740481189.8058267,21.579979419708252,0.0,1740481189.8058286,21.579979419708252,0.0,1740481189.8058312,21.579979419708252,0.0,1740481189.8058326,21.579979419708252,0.9946357163517343,1740481189.8058355,21.579979419708252,0.05364283648261803,1740481189.805837,21.579979419708252,0.08452735664055899,1740481189.8058388,21.579979419708252,0.0,1740481189.805841,21.579979419708252,0.9637511961937933,, -1740481189.8239365,21.599979400634766,13.477189842202876,1740481189.8239386,21.599979400634766,0.0,1740481189.8239408,21.599979400634766,0.0,1740481189.823943,21.599979400634766,17.404692234590463,1740481189.8239439,21.599979400634766,0.0,1740481189.823945,21.599979400634766,0.0,1740481189.823946,21.599979400634766,0.0,1740481189.823947,21.599979400634766,0.0,1740481189.8239481,21.599979400634766,0.9946357163517343,1740481189.8239493,21.599979400634766,0.05364283648261803,1740481189.8239505,21.599979400634766,0.08452735664055899,1740481189.8239512,21.599979400634766,0.0,1740481189.8239524,21.599979400634766,0.9637511961937933,, -1740481189.8446226,21.61997938156128,13.477189842202876,1740481189.8446257,21.61997938156128,0.0,1740481189.8446288,21.61997938156128,0.0,1740481189.8446314,21.61997938156128,17.404692234590463,1740481189.844633,21.61997938156128,0.0,1740481189.8446355,21.61997938156128,0.0,1740481189.8446367,21.61997938156128,0.0,1740481189.8446379,21.61997938156128,0.0,1740481189.8446393,21.61997938156128,0.9946357163517343,1740481189.8446412,21.61997938156128,0.05364283648261803,1740481189.844643,21.61997938156128,0.08452735664055899,1740481189.8446445,21.61997938156128,0.0,1740481189.8446467,21.61997938156128,0.9637511961937933,, -1740481189.8651388,21.639979362487793,13.477189842202876,1740481189.8651404,21.639979362487793,0.0,1740481189.8651426,21.639979362487793,0.0,1740481189.8651443,21.639979362487793,17.404692234590463,1740481189.8651454,21.639979362487793,0.0,1740481189.8651464,21.639979362487793,0.0,1740481189.8651474,21.639979362487793,0.0,1740481189.8651488,21.639979362487793,0.0,1740481189.8651495,21.639979362487793,0.9946357163517343,1740481189.8651505,21.639979362487793,0.05364283648261803,1740481189.8651512,21.639979362487793,0.08452735664055899,1740481189.8651524,21.639979362487793,0.0,1740481189.865153,21.639979362487793,0.9637511961937933,, -1740481189.8849804,21.659979343414307,13.583348571499474,1740481189.8849823,21.659979343414307,0.0,1740481189.8849843,21.659979343414307,0.017242654568692173,1740481189.8849864,21.659979343414307,17.42781580206221,1740481189.8849874,21.659979343414307,0.0,1740481189.8849888,21.659979343414307,0.0,1740481189.8849897,21.659979343414307,0.0,1740481189.8849907,21.659979343414307,0.0,1740481189.8849916,21.659979343414307,0.9999999999999961,1740481189.8849928,21.659979343414307,5.551115123125783e-15,1740481189.8849938,21.659979343414307,0.03441008804026101,1740481189.8849945,21.659979343414307,0.0,1740481189.8849957,21.659979343414307,0.9666916526453214,, -1740481189.9075475,21.67997932434082,13.583348571499474,1740481189.9075513,21.67997932434082,0.0,1740481189.9075563,21.67997932434082,0.017242654568692173,1740481189.90756,21.67997932434082,17.42781580206221,1740481189.907562,21.67997932434082,0.0,1740481189.9075649,21.67997932434082,0.0,1740481189.9075665,21.67997932434082,0.0,1740481189.9075685,21.67997932434082,0.0,1740481189.9075882,21.67997932434082,0.9999999999999961,1740481189.9075942,21.67997932434082,5.551115123125783e-15,1740481189.907596,21.67997932434082,0.033308347354680246,1740481189.907598,21.67997932434082,0.0,1740481189.9076002,21.67997932434082,0.9666916526453214,, -1740481189.9240012,21.699979305267334,13.583348571499474,1740481189.9240031,21.699979305267334,0.0,1740481189.924005,21.699979305267334,0.017242654568692173,1740481189.924007,21.699979305267334,17.42781580206221,1740481189.924008,21.699979305267334,0.0,1740481189.9240093,21.699979305267334,0.0,1740481189.9240103,21.699979305267334,0.0,1740481189.924011,21.699979305267334,0.0,1740481189.924012,21.699979305267334,0.9999999999999961,1740481189.9240131,21.699979305267334,5.551115123125783e-15,1740481189.924014,21.699979305267334,0.033308347354680246,1740481189.9240148,21.699979305267334,0.0,1740481189.9240158,21.699979305267334,0.9666916526453214,, -1740481189.9453275,21.719979286193848,13.583348571499474,1740481189.9453301,21.719979286193848,0.0,1740481189.9453335,21.719979286193848,0.017242654568692173,1740481189.9453359,21.719979286193848,17.42781580206221,1740481189.945337,21.719979286193848,0.0,1740481189.945339,21.719979286193848,0.0,1740481189.9453413,21.719979286193848,0.0,1740481189.9453425,21.719979286193848,0.0,1740481189.945344,21.719979286193848,0.9999999999999961,1740481189.9453459,21.719979286193848,5.551115123125783e-15,1740481189.9453468,21.719979286193848,0.033308347354680246,1740481189.9453483,21.719979286193848,0.0,1740481189.9453495,21.719979286193848,0.9666916526453214,, -1740481189.964285,21.73997926712036,13.583348571499474,1740481189.9642868,21.73997926712036,0.0,1740481189.964289,21.73997926712036,0.0,1740481189.964291,21.73997926712036,17.516731876790118,1740481189.964292,21.73997926712036,0.0,1740481189.9642935,21.73997926712036,0.0,1740481189.9642944,21.73997926712036,0.0,1740481189.9642951,21.73997926712036,0.0,1740481189.964296,21.73997926712036,0.9954707056570888,1740481189.9642973,21.73997926712036,0.0,1740481189.964298,21.73997926712036,0.02877905301176742,1740481189.964299,21.73997926712036,0.0,1740481189.9643,21.73997926712036,0.9666916526453214,, -1740481189.984705,21.759979248046875,13.689603364946514,1740481189.984707,21.759979248046875,0.0,1740481189.9847097,21.759979248046875,0.017272745807376158,1740481189.984712,21.759979248046875,17.529541514583364,1740481189.9847133,21.759979248046875,0.0,1740481189.9847147,21.759979248046875,0.0,1740481189.984716,21.759979248046875,0.0,1740481189.9847171,21.759979248046875,0.0,1740481189.984718,21.759979248046875,0.9954707056570888,1740481189.9847193,21.759979248046875,0.04529294342924928,1740481189.9847205,21.759979248046875,0.07731789414591914,1740481189.9847214,21.759979248046875,0.0,1740481189.9847224,21.759979248046875,0.9644600986382565,, -1740481190.0046217,21.77997922897339,13.689603364946514,1740481190.0046244,21.77997922897339,0.0,1740481190.004627,21.77997922897339,0.017272745807376158,1740481190.004629,21.77997922897339,17.529541514583364,1740481190.0046303,21.77997922897339,0.0,1740481190.0046318,21.77997922897339,0.0,1740481190.0046332,21.77997922897339,0.0,1740481190.0046341,21.77997922897339,0.0,1740481190.004635,21.77997922897339,0.9954707056570888,1740481190.004636,21.77997922897339,0.04529294342924928,1740481190.0046372,21.77997922897339,0.07630355044808157,1740481190.0046382,21.77997922897339,0.0,1740481190.0046394,21.77997922897339,0.9644600986382565,, -1740481190.0240774,21.799979209899902,13.689603364946514,1740481190.0240788,21.799979209899902,0.0,1740481190.0240812,21.799979209899902,0.017272745807376158,1740481190.0240831,21.799979209899902,17.529541514583364,1740481190.0240843,21.799979209899902,0.0,1740481190.0240858,21.799979209899902,0.0,1740481190.024087,21.799979209899902,0.0,1740481190.024088,21.799979209899902,0.0,1740481190.0240889,21.799979209899902,0.9954707056570888,1740481190.0240898,21.799979209899902,0.04529294342924928,1740481190.0240905,21.799979209899902,0.07630355044808157,1740481190.0240917,21.799979209899902,0.0,1740481190.0240924,21.799979209899902,0.9644600986382565,, -1740481190.0446575,21.819979190826416,13.689603364946514,1740481190.0446591,21.819979190826416,0.0,1740481190.0446715,21.819979190826416,0.017272745807376158,1740481190.0446742,21.819979190826416,17.529541514583364,1740481190.044675,21.819979190826416,0.0,1740481190.0446765,21.819979190826416,0.0,1740481190.044678,21.819979190826416,0.0,1740481190.0446787,21.819979190826416,0.0,1740481190.0446796,21.819979190826416,0.9954707056570888,1740481190.0446806,21.819979190826416,0.04529294342924928,1740481190.0446818,21.819979190826416,0.07630355044808157,1740481190.0446827,21.819979190826416,0.0,1740481190.0446837,21.819979190826416,0.9644600986382565,, -1740481190.0646343,21.83997917175293,13.689603364946514,1740481190.0646362,21.83997917175293,0.0,1740481190.0646381,21.83997917175293,0.0,1740481190.0646403,21.83997917175293,17.618523562223025,1740481190.0646412,21.83997917175293,0.0,1740481190.0646427,21.83997917175293,0.0,1740481190.0646436,21.83997917175293,0.0,1740481190.0646443,21.83997917175293,0.0,1740481190.0646453,21.83997917175293,0.9948434787591004,1740481190.0646465,21.83997917175293,0.0,1740481190.0646474,21.83997917175293,0.03038338012084385,1740481190.0646484,21.83997917175293,0.0,1740481190.0646496,21.83997917175293,0.9644600986382565,, -1740481190.084358,21.859979152679443,13.689603364946514,1740481190.08436,21.859979152679443,0.0,1740481190.0843623,21.859979152679443,0.0,1740481190.0843642,21.859979152679443,17.618523562223025,1740481190.0843656,21.859979152679443,0.0,1740481190.0843668,21.859979152679443,0.0,1740481190.084368,21.859979152679443,0.0,1740481190.0843692,21.859979152679443,0.0,1740481190.0843701,21.859979152679443,0.9948434787591004,1740481190.0843716,21.859979152679443,0.0,1740481190.0843728,21.859979152679443,0.03038338012084385,1740481190.0843737,21.859979152679443,0.0,1740481190.0843747,21.859979152679443,0.9644600986382565,, -1740481190.104202,21.879979133605957,13.795785192993907,1740481190.1042035,21.879979133605957,0.0,1740481190.1042056,21.879979133605957,0.01725000882439215,1740481190.1042075,21.879979133605957,17.637177608647193,1740481190.1042087,21.879979133605957,0.0,1740481190.10421,21.879979133605957,0.0,1740481190.1042109,21.879979133605957,0.0,1740481190.104212,21.879979133605957,0.0,1740481190.104213,21.879979133605957,0.9948434787591004,1740481190.104214,21.879979133605957,0.05156521240895717,1740481190.1042154,21.879979133605957,0.08092747397110452,1740481190.104216,21.879979133605957,0.0,1740481190.1042168,21.879979133605957,0.9651621174381423,, -1740481190.123631,21.89997911453247,13.795785192993907,1740481190.123633,21.89997911453247,0.0,1740481190.1236353,21.89997911453247,0.01725000882439215,1740481190.1236372,21.89997911453247,17.637177608647193,1740481190.1236382,21.89997911453247,0.0,1740481190.1236396,21.89997911453247,0.0,1740481190.1236405,21.89997911453247,0.0,1740481190.1236415,21.89997911453247,0.0,1740481190.1236424,21.89997911453247,0.9948434787591004,1740481190.1236436,21.89997911453247,0.05156521240895717,1740481190.1236444,21.89997911453247,0.08124657372991528,1740481190.1236455,21.89997911453247,0.0,1740481190.1236463,21.89997911453247,0.9651621174381423,, -1740481190.1464427,21.919979095458984,13.795785192993907,1740481190.1464448,21.919979095458984,0.0,1740481190.146447,21.919979095458984,0.01725000882439215,1740481190.1464489,21.919979095458984,17.637177608647193,1740481190.1464498,21.919979095458984,0.0,1740481190.1464512,21.919979095458984,0.0,1740481190.1464522,21.919979095458984,0.0,1740481190.1464531,21.919979095458984,0.0,1740481190.1464546,21.919979095458984,0.9948434787591004,1740481190.1464553,21.919979095458984,0.05156521240895717,1740481190.1464658,21.919979095458984,0.08124657372991528,1740481190.1464694,21.919979095458984,0.0,1740481190.1464703,21.919979095458984,0.9651621174381423,, -1740481190.1681745,21.939979076385498,13.795785192993907,1740481190.168177,21.939979076385498,0.0,1740481190.16818,21.939979076385498,0.0,1740481190.168183,21.939979076385498,17.726109427870192,1740481190.1681845,21.939979076385498,0.0,1740481190.1681864,21.939979076385498,0.0,1740481190.1681879,21.939979076385498,0.0,1740481190.1681898,21.939979076385498,0.0,1740481190.168191,21.939979076385498,0.9950451800626208,1740481190.1681926,21.939979076385498,0.0,1740481190.1681938,21.939979076385498,0.029883062624478485,1740481190.168195,21.939979076385498,0.0,1740481190.1681964,21.939979076385498,0.9651621174381423,, -1740481190.1834373,21.95997905731201,13.795785192993907,1740481190.1834388,21.95997905731201,0.0,1740481190.1834412,21.95997905731201,0.0,1740481190.1834433,21.95997905731201,17.726109427870192,1740481190.1834445,21.95997905731201,0.0,1740481190.1834457,21.95997905731201,0.0,1740481190.183447,21.95997905731201,0.0,1740481190.1834478,21.95997905731201,0.0,1740481190.1834486,21.95997905731201,0.9950451800626208,1740481190.1834497,21.95997905731201,0.0,1740481190.183451,21.95997905731201,0.029883062624478485,1740481190.183452,21.95997905731201,0.0,1740481190.1834528,21.95997905731201,0.9651621174381423,, -1740481190.2235546,21.99997901916504,13.902000907770052,1740481190.2235563,21.99997901916504,0.0,1740481190.2235587,21.99997901916504,0.01725901246923722,1740481190.2235608,21.99997901916504,17.7434307735628,1740481190.2235618,21.99997901916504,0.0,1740481190.223575,21.99997901916504,0.0,1740481190.223576,21.99997901916504,0.0,1740481190.223577,21.99997901916504,0.0,1740481190.2235782,21.99997901916504,0.9950451800626208,1740481190.2235792,21.99997901916504,0.04954819937392996,1740481190.22358,21.99997901916504,0.07938592873153628,1740481190.2235808,21.99997901916504,0.0,1740481190.2235818,21.99997901916504,0.9651932840498285,, -1740481190.2437959,22.019979000091553,13.902000907770052,1740481190.243798,22.019979000091553,0.0,1740481190.2438,22.019979000091553,0.01725901246923722,1740481190.2438018,22.019979000091553,17.7434307735628,1740481190.2438028,22.019979000091553,0.0,1740481190.2438042,22.019979000091553,0.0,1740481190.2438052,22.019979000091553,0.0,1740481190.2438061,22.019979000091553,0.0,1740481190.2438073,22.019979000091553,0.9950451800626208,1740481190.2438083,22.019979000091553,0.04954819937392996,1740481190.243809,22.019979000091553,0.07940009538672221,1740481190.24381,22.019979000091553,0.0,1740481190.2438111,22.019979000091553,0.9651932840498285,, -1740481190.263778,22.039978981018066,13.902000907770052,1740481190.2637799,22.039978981018066,0.0,1740481190.2637818,22.039978981018066,0.0,1740481190.263784,22.039978981018066,17.83238747586971,1740481190.263785,22.039978981018066,0.0,1740481190.2637863,22.039978981018066,0.0,1740481190.2637873,22.039978981018066,0.0,1740481190.263788,22.039978981018066,0.0,1740481190.263789,22.039978981018066,0.9950540414435072,1740481190.2637904,22.039978981018066,0.0,1740481190.2637913,22.039978981018066,0.02986075739367866,1740481190.263792,22.039978981018066,0.0,1740481190.2638054,22.039978981018066,0.9651932840498285,, -1740481190.2846308,22.05997896194458,13.902000907770052,1740481190.2846332,22.05997896194458,0.0,1740481190.284635,22.05997896194458,0.0,1740481190.2846372,22.05997896194458,17.83238747586971,1740481190.2846382,22.05997896194458,0.0,1740481190.2846396,22.05997896194458,0.0,1740481190.2846408,22.05997896194458,0.0,1740481190.2846417,22.05997896194458,0.0,1740481190.2846425,22.05997896194458,0.9950540414435072,1740481190.284644,22.05997896194458,0.0,1740481190.2846448,22.05997896194458,0.02986075739367866,1740481190.2846456,22.05997896194458,0.0,1740481190.2846467,22.05997896194458,0.9651932840498285,, -1740481190.3062813,22.079978942871094,13.902000907770052,1740481190.3062854,22.079978942871094,0.0,1740481190.3062892,22.079978942871094,0.0,1740481190.306308,22.079978942871094,17.83238747586971,1740481190.306311,22.079978942871094,0.0,1740481190.306314,22.079978942871094,0.0,1740481190.3063157,22.079978942871094,0.0,1740481190.3063173,22.079978942871094,0.0,1740481190.3063185,22.079978942871094,0.9950540414435072,1740481190.3063207,22.079978942871094,0.0,1740481190.306322,22.079978942871094,0.02986075739367866,1740481190.3063235,22.079978942871094,0.0,1740481190.306325,22.079978942871094,0.9651932840498285,, -1740481190.3237355,22.099978923797607,14.008148623171483,1740481190.3237371,22.099978923797607,0.0,1740481190.323739,22.099978923797607,0.01724811683925277,1740481190.3237412,22.099978923797607,17.84750505335072,1740481190.3237422,22.099978923797607,0.0,1740481190.3237438,22.099978923797607,0.0,1740481190.3237445,22.099978923797607,0.0,1740481190.3237457,22.099978923797607,0.0,1740481190.323747,22.099978923797607,0.9950540414435072,1740481190.3237476,22.099978923797607,0.049459585564889386,1740481190.3237486,22.099978923797607,0.08086982658998151,1740481190.3237493,22.099978923797607,0.0,1740481190.3237505,22.099978923797607,0.9641280143707072,, -1740481190.3435235,22.11997890472412,14.008148623171483,1740481190.3435254,22.11997890472412,0.0,1740481190.3435273,22.11997890472412,0.01724811683925277,1740481190.3435295,22.11997890472412,17.84750505335072,1740481190.3435302,22.11997890472412,0.0,1740481190.3435316,22.11997890472412,0.0,1740481190.3435326,22.11997890472412,0.0,1740481190.3435333,22.11997890472412,0.0,1740481190.343534,22.11997890472412,0.9950540414435072,1740481190.3435352,22.11997890472412,0.049459585564889386,1740481190.3435361,22.11997890472412,0.0803856126376894,1740481190.343537,22.11997890472412,0.0,1740481190.3435378,22.11997890472412,0.9641280143707072,, -1740481190.3644657,22.139978885650635,14.008148623171483,1740481190.3644674,22.139978885650635,0.0,1740481190.3644698,22.139978885650635,0.0,1740481190.3644714,22.139978885650635,17.9364046519129,1740481190.3644729,22.139978885650635,0.0,1740481190.3644738,22.139978885650635,0.0,1740481190.3644748,22.139978885650635,0.0,1740481190.364476,22.139978885650635,0.0,1740481190.3644767,22.139978885650635,0.9947466636397301,1740481190.3644776,22.139978885650635,0.0,1740481190.3644783,22.139978885650635,0.030618649269022913,1740481190.3644795,22.139978885650635,0.0,1740481190.3644922,22.139978885650635,0.9641280143707072,, -1740481190.3834224,22.15997886657715,14.008148623171483,1740481190.3834243,22.15997886657715,0.0,1740481190.3834271,22.15997886657715,0.0,1740481190.3834293,22.15997886657715,17.9364046519129,1740481190.3834305,22.15997886657715,0.0,1740481190.3834317,22.15997886657715,0.0,1740481190.3834326,22.15997886657715,0.0,1740481190.3834336,22.15997886657715,0.0,1740481190.3834345,22.15997886657715,0.9947466636397301,1740481190.3834355,22.15997886657715,0.0,1740481190.3834362,22.15997886657715,0.030618649269022913,1740481190.3834372,22.15997886657715,0.0,1740481190.383438,22.15997886657715,0.9641280143707072,, -1740481190.403528,22.169978857040405,14.008148623171483,1740481190.4035296,22.169978857040405,0.0,1740481190.4035323,22.169978857040405,0.0,1740481190.403535,22.169978857040405,17.9364046519129,1740481190.403536,22.169978857040405,0.0,1740481190.4035375,22.169978857040405,0.0,1740481190.4035387,22.169978857040405,0.0,1740481190.4035397,22.169978857040405,0.0,1740481190.4035408,22.169978857040405,0.9947466636397301,1740481190.403542,22.169978857040405,0.0,1740481190.4035428,22.169978857040405,0.030618649269022913,1740481190.4035437,22.169978857040405,0.0,1740481190.403545,22.169978857040405,0.9641280143707072,, -1740481190.4258456,22.199978828430176,14.11420417619556,1740481190.4258473,22.199978828430176,0.0,1740481190.42585,22.199978828430176,0.017227817808503663,1740481190.4258518,22.199978828430176,17.951703533768057,1740481190.4258533,22.199978828430176,0.0,1740481190.4258544,22.199978828430176,0.0,1740481190.4258556,22.199978828430176,0.0,1740481190.4258568,22.199978828430176,0.0,1740481190.4258575,22.199978828430176,0.9947466636397301,1740481190.4258585,22.199978828430176,0.052533363602660366,1740481190.4258597,22.199978828430176,0.08455487580129162,1740481190.4258606,22.199978828430176,0.0,1740481190.4258616,22.199978828430176,0.9631635463940356,, -1740481190.4454231,22.21997880935669,14.11420417619556,1740481190.445425,22.21997880935669,0.0,1740481190.4454274,22.21997880935669,0.017227817808503663,1740481190.4454298,22.21997880935669,17.951703533768057,1740481190.445431,22.21997880935669,0.0,1740481190.4454327,22.21997880935669,0.0,1740481190.4454339,22.21997880935669,0.0,1740481190.4454348,22.21997880935669,0.0,1740481190.4454362,22.21997880935669,0.9947466636397301,1740481190.4454372,22.21997880935669,0.052533363602660366,1740481190.4454381,22.21997880935669,0.08411648084835488,1740481190.4454393,22.21997880935669,0.0,1740481190.4454403,22.21997880935669,0.9631635463940356,, -1740481190.4762583,22.239978790283203,14.11420417619556,1740481190.4762602,22.239978790283203,0.0,1740481190.4762623,22.239978790283203,0.0,1740481190.4762647,22.239978790283203,18.04053126898363,1740481190.4762657,22.239978790283203,0.0,1740481190.476267,22.239978790283203,0.0,1740481190.4762683,22.239978790283203,0.0,1740481190.4762692,22.239978790283203,0.0,1740481190.4762704,22.239978790283203,0.9944603796841252,1740481190.4762714,22.239978790283203,0.0,1740481190.476272,22.239978790283203,0.03129683329008959,1740481190.476273,22.239978790283203,0.0,1740481190.4762743,22.239978790283203,0.9631635463940356,, -1740481190.4841037,22.259978771209717,14.11420417619556,1740481190.484105,22.259978771209717,0.0,1740481190.4841075,22.259978771209717,0.0,1740481190.4841096,22.259978771209717,18.04053126898363,1740481190.4841106,22.259978771209717,0.0,1740481190.4841118,22.259978771209717,0.0,1740481190.484113,22.259978771209717,0.0,1740481190.484114,22.259978771209717,0.0,1740481190.484115,22.259978771209717,0.9944603796841252,1740481190.484116,22.259978771209717,0.0,1740481190.484117,22.259978771209717,0.03129683329008959,1740481190.4841177,22.259978771209717,0.0,1740481190.4841187,22.259978771209717,0.9631635463940356,, -1740481190.5034425,22.27997875213623,14.11420417619556,1740481190.503444,22.27997875213623,0.0,1740481190.503446,22.27997875213623,0.0,1740481190.503448,22.27997875213623,18.04053126898363,1740481190.5034494,22.27997875213623,0.0,1740481190.5034506,22.27997875213623,0.0,1740481190.5034516,22.27997875213623,0.0,1740481190.5034523,22.27997875213623,0.0,1740481190.5034535,22.27997875213623,0.9944603796841252,1740481190.5034542,22.27997875213623,0.0,1740481190.5034552,22.27997875213623,0.03129683329008959,1740481190.503456,22.27997875213623,0.0,1740481190.503457,22.27997875213623,0.9631635463940356,, -1740481190.5255694,22.289978742599487,14.11420417619556,1740481190.5255713,22.289978742599487,0.0,1740481190.5255737,22.289978742599487,0.0,1740481190.5255756,22.289978742599487,18.04053126898363,1740481190.525577,22.289978742599487,0.0,1740481190.5255783,22.289978742599487,0.0,1740481190.5255792,22.289978742599487,0.0,1740481190.5255804,22.289978742599487,0.0,1740481190.5255814,22.289978742599487,0.9944603796841252,1740481190.5255823,22.289978742599487,0.0,1740481190.525583,22.289978742599487,0.03129683329008959,1740481190.5255842,22.289978742599487,0.0,1740481190.525585,22.289978742599487,0.9631635463940356,, -1740481190.5444336,22.319978713989258,14.2202202839661,1740481190.5444357,22.319978713989258,0.0,1740481190.5444381,22.319978713989258,0.017216454014023785,1740481190.5444403,22.319978713989258,18.057287385682663,1740481190.5444415,22.319978713989258,0.0,1740481190.5444427,22.319978713989258,0.0,1740481190.5444436,22.319978713989258,0.0,1740481190.5444446,22.319978713989258,0.0,1740481190.5444458,22.319978713989258,0.9944603796841252,1740481190.5444467,22.319978713989258,0.055396203158709634,1740481190.5444477,22.319978713989258,0.08702782732311411,1740481190.5444489,22.319978713989258,0.0,1740481190.5444498,22.319978713989258,0.9629333777365398,, -1740481190.5656588,22.33997869491577,14.2202202839661,1740481190.5656607,22.33997869491577,0.0,1740481190.5656629,22.33997869491577,0.0,1740481190.5656652,22.33997869491577,18.14608703943918,1740481190.5656662,22.33997869491577,0.0,1740481190.5656679,22.33997869491577,0.0,1740481190.5656688,22.33997869491577,0.0,1740481190.5656698,22.33997869491577,0.0,1740481190.565671,22.33997869491577,0.9943909359487243,1740481190.565672,22.33997869491577,0.0,1740481190.5656729,22.33997869491577,0.031457558212184544,1740481190.565674,22.33997869491577,0.0,1740481190.565675,22.33997869491577,0.9629333777365398,, -1740481190.584715,22.359978675842285,14.2202202839661,1740481190.584717,22.359978675842285,0.0,1740481190.58472,22.359978675842285,0.0,1740481190.5847223,22.359978675842285,18.14608703943918,1740481190.5847235,22.359978675842285,0.0,1740481190.584725,22.359978675842285,0.0,1740481190.5847273,22.359978675842285,0.0,1740481190.5847282,22.359978675842285,0.0,1740481190.5847294,22.359978675842285,0.9943909359487243,1740481190.5847304,22.359978675842285,0.0,1740481190.5847316,22.359978675842285,0.031457558212184544,1740481190.5847328,22.359978675842285,0.0,1740481190.5847342,22.359978675842285,0.9629333777365398,, -1740481190.6036751,22.3799786567688,14.2202202839661,1740481190.6036773,22.3799786567688,0.0,1740481190.60368,22.3799786567688,0.0,1740481190.603682,22.3799786567688,18.14608703943918,1740481190.6036832,22.3799786567688,0.0,1740481190.6036847,22.3799786567688,0.0,1740481190.603686,22.3799786567688,0.0,1740481190.6036873,22.3799786567688,0.0,1740481190.603688,22.3799786567688,0.9943909359487243,1740481190.603689,22.3799786567688,0.0,1740481190.60369,22.3799786567688,0.031457558212184544,1740481190.603691,22.3799786567688,0.0,1740481190.603692,22.3799786567688,0.9629333777365398,, -1740481190.6244793,22.399978637695312,14.2202202839661,1740481190.624481,22.399978637695312,0.0,1740481190.6244833,22.399978637695312,0.0,1740481190.6244855,22.399978637695312,18.14608703943918,1740481190.6244867,22.399978637695312,0.0,1740481190.6244879,22.399978637695312,0.0,1740481190.624489,22.399978637695312,0.0,1740481190.6244898,22.399978637695312,0.0,1740481190.6244905,22.399978637695312,0.9943909359487243,1740481190.6244915,22.399978637695312,0.0,1740481190.6244926,22.399978637695312,0.031457558212184544,1740481190.6244934,22.399978637695312,0.0,1740481190.6244946,22.399978637695312,0.9629333777365398,, -1740481190.6484926,22.419978618621826,14.326094526719686,1740481190.6484942,22.419978618621826,0.0,1740481190.6484966,22.419978618621826,0.017192215261122665,1740481190.6484988,22.419978618621826,18.159794024216378,1740481190.6485,22.419978618621826,0.0,1740481190.6485014,22.419978618621826,0.0,1740481190.6485028,22.419978618621826,0.0,1740481190.648521,22.419978618621826,0.0,1740481190.6485221,22.419978618621826,0.9943909359487243,1740481190.6485233,22.419978618621826,0.05609064051271817,1740481190.648524,22.419978618621826,0.09008291255952451,1740481190.648525,22.419978618621826,0.0,1740481190.6485262,22.419978618621826,0.9611907624945776,, -1740481190.6722696,22.43997859954834,14.326094526719686,1740481190.6722727,22.43997859954834,0.0,1740481190.6722753,22.43997859954834,0.0,1740481190.6722775,22.43997859954834,18.248476051708842,1740481190.672279,22.43997859954834,0.0,1740481190.6722803,22.43997859954834,0.0,1740481190.6722815,22.43997859954834,0.0,1740481190.6722827,22.43997859954834,0.0,1740481190.672284,22.43997859954834,0.99385114013974,1740481190.6722856,22.43997859954834,0.0,1740481190.672287,22.43997859954834,0.032660377645162386,1740481190.6722884,22.43997859954834,0.0,1740481190.6722896,22.43997859954834,0.9611907624945776,, -1740481190.6836197,22.459978580474854,14.326094526719686,1740481190.6836216,22.459978580474854,0.0,1740481190.6836243,22.459978580474854,0.0,1740481190.6836262,22.459978580474854,18.248476051708842,1740481190.6836274,22.459978580474854,0.0,1740481190.6836286,22.459978580474854,0.0,1740481190.6836295,22.459978580474854,0.0,1740481190.6836307,22.459978580474854,0.0,1740481190.6836317,22.459978580474854,0.99385114013974,1740481190.6836329,22.459978580474854,0.0,1740481190.6836338,22.459978580474854,0.032660377645162386,1740481190.683635,22.459978580474854,0.0,1740481190.6836376,22.459978580474854,0.9611907624945776,, -1740481190.7050152,22.479978561401367,14.326094526719686,1740481190.7050242,22.479978561401367,0.0,1740481190.705035,22.479978561401367,0.0,1740481190.7050412,22.479978561401367,18.248476051708842,1740481190.705046,22.479978561401367,0.0,1740481190.705052,22.479978561401367,0.0,1740481190.705099,22.479978561401367,0.0,1740481190.705102,22.479978561401367,0.0,1740481190.7051046,22.479978561401367,0.99385114013974,1740481190.7051086,22.479978561401367,0.0,1740481190.7051132,22.479978561401367,0.032660377645162386,1740481190.7051156,22.479978561401367,0.0,1740481190.7051194,22.479978561401367,0.9611907624945776,, -1740481190.7235749,22.49997854232788,14.326094526719686,1740481190.7235765,22.49997854232788,0.0,1740481190.723579,22.49997854232788,0.0,1740481190.723581,22.49997854232788,18.248476051708842,1740481190.7235823,22.49997854232788,0.0,1740481190.7235835,22.49997854232788,0.0,1740481190.7235844,22.49997854232788,0.0,1740481190.7235856,22.49997854232788,0.0,1740481190.7235866,22.49997854232788,0.99385114013974,1740481190.7235873,22.49997854232788,0.0,1740481190.7235885,22.49997854232788,0.032660377645162386,1740481190.7235892,22.49997854232788,0.0,1740481190.7235901,22.49997854232788,0.9611907624945776,, -1740481190.7436142,22.519978523254395,14.326094526719686,1740481190.7436156,22.519978523254395,0.0,1740481190.7436178,22.519978523254395,0.0,1740481190.74362,22.519978523254395,18.248476051708842,1740481190.7436209,22.519978523254395,0.0,1740481190.743622,22.519978523254395,0.0,1740481190.7436233,22.519978523254395,0.0,1740481190.7436242,22.519978523254395,0.0,1740481190.7436252,22.519978523254395,0.99385114013974,1740481190.7436264,22.519978523254395,0.0,1740481190.743627,22.519978523254395,0.032660377645162386,1740481190.743628,22.519978523254395,0.0,1740481190.743629,22.519978523254395,0.9611907624945776,, -1740481190.763993,22.539978504180908,14.431844890680622,1740481190.763995,22.539978504180908,0.0,1740481190.7639976,22.539978504180908,0.0,1740481190.7639995,22.539978504180908,18.35224871579107,1740481190.7640004,22.539978504180908,0.0,1740481190.7640018,22.539978504180908,0.0,1740481190.7640028,22.539978504180908,0.0,1740481190.7640035,22.539978504180908,0.0,1740481190.7640047,22.539978504180908,0.9935338052795356,1740481190.7640057,22.539978504180908,0.06466194720460505,1740481190.7640064,22.539978504180908,0.09829907434689557,1740481190.7640073,22.539978504180908,0.0,1740481190.7640083,22.539978504180908,0.9602019125552249,, -1740481190.7832685,22.559978485107422,14.431844890680622,1740481190.78327,22.559978485107422,0.0,1740481190.7832723,22.559978485107422,0.0,1740481190.7832744,22.559978485107422,18.35224871579107,1740481190.7832756,22.559978485107422,0.0,1740481190.7832768,22.559978485107422,0.0,1740481190.7832778,22.559978485107422,0.0,1740481190.7832787,22.559978485107422,0.0,1740481190.7832797,22.559978485107422,0.9935338052795356,1740481190.7832808,22.559978485107422,0.06466194720460505,1740481190.7832818,22.559978485107422,0.09799383992891575,1740481190.7832835,22.559978485107422,0.0,1740481190.783285,22.559978485107422,0.9602019125552249,, -1740481190.8041642,22.579978466033936,14.431844890680622,1740481190.804166,22.579978466033936,0.0,1740481190.8041682,22.579978466033936,0.0,1740481190.8041701,22.579978466033936,18.35224871579107,1740481190.8041713,22.579978466033936,0.0,1740481190.8041725,22.579978466033936,0.0,1740481190.8041735,22.579978466033936,0.0,1740481190.8041747,22.579978466033936,0.0,1740481190.8041754,22.579978466033936,0.9935338052795356,1740481190.8041763,22.579978466033936,0.06466194720460505,1740481190.804177,22.579978466033936,0.09799383992891575,1740481190.8041782,22.579978466033936,0.0,1740481190.8041792,22.579978466033936,0.9602019125552249,, -1740481190.8237143,22.59997844696045,14.431844890680622,1740481190.8237162,22.59997844696045,0.0,1740481190.823718,22.59997844696045,0.0,1740481190.8237202,22.59997844696045,18.35224871579107,1740481190.8237212,22.59997844696045,0.0,1740481190.8237226,22.59997844696045,0.0,1740481190.8237236,22.59997844696045,0.0,1740481190.8237245,22.59997844696045,0.0,1740481190.8237252,22.59997844696045,0.9935338052795356,1740481190.8237264,22.59997844696045,0.06466194720460505,1740481190.8237274,22.59997844696045,0.09799383992891575,1740481190.823728,22.59997844696045,0.0,1740481190.8237288,22.59997844696045,0.9602019125552249,, -1740481190.8439116,22.619978427886963,14.431844890680622,1740481190.8439145,22.619978427886963,0.0,1740481190.843917,22.619978427886963,0.0,1740481190.8439193,22.619978427886963,18.35224871579107,1740481190.8439207,22.619978427886963,0.0,1740481190.8439221,22.619978427886963,0.0,1740481190.843923,22.619978427886963,0.0,1740481190.8439245,22.619978427886963,0.0,1740481190.8439252,22.619978427886963,0.9935338052795356,1740481190.8439264,22.619978427886963,0.06466194720460505,1740481190.8439276,22.619978427886963,0.09799383992891575,1740481190.8439288,22.619978427886963,0.0,1740481190.8439298,22.619978427886963,0.9602019125552249,, -1740481190.864678,22.639978408813477,14.537626224608736,1740481190.8646796,22.639978408813477,0.0,1740481190.8646817,22.639978408813477,0.0,1740481190.8646839,22.639978408813477,18.46568160884493,1740481190.8646848,22.639978408813477,0.0,1740481190.864686,22.639978408813477,0.0,1740481190.864687,22.639978408813477,0.0,1740481190.864688,22.639978408813477,0.0,1740481190.8646889,22.639978408813477,0.9947172388120288,1740481190.8646898,22.639978408813477,-0.197801478424926,1740481190.8646913,22.639978408813477,-0.16831299925386486,1740481190.8646922,22.639978408813477,0.0,1740481190.864693,22.639978408813477,0.9640276921180959,, -1740481190.883498,22.65997838973999,14.537626224608736,1740481190.8834999,22.65997838973999,0.0,1740481190.883502,22.65997838973999,0.0,1740481190.883504,22.65997838973999,18.46568160884493,1740481190.883505,22.65997838973999,0.0,1740481190.8835065,22.65997838973999,0.0,1740481190.8835077,22.65997838973999,0.0,1740481190.8835087,22.65997838973999,0.0,1740481190.8835099,22.65997838973999,0.9947172388120288,1740481190.8835108,22.65997838973999,-0.197801478424926,1740481190.8835118,22.65997838973999,-0.16711193173099315,1740481190.8835125,22.65997838973999,0.0,1740481190.8835137,22.65997838973999,0.9640276921180959,, -1740481190.9036531,22.679978370666504,14.537626224608736,1740481190.9036567,22.679978370666504,0.0,1740481190.9036677,22.679978370666504,0.0,1740481190.903673,22.679978370666504,18.46568160884493,1740481190.9036748,22.679978370666504,0.0,1740481190.9036794,22.679978370666504,0.0,1740481190.9036832,22.679978370666504,0.0,1740481190.9036846,22.679978370666504,0.0,1740481190.9036887,22.679978370666504,0.9947172388120288,1740481190.9036908,22.679978370666504,-0.197801478424926,1740481190.9036925,22.679978370666504,-0.16711193173099315,1740481190.9036944,22.679978370666504,0.0,1740481190.9036953,22.679978370666504,0.9640276921180959,, -1740481190.9235902,22.699978351593018,14.537626224608736,1740481190.9235923,22.699978351593018,0.0,1740481190.9235945,22.699978351593018,0.0,1740481190.9236085,22.699978351593018,18.46568160884493,1740481190.9236112,22.699978351593018,0.0,1740481190.9236135,22.699978351593018,0.0,1740481190.9236145,22.699978351593018,0.0,1740481190.9236155,22.699978351593018,0.0,1740481190.9236164,22.699978351593018,0.9947172388120288,1740481190.9236176,22.699978351593018,-0.197801478424926,1740481190.9236186,22.699978351593018,-0.16711193173099315,1740481190.9236193,22.699978351593018,0.0,1740481190.9236205,22.699978351593018,0.9640276921180959,, -1740481190.9448135,22.71997833251953,14.537626224608736,1740481190.9448156,22.71997833251953,0.0,1740481190.944818,22.71997833251953,0.0,1740481190.94482,22.71997833251953,18.46568160884493,1740481190.944821,22.71997833251953,0.0,1740481190.9448223,22.71997833251953,0.0,1740481190.9448233,22.71997833251953,0.0,1740481190.9448242,22.71997833251953,0.0,1740481190.9448254,22.71997833251953,0.9947172388120288,1740481190.9448261,22.71997833251953,-0.197801478424926,1740481190.9448273,22.71997833251953,-0.16711193173099315,1740481190.9448283,22.71997833251953,0.0,1740481190.9448292,22.71997833251953,0.9640276921180959,, -1740481190.9640782,22.739978313446045,14.537626224608736,1740481190.9640799,22.739978313446045,0.0,1740481190.9640822,22.739978313446045,0.0,1740481190.9640841,22.739978313446045,18.46568160884493,1740481190.964085,22.739978313446045,0.0,1740481190.9640863,22.739978313446045,0.0,1740481190.9640872,22.739978313446045,0.0,1740481190.9640882,22.739978313446045,0.0,1740481190.9640894,22.739978313446045,0.9947172388120288,1740481190.9640903,22.739978313446045,-0.197801478424926,1740481190.964091,22.739978313446045,-0.16711193173099315,1740481190.9640923,22.739978313446045,0.0,1740481190.964093,22.739978313446045,0.9640276921180959,, -1740481190.9840267,22.75997829437256,14.642255982888702,1740481190.9840307,22.75997829437256,0.0,1740481190.984035,22.75997829437256,0.016995706891274852,1740481190.9840379,22.75997829437256,18.42622376106883,1740481190.984039,22.75997829437256,0.0,1740481190.984041,22.75997829437256,0.0,1740481190.9841373,22.75997829437256,0.0,1740481190.9841385,22.75997829437256,0.0,1740481190.9841392,22.75997829437256,0.9749370909695362,1740481190.9841406,22.75997829437256,-1.7506282997896205,1740481190.9841413,22.75997829437256,-1.707652742901523,1740481190.9841423,22.75997829437256,0.0,1740481190.984143,22.75997829437256,0.9358009147844093,, -1740481191.0039463,22.779978275299072,14.642255982888702,1740481191.003948,22.779978275299072,0.0,1740481191.00395,22.779978275299072,0.016995706891274852,1740481191.003952,22.779978275299072,18.42622376106883,1740481191.0039532,22.779978275299072,0.0,1740481191.0039542,22.779978275299072,0.0,1740481191.0039551,22.779978275299072,0.0,1740481191.0039563,22.779978275299072,0.0,1740481191.003957,22.779978275299072,0.9749370909695362,1740481191.0039582,22.779978275299072,-1.7506282997896205,1740481191.003959,22.779978275299072,-1.7114921236044935,1740481191.0039601,22.779978275299072,0.0,1740481191.0039608,22.779978275299072,0.9358009147844093,, -1740481191.0237548,22.799978256225586,14.642255982888702,1740481191.0237565,22.799978256225586,0.0,1740481191.0237586,22.799978256225586,0.016995706891274852,1740481191.0237603,22.799978256225586,18.42622376106883,1740481191.0237615,22.799978256225586,0.0,1740481191.0237627,22.799978256225586,0.0,1740481191.0237637,22.799978256225586,0.0,1740481191.0237648,22.799978256225586,0.0,1740481191.0237656,22.799978256225586,0.9749370909695362,1740481191.0237665,22.799978256225586,-1.7506282997896205,1740481191.0237675,22.799978256225586,-1.7114921236044935,1740481191.0237687,22.799978256225586,0.0,1740481191.0237696,22.799978256225586,0.9358009147844093,, -1740481191.0450165,22.8199782371521,14.642255982888702,1740481191.0450213,22.8199782371521,0.0,1740481191.0450249,22.8199782371521,0.016995706891274852,1740481191.0450273,22.8199782371521,18.42622376106883,1740481191.0450287,22.8199782371521,0.0,1740481191.0450306,22.8199782371521,0.0,1740481191.045033,22.8199782371521,0.0,1740481191.0450346,22.8199782371521,0.0,1740481191.0450366,22.8199782371521,0.9749370909695362,1740481191.0450387,22.8199782371521,-1.7506282997896205,1740481191.045041,22.8199782371521,-1.7114921236044935,1740481191.0450428,22.8199782371521,0.0,1740481191.0450444,22.8199782371521,0.9358009147844093,, -1740481191.0646093,22.839978218078613,14.642255982888702,1740481191.0646133,22.839978218078613,0.0,1740481191.0646167,22.839978218078613,0.0,1740481191.064619,22.839978218078613,18.51385781245752,1740481191.0646205,22.839978218078613,0.0,1740481191.0646238,22.839978218078613,0.0,1740481191.0646255,22.839978218078613,0.0,1740481191.0646288,22.839978218078613,0.0,1740481191.06463,22.839978218078613,0.966097064717689,1740481191.0646322,22.839978218078613,0.0,1740481191.0646336,22.839978218078613,0.03029614993327967,1740481191.0646348,22.839978218078613,0.0,1740481191.0646374,22.839978218078613,0.9358009147844093,, -1740481191.086093,22.859978199005127,14.740536571595726,1740481191.0860958,22.859978199005127,0.0,1740481191.0860984,22.859978199005127,0.015505039537042296,1740481191.0861006,22.859978199005127,18.363466313918078,1740481191.0861018,22.859978199005127,0.0,1740481191.0861034,22.859978199005127,0.0,1740481191.0861046,22.859978199005127,0.0,1740481191.0861056,22.859978199005127,0.0,1740481191.0861063,22.859978199005127,0.966097064717689,1740481191.0861077,22.859978199005127,-1.7171229947615785,1740481191.0861087,22.859978199005127,-1.5661747811791686,1740481191.0861096,22.859978199005127,0.0,1740481191.0861108,22.859978199005127,0.8528526457461664,, -1740481191.104126,22.87997817993164,14.740536571595726,1740481191.104128,22.87997817993164,0.0,1740481191.1041303,22.87997817993164,0.015505039537042296,1740481191.1041327,22.87997817993164,18.363466313918078,1740481191.1041338,22.87997817993164,0.0,1740481191.1041353,22.87997817993164,0.0,1740481191.1041362,22.87997817993164,0.0,1740481191.1041372,22.87997817993164,0.0,1740481191.1041381,22.87997817993164,0.966097064717689,1740481191.104139,22.87997817993164,-1.7171229947615785,1740481191.10414,22.87997817993164,-1.603878575790056,1740481191.1041408,22.87997817993164,0.0,1740481191.1041417,22.87997817993164,0.8528526457461664,, -1740481191.124616,22.899978160858154,14.740536571595726,1740481191.124618,22.899978160858154,0.0,1740481191.1246204,22.899978160858154,0.015505039537042296,1740481191.1246228,22.899978160858154,18.363466313918078,1740481191.1246245,22.899978160858154,0.0,1740481191.124626,22.899978160858154,0.0,1740481191.1246269,22.899978160858154,0.0,1740481191.1246283,22.899978160858154,0.0,1740481191.1246302,22.899978160858154,0.966097064717689,1740481191.1246314,22.899978160858154,-1.7171229947615785,1740481191.1246324,22.899978160858154,-1.603878575790056,1740481191.1246333,22.899978160858154,0.0,1740481191.1246347,22.899978160858154,0.8528526457461664,, -1740481191.144209,22.919978141784668,14.740536571595726,1740481191.1442113,22.919978141784668,0.0,1740481191.1442142,22.919978141784668,0.015505039537042296,1740481191.1442165,22.919978141784668,18.363466313918078,1740481191.144218,22.919978141784668,0.0,1740481191.1442192,22.919978141784668,0.0,1740481191.1442204,22.919978141784668,0.0,1740481191.1442218,22.919978141784668,0.0,1740481191.1442227,22.919978141784668,0.966097064717689,1740481191.1442237,22.919978141784668,-1.7171229947615785,1740481191.144225,22.919978141784668,-1.603878575790056,1740481191.1442258,22.919978141784668,0.0,1740481191.1442266,22.919978141784668,0.8528526457461664,, -1740481191.1663098,22.93997812271118,14.740536571595726,1740481191.1663122,22.93997812271118,0.0,1740481191.1663148,22.93997812271118,0.0,1740481191.166317,22.93997812271118,18.44624186308806,1740481191.1663182,22.93997812271118,0.0,1740481191.1663196,22.93997812271118,0.0,1740481191.1663203,22.93997812271118,0.0,1740481191.1663215,22.93997812271118,0.0,1740481191.1663225,22.93997812271118,0.8316855900821778,1740481191.1663232,22.93997812271118,0.0,1740481191.1663241,22.93997812271118,-0.021167055663988577,1740481191.1663253,22.93997812271118,0.0,1740481191.1663265,22.93997812271118,0.8528526457461664,, -1740481191.1836033,22.959978103637695,14.740536571595726,1740481191.183605,22.959978103637695,0.0,1740481191.1836073,22.959978103637695,0.0,1740481191.183609,22.959978103637695,18.44624186308806,1740481191.1836102,22.959978103637695,0.0,1740481191.1836116,22.959978103637695,0.0,1740481191.1836126,22.959978103637695,0.0,1740481191.1836138,22.959978103637695,0.0,1740481191.1836145,22.959978103637695,0.8316855900821778,1740481191.1836154,22.959978103637695,0.0,1740481191.1836164,22.959978103637695,-0.021167055663988577,1740481191.1836174,22.959978103637695,0.0,1740481191.1836183,22.959978103637695,0.8528526457461664,, -1740481191.2037117,22.97997808456421,14.829130632123295,1740481191.2037134,22.97997808456421,0.0,1740481191.2037156,22.97997808456421,0.01203228610770627,1740481191.2037177,22.97997808456421,18.29432976976031,1740481191.2037184,22.97997808456421,0.0,1740481191.2037196,22.97997808456421,0.0,1740481191.203721,22.97997808456421,0.0,1740481191.2037218,22.97997808456421,0.0,1740481191.2037227,22.97997808456421,0.8316855900821778,1740481191.2037237,22.97997808456421,-2.0,1740481191.2037246,22.97997808456421,-1.9019347441769099,1740481191.2037256,22.97997808456421,0.0,1740481191.2037268,22.97997808456421,0.7708804560284394,, -1740481191.223443,22.999978065490723,14.829130632123295,1740481191.223445,22.999978065490723,0.0,1740481191.2234473,22.999978065490723,0.01203228610770627,1740481191.223449,22.999978065490723,18.29432976976031,1740481191.2234502,22.999978065490723,0.0,1740481191.2234514,22.999978065490723,0.0,1740481191.223452,22.999978065490723,0.0,1740481191.2234533,22.999978065490723,0.0,1740481191.2234542,22.999978065490723,0.8316855900821778,1740481191.223455,22.999978065490723,-2.0,1740481191.2234557,22.999978065490723,-1.9391948659462614,1740481191.2234569,22.999978065490723,0.0,1740481191.2234576,22.999978065490723,0.7708804560284394,, -1740481191.24367,23.019978046417236,14.829130632123295,1740481191.243672,23.019978046417236,0.0,1740481191.243674,23.019978046417236,0.01203228610770627,1740481191.2436762,23.019978046417236,18.29432976976031,1740481191.2436771,23.019978046417236,0.0,1740481191.2436786,23.019978046417236,0.0,1740481191.2436795,23.019978046417236,0.0,1740481191.2436805,23.019978046417236,0.0,1740481191.2436812,23.019978046417236,0.8316855900821778,1740481191.2436824,23.019978046417236,-2.0,1740481191.243683,23.019978046417236,-1.9391948659462614,1740481191.243684,23.019978046417236,0.0,1740481191.243685,23.019978046417236,0.7708804560284394,, -1740481191.263793,23.03997802734375,14.829130632123295,1740481191.2637947,23.03997802734375,0.0,1740481191.263797,23.03997802734375,0.0,1740481191.263799,23.03997802734375,18.370891544180175,1740481191.2638001,23.03997802734375,0.0,1740481191.263801,23.03997802734375,0.0,1740481191.263802,23.03997802734375,0.0,1740481191.2638032,23.03997802734375,0.0,1740481191.2638042,23.03997802734375,0.6612157772959436,1740481191.2638052,23.03997802734375,0.0,1740481191.2638059,23.03997802734375,-0.10966467873249575,1740481191.2638073,23.03997802734375,0.0,1740481191.263808,23.03997802734375,0.7708804560284394,, -1740481191.2838497,23.059978008270264,14.829130632123295,1740481191.2838528,23.059978008270264,0.0,1740481191.283856,23.059978008270264,0.0,1740481191.2838578,23.059978008270264,18.370891544180175,1740481191.2838588,23.059978008270264,0.0,1740481191.2838602,23.059978008270264,0.0,1740481191.2838612,23.059978008270264,0.0,1740481191.2838624,23.059978008270264,0.0,1740481191.2838633,23.059978008270264,0.6612157772959436,1740481191.283864,23.059978008270264,0.0,1740481191.283865,23.059978008270264,-0.10966467873249575,1740481191.2838662,23.059978008270264,0.0,1740481191.283867,23.059978008270264,0.7708804560284394,, -1740481191.3051186,23.079977989196777,14.909817557149807,1740481191.3051207,23.079977989196777,0.0,1740481191.305123,23.079977989196777,0.008712258217240861,1740481191.3051248,23.079977989196777,18.239064808966855,1740481191.305126,23.079977989196777,0.0,1740481191.3051271,23.079977989196777,0.0,1740481191.305128,23.079977989196777,0.0,1740481191.3051293,23.079977989196777,0.0,1740481191.3051705,23.079977989196777,0.6612157772959436,1740481191.3051744,23.079977989196777,-2.0,1740481191.3051753,23.079977989196777,-2.0074544712310542,1740481191.3051763,23.079977989196777,0.0,1740481191.305177,23.079977989196777,0.7006109593131602,, -1740481191.3237514,23.09997797012329,14.909817557149807,1740481191.323753,23.09997797012329,0.0,1740481191.3237555,23.09997797012329,0.008712258217240861,1740481191.3237576,23.09997797012329,18.239064808966855,1740481191.3237586,23.09997797012329,0.0,1740481191.3237596,23.09997797012329,0.0,1740481191.3237607,23.09997797012329,0.0,1740481191.3237617,23.09997797012329,0.0,1740481191.3237627,23.09997797012329,0.6612157772959436,1740481191.3237634,23.09997797012329,-2.0,1740481191.3237646,23.09997797012329,-2.0393951820172167,1740481191.3237653,23.09997797012329,0.0,1740481191.3237662,23.09997797012329,0.7006109593131602,, -1740481191.3459969,23.119977951049805,14.909817557149807,1740481191.3459988,23.119977951049805,0.0,1740481191.346001,23.119977951049805,0.008712258217240861,1740481191.346003,23.119977951049805,18.239064808966855,1740481191.346004,23.119977951049805,0.0,1740481191.3460174,23.119977951049805,0.0,1740481191.3460188,23.119977951049805,0.0,1740481191.3460197,23.119977951049805,0.0,1740481191.3460207,23.119977951049805,0.6612157772959436,1740481191.3460217,23.119977951049805,-2.0,1740481191.3460226,23.119977951049805,-2.0393951820172167,1740481191.3460233,23.119977951049805,0.0,1740481191.3460245,23.119977951049805,0.7006109593131602,, -1740481191.3728402,23.13997793197632,14.909817557149807,1740481191.3728428,23.13997793197632,0.0,1740481191.3728456,23.13997793197632,0.0,1740481191.372848,23.13997793197632,18.311039475776127,1740481191.3728492,23.13997793197632,0.0,1740481191.3728511,23.13997793197632,0.0,1740481191.3728526,23.13997793197632,0.0,1740481191.3728535,23.13997793197632,0.0,1740481191.3728552,23.13997793197632,0.5748087301181215,1740481191.3728578,23.13997793197632,0.0,1740481191.3728588,23.13997793197632,-0.1258022291950387,1740481191.3728602,23.13997793197632,0.0,1740481191.3728616,23.13997793197632,0.7006109593131602,, -1740481191.3841162,23.159977912902832,14.909817557149807,1740481191.3841183,23.159977912902832,0.0,1740481191.384121,23.159977912902832,0.0,1740481191.384123,23.159977912902832,18.311039475776127,1740481191.3841243,23.159977912902832,0.0,1740481191.3841255,23.159977912902832,0.0,1740481191.3841267,23.159977912902832,0.0,1740481191.3841279,23.159977912902832,0.0,1740481191.3841288,23.159977912902832,0.5748087301181215,1740481191.3841298,23.159977912902832,0.0,1740481191.3841307,23.159977912902832,-0.1258022291950387,1740481191.384132,23.159977912902832,0.0,1740481191.3841329,23.159977912902832,0.7006109593131602,, -1740481191.4035087,23.179977893829346,14.909817557149807,1740481191.4035106,23.179977893829346,0.0,1740481191.4035127,23.179977893829346,0.0,1740481191.4035149,23.179977893829346,18.311039475776127,1740481191.4035156,23.179977893829346,0.0,1740481191.4035172,23.179977893829346,0.0,1740481191.403518,23.179977893829346,0.0,1740481191.403519,23.179977893829346,0.0,1740481191.4035203,23.179977893829346,0.5748087301181215,1740481191.4035213,23.179977893829346,0.0,1740481191.403522,23.179977893829346,-0.1258022291950387,1740481191.403523,23.179977893829346,0.0,1740481191.4035242,23.179977893829346,0.7006109593131602,, -1740481191.42341,23.19997787475586,14.981843517264423,1740481191.4234116,23.19997787475586,0.0,1740481191.4234145,23.19997787475586,0.004140115066902053,1740481191.4234166,23.19997787475586,18.15635668272273,1740481191.4234173,23.19997787475586,0.0,1740481191.4234185,23.19997787475586,0.0,1740481191.4234197,23.19997787475586,0.0,1740481191.4234207,23.19997787475586,0.0,1740481191.4234216,23.19997787475586,0.3270156983838035,1740481191.4234226,23.19997787475586,0.0,1740481191.4234235,23.19997787475586,-0.37072096062171,1740481191.4234242,23.19997787475586,0.0,1740481191.4234252,23.19997787475586,0.6211995052530103,, -1740481191.4463553,23.219977855682373,14.981843517264423,1740481191.4463575,23.219977855682373,0.0,1740481191.44636,23.219977855682373,0.004140115066902053,1740481191.446362,23.219977855682373,18.15635668272273,1740481191.4463632,23.219977855682373,0.0,1740481191.4463644,23.219977855682373,0.0,1740481191.4463654,23.219977855682373,0.0,1740481191.4463665,23.219977855682373,0.0,1740481191.4463675,23.219977855682373,0.3270156983838035,1740481191.4463687,23.219977855682373,0.0,1740481191.4463696,23.219977855682373,-0.29418380686920675,1740481191.4463706,23.219977855682373,0.0,1740481191.4463716,23.219977855682373,0.6211995052530103,, -1740481191.4635515,23.239977836608887,14.981843517264423,1740481191.4635534,23.239977836608887,0.0,1740481191.4635558,23.239977836608887,0.0,1740481191.4635577,23.239977836608887,18.224242527770443,1740481191.4635587,23.239977836608887,0.0,1740481191.46356,23.239977836608887,0.0,1740481191.463561,23.239977836608887,0.0,1740481191.463562,23.239977836608887,0.0,1740481191.4635627,23.239977836608887,1.0,1740481191.4635637,23.239977836608887,0.0,1740481191.4635649,23.239977836608887,0.37880049474698974,1740481191.4635656,23.239977836608887,0.0,1740481191.4635665,23.239977836608887,0.6211995052530103,, -1740481191.48747,23.2599778175354,14.981843517264423,1740481191.4874716,23.2599778175354,0.0,1740481191.4874737,23.2599778175354,0.0,1740481191.4874756,23.2599778175354,18.224242527770443,1740481191.4874766,23.2599778175354,0.0,1740481191.4874778,23.2599778175354,0.0,1740481191.4874785,23.2599778175354,0.0,1740481191.4874794,23.2599778175354,0.0,1740481191.4874804,23.2599778175354,1.0,1740481191.4874814,23.2599778175354,0.0,1740481191.487482,23.2599778175354,0.37880049474698974,1740481191.4874828,23.2599778175354,0.0,1740481191.4874842,23.2599778175354,0.6211995052530103,, -1740481191.5032043,23.279977798461914,14.981843517264423,1740481191.5032065,23.279977798461914,0.0,1740481191.5032086,23.279977798461914,0.0,1740481191.5032105,23.279977798461914,18.224242527770443,1740481191.5032115,23.279977798461914,0.0,1740481191.5032127,23.279977798461914,0.0,1740481191.503214,23.279977798461914,0.0,1740481191.5032148,23.279977798461914,0.0,1740481191.503216,23.279977798461914,1.0,1740481191.5032175,23.279977798461914,0.0,1740481191.5032182,23.279977798461914,0.37880049474698974,1740481191.5032191,23.279977798461914,0.0,1740481191.5032206,23.279977798461914,0.6211995052530103,, -1740481191.52367,23.299977779388428,15.049341527320987,1740481191.5236719,23.299977779388428,0.0,1740481191.523674,23.299977779388428,0.0012255264542778172,1740481191.5236762,23.299977779388428,18.232749692792765,1740481191.5236924,23.299977779388428,0.0,1740481191.5236948,23.299977779388428,0.0,1740481191.523696,23.299977779388428,0.0,1740481191.523697,23.299977779388428,0.0,1740481191.5236979,23.299977779388428,1.0,1740481191.5236988,23.299977779388428,0.0,1740481191.5236998,23.299977779388428,0.37350475602833905,1740481191.5237005,23.299977779388428,0.0,1740481191.5237014,23.299977779388428,0.6248403245370329,, -1740481191.543626,23.31997776031494,15.049341527320987,1740481191.543628,23.31997776031494,0.0,1740481191.5436304,23.31997776031494,0.0012255264542778172,1740481191.543632,23.31997776031494,18.232749692792765,1740481191.5436332,23.31997776031494,0.0,1740481191.5436347,23.31997776031494,0.0,1740481191.5436363,23.31997776031494,0.0,1740481191.5436375,23.31997776031494,0.0,1740481191.5436385,23.31997776031494,1.0,1740481191.5436401,23.31997776031494,0.0,1740481191.543641,23.31997776031494,0.37515967546296713,1740481191.543642,23.31997776031494,0.0,1740481191.5436432,23.31997776031494,0.6248403245370329,, -1740481191.5649607,23.339977741241455,15.049341527320987,1740481191.5649621,23.339977741241455,0.0,1740481191.5649643,23.339977741241455,0.0,1740481191.5649664,23.339977741241455,18.249680649074065,1740481191.5649674,23.339977741241455,0.0,1740481191.564969,23.339977741241455,0.0,1740481191.56497,23.339977741241455,0.0,1740481191.564971,23.339977741241455,0.0,1740481191.5649724,23.339977741241455,0.0,1740481191.5649734,23.339977741241455,-2.0,1740481191.564974,23.339977741241455,-2.6248403245370326,1740481191.5649753,23.339977741241455,0.0,1740481191.5649765,23.339977741241455,0.6248403245370329,, -1740481191.58766,23.35997772216797,15.049341527320987,1740481191.5876615,23.35997772216797,0.0,1740481191.587664,23.35997772216797,0.0,1740481191.5876656,23.35997772216797,18.249680649074065,1740481191.5876667,23.35997772216797,0.0,1740481191.587668,23.35997772216797,0.0,1740481191.587669,23.35997772216797,0.0,1740481191.58767,23.35997772216797,0.0,1740481191.587671,23.35997772216797,0.0,1740481191.5876718,23.35997772216797,-2.0,1740481191.587673,23.35997772216797,-2.6248403245370326,1740481191.5876737,23.35997772216797,0.0,1740481191.5876744,23.35997772216797,0.6248403245370329,, -1740481191.6033006,23.379977703094482,15.049341527320987,1740481191.6033025,23.379977703094482,0.0,1740481191.6033044,23.379977703094482,0.0,1740481191.6033068,23.379977703094482,18.249680649074065,1740481191.6033075,23.379977703094482,0.0,1740481191.6033092,23.379977703094482,0.0,1740481191.6033103,23.379977703094482,0.0,1740481191.6033113,23.379977703094482,0.0,1740481191.6033125,23.379977703094482,0.0,1740481191.6033137,23.379977703094482,-2.0,1740481191.6033146,23.379977703094482,-2.6248403245370326,1740481191.6033154,23.379977703094482,0.0,1740481191.6033165,23.379977703094482,0.6248403245370329,, -1740481191.6233559,23.399977684020996,15.049341527320987,1740481191.6233575,23.399977684020996,0.0,1740481191.6233594,23.399977684020996,0.0,1740481191.6233616,23.399977684020996,18.249680649074065,1740481191.6233625,23.399977684020996,0.0,1740481191.6233637,23.399977684020996,0.0,1740481191.623365,23.399977684020996,0.0,1740481191.6233659,23.399977684020996,0.0,1740481191.6233668,23.399977684020996,0.0,1740481191.623368,23.399977684020996,-2.0,1740481191.6233687,23.399977684020996,-2.6248403245370326,1740481191.6233695,23.399977684020996,0.0,1740481191.6233704,23.399977684020996,0.6248403245370329,, -1740481191.6451235,23.41997766494751,15.117125889986575,1740481191.6451254,23.41997766494751,0.0,1740481191.6451652,23.41997766494751,0.0,1740481191.6451697,23.41997766494751,18.136790106903078,1740481191.645171,23.41997766494751,0.0,1740481191.6451726,23.41997766494751,0.0,1740481191.6451735,23.41997766494751,0.0,1740481191.6451745,23.41997766494751,0.0,1740481191.6451757,23.41997766494751,0.0,1740481191.645177,23.41997766494751,-2.0,1740481191.6451778,23.41997766494751,-2.5427380875806525,1740481191.6451788,23.41997766494751,0.0,1740481191.64518,23.41997766494751,0.5683950534515387,, -1740481191.6644094,23.439977645874023,15.117125889986575,1740481191.664411,23.439977645874023,0.0,1740481191.6644132,23.439977645874023,0.0,1740481191.6644151,23.439977645874023,18.136790106903078,1740481191.6644166,23.439977645874023,0.0,1740481191.6644177,23.439977645874023,0.0,1740481191.6644187,23.439977645874023,0.0,1740481191.66442,23.439977645874023,0.0,1740481191.6644208,23.439977645874023,0.0,1740481191.6644218,23.439977645874023,-2.0,1740481191.6644228,23.439977645874023,-2.568395053451539,1740481191.6644237,23.439977645874023,0.0,1740481191.6644247,23.439977645874023,0.5683950534515387,, -1740481191.6834497,23.459977626800537,15.117125889986575,1740481191.6834512,23.459977626800537,0.0,1740481191.683453,23.459977626800537,0.0,1740481191.6834552,23.459977626800537,18.136790106903078,1740481191.6834562,23.459977626800537,0.0,1740481191.6834576,23.459977626800537,0.0,1740481191.6834586,23.459977626800537,0.0,1740481191.6834595,23.459977626800537,0.0,1740481191.6834607,23.459977626800537,0.0,1740481191.6834617,23.459977626800537,-2.0,1740481191.6834626,23.459977626800537,-2.568395053451539,1740481191.6834633,23.459977626800537,0.0,1740481191.6834645,23.459977626800537,0.5683950534515387,, -1740481191.7033205,23.47997760772705,15.117125889986575,1740481191.7033224,23.47997760772705,0.0,1740481191.7033246,23.47997760772705,0.0,1740481191.7033267,23.47997760772705,18.136790106903078,1740481191.7033277,23.47997760772705,0.0,1740481191.703329,23.47997760772705,0.0,1740481191.70333,23.47997760772705,0.0,1740481191.7033308,23.47997760772705,0.0,1740481191.7033322,23.47997760772705,0.0,1740481191.7033331,23.47997760772705,-2.0,1740481191.7033339,23.47997760772705,-2.568395053451539,1740481191.7033348,23.47997760772705,0.0,1740481191.703336,23.47997760772705,0.5683950534515387,, -1740481191.7243614,23.499977588653564,15.117125889986575,1740481191.724363,23.499977588653564,0.0,1740481191.724365,23.499977588653564,0.0,1740481191.7243671,23.499977588653564,18.136790106903078,1740481191.724368,23.499977588653564,0.0,1740481191.7243695,23.499977588653564,0.0,1740481191.7243702,23.499977588653564,0.0,1740481191.7243712,23.499977588653564,0.0,1740481191.7243721,23.499977588653564,0.0,1740481191.7243733,23.499977588653564,-2.0,1740481191.724374,23.499977588653564,-2.568395053451539,1740481191.724375,23.499977588653564,0.0,1740481191.7243757,23.499977588653564,0.5683950534515387,, -1740481191.743855,23.519977569580078,15.174149345866248,1740481191.7438574,23.519977569580078,0.0,1740481191.7438605,23.519977569580078,0.0,1740481191.7438629,23.519977569580078,17.91679010690308,1740481191.743865,23.519977569580078,0.0,1740481191.7438667,23.519977569580078,0.0,1740481191.7438679,23.519977569580078,0.0,1740481191.74387,23.519977569580078,0.0,1740481191.7438712,23.519977569580078,0.0,1740481191.7438731,23.519977569580078,-2.0,1740481191.7438748,23.519977569580078,-2.4083950057677774,1740481191.7438765,23.519977569580078,0.0,1740481191.743878,23.519977569580078,0.45839505345153864,, -1740481191.7667143,23.539977550506592,15.174149345866248,1740481191.7667174,23.539977550506592,0.0,1740481191.7667212,23.539977550506592,0.0,1740481191.7667248,23.539977550506592,17.91679010690308,1740481191.7667272,23.539977550506592,0.0,1740481191.7667294,23.539977550506592,0.0,1740481191.7667315,23.539977550506592,0.0,1740481191.7667344,23.539977550506592,0.0,1740481191.7667363,23.539977550506592,0.0,1740481191.7667382,23.539977550506592,-2.0,1740481191.7667406,23.539977550506592,-2.4583950534515386,1740481191.7667422,23.539977550506592,0.0,1740481191.7667446,23.539977550506592,0.45839505345153864,, -1740481191.7835867,23.559977531433105,15.174149345866248,1740481191.7835891,23.559977531433105,0.0,1740481191.783593,23.559977531433105,0.0,1740481191.7835956,23.559977531433105,17.91679010690308,1740481191.7835968,23.559977531433105,0.0,1740481191.783599,23.559977531433105,0.0,1740481191.7836,23.559977531433105,0.0,1740481191.7836015,23.559977531433105,0.0,1740481191.7836032,23.559977531433105,0.0,1740481191.7836056,23.559977531433105,-2.0,1740481191.7836068,23.559977531433105,-2.4583950534515386,1740481191.783608,23.559977531433105,0.0,1740481191.7836092,23.559977531433105,0.45839505345153864,, -1740481191.8037322,23.57997751235962,15.174149345866248,1740481191.8037336,23.57997751235962,0.0,1740481191.8037357,23.57997751235962,0.0,1740481191.8037379,23.57997751235962,17.91679010690308,1740481191.8037388,23.57997751235962,0.0,1740481191.8037403,23.57997751235962,0.0,1740481191.8037412,23.57997751235962,0.0,1740481191.803742,23.57997751235962,0.0,1740481191.803743,23.57997751235962,0.0,1740481191.803744,23.57997751235962,-2.0,1740481191.803745,23.57997751235962,-2.4583950534515386,1740481191.8037457,23.57997751235962,0.0,1740481191.8037465,23.57997751235962,0.45839505345153864,, -1740481191.8237088,23.599977493286133,15.174149345866248,1740481191.8237102,23.599977493286133,0.0,1740481191.8237126,23.599977493286133,0.0,1740481191.8237143,23.599977493286133,17.91679010690308,1740481191.8237152,23.599977493286133,0.0,1740481191.8237166,23.599977493286133,0.0,1740481191.8237176,23.599977493286133,0.0,1740481191.823719,23.599977493286133,0.0,1740481191.82372,23.599977493286133,0.0,1740481191.823721,23.599977493286133,-2.0,1740481191.8237216,23.599977493286133,-2.4583950534515386,1740481191.8237228,23.599977493286133,0.0,1740481191.8237236,23.599977493286133,0.45839505345153864,, -1740481191.844567,23.619977474212646,15.174149345866248,1740481191.8445685,23.619977474212646,0.0,1740481191.844571,23.619977474212646,0.0,1740481191.8445733,23.619977474212646,17.91679010690308,1740481191.8445742,23.619977474212646,0.0,1740481191.8445756,23.619977474212646,0.0,1740481191.8445766,23.619977474212646,0.0,1740481191.8445778,23.619977474212646,0.0,1740481191.844579,23.619977474212646,0.0,1740481191.84458,23.619977474212646,-2.0,1740481191.844581,23.619977474212646,-2.4583950534515386,1740481191.8445818,23.619977474212646,0.0,1740481191.8445826,23.619977474212646,0.45839505345153864,, -1740481191.865459,23.63997745513916,15.219072801745913,1740481191.8654604,23.63997745513916,0.0,1740481191.8654628,23.63997745513916,0.0,1740481191.865465,23.63997745513916,17.696790106903077,1740481191.8654659,23.63997745513916,0.0,1740481191.865467,23.63997745513916,0.0,1740481191.8654683,23.63997745513916,0.0,1740481191.8654692,23.63997745513916,0.0,1740481191.8654702,23.63997745513916,0.0,1740481191.8654711,23.63997745513916,-2.0,1740481191.8654723,23.63997745513916,-2.298395005767777,1740481191.865473,23.63997745513916,0.0,1740481191.865474,23.63997745513916,0.34839505345153854,, -1740481191.884009,23.659977436065674,15.219072801745913,1740481191.8840106,23.659977436065674,0.0,1740481191.8840127,23.659977436065674,0.0,1740481191.8840148,23.659977436065674,17.696790106903077,1740481191.8840158,23.659977436065674,0.0,1740481191.8840172,23.659977436065674,0.0,1740481191.8840182,23.659977436065674,0.0,1740481191.8840191,23.659977436065674,0.0,1740481191.8840203,23.659977436065674,0.0,1740481191.8840213,23.659977436065674,-2.0,1740481191.8840222,23.659977436065674,-2.3483950534515383,1740481191.884023,23.659977436065674,0.0,1740481191.884024,23.659977436065674,0.34839505345153854,, -1740481191.9037619,23.679977416992188,15.219072801745913,1740481191.9037635,23.679977416992188,0.0,1740481191.9037654,23.679977416992188,0.0,1740481191.9037676,23.679977416992188,17.696790106903077,1740481191.9037688,23.679977416992188,0.0,1740481191.9037702,23.679977416992188,0.0,1740481191.9037712,23.679977416992188,0.0,1740481191.903772,23.679977416992188,0.0,1740481191.9037728,23.679977416992188,0.0,1740481191.903774,23.679977416992188,-2.0,1740481191.903775,23.679977416992188,-2.3483950534515383,1740481191.903776,23.679977416992188,0.0,1740481191.903777,23.679977416992188,0.34839505345153854,, -1740481191.924058,23.6999773979187,15.219072801745913,1740481191.9240594,23.6999773979187,0.0,1740481191.9240615,23.6999773979187,0.0,1740481191.9240634,23.6999773979187,17.696790106903077,1740481191.9240642,23.6999773979187,0.0,1740481191.9240656,23.6999773979187,0.0,1740481191.9240665,23.6999773979187,0.0,1740481191.9240673,23.6999773979187,0.0,1740481191.9240685,23.6999773979187,0.0,1740481191.9240694,23.6999773979187,-2.0,1740481191.9240701,23.6999773979187,-2.3483950534515383,1740481191.924071,23.6999773979187,0.0,1740481191.924072,23.6999773979187,0.34839505345153854,, -1740481191.9437916,23.719977378845215,15.219072801745913,1740481191.943793,23.719977378845215,0.0,1740481191.9437954,23.719977378845215,0.0,1740481191.9437978,23.719977378845215,17.696790106903077,1740481191.9437988,23.719977378845215,0.0,1740481191.9438,23.719977378845215,0.0,1740481191.9438012,23.719977378845215,0.0,1740481191.943802,23.719977378845215,0.0,1740481191.943803,23.719977378845215,0.0,1740481191.9438038,23.719977378845215,-2.0,1740481191.943805,23.719977378845215,-2.3483950534515383,1740481191.943806,23.719977378845215,0.0,1740481191.9438066,23.719977378845215,0.34839505345153854,, -1740481191.964399,23.73997735977173,15.251896257625582,1740481191.964401,23.73997735977173,0.0,1740481191.9644027,23.73997735977173,0.0,1740481191.9644048,23.73997735977173,17.476790106903078,1740481191.9644058,23.73997735977173,0.0,1740481191.964407,23.73997735977173,0.0,1740481191.9644082,23.73997735977173,0.0,1740481191.964409,23.73997735977173,0.0,1740481191.96441,23.73997735977173,0.0,1740481191.9644108,23.73997735977173,-2.0,1740481191.964412,23.73997735977173,-2.1883950057677772,1740481191.9644127,23.73997735977173,0.0,1740481191.964414,23.73997735977173,0.23839505345153844,, -1740481191.9853487,23.759977340698242,15.251896257625582,1740481191.9853501,23.759977340698242,0.0,1740481191.9853523,23.759977340698242,0.0,1740481191.985354,23.759977340698242,17.476790106903078,1740481191.985355,23.759977340698242,0.0,1740481191.9853563,23.759977340698242,0.0,1740481191.9853573,23.759977340698242,0.0,1740481191.985358,23.759977340698242,0.0,1740481191.9853592,23.759977340698242,0.0,1740481191.98536,23.759977340698242,-2.0,1740481191.9853837,23.759977340698242,-2.2383950534515384,1740481191.9853857,23.759977340698242,0.0,1740481191.9853866,23.759977340698242,0.23839505345153844,, -1740481192.0035179,23.779977321624756,15.251896257625582,1740481192.0035198,23.779977321624756,0.0,1740481192.0035217,23.779977321624756,0.0,1740481192.0035236,23.779977321624756,17.476790106903078,1740481192.0035245,23.779977321624756,0.0,1740481192.003526,23.779977321624756,0.0,1740481192.0035267,23.779977321624756,0.0,1740481192.0035276,23.779977321624756,0.0,1740481192.0035286,23.779977321624756,0.0,1740481192.0035295,23.779977321624756,-2.0,1740481192.0035305,23.779977321624756,-2.2383950534515384,1740481192.0035312,23.779977321624756,0.0,1740481192.003532,23.779977321624756,0.23839505345153844,, -1740481192.0238469,23.79997730255127,15.251896257625582,1740481192.0238485,23.79997730255127,0.0,1740481192.0238507,23.79997730255127,0.0,1740481192.0238528,23.79997730255127,17.476790106903078,1740481192.0238535,23.79997730255127,0.0,1740481192.0238547,23.79997730255127,0.0,1740481192.023856,23.79997730255127,0.0,1740481192.0238569,23.79997730255127,0.0,1740481192.0238576,23.79997730255127,0.0,1740481192.0238588,23.79997730255127,-2.0,1740481192.0238595,23.79997730255127,-2.2383950534515384,1740481192.0238602,23.79997730255127,0.0,1740481192.0238612,23.79997730255127,0.23839505345153844,, -1740481192.0438921,23.819977283477783,15.251896257625582,1740481192.0438948,23.819977283477783,0.0,1740481192.043898,23.819977283477783,0.0,1740481192.043901,23.819977283477783,17.476790106903078,1740481192.0439034,23.819977283477783,0.0,1740481192.0439053,23.819977283477783,0.0,1740481192.0439079,23.819977283477783,0.0,1740481192.0439093,23.819977283477783,0.0,1740481192.0439107,23.819977283477783,0.0,1740481192.043912,23.819977283477783,-2.0,1740481192.0439134,23.819977283477783,-2.2383950534515384,1740481192.043917,23.819977283477783,0.0,1740481192.0439193,23.819977283477783,0.23839505345153844,, -1740481192.0679157,23.839977264404297,15.251896257625582,1740481192.0679176,23.839977264404297,0.0,1740481192.0679197,23.839977264404297,0.0,1740481192.0679216,23.839977264404297,17.476790106903078,1740481192.0679226,23.839977264404297,0.0,1740481192.067924,23.839977264404297,0.0,1740481192.0679247,23.839977264404297,0.0,1740481192.0679257,23.839977264404297,0.0,1740481192.067927,23.839977264404297,0.0,1740481192.0679278,23.839977264404297,-2.0,1740481192.0679286,23.839977264404297,-2.2383950534515384,1740481192.0679293,23.839977264404297,0.0,1740481192.0679305,23.839977264404297,0.23839505345153844,, -1740481192.0840538,23.85997724533081,15.272619713505254,1740481192.0840552,23.85997724533081,0.0,1740481192.0840573,23.85997724533081,0.0,1740481192.0840592,23.85997724533081,17.256790106903075,1740481192.0840602,23.85997724533081,0.0,1740481192.0840614,23.85997724533081,0.0,1740481192.0840745,23.85997724533081,0.0,1740481192.084076,23.85997724533081,0.0,1740481192.0840771,23.85997724533081,0.0,1740481192.084078,23.85997724533081,-2.0,1740481192.0840788,23.85997724533081,-2.0783950057677774,1740481192.08408,23.85997724533081,0.0,1740481192.0840807,23.85997724533081,0.12839505345153834,, -1740481192.1036847,23.879977226257324,15.272619713505254,1740481192.103686,23.879977226257324,0.0,1740481192.1036882,23.879977226257324,0.0,1740481192.10369,23.879977226257324,17.256790106903075,1740481192.103691,23.879977226257324,0.0,1740481192.1036923,23.879977226257324,0.0,1740481192.103693,23.879977226257324,0.0,1740481192.103694,23.879977226257324,0.0,1740481192.1036952,23.879977226257324,0.0,1740481192.1036959,23.879977226257324,-2.0,1740481192.1036968,23.879977226257324,-2.1283950534515386,1740481192.103698,23.879977226257324,0.0,1740481192.103699,23.879977226257324,0.12839505345153834,, -1740481192.123871,23.899977207183838,15.272619713505254,1740481192.1238725,23.899977207183838,0.0,1740481192.1238747,23.899977207183838,0.0,1740481192.1238763,23.899977207183838,17.256790106903075,1740481192.1238773,23.899977207183838,0.0,1740481192.1238785,23.899977207183838,0.0,1740481192.1238794,23.899977207183838,0.0,1740481192.1238801,23.899977207183838,0.0,1740481192.123881,23.899977207183838,0.0,1740481192.1238823,23.899977207183838,-2.0,1740481192.123883,23.899977207183838,-2.1283950534515386,1740481192.123884,23.899977207183838,0.0,1740481192.123885,23.899977207183838,0.12839505345153834,, -1740481192.1439178,23.91997718811035,15.272619713505254,1740481192.1439195,23.91997718811035,0.0,1740481192.1439216,23.91997718811035,0.0,1740481192.1439235,23.91997718811035,17.256790106903075,1740481192.1439245,23.91997718811035,0.0,1740481192.1439257,23.91997718811035,0.0,1740481192.1439269,23.91997718811035,0.0,1740481192.1439278,23.91997718811035,0.0,1740481192.1439288,23.91997718811035,0.0,1740481192.1439295,23.91997718811035,-2.0,1740481192.1439307,23.91997718811035,-2.1283950534515386,1740481192.1439314,23.91997718811035,0.0,1740481192.1439323,23.91997718811035,0.12839505345153834,, -1740481192.1636214,23.939977169036865,15.272619713505254,1740481192.163623,23.939977169036865,0.0,1740481192.1636379,23.939977169036865,0.0,1740481192.1636403,23.939977169036865,17.256790106903075,1740481192.1636415,23.939977169036865,0.0,1740481192.1636426,23.939977169036865,0.0,1740481192.1636438,23.939977169036865,0.0,1740481192.163645,23.939977169036865,0.0,1740481192.163646,23.939977169036865,0.0,1740481192.163647,23.939977169036865,-2.0,1740481192.1636477,23.939977169036865,-2.1283950534515386,1740481192.1636486,23.939977169036865,0.0,1740481192.1636496,23.939977169036865,0.12839505345153834,, -1740481192.1833954,23.95997714996338,15.281243169384922,1740481192.183397,23.95997714996338,0.0,1740481192.1833992,23.95997714996338,0.0,1740481192.183401,23.95997714996338,17.036790106903076,1740481192.1834023,23.95997714996338,0.0,1740481192.1834035,23.95997714996338,0.0,1740481192.1834044,23.95997714996338,0.0,1740481192.1834056,23.95997714996338,0.0,1740481192.1834066,23.95997714996338,0.0,1740481192.1834075,23.95997714996338,-2.0,1740481192.1834087,23.95997714996338,-1.968395005767777,1740481192.1834097,23.95997714996338,0.0,1740481192.1834104,23.95997714996338,0.018395053451538364,, -1740481192.2042024,23.979977130889893,15.281243169384922,1740481192.204204,23.979977130889893,0.0,1740481192.204206,23.979977130889893,0.0,1740481192.2042081,23.979977130889893,17.036790106903076,1740481192.204209,23.979977130889893,0.0,1740481192.2042103,23.979977130889893,0.0,1740481192.2042112,23.979977130889893,0.0,1740481192.2042122,23.979977130889893,0.0,1740481192.2042131,23.979977130889893,0.0,1740481192.204214,23.979977130889893,-2.0,1740481192.204215,23.979977130889893,-2.0183950534515382,1740481192.2042158,23.979977130889893,0.0,1740481192.2042165,23.979977130889893,0.018395053451538364,, -1740481192.223328,23.999977111816406,15.281243169384922,1740481192.2233298,23.999977111816406,0.0,1740481192.223333,23.999977111816406,0.0,1740481192.223335,23.999977111816406,17.036790106903076,1740481192.2233357,23.999977111816406,0.0,1740481192.223337,23.999977111816406,0.0,1740481192.223338,23.999977111816406,0.0,1740481192.2233388,23.999977111816406,0.0,1740481192.2233398,23.999977111816406,0.0,1740481192.2233407,23.999977111816406,-2.0,1740481192.2233415,23.999977111816406,-2.0183950534515382,1740481192.2233424,23.999977111816406,0.0,1740481192.2233434,23.999977111816406,0.018395053451538364,, -1740481192.2453547,24.01997709274292,15.281243169384922,1740481192.2453563,24.01997709274292,0.0,1740481192.2453582,24.01997709274292,0.0,1740481192.2453604,24.01997709274292,17.036790106903076,1740481192.2453613,24.01997709274292,0.0,1740481192.2453625,24.01997709274292,0.0,1740481192.2453635,24.01997709274292,0.0,1740481192.2453644,24.01997709274292,0.0,1740481192.2453656,24.01997709274292,0.0,1740481192.2453663,24.01997709274292,-2.0,1740481192.2453673,24.01997709274292,-2.0183950534515382,1740481192.245368,24.01997709274292,0.0,1740481192.2453692,24.01997709274292,0.018395053451538364,, -1740481192.2671142,24.039977073669434,15.281243169384922,1740481192.267116,24.039977073669434,0.0,1740481192.2671185,24.039977073669434,0.0,1740481192.2671204,24.039977073669434,17.036790106903076,1740481192.267121,24.039977073669434,0.0,1740481192.2671227,24.039977073669434,0.0,1740481192.2671235,24.039977073669434,0.0,1740481192.2671247,24.039977073669434,0.0,1740481192.2671258,24.039977073669434,0.0,1740481192.2671268,24.039977073669434,-2.0,1740481192.2671275,24.039977073669434,-2.0183950534515382,1740481192.2671282,24.039977073669434,0.0,1740481192.2671294,24.039977073669434,0.018395053451538364,, -1740481192.2861936,24.059977054595947,15.281243169384922,1740481192.2861962,24.059977054595947,0.0,1740481192.2861996,24.059977054595947,0.0,1740481192.286203,24.059977054595947,17.036790106903076,1740481192.2862043,24.059977054595947,0.0,1740481192.2862065,24.059977054595947,0.0,1740481192.286208,24.059977054595947,0.0,1740481192.2862098,24.059977054595947,0.0,1740481192.2862115,24.059977054595947,0.0,1740481192.2862132,24.059977054595947,-2.0,1740481192.2862146,24.059977054595947,-2.0183950534515382,1740481192.2862163,24.059977054595947,0.0,1740481192.2862177,24.059977054595947,0.018395053451538364,, -1740481192.303992,24.069977045059204,15.281511070453956,1740481192.3039954,24.069977045059204,0.0,1740481192.3040006,24.069977045059204,0.0,1740481192.3040051,24.069977045059204,17.0,1740481192.3040075,24.069977045059204,0.0,1740481192.3040109,24.069977045059204,0.0,1740481192.3040133,24.069977045059204,0.0,1740481192.3040159,24.069977045059204,0.0,1740481192.3040185,24.069977045059204,0.0,1740481192.304021,24.069977045059204,-2.0,1740481192.3040235,24.069977045059204,-1.991638604093434,1740481192.304026,24.069977045059204,0.0,1740481192.3040285,24.069977045059204,0.0,, -1740481192.3240838,24.099977016448975,15.281511070453956,1740481192.3240852,24.099977016448975,0.0,1740481192.3240874,24.099977016448975,0.0,1740481192.324089,24.099977016448975,17.0,1740481192.32409,24.099977016448975,0.0,1740481192.3240914,24.099977016448975,0.0,1740481192.3240924,24.099977016448975,0.0,1740481192.324093,24.099977016448975,0.0,1740481192.3240943,24.099977016448975,0.0,1740481192.324095,24.099977016448975,-2.0,1740481192.324096,24.099977016448975,-2.0,1740481192.3240967,24.099977016448975,0.0,1740481192.3240979,24.099977016448975,0.0,, -1740481192.343841,24.11997699737549,15.281511070453956,1740481192.3438432,24.11997699737549,0.0,1740481192.3438468,24.11997699737549,0.0,1740481192.3438494,24.11997699737549,17.0,1740481192.343851,24.11997699737549,0.0,1740481192.3438535,24.11997699737549,0.0,1740481192.3438554,24.11997699737549,0.0,1740481192.3438566,24.11997699737549,0.0,1740481192.343859,24.11997699737549,0.0,1740481192.3438601,24.11997699737549,-2.0,1740481192.3438623,24.11997699737549,-2.0,1740481192.3438635,24.11997699737549,0.0,1740481192.3438652,24.11997699737549,0.0,, -1740481192.3641067,24.139976978302002,15.281511070453956,1740481192.3641086,24.139976978302002,0.0,1740481192.364111,24.139976978302002,0.0,1740481192.3641129,24.139976978302002,17.0,1740481192.3641138,24.139976978302002,0.0,1740481192.3641152,24.139976978302002,0.0,1740481192.3641164,24.139976978302002,0.0,1740481192.3641176,24.139976978302002,0.0,1740481192.3641188,24.139976978302002,0.0,1740481192.3641198,24.139976978302002,-2.0,1740481192.3641207,24.139976978302002,-2.0,1740481192.364122,24.139976978302002,0.0,1740481192.3641229,24.139976978302002,0.0,, -1740481192.3851168,24.159976959228516,15.281511070453956,1740481192.3851185,24.159976959228516,0.0,1740481192.3851209,24.159976959228516,0.0,1740481192.385123,24.159976959228516,17.0,1740481192.3851242,24.159976959228516,0.0,1740481192.3851254,24.159976959228516,0.0,1740481192.3851264,24.159976959228516,0.0,1740481192.385127,24.159976959228516,0.0,1740481192.3851283,24.159976959228516,0.0,1740481192.3851292,24.159976959228516,-2.0,1740481192.38513,24.159976959228516,-2.0,1740481192.3851311,24.159976959228516,0.0,1740481192.3851318,24.159976959228516,0.0,, -1740481192.4032497,24.17997694015503,15.281511070453956,1740481192.4032512,24.17997694015503,0.0,1740481192.4032536,24.17997694015503,0.0,1740481192.4032555,24.17997694015503,17.0,1740481192.403257,24.17997694015503,0.0,1740481192.4032583,24.17997694015503,0.0,1740481192.4032593,24.17997694015503,0.0,1740481192.4032605,24.17997694015503,0.0,1740481192.4032614,24.17997694015503,0.0,1740481192.4032624,24.17997694015503,-2.0,1740481192.403264,24.17997694015503,-2.0,1740481192.403265,24.17997694015503,0.0,1740481192.403266,24.17997694015503,0.0,, -1740481192.4237356,24.199976921081543,15.281511070453956,1740481192.4237373,24.199976921081543,0.0,1740481192.4237394,24.199976921081543,0.0,1740481192.4237416,24.199976921081543,17.0,1740481192.4237428,24.199976921081543,0.0,1740481192.423744,24.199976921081543,0.0,1740481192.423745,24.199976921081543,0.0,1740481192.423746,24.199976921081543,0.0,1740481192.4237473,24.199976921081543,0.0,1740481192.4237483,24.199976921081543,-2.0,1740481192.4237494,24.199976921081543,-2.0,1740481192.4237502,24.199976921081543,0.0,1740481192.423751,24.199976921081543,0.0,, -1740481192.443501,24.219976902008057,15.281511070453956,1740481192.4435031,24.219976902008057,0.0,1740481192.4435062,24.219976902008057,0.0,1740481192.4435084,24.219976902008057,17.0,1740481192.4435096,24.219976902008057,0.0,1740481192.443511,24.219976902008057,0.0,1740481192.443512,24.219976902008057,0.0,1740481192.4435134,24.219976902008057,0.0,1740481192.4435143,24.219976902008057,0.0,1740481192.4435153,24.219976902008057,-2.0,1740481192.4435165,24.219976902008057,-2.0,1740481192.4435172,24.219976902008057,0.0,1740481192.4435182,24.219976902008057,0.0,, -1740481192.4635289,24.23997688293457,15.281511070453956,1740481192.4635305,24.23997688293457,0.0,1740481192.4635327,24.23997688293457,0.0,1740481192.4635346,24.23997688293457,17.0,1740481192.4635355,24.23997688293457,0.0,1740481192.463537,24.23997688293457,0.0,1740481192.4635382,24.23997688293457,0.0,1740481192.463539,24.23997688293457,0.0,1740481192.4635403,24.23997688293457,0.0,1740481192.4635413,24.23997688293457,-2.0,1740481192.4635422,24.23997688293457,-2.0,1740481192.463543,24.23997688293457,0.0,1740481192.4635441,24.23997688293457,0.0,, -1740481192.4834015,24.259976863861084,15.281511070453956,1740481192.483403,24.259976863861084,0.0,1740481192.483405,24.259976863861084,0.0,1740481192.483407,24.259976863861084,17.0,1740481192.4834082,24.259976863861084,0.0,1740481192.4834094,24.259976863861084,0.0,1740481192.4834104,24.259976863861084,0.0,1740481192.4834116,24.259976863861084,0.0,1740481192.4834125,24.259976863861084,0.0,1740481192.4834137,24.259976863861084,-2.0,1740481192.4834144,24.259976863861084,-2.0,1740481192.4834156,24.259976863861084,0.0,1740481192.4834166,24.259976863861084,0.0,, -1740481192.5043275,24.279976844787598,15.281511070453956,1740481192.5043287,24.279976844787598,0.0,1740481192.504331,24.279976844787598,0.0,1740481192.5043328,24.279976844787598,17.0,1740481192.5043337,24.279976844787598,0.0,1740481192.5043352,24.279976844787598,0.0,1740481192.504336,24.279976844787598,0.0,1740481192.504337,24.279976844787598,0.0,1740481192.5043383,24.279976844787598,0.0,1740481192.5043392,24.279976844787598,-2.0,1740481192.5043402,24.279976844787598,-2.0,1740481192.504341,24.279976844787598,0.0,1740481192.504342,24.279976844787598,0.0,, -1740481192.5234709,24.29997682571411,15.281511070453956,1740481192.5234725,24.29997682571411,0.0,1740481192.523475,24.29997682571411,0.0,1740481192.5234768,24.29997682571411,17.0,1740481192.5234778,24.29997682571411,0.0,1740481192.5234792,24.29997682571411,0.0,1740481192.5234804,24.29997682571411,0.0,1740481192.5234816,24.29997682571411,0.0,1740481192.5234826,24.29997682571411,0.0,1740481192.5234838,24.29997682571411,-2.0,1740481192.5234847,24.29997682571411,-2.0,1740481192.5234854,24.29997682571411,0.0,1740481192.5234864,24.29997682571411,0.0,, -1740481192.5448976,24.319976806640625,15.281511070453956,1740481192.544899,24.319976806640625,0.0,1740481192.5449011,24.319976806640625,0.0,1740481192.5449033,24.319976806640625,17.0,1740481192.544904,24.319976806640625,0.0,1740481192.5449052,24.319976806640625,0.0,1740481192.5449061,24.319976806640625,0.0,1740481192.544907,24.319976806640625,0.0,1740481192.544908,24.319976806640625,0.0,1740481192.544909,24.319976806640625,-2.0,1740481192.5449097,24.319976806640625,-2.0,1740481192.544911,24.319976806640625,0.0,1740481192.5449119,24.319976806640625,0.0,, -1740481192.5671194,24.33997678756714,15.281511070453956,1740481192.5671206,24.33997678756714,0.0,1740481192.567123,24.33997678756714,0.0,1740481192.5671248,24.33997678756714,17.0,1740481192.5671258,24.33997678756714,0.0,1740481192.567127,24.33997678756714,0.0,1740481192.5671277,24.33997678756714,0.0,1740481192.567129,24.33997678756714,0.0,1740481192.5671299,24.33997678756714,0.0,1740481192.5671306,24.33997678756714,-2.0,1740481192.5671318,24.33997678756714,-2.0,1740481192.5671325,24.33997678756714,0.0,1740481192.5671334,24.33997678756714,0.0,, -1740481192.5836713,24.359976768493652,15.281511070453956,1740481192.5836728,24.359976768493652,0.0,1740481192.583675,24.359976768493652,0.0,1740481192.5836766,24.359976768493652,17.0,1740481192.5836775,24.359976768493652,0.0,1740481192.5836787,24.359976768493652,0.0,1740481192.5836797,24.359976768493652,0.0,1740481192.5836809,24.359976768493652,0.0,1740481192.5836816,24.359976768493652,0.0,1740481192.5836825,24.359976768493652,-2.0,1740481192.5836973,24.359976768493652,-2.0,1740481192.5836985,24.359976768493652,0.0,1740481192.5836992,24.359976768493652,0.0,, -1740481192.6034124,24.379976749420166,15.281511070453956,1740481192.603414,24.379976749420166,0.0,1740481192.603416,24.379976749420166,0.0,1740481192.6034179,24.379976749420166,17.0,1740481192.6034188,24.379976749420166,0.0,1740481192.6034203,24.379976749420166,0.0,1740481192.6034212,24.379976749420166,0.0,1740481192.6034222,24.379976749420166,0.0,1740481192.6034229,24.379976749420166,0.0,1740481192.603424,24.379976749420166,-2.0,1740481192.6034248,24.379976749420166,-2.0,1740481192.6034255,24.379976749420166,0.0,1740481192.6034265,24.379976749420166,0.0,, -1740481192.627083,24.39997673034668,15.281511070453956,1740481192.6270845,24.39997673034668,0.0,1740481192.6270864,24.39997673034668,0.0,1740481192.6270883,24.39997673034668,17.0,1740481192.6270895,24.39997673034668,0.0,1740481192.6271114,24.39997673034668,0.0,1740481192.6271122,24.39997673034668,0.0,1740481192.627113,24.39997673034668,0.0,1740481192.6271143,24.39997673034668,0.0,1740481192.627115,24.39997673034668,-2.0,1740481192.627116,24.39997673034668,-2.0,1740481192.627117,24.39997673034668,0.0,1740481192.6271179,24.39997673034668,0.0,, -1740481192.646052,24.419976711273193,15.281511070453956,1740481192.6460533,24.419976711273193,0.0,1740481192.6460557,24.419976711273193,0.0,1740481192.6460578,24.419976711273193,17.0,1740481192.6460588,24.419976711273193,0.0,1740481192.64606,24.419976711273193,0.0,1740481192.646061,24.419976711273193,0.0,1740481192.6460621,24.419976711273193,0.0,1740481192.646063,24.419976711273193,0.0,1740481192.6460638,24.419976711273193,-2.0,1740481192.646065,24.419976711273193,-2.0,1740481192.6460657,24.419976711273193,0.0,1740481192.6460667,24.419976711273193,0.0,, -1740481192.665968,24.439976692199707,15.281511070453956,1740481192.6659694,24.439976692199707,0.0,1740481192.6659718,24.439976692199707,0.0,1740481192.6659882,24.439976692199707,17.0,1740481192.6659894,24.439976692199707,0.0,1740481192.6659908,24.439976692199707,0.0,1740481192.665992,24.439976692199707,0.0,1740481192.665993,24.439976692199707,0.0,1740481192.665994,24.439976692199707,0.0,1740481192.6659951,24.439976692199707,-2.0,1740481192.665996,24.439976692199707,-2.0,1740481192.6659968,24.439976692199707,0.0,1740481192.6659977,24.439976692199707,0.0,, -1740481192.6843987,24.45997667312622,15.281511070453956,1740481192.6844,24.45997667312622,0.0,1740481192.6844022,24.45997667312622,0.0,1740481192.6844041,24.45997667312622,17.0,1740481192.6844056,24.45997667312622,0.0,1740481192.6844068,24.45997667312622,0.0,1740481192.6844077,24.45997667312622,0.0,1740481192.684409,24.45997667312622,0.0,1740481192.68441,24.45997667312622,0.0,1740481192.6844108,24.45997667312622,-2.0,1740481192.6844122,24.45997667312622,-2.0,1740481192.6844132,24.45997667312622,0.0,1740481192.684414,24.45997667312622,0.0,, -1740481192.7032652,24.479976654052734,15.281511070453956,1740481192.703267,24.479976654052734,0.0,1740481192.7032695,24.479976654052734,0.0,1740481192.7032974,24.479976654052734,17.0,1740481192.7032986,24.479976654052734,0.0,1740481192.7033,24.479976654052734,0.0,1740481192.7033012,24.479976654052734,0.0,1740481192.7033024,24.479976654052734,0.0,1740481192.7033033,24.479976654052734,0.0,1740481192.7033045,24.479976654052734,-2.0,1740481192.7033055,24.479976654052734,-2.0,1740481192.703329,24.479976654052734,0.0,1740481192.7033303,24.479976654052734,0.0,, -1740481192.7235148,24.499976634979248,15.281511070453956,1740481192.7235165,24.499976634979248,0.0,1740481192.7235186,24.499976634979248,0.0,1740481192.7235208,24.499976634979248,17.0,1740481192.7235215,24.499976634979248,0.0,1740481192.7235231,24.499976634979248,0.0,1740481192.723524,24.499976634979248,0.0,1740481192.723525,24.499976634979248,0.0,1740481192.7235265,24.499976634979248,0.0,1740481192.7235272,24.499976634979248,-2.0,1740481192.7235281,24.499976634979248,-2.0,1740481192.7235289,24.499976634979248,0.0,1740481192.72353,24.499976634979248,0.0,, -1740481192.7458577,24.51997661590576,15.281511070453956,1740481192.7458594,24.51997661590576,0.0,1740481192.7458615,24.51997661590576,0.0,1740481192.745864,24.51997661590576,17.0,1740481192.7458649,24.51997661590576,0.0,1740481192.7458665,24.51997661590576,0.0,1740481192.7458675,24.51997661590576,0.0,1740481192.7458692,24.51997661590576,0.0,1740481192.7458704,24.51997661590576,0.0,1740481192.7458713,24.51997661590576,-2.0,1740481192.7458725,24.51997661590576,-2.0,1740481192.7458735,24.51997661590576,0.0,1740481192.7458744,24.51997661590576,0.0,, -1740481192.7659786,24.539976596832275,15.281511070453956,1740481192.7659802,24.539976596832275,0.0,1740481192.7659822,24.539976596832275,0.0,1740481192.7659843,24.539976596832275,17.0,1740481192.7659853,24.539976596832275,0.0,1740481192.7659864,24.539976596832275,0.0,1740481192.7659874,24.539976596832275,0.0,1740481192.7659883,24.539976596832275,0.0,1740481192.7659893,24.539976596832275,0.0,1740481192.7659905,24.539976596832275,-2.0,1740481192.7659914,24.539976596832275,-2.0,1740481192.7659924,24.539976596832275,0.0,1740481192.7659934,24.539976596832275,0.0,, -1740481192.7833302,24.55997657775879,15.281511070453956,1740481192.783332,24.55997657775879,0.0,1740481192.7833343,24.55997657775879,0.0,1740481192.7833362,24.55997657775879,17.0,1740481192.783337,24.55997657775879,0.0,1740481192.7833385,24.55997657775879,0.0,1740481192.7833393,24.55997657775879,0.0,1740481192.7833402,24.55997657775879,0.0,1740481192.7833416,24.55997657775879,0.0,1740481192.7833426,24.55997657775879,-2.0,1740481192.7833436,24.55997657775879,-2.0,1740481192.7833443,24.55997657775879,0.0,1740481192.7833455,24.55997657775879,0.0,, -1740481192.803522,24.579976558685303,15.281511070453956,1740481192.8035233,24.579976558685303,0.0,1740481192.8035257,24.579976558685303,0.0,1740481192.8035274,24.579976558685303,17.0,1740481192.8035285,24.579976558685303,0.0,1740481192.8035297,24.579976558685303,0.0,1740481192.8035307,24.579976558685303,0.0,1740481192.803532,24.579976558685303,0.0,1740481192.8035328,24.579976558685303,0.0,1740481192.8035338,24.579976558685303,-2.0,1740481192.8035345,24.579976558685303,-2.0,1740481192.8035357,24.579976558685303,0.0,1740481192.8035367,24.579976558685303,0.0,, -1740481192.8234339,24.599976539611816,15.281511070453956,1740481192.8234358,24.599976539611816,0.0,1740481192.8234384,24.599976539611816,0.0,1740481192.8234406,24.599976539611816,17.0,1740481192.823442,24.599976539611816,0.0,1740481192.8234434,24.599976539611816,0.0,1740481192.8234444,24.599976539611816,0.0,1740481192.8234458,24.599976539611816,0.0,1740481192.8234468,24.599976539611816,0.0,1740481192.8234646,24.599976539611816,-2.0,1740481192.8234658,24.599976539611816,-2.0,1740481192.8234665,24.599976539611816,0.0,1740481192.8234675,24.599976539611816,0.0,, -1740481192.8436203,24.61997652053833,15.281511070453956,1740481192.8436217,24.61997652053833,0.0,1740481192.8436239,24.61997652053833,0.0,1740481192.8436258,24.61997652053833,17.0,1740481192.8436267,24.61997652053833,0.0,1740481192.843628,24.61997652053833,0.0,1740481192.8436291,24.61997652053833,0.0,1740481192.84363,24.61997652053833,0.0,1740481192.843631,24.61997652053833,0.0,1740481192.8436322,24.61997652053833,-2.0,1740481192.8436332,24.61997652053833,-2.0,1740481192.8436341,24.61997652053833,0.0,1740481192.8436348,24.61997652053833,0.0,, -1740481192.8649108,24.639976501464844,15.281511070453956,1740481192.8649123,24.639976501464844,0.0,1740481192.864915,24.639976501464844,0.0,1740481192.8649168,24.639976501464844,17.0,1740481192.8649178,24.639976501464844,0.0,1740481192.864919,24.639976501464844,0.0,1740481192.8649201,24.639976501464844,0.0,1740481192.864921,24.639976501464844,0.0,1740481192.8649223,24.639976501464844,0.0,1740481192.8649232,24.639976501464844,-2.0,1740481192.8649242,24.639976501464844,-2.0,1740481192.8649251,24.639976501464844,0.0,1740481192.8649259,24.639976501464844,0.0,, -1740481192.883603,24.659976482391357,15.281511070453956,1740481192.8836048,24.659976482391357,0.0,1740481192.8836071,24.659976482391357,0.0,1740481192.883609,24.659976482391357,17.0,1740481192.8836098,24.659976482391357,0.0,1740481192.8836114,24.659976482391357,0.0,1740481192.8836124,24.659976482391357,0.0,1740481192.8836133,24.659976482391357,0.0,1740481192.8836145,24.659976482391357,0.0,1740481192.8836155,24.659976482391357,-2.0,1740481192.8836164,24.659976482391357,-2.0,1740481192.8836176,24.659976482391357,0.0,1740481192.8836186,24.659976482391357,0.0,, -1740481192.903437,24.67997646331787,15.281511070453956,1740481192.9034383,24.67997646331787,0.0,1740481192.9034405,24.67997646331787,0.0,1740481192.903461,24.67997646331787,17.0,1740481192.9034948,24.67997646331787,0.0,1740481192.9034977,24.67997646331787,0.0,1740481192.9034991,24.67997646331787,0.0,1740481192.903516,24.67997646331787,0.0,1740481192.9035172,24.67997646331787,0.0,1740481192.9035182,24.67997646331787,-2.0,1740481192.9035192,24.67997646331787,-2.0,1740481192.9035203,24.67997646331787,0.0,1740481192.9035218,24.67997646331787,0.0,, -1740481192.9233878,24.699976444244385,15.281511070453956,1740481192.9233897,24.699976444244385,0.0,1740481192.9233918,24.699976444244385,0.0,1740481192.9233935,24.699976444244385,17.0,1740481192.923395,24.699976444244385,0.0,1740481192.923396,24.699976444244385,0.0,1740481192.9233968,24.699976444244385,0.0,1740481192.9233983,24.699976444244385,0.0,1740481192.9233992,24.699976444244385,0.0,1740481192.9234,24.699976444244385,-2.0,1740481192.9234009,24.699976444244385,-2.0,1740481192.9234018,24.699976444244385,0.0,1740481192.9234028,24.699976444244385,0.0,, -1740481192.9437807,24.7199764251709,15.281511070453956,1740481192.943782,24.7199764251709,0.0,1740481192.9437857,24.7199764251709,0.0,1740481192.9437883,24.7199764251709,17.0,1740481192.9437895,24.7199764251709,0.0,1740481192.9437919,24.7199764251709,0.0,1740481192.9437933,24.7199764251709,0.0,1740481192.9437954,24.7199764251709,0.0,1740481192.9437969,24.7199764251709,0.0,1740481192.9437983,24.7199764251709,-2.0,1740481192.9437995,24.7199764251709,-2.0,1740481192.9438007,24.7199764251709,0.0,1740481192.943802,24.7199764251709,0.0,, -1740481192.9660716,24.739976406097412,15.281511070453956,1740481192.9660728,24.739976406097412,0.0,1740481192.9660752,24.739976406097412,0.0,1740481192.9660769,24.739976406097412,17.0,1740481192.966078,24.739976406097412,0.0,1740481192.966079,24.739976406097412,0.0,1740481192.96608,24.739976406097412,0.0,1740481192.9660811,24.739976406097412,0.0,1740481192.9660823,24.739976406097412,0.0,1740481192.966083,24.739976406097412,-2.0,1740481192.966084,24.739976406097412,-2.0,1740481192.9660852,24.739976406097412,0.0,1740481192.966086,24.739976406097412,0.0,, -1740481192.9845502,24.759976387023926,15.281511070453956,1740481192.9845517,24.759976387023926,0.0,1740481192.984554,24.759976387023926,0.0,1740481192.984556,24.759976387023926,17.0,1740481192.9845572,24.759976387023926,0.0,1740481192.9845586,24.759976387023926,0.0,1740481192.9845598,24.759976387023926,0.0,1740481192.984561,24.759976387023926,0.0,1740481192.984562,24.759976387023926,0.0,1740481192.9845629,24.759976387023926,-2.0,1740481192.9845643,24.759976387023926,-2.0,1740481192.9845653,24.759976387023926,0.0,1740481192.9845665,24.759976387023926,0.0,, -1740481193.003372,24.77997636795044,15.281511070453956,1740481193.0033739,24.77997636795044,0.0,1740481193.0033762,24.77997636795044,0.0,1740481193.0033782,24.77997636795044,17.0,1740481193.003379,24.77997636795044,0.0,1740481193.0033805,24.77997636795044,0.0,1740481193.0033817,24.77997636795044,0.0,1740481193.0033827,24.77997636795044,0.0,1740481193.003384,24.77997636795044,0.0,1740481193.003385,24.77997636795044,-2.0,1740481193.0033858,24.77997636795044,-2.0,1740481193.003387,24.77997636795044,0.0,1740481193.003388,24.77997636795044,0.0,, -1740481193.0235133,24.799976348876953,15.281511070453956,1740481193.023515,24.799976348876953,0.0,1740481193.0235171,24.799976348876953,0.0,1740481193.023519,24.799976348876953,17.0,1740481193.02352,24.799976348876953,0.0,1740481193.0235214,24.799976348876953,0.0,1740481193.0235224,24.799976348876953,0.0,1740481193.0235236,24.799976348876953,0.0,1740481193.0235245,24.799976348876953,0.0,1740481193.0235257,24.799976348876953,-2.0,1740481193.0235267,24.799976348876953,-2.0,1740481193.0235276,24.799976348876953,0.0,1740481193.0235283,24.799976348876953,0.0,, -1740481193.0445082,24.819976329803467,15.281511070453956,1740481193.04451,24.819976329803467,0.0,1740481193.0445132,24.819976329803467,0.0,1740481193.0445166,24.819976329803467,17.0,1740481193.0445187,24.819976329803467,0.0,1740481193.0445201,24.819976329803467,0.0,1740481193.044522,24.819976329803467,0.0,1740481193.0445235,24.819976329803467,0.0,1740481193.0445256,24.819976329803467,0.0,1740481193.044527,24.819976329803467,-2.0,1740481193.0445285,24.819976329803467,-2.0,1740481193.0445297,24.819976329803467,0.0,1740481193.0445313,24.819976329803467,0.0,, -1740481193.0643969,24.83997631072998,15.281511070453956,1740481193.0643983,24.83997631072998,0.0,1740481193.0644004,24.83997631072998,0.0,1740481193.0644023,24.83997631072998,17.0,1740481193.0644035,24.83997631072998,0.0,1740481193.0644052,24.83997631072998,0.0,1740481193.064406,24.83997631072998,0.0,1740481193.064407,24.83997631072998,0.0,1740481193.0644083,24.83997631072998,0.0,1740481193.064409,24.83997631072998,-2.0,1740481193.0644102,24.83997631072998,-2.0,1740481193.064411,24.83997631072998,0.0,1740481193.0644119,24.83997631072998,0.0,, -1740481193.0840356,24.859976291656494,15.281511070453956,1740481193.084037,24.859976291656494,0.0,1740481193.0840394,24.859976291656494,0.0,1740481193.084041,24.859976291656494,17.0,1740481193.0840423,24.859976291656494,0.0,1740481193.0840433,24.859976291656494,0.0,1740481193.0840442,24.859976291656494,0.0,1740481193.0840454,24.859976291656494,0.0,1740481193.0840461,24.859976291656494,0.0,1740481193.0840473,24.859976291656494,-2.0,1740481193.0840483,24.859976291656494,-2.0,1740481193.0840497,24.859976291656494,0.0,1740481193.0840504,24.859976291656494,0.0,, -1740481193.1046572,24.879976272583008,15.281511070453956,1740481193.1046586,24.879976272583008,0.0,1740481193.1046607,24.879976272583008,0.0,1740481193.1046624,24.879976272583008,17.0,1740481193.1046636,24.879976272583008,0.0,1740481193.1046648,24.879976272583008,0.0,1740481193.104666,24.879976272583008,0.0,1740481193.1046672,24.879976272583008,0.0,1740481193.1046684,24.879976272583008,0.0,1740481193.1046693,24.879976272583008,-2.0,1740481193.1046705,24.879976272583008,-2.0,1740481193.1046715,24.879976272583008,0.0,1740481193.1046722,24.879976272583008,0.0,, -1740481193.1232307,24.89997625350952,15.281511070453956,1740481193.1232324,24.89997625350952,0.0,1740481193.1232347,24.89997625350952,0.0,1740481193.1232374,24.89997625350952,17.0,1740481193.1232386,24.89997625350952,0.0,1740481193.1232402,24.89997625350952,0.0,1740481193.1232414,24.89997625350952,0.0,1740481193.1232424,24.89997625350952,0.0,1740481193.1232438,24.89997625350952,0.0,1740481193.1232448,24.89997625350952,-2.0,1740481193.1232457,24.89997625350952,-2.0,1740481193.1232467,24.89997625350952,0.0,1740481193.1232479,24.89997625350952,0.0,, -1740481193.1448102,24.919976234436035,15.281511070453956,1740481193.144812,24.919976234436035,0.0,1740481193.1448157,24.919976234436035,0.0,1740481193.1448176,24.919976234436035,17.0,1740481193.1448188,24.919976234436035,0.0,1740481193.14482,24.919976234436035,0.0,1740481193.1448207,24.919976234436035,0.0,1740481193.1448221,24.919976234436035,0.0,1740481193.1448233,24.919976234436035,0.0,1740481193.1448243,24.919976234436035,-2.0,1740481193.1448255,24.919976234436035,-2.0,1740481193.1448262,24.919976234436035,0.0,1740481193.1448271,24.919976234436035,0.0,, -1740481193.165114,24.93997621536255,15.281511070453956,1740481193.1651154,24.93997621536255,0.0,1740481193.1651175,24.93997621536255,0.0,1740481193.1651194,24.93997621536255,17.0,1740481193.1651206,24.93997621536255,0.0,1740481193.1651218,24.93997621536255,0.0,1740481193.1651227,24.93997621536255,0.0,1740481193.1651242,24.93997621536255,0.0,1740481193.1651251,24.93997621536255,0.0,1740481193.165126,24.93997621536255,-2.0,1740481193.1651273,24.93997621536255,-2.0,1740481193.165128,24.93997621536255,0.0,1740481193.165129,24.93997621536255,0.0,, -1740481193.1845424,24.959976196289062,15.281511070453956,1740481193.184544,24.959976196289062,0.0,1740481193.1845465,24.959976196289062,0.0,1740481193.1845486,24.959976196289062,17.0,1740481193.1845496,24.959976196289062,0.0,1740481193.1845512,24.959976196289062,0.0,1740481193.1845522,24.959976196289062,0.0,1740481193.1845531,24.959976196289062,0.0,1740481193.1845546,24.959976196289062,0.0,1740481193.1845553,24.959976196289062,-2.0,1740481193.1845562,24.959976196289062,-2.0,1740481193.1845572,24.959976196289062,0.0,1740481193.1845584,24.959976196289062,0.0,, -1740481193.2037578,24.979976177215576,15.281511070453956,1740481193.2037594,24.979976177215576,0.0,1740481193.2037613,24.979976177215576,0.0,1740481193.2037632,24.979976177215576,17.0,1740481193.2037644,24.979976177215576,0.0,1740481193.2037659,24.979976177215576,0.0,1740481193.2037668,24.979976177215576,0.0,1740481193.2037675,24.979976177215576,0.0,1740481193.2037692,24.979976177215576,0.0,1740481193.2037702,24.979976177215576,-2.0,1740481193.203771,24.979976177215576,-2.0,1740481193.2037718,24.979976177215576,0.0,1740481193.203773,24.979976177215576,0.0,, -1740481193.2235699,24.99997615814209,15.281511070453956,1740481193.2235715,24.99997615814209,0.0,1740481193.2235734,24.99997615814209,0.0,1740481193.2235758,24.99997615814209,17.0,1740481193.2235768,24.99997615814209,0.0,1740481193.2235782,24.99997615814209,0.0,1740481193.223579,24.99997615814209,0.0,1740481193.22358,24.99997615814209,0.0,1740481193.2235808,24.99997615814209,0.0,1740481193.223582,24.99997615814209,-2.0,1740481193.2235827,24.99997615814209,-2.0,1740481193.2235837,24.99997615814209,0.0,1740481193.2235847,24.99997615814209,0.0,, -1740481193.2437491,25.019976139068604,15.281511070453956,1740481193.2437506,25.019976139068604,0.0,1740481193.243753,25.019976139068604,0.0,1740481193.2437549,25.019976139068604,17.0,1740481193.243756,25.019976139068604,0.0,1740481193.2437572,25.019976139068604,0.0,1740481193.2437584,25.019976139068604,0.0,1740481193.2437596,25.019976139068604,0.0,1740481193.2437606,25.019976139068604,0.0,1740481193.243762,25.019976139068604,-2.0,1740481193.243763,25.019976139068604,-2.0,1740481193.2437637,25.019976139068604,0.0,1740481193.2437646,25.019976139068604,0.0,, -1740481193.2646139,25.039976119995117,15.281511070453956,1740481193.2646155,25.039976119995117,0.0,1740481193.2646174,25.039976119995117,0.0,1740481193.2646196,25.039976119995117,17.0,1740481193.2646203,25.039976119995117,0.0,1740481193.2646215,25.039976119995117,0.0,1740481193.264623,25.039976119995117,0.0,1740481193.2646239,25.039976119995117,0.0,1740481193.2646248,25.039976119995117,0.0,1740481193.264626,25.039976119995117,-2.0,1740481193.264627,25.039976119995117,-2.0,1740481193.2646277,25.039976119995117,0.0,1740481193.2646286,25.039976119995117,0.0,, -1740481193.2834897,25.05997610092163,15.281511070453956,1740481193.2834914,25.05997610092163,0.0,1740481193.2834935,25.05997610092163,0.0,1740481193.2834954,25.05997610092163,17.0,1740481193.2834964,25.05997610092163,0.0,1740481193.2834978,25.05997610092163,0.0,1740481193.2834988,25.05997610092163,0.0,1740481193.2834997,25.05997610092163,0.0,1740481193.283501,25.05997610092163,0.0,1740481193.2835019,25.05997610092163,-2.0,1740481193.2835028,25.05997610092163,-2.0,1740481193.2835035,25.05997610092163,0.0,1740481193.2835045,25.05997610092163,0.0,, diff --git a/tuning logs/2025-02-25_02-59-27/behavior.json b/tuning logs/2025-02-25_02-59-27/behavior.json deleted file mode 100644 index 5da32160f..000000000 --- a/tuning logs/2025-02-25_02-59-27/behavior.json +++ /dev/null @@ -1,2834 +0,0 @@ -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.303631, "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": 1740481167.323631} -{"agents": {}, "time": 1740481167.323631} -{"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": 1740481167.323631} -{"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": 1740481167.343631} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.0, 0.0], [0.010000000000000002, 0.0], [0.04000000000000001, 0.0], [0.09000000000000002, 0.0], [0.16000000000000003, 0.0], [0.25, 0.0], [0.36, 0.0], [0.4899999999999999, 0.0], [0.6399999999999999, 0.0], [0.80302717900324, 0.0], [0.9030271790032401, 0.0], [1.0030271790032401, 0.0], [1.1030271790032402, 0.0], [1.2030271790032403, 0.0], [1.3030271790032404, 0.0], [1.4030271790032405, 0.0], [1.5030271790032406, 0.0], [1.6030271790032407, 0.0], [1.7030271790032407, 0.0], [1.8030271790032408, 0.0], [1.903027179003241, 0.0], [2.003027179003241, 0.0], [2.103027179003241, 0.0], [2.203027179003241, 0.0], [2.3030271790032413, 0.0], [2.4030271790032414, 0.0], [2.5030271790032415, 0.0], [2.6030271790032415, 0.0], [2.7030271790032416, 0.0], [2.8030271790032413, 0.0], [2.903027179003242, 0.0], [3.0030271790032415, 0.0], [3.103027179003242, 0.0], [3.2030271790032416, 0.0], [3.303027179003242, 0.0], [3.403027179003242, 0.0], [3.5030271790032415, 0.0], [3.603027179003241, 0.0], [3.7030271790032407, 0.0], [3.8030271790032404, 0.0], [3.90302717900324, 0.0], [4.00302717900324, 0.0], [4.10302717900324, 0.0], [4.203027179003239, 0.0], [4.303027179003239, 0.0], [4.403027179003239, 0.0], [4.503027179003238, 0.0], [4.603027179003238, 0.0], [4.703027179003238, 0.0], [4.803027179003237, 0.0], [4.903027179003237, 0.0], [5.003027179003237, 0.0], [5.103027179003236, 0.0], [5.203027179003236, 0.0], [5.3030271790032355, 0.0], [5.403027179003235, 0.0], [5.503027179003235, 0.0], [5.603027179003234, 0.0], [5.703027179003234, 0.0], [5.803027179003234, 0.0], [5.903027179003233, 0.0], [6.003027179003233, 0.0], [6.103027179003233, 0.0], [6.203027179003232, 0.0], [6.303027179003232, 0.0], [6.403027179003232, 0.0], [6.503027179003231, 0.0], [6.603027179003231, 0.0], [6.7030271790032305, 0.0], [6.80302717900323, 0.0], [6.90302717900323, 0.0], [7.0030271790032295, 0.0], [7.103027179003229, 0.0], [7.203027179003229, 0.0], [7.303027179003228, 0.0], [7.403027179003228, 0.0], [7.503027179003228, 0.0], [7.603027179003227, 0.0], [7.703027179003227, 0.0], [7.803027179003227, 0.0], [7.903027179003226, 0.0], [8.003027179003226, 0.0], [8.103027179003226, 0.0], [8.203027179003225, 0.0], [8.303027179003225, 0.0], [8.403027179003224, 0.0], [8.503027179003224, 0.0], [8.603027179003224, 0.0], [8.703027179003222, 0.0], [8.803027179003221, 0.0], [8.903027179003221, 0.0], [9.00302717900322, 0.0], [9.10302717900322, 0.0], [9.20302717900322, 0.0], [9.30302717900322, 0.0], [9.40302717900322, 0.0], [9.503027179003219, 0.0], [9.603027179003218, 0.0], [9.703027179003218, 0.0], [9.803027179003218, 0.0], [9.903027179003217, 0.0], [10.003027179003217, 0.0], [10.103027179003217, 0.0], [10.203027179003216, 0.0], [10.303027179003216, 0.0], [10.403027179003216, 0.0], [10.503027179003215, 0.0], [10.603027179003215, 0.0], [10.703027179003215, 0.0], [10.803027179003214, 0.0], [10.903027179003214, 0.0], [11.003027179003213, 0.0], [11.103027179003213, 0.0], [11.203027179003213, 0.0], [11.303027179003212, 0.0], [11.403027179003212, 0.0], [11.503027179003212, 0.0], [11.603027179003211, 0.0], [11.703027179003211, 0.0], [11.80302717900321, 0.0], [11.90302717900321, 0.0], [12.00302717900321, 0.0], [12.10302717900321, 0.0], [12.20302717900321, 0.0], [12.303027179003209, 0.0], [12.403027179003209, 0.0], [12.503027179003208, 0.0], [12.603027179003208, 0.0], [12.703027179003207, 0.0], [12.803027179003207, 0.0], [12.903027179003207, 0.0], [13.003027179003206, 0.0], [13.103027179003206, 0.0], [13.203027179003206, 0.0], [13.303027179003205, 0.0], [13.403027179003205, 0.0], [13.503027179003205, 0.0], [13.603027179003204, 0.0], [13.703027179003204, 0.0], [13.803027179003204, 0.0], [13.903027179003203, 0.0], [14.003027179003203, 0.0], [14.103027179003202, 0.0], [14.203027179003202, 0.0], [14.303027179003202, 0.0], [14.403027179003201, 0.0], [14.503027179003201, 0.0], [14.6030271790032, 0.0], [14.7030271790032, 0.0], [14.800215297290162, 0.0], [14.879609861489522, 0.0], [14.939004425688882, 0.0], [14.978398989888243, 0.0], [14.997793554087602, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884, 10.969693845669884, 11.069693845669883, 11.169693845669883, 11.269693845669883, 11.369693845669882, 11.469693845669882, 11.569693845669882, 11.669693845669881, 11.769693845669881, 11.86969384566988, 11.96969384566988, 12.06969384566988, 12.16969384566988, 12.26969384566988, 12.369693845669879, 12.469693845669878, 12.569693845669878, 12.669693845669878, 12.769693845669877, 12.869693845669877, 12.969693845669877, 13.069693845669876, 13.169693845669876, 13.269693845669876, 13.369693845669875, 13.469693845669875, 13.569693845669875, 13.669693845669874, 13.769693845669874, 13.869693845669874, 13.969693845669873, 14.069693845669873, 14.169693845669872, 14.269693845669872, 14.369693845669872, 14.469693845669871, 14.569693845669871, 14.66969384566987, 14.76969384566987, 14.86969384566987, 14.96969384566987, 15.06969384566987, 15.169693845669869, 15.269693845669869, 15.369693845669868, 15.469693845669868, 15.569693845669867, 15.669693845669867, 15.769693845669867, 15.869693845669866], "velocities": null}}, "time": 1740481167.343631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481167.343631} -{"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": 1740481167.363631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0012244386476737384, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.363631} -{"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": 1740481167.383631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0018361987141206945, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.383631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.413631, "x": 4.000091794632344, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.413631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.003669642823243459, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.413631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.423631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02366095407098251, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.423631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.443631} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.179463234421092e-05, 0.0], [0.010691044796025064, 0.0], [0.04129029495970592, 0.0], [0.09188954512338679, 0.0], [0.16248879528706764, 0.0], [0.2530880454507485, 0.0], [0.3636872956144293, 0.0], [0.49428654577811004, 0.0], [0.644885795941791, 0.0], [0.8080028532142753, 0.0], [0.9080028532142754, 0.0], [1.0080028532142755, 0.0], [1.1080028532142756, 0.0], [1.2080028532142757, 0.0], [1.3080028532142758, 0.0], [1.4080028532142757, 0.0], [1.5080028532142757, 0.0], [1.6080028532142758, 0.0], [1.708002853214276, 0.0], [1.808002853214276, 0.0], [1.908002853214276, 0.0], [2.0080028532142764, 0.0], [2.108002853214276, 0.0], [2.2080028532142766, 0.0], [2.3080028532142762, 0.0], [2.4080028532142768, 0.0], [2.5080028532142764, 0.0], [2.608002853214277, 0.0], [2.7080028532142766, 0.0], [2.808002853214277, 0.0], [2.9080028532142768, 0.0], [3.0080028532142773, 0.0], [3.108002853214277, 0.0], [3.2080028532142775, 0.0], [3.308002853214277, 0.0], [3.4080028532142768, 0.0], [3.5080028532142764, 0.0], [3.608002853214276, 0.0], [3.7080028532142757, 0.0], [3.8080028532142753, 0.0], [3.908002853214275, 0.0], [4.008002853214275, 0.0], [4.108002853214274, 0.0], [4.208002853214274, 0.0], [4.308002853214274, 0.0], [4.408002853214273, 0.0], [4.508002853214273, 0.0], [4.6080028532142725, 0.0], [4.708002853214272, 0.0], [4.808002853214272, 0.0], [4.908002853214271, 0.0], [5.008002853214271, 0.0], [5.108002853214271, 0.0], [5.20800285321427, 0.0], [5.30800285321427, 0.0], [5.40800285321427, 0.0], [5.508002853214269, 0.0], [5.608002853214269, 0.0], [5.708002853214269, 0.0], [5.808002853214268, 0.0], [5.908002853214268, 0.0], [6.0080028532142675, 0.0], [6.108002853214267, 0.0], [6.208002853214267, 0.0], [6.3080028532142665, 0.0], [6.408002853214266, 0.0], [6.508002853214266, 0.0], [6.608002853214265, 0.0], [6.708002853214265, 0.0], [6.808002853214265, 0.0], [6.908002853214264, 0.0], [7.008002853214264, 0.0], [7.108002853214264, 0.0], [7.208002853214263, 0.0], [7.308002853214263, 0.0], [7.4080028532142626, 0.0], [7.508002853214262, 0.0], [7.608002853214262, 0.0], [7.7080028532142615, 0.0], [7.808002853214261, 0.0], [7.908002853214261, 0.0], [8.00800285321426, 0.0], [8.10800285321426, 0.0], [8.208002853214259, 0.0], [8.308002853214258, 0.0], [8.408002853214258, 0.0], [8.508002853214258, 0.0], [8.608002853214257, 0.0], [8.708002853214257, 0.0], [8.808002853214257, 0.0], [8.908002853214256, 0.0], [9.008002853214256, 0.0], [9.108002853214256, 0.0], [9.208002853214255, 0.0], [9.308002853214255, 0.0], [9.408002853214255, 0.0], [9.508002853214254, 0.0], [9.608002853214254, 0.0], [9.708002853214253, 0.0], [9.808002853214253, 0.0], [9.908002853214253, 0.0], [10.008002853214252, 0.0], [10.108002853214252, 0.0], [10.208002853214252, 0.0], [10.308002853214251, 0.0], [10.408002853214251, 0.0], [10.50800285321425, 0.0], [10.60800285321425, 0.0], [10.70800285321425, 0.0], [10.80800285321425, 0.0], [10.90800285321425, 0.0], [11.008002853214249, 0.0], [11.108002853214249, 0.0], [11.208002853214248, 0.0], [11.308002853214248, 0.0], [11.408002853214247, 0.0], [11.508002853214247, 0.0], [11.608002853214247, 0.0], [11.708002853214246, 0.0], [11.808002853214246, 0.0], [11.908002853214246, 0.0], [12.008002853214245, 0.0], [12.108002853214245, 0.0], [12.208002853214245, 0.0], [12.308002853214244, 0.0], [12.408002853214244, 0.0], [12.508002853214244, 0.0], [12.608002853214243, 0.0], [12.708002853214243, 0.0], [12.808002853214242, 0.0], [12.908002853214242, 0.0], [13.008002853214242, 0.0], [13.108002853214241, 0.0], [13.208002853214241, 0.0], [13.30800285321424, 0.0], [13.40800285321424, 0.0], [13.50800285321424, 0.0], [13.60800285321424, 0.0], [13.70800285321424, 0.0], [13.808002853214239, 0.0], [13.908002853214239, 0.0], [14.008002853214238, 0.0], [14.108002853214238, 0.0], [14.208002853214238, 0.0], [14.308002853214237, 0.0], [14.408002853214237, 0.0], [14.508002853214236, 0.0], [14.608002853214236, 0.0], [14.708002853214236, 0.0], [14.804638522233244, 0.0], [14.883037951590396, 0.0], [14.94143738094755, 0.0], [14.979836810304702, 0.0], [14.998236239661855, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884, 10.969693845669884, 11.069693845669883, 11.169693845669883, 11.269693845669883, 11.369693845669882, 11.469693845669882, 11.569693845669882, 11.669693845669881, 11.769693845669881, 11.86969384566988, 11.96969384566988, 12.06969384566988, 12.16969384566988, 12.26969384566988, 12.369693845669879, 12.469693845669878, 12.569693845669878, 12.669693845669878, 12.769693845669877, 12.869693845669877, 12.969693845669877, 13.069693845669876, 13.169693845669876, 13.269693845669876, 13.369693845669875, 13.469693845669875, 13.569693845669875, 13.669693845669874, 13.769693845669874, 13.869693845669874, 13.969693845669873, 14.069693845669873, 14.169693845669872, 14.269693845669872, 14.369693845669872, 14.469693845669871, 14.569693845669871, 14.66969384566987, 14.76969384566987, 14.86969384566987, 14.96969384566987, 15.06969384566987, 15.169693845669869, 15.269693845669869, 15.369693845669868, 15.469693845669868, 15.569693845669867, 15.669693845669867, 15.769693845669867, 15.869693845669866], "velocities": null}}, "time": 1740481167.443631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.043632129850092224, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.443631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.473631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04481256146944708, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.473631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.493631} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.045991791943005525, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.493631} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 9.179463234421092e-05, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.003669642823243459, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.06105362676563264, "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": 1740481167.5136309} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04716982193689877, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5136309} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.5236309, "x": 4.004016390192038, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5336308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39153730273173676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04834665211827801, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5336308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5536308} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.004016390192037811, 0.0], [0.021815302125124995, 0.0], [0.059614214058212184, 0.0], [0.11741312599129938, 0.0], [0.19521203792438657, 0.0], [0.2930109498574737, 0.0], [0.4108098617905609, 0.0], [0.5486087737236479, 0.0], [0.7059015266094528, 0.0], [0.8059015266094529, 0.0], [0.905901526609453, 0.0], [1.005901526609453, 0.0], [1.1059015266094532, 0.0], [1.2059015266094533, 0.0], [1.3059015266094534, 0.0], [1.4059015266094532, 0.0], [1.5059015266094533, 0.0], [1.6059015266094534, 0.0], [1.7059015266094535, 0.0], [1.8059015266094536, 0.0], [1.9059015266094537, 0.0], [2.0059015266094535, 0.0], [2.105901526609454, 0.0], [2.2059015266094537, 0.0], [2.3059015266094542, 0.0], [2.405901526609454, 0.0], [2.5059015266094544, 0.0], [2.605901526609454, 0.0], [2.705901526609454, 0.0], [2.8059015266094547, 0.0], [2.9059015266094543, 0.0], [3.005901526609455, 0.0], [3.1059015266094545, 0.0], [3.205901526609455, 0.0], [3.3059015266094547, 0.0], [3.4059015266094543, 0.0], [3.505901526609454, 0.0], [3.6059015266094536, 0.0], [3.7059015266094533, 0.0], [3.805901526609453, 0.0], [3.9059015266094526, 0.0], [4.005901526609452, 0.0], [4.105901526609451, 0.0], [4.205901526609451, 0.0], [4.305901526609451, 0.0], [4.40590152660945, 0.0], [4.50590152660945, 0.0], [4.60590152660945, 0.0], [4.705901526609449, 0.0], [4.805901526609449, 0.0], [4.905901526609449, 0.0], [5.005901526609448, 0.0], [5.105901526609448, 0.0], [5.2059015266094475, 0.0], [5.305901526609447, 0.0], [5.405901526609447, 0.0], [5.505901526609446, 0.0], [5.605901526609446, 0.0], [5.705901526609446, 0.0], [5.805901526609445, 0.0], [5.905901526609445, 0.0], [6.005901526609445, 0.0], [6.105901526609444, 0.0], [6.205901526609444, 0.0], [6.305901526609444, 0.0], [6.405901526609443, 0.0], [6.505901526609443, 0.0], [6.6059015266094425, 0.0], [6.705901526609442, 0.0], [6.805901526609442, 0.0], [6.9059015266094415, 0.0], [7.005901526609441, 0.0], [7.105901526609441, 0.0], [7.20590152660944, 0.0], [7.30590152660944, 0.0], [7.4059015266094415, 0.0], [7.505901526609441, 0.0], [7.605901526609441, 0.0], [7.70590152660944, 0.0], [7.80590152660944, 0.0], [7.90590152660944, 0.0], [8.00590152660944, 0.0], [8.10590152660944, 0.0], [8.20590152660944, 0.0], [8.30590152660944, 0.0], [8.405901526609439, 0.0], [8.505901526609438, 0.0], [8.605901526609438, 0.0], [8.705901526609438, 0.0], [8.805901526609437, 0.0], [8.905901526609437, 0.0], [9.005901526609437, 0.0], [9.105901526609436, 0.0], [9.205901526609436, 0.0], [9.305901526609436, 0.0], [9.405901526609435, 0.0], [9.505901526609435, 0.0], [9.605901526609435, 0.0], [9.705901526609434, 0.0], [9.805901526609434, 0.0], [9.905901526609433, 0.0], [10.005901526609433, 0.0], [10.105901526609433, 0.0], [10.205901526609432, 0.0], [10.305901526609432, 0.0], [10.405901526609432, 0.0], [10.505901526609431, 0.0], [10.605901526609431, 0.0], [10.70590152660943, 0.0], [10.80590152660943, 0.0], [10.90590152660943, 0.0], [11.00590152660943, 0.0], [11.10590152660943, 0.0], [11.205901526609429, 0.0], [11.305901526609428, 0.0], [11.405901526609428, 0.0], [11.505901526609428, 0.0], [11.605901526609427, 0.0], [11.705901526609427, 0.0], [11.805901526609427, 0.0], [11.905901526609426, 0.0], [12.005901526609426, 0.0], [12.105901526609426, 0.0], [12.205901526609425, 0.0], [12.305901526609425, 0.0], [12.405901526609425, 0.0], [12.505901526609424, 0.0], [12.605901526609424, 0.0], [12.705901526609424, 0.0], [12.805901526609423, 0.0], [12.905901526609423, 0.0], [13.005901526609422, 0.0], [13.105901526609422, 0.0], [13.205901526609422, 0.0], [13.305901526609421, 0.0], [13.405901526609421, 0.0], [13.50590152660942, 0.0], [13.60590152660942, 0.0], [13.70590152660942, 0.0], [13.80590152660942, 0.0], [13.90590152660942, 0.0], [14.005901526609419, 0.0], [14.105901526609419, 0.0], [14.205901526609418, 0.0], [14.305901526609418, 0.0], [14.405901526609417, 0.0], [14.505901526609417, 0.0], [14.605901526609417, 0.0], [14.705901526609416, 0.0], [14.802776545932153, 0.0], [14.88159624061027, 0.0], [14.940415935288385, 0.0], [14.979235629966503, 0.0], [14.99805532464462, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323, 15.806394529484322], "velocities": null}}, "time": 1740481167.5536308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0682349214193812, "gear": 1, "accelerator_pedal_position": 0.39153730273173676, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5536308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5736308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06939020335529934, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5736308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.5936308} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.3505635, "x": 15.0, "y": 2.1249999999999982, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481167.5936308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07054429838169154, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.5936308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.004016390192037811, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.04775838696241595, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.058826515586205996, "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": 1740481167.6136308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0716972071853235, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6136308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.6336308, "x": 4.011180782430692, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6336308} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07284893045389727, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6336308} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6436307} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.011180782430692204, 0.0], [0.03307696295866197, 0.0], [0.07497314348663174, 0.0], [0.13686932401460153, 0.0], [0.2187655045425713, 0.0], [0.32066168507054105, 0.0], [0.4425578655985108, 0.0], [0.5844540461264804, 0.0], [0.744502574741399, 0.0], [0.8445025747413991, 0.0], [0.9445025747413992, 0.0], [1.0445025747413994, 0.0], [1.1445025747413995, 0.0], [1.2445025747413996, 0.0], [1.3445025747413997, 0.0], [1.4445025747413993, 0.0], [1.5445025747413994, 0.0], [1.6445025747413995, 0.0], [1.7445025747413996, 0.0], [1.8445025747413997, 0.0], [1.9445025747413998, 0.0], [2.0445025747414, 0.0], [2.1445025747414, 0.0], [2.2445025747414, 0.0], [2.3445025747414, 0.0], [2.4445025747414, 0.0], [2.5445025747414003, 0.0], [2.6445025747414004, 0.0], [2.744502574741401, 0.0], [2.8445025747414006, 0.0], [2.944502574741401, 0.0], [3.0445025747414007, 0.0], [3.1445025747414013, 0.0], [3.244502574741401, 0.0], [3.3445025747414014, 0.0], [3.444502574741401, 0.0], [3.5445025747414007, 0.0], [3.6445025747414004, 0.0], [3.7445025747414, 0.0], [3.8445025747413997, 0.0], [3.9445025747413993, 0.0], [4.044502574741399, 0.0], [4.144502574741399, 0.0], [4.244502574741398, 0.0], [4.344502574741398, 0.0], [4.4445025747413975, 0.0], [4.544502574741397, 0.0], [4.644502574741397, 0.0], [4.7445025747413965, 0.0], [4.844502574741396, 0.0], [4.944502574741396, 0.0], [5.044502574741395, 0.0], [5.144502574741395, 0.0], [5.244502574741395, 0.0], [5.344502574741394, 0.0], [5.444502574741394, 0.0], [5.544502574741394, 0.0], [5.644502574741393, 0.0], [5.744502574741393, 0.0], [5.844502574741393, 0.0], [5.944502574741392, 0.0], [6.044502574741392, 0.0], [6.1445025747413915, 0.0], [6.244502574741391, 0.0], [6.344502574741391, 0.0], [6.44450257474139, 0.0], [6.54450257474139, 0.0], [6.64450257474139, 0.0], [6.744502574741389, 0.0], [6.844502574741389, 0.0], [6.944502574741389, 0.0], [7.044502574741388, 0.0], [7.144502574741388, 0.0], [7.244502574741388, 0.0], [7.344502574741387, 0.0], [7.444502574741388, 0.0], [7.544502574741387, 0.0], [7.644502574741387, 0.0], [7.744502574741387, 0.0], [7.844502574741386, 0.0], [7.944502574741386, 0.0], [8.044502574741385, 0.0], [8.144502574741384, 0.0], [8.244502574741384, 0.0], [8.344502574741384, 0.0], [8.444502574741383, 0.0], [8.544502574741383, 0.0], [8.644502574741383, 0.0], [8.744502574741382, 0.0], [8.844502574741382, 0.0], [8.944502574741382, 0.0], [9.044502574741381, 0.0], [9.14450257474138, 0.0], [9.24450257474138, 0.0], [9.34450257474138, 0.0], [9.44450257474138, 0.0], [9.54450257474138, 0.0], [9.644502574741379, 0.0], [9.744502574741379, 0.0], [9.844502574741378, 0.0], [9.944502574741378, 0.0], [10.044502574741378, 0.0], [10.144502574741377, 0.0], [10.244502574741377, 0.0], [10.344502574741377, 0.0], [10.444502574741376, 0.0], [10.544502574741376, 0.0], [10.644502574741376, 0.0], [10.744502574741375, 0.0], [10.844502574741375, 0.0], [10.944502574741374, 0.0], [11.044502574741374, 0.0], [11.144502574741374, 0.0], [11.244502574741373, 0.0], [11.344502574741373, 0.0], [11.444502574741373, 0.0], [11.544502574741372, 0.0], [11.644502574741372, 0.0], [11.744502574741372, 0.0], [11.844502574741371, 0.0], [11.944502574741371, 0.0], [12.04450257474137, 0.0], [12.14450257474137, 0.0], [12.24450257474137, 0.0], [12.34450257474137, 0.0], [12.44450257474137, 0.0], [12.544502574741369, 0.0], [12.644502574741368, 0.0], [12.744502574741368, 0.0], [12.844502574741368, 0.0], [12.944502574741367, 0.0], [13.044502574741367, 0.0], [13.144502574741367, 0.0], [13.244502574741366, 0.0], [13.344502574741366, 0.0], [13.444502574741366, 0.0], [13.544502574741365, 0.0], [13.644502574741365, 0.0], [13.744502574741364, 0.0], [13.844502574741364, 0.0], [13.944502574741364, 0.0], [14.044502574741363, 0.0], [14.144502574741363, 0.0], [14.244502574741363, 0.0], [14.344502574741362, 0.0], [14.444502574741362, 0.0], [14.544502574741362, 0.0], [14.644502574741361, 0.0], [14.744502574741361, 0.0], [14.835571838108613, 0.0], [14.906671323160342, 0.0], [14.95777080821207, 0.0], [14.988870293263798, 0.0], [14.999969778315526, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323, 15.806394529484322], "velocities": null}}, "time": 1740481167.6436307} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09276988352203232, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6436307} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6736307} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09389984417892214, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6736307} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.6836307} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0950286328656605, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.6836307} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.7036307} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09559258794081704, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7036307} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.011180782430692204, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07284893045389727, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.05754172738020169, "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": 1740481167.7336307} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09728269715356862, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7336307} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.7436306, "x": 4.021289880601261, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7536306} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.02128988060126069, 0.0], [0.04726798087894486, 0.0], [0.09324608115662905, 0.0], [0.15922418143431324, 0.0], [0.24520228171199743, 0.0], [0.35118038198968154, 0.0], [0.4771584822673657, 0.0], [0.6231365825450498, 0.0], [0.7850958936713571, 0.0], [0.8850958936713572, 0.0], [0.9850958936713573, 0.0], [1.0850958936713573, 0.0], [1.1850958936713574, 0.0], [1.2850958936713575, 0.0], [1.3850958936713575, 0.0], [1.4850958936713576, 0.0], [1.5850958936713577, 0.0], [1.6850958936713578, 0.0], [1.785095893671358, 0.0], [1.885095893671358, 0.0], [1.985095893671358, 0.0], [2.085095893671358, 0.0], [2.1850958936713583, 0.0], [2.2850958936713583, 0.0], [2.3850958936713584, 0.0], [2.4850958936713585, 0.0], [2.5850958936713586, 0.0], [2.6850958936713587, 0.0], [2.7850958936713583, 0.0], [2.885095893671359, 0.0], [2.9850958936713585, 0.0], [3.085095893671359, 0.0], [3.1850958936713587, 0.0], [3.2850958936713592, 0.0], [3.385095893671359, 0.0], [3.4850958936713585, 0.0], [3.585095893671358, 0.0], [3.685095893671358, 0.0], [3.7850958936713575, 0.0], [3.885095893671357, 0.0], [3.9850958936713567, 0.0], [4.085095893671356, 0.0], [4.185095893671356, 0.0], [4.285095893671356, 0.0], [4.385095893671355, 0.0], [4.485095893671355, 0.0], [4.585095893671355, 0.0], [4.685095893671354, 0.0], [4.785095893671354, 0.0], [4.8850958936713536, 0.0], [4.985095893671353, 0.0], [5.085095893671353, 0.0], [5.1850958936713525, 0.0], [5.285095893671352, 0.0], [5.385095893671352, 0.0], [5.485095893671351, 0.0], [5.585095893671351, 0.0], [5.685095893671351, 0.0], [5.78509589367135, 0.0], [5.88509589367135, 0.0], [5.98509589367135, 0.0], [6.085095893671349, 0.0], [6.185095893671349, 0.0], [6.285095893671349, 0.0], [6.385095893671348, 0.0], [6.485095893671348, 0.0], [6.5850958936713475, 0.0], [6.685095893671347, 0.0], [6.785095893671347, 0.0], [6.8850958936713464, 0.0], [6.985095893671346, 0.0], [7.085095893671346, 0.0], [7.185095893671345, 0.0], [7.285095893671345, 0.0], [7.385095893671345, 0.0], [7.485095893671345, 0.0], [7.585095893671345, 0.0], [7.6850958936713445, 0.0], [7.785095893671344, 0.0], [7.885095893671344, 0.0], [7.985095893671343, 0.0], [8.085095893671344, 0.0], [8.185095893671344, 0.0], [8.285095893671343, 0.0], [8.385095893671343, 0.0], [8.485095893671343, 0.0], [8.585095893671342, 0.0], [8.685095893671342, 0.0], [8.785095893671341, 0.0], [8.885095893671341, 0.0], [8.98509589367134, 0.0], [9.08509589367134, 0.0], [9.18509589367134, 0.0], [9.28509589367134, 0.0], [9.38509589367134, 0.0], [9.485095893671339, 0.0], [9.585095893671339, 0.0], [9.685095893671338, 0.0], [9.785095893671338, 0.0], [9.885095893671338, 0.0], [9.985095893671337, 0.0], [10.085095893671337, 0.0], [10.185095893671336, 0.0], [10.285095893671336, 0.0], [10.385095893671336, 0.0], [10.485095893671335, 0.0], [10.585095893671335, 0.0], [10.685095893671335, 0.0], [10.785095893671334, 0.0], [10.885095893671334, 0.0], [10.985095893671334, 0.0], [11.085095893671333, 0.0], [11.185095893671333, 0.0], [11.285095893671333, 0.0], [11.385095893671332, 0.0], [11.485095893671332, 0.0], [11.585095893671332, 0.0], [11.685095893671331, 0.0], [11.78509589367133, 0.0], [11.88509589367133, 0.0], [11.98509589367133, 0.0], [12.08509589367133, 0.0], [12.18509589367133, 0.0], [12.285095893671329, 0.0], [12.385095893671329, 0.0], [12.485095893671328, 0.0], [12.585095893671328, 0.0], [12.685095893671328, 0.0], [12.785095893671327, 0.0], [12.885095893671327, 0.0], [12.985095893671327, 0.0], [13.085095893671326, 0.0], [13.185095893671326, 0.0], [13.285095893671325, 0.0], [13.385095893671325, 0.0], [13.485095893671325, 0.0], [13.585095893671324, 0.0], [13.685095893671324, 0.0], [13.785095893671324, 0.0], [13.885095893671323, 0.0], [13.985095893671323, 0.0], [14.085095893671323, 0.0], [14.185095893671322, 0.0], [14.285095893671322, 0.0], [14.385095893671322, 0.0], [14.485095893671321, 0.0], [14.58509589367132, 0.0], [14.68509589367132, 0.0], [14.783864171918731, 0.0], [14.866844993184467, 0.0], [14.929825814450203, 0.0], [14.972806635715939, 0.0], [14.995787456981676, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323], "velocities": null}}, "time": 1740481167.7536306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09840797416931088, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7536306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7636306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11830244872708315, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7636306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.7936306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1381761324083651, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.7936306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8136306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15802888899716164, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8136306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8336306} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.5710602, "x": 15.0, "y": 2.234999999999996, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481167.8336306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17786058291891527, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8336306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.02128988060126069, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09784548184837108, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.05624923209397961, "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": 1740481167.8436306} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.02128988060126069, 0.0], [0.04726798087894486, 0.0], [0.09324608115662905, 0.0], [0.15922418143431324, 0.0], [0.24520228171199743, 0.0], [0.35118038198968154, 0.0], [0.4771584822673657, 0.0], [0.6231365825450498, 0.0], [0.7850958936713571, 0.0], [0.8850958936713572, 0.0], [0.9850958936713573, 0.0], [1.0850958936713573, 0.0], [1.1850958936713574, 0.0], [1.2850958936713575, 0.0], [1.3850958936713575, 0.0], [1.4850958936713576, 0.0], [1.5850958936713577, 0.0], [1.6850958936713578, 0.0], [1.785095893671358, 0.0], [1.885095893671358, 0.0], [1.985095893671358, 0.0], [2.085095893671358, 0.0], [2.1850958936713583, 0.0], [2.2850958936713583, 0.0], [2.3850958936713584, 0.0], [2.4850958936713585, 0.0], [2.5850958936713586, 0.0], [2.6850958936713587, 0.0], [2.7850958936713583, 0.0], [2.885095893671359, 0.0], [2.9850958936713585, 0.0], [3.085095893671359, 0.0], [3.1850958936713587, 0.0], [3.2850958936713592, 0.0], [3.385095893671359, 0.0], [3.4850958936713585, 0.0], [3.585095893671358, 0.0], [3.685095893671358, 0.0], [3.7850958936713575, 0.0], [3.885095893671357, 0.0], [3.9850958936713567, 0.0], [4.085095893671356, 0.0], [4.185095893671356, 0.0], [4.285095893671356, 0.0], [4.385095893671355, 0.0], [4.485095893671355, 0.0], [4.585095893671355, 0.0], [4.685095893671354, 0.0], [4.785095893671354, 0.0], [4.8850958936713536, 0.0], [4.985095893671353, 0.0], [5.085095893671353, 0.0], [5.1850958936713525, 0.0], [5.285095893671352, 0.0], [5.385095893671352, 0.0], [5.485095893671351, 0.0], [5.585095893671351, 0.0], [5.685095893671351, 0.0], [5.78509589367135, 0.0], [5.88509589367135, 0.0], [5.98509589367135, 0.0], [6.085095893671349, 0.0], [6.185095893671349, 0.0], [6.285095893671349, 0.0], [6.385095893671348, 0.0], [6.485095893671348, 0.0], [6.5850958936713475, 0.0], [6.685095893671347, 0.0], [6.785095893671347, 0.0], [6.8850958936713464, 0.0], [6.985095893671346, 0.0], [7.085095893671346, 0.0], [7.185095893671345, 0.0], [7.285095893671345, 0.0], [7.385095893671345, 0.0], [7.485095893671345, 0.0], [7.585095893671345, 0.0], [7.6850958936713445, 0.0], [7.785095893671344, 0.0], [7.885095893671344, 0.0], [7.985095893671343, 0.0], [8.085095893671344, 0.0], [8.185095893671344, 0.0], [8.285095893671343, 0.0], [8.385095893671343, 0.0], [8.485095893671343, 0.0], [8.585095893671342, 0.0], [8.685095893671342, 0.0], [8.785095893671341, 0.0], [8.885095893671341, 0.0], [8.98509589367134, 0.0], [9.08509589367134, 0.0], [9.18509589367134, 0.0], [9.28509589367134, 0.0], [9.38509589367134, 0.0], [9.485095893671339, 0.0], [9.585095893671339, 0.0], [9.685095893671338, 0.0], [9.785095893671338, 0.0], [9.885095893671338, 0.0], [9.985095893671337, 0.0], [10.085095893671337, 0.0], [10.185095893671336, 0.0], [10.285095893671336, 0.0], [10.385095893671336, 0.0], [10.485095893671335, 0.0], [10.585095893671335, 0.0], [10.685095893671335, 0.0], [10.785095893671334, 0.0], [10.885095893671334, 0.0], [10.985095893671334, 0.0], [11.085095893671333, 0.0], [11.185095893671333, 0.0], [11.285095893671333, 0.0], [11.385095893671332, 0.0], [11.485095893671332, 0.0], [11.585095893671332, 0.0], [11.685095893671331, 0.0], [11.78509589367133, 0.0], [11.88509589367133, 0.0], [11.98509589367133, 0.0], [12.08509589367133, 0.0], [12.18509589367133, 0.0], [12.285095893671329, 0.0], [12.385095893671329, 0.0], [12.485095893671328, 0.0], [12.585095893671328, 0.0], [12.685095893671328, 0.0], [12.785095893671327, 0.0], [12.885095893671327, 0.0], [12.985095893671327, 0.0], [13.085095893671326, 0.0], [13.185095893671326, 0.0], [13.285095893671325, 0.0], [13.385095893671325, 0.0], [13.485095893671325, 0.0], [13.585095893671324, 0.0], [13.685095893671324, 0.0], [13.785095893671324, 0.0], [13.885095893671323, 0.0], [13.985095893671323, 0.0], [14.085095893671323, 0.0], [14.185095893671322, 0.0], [14.285095893671322, 0.0], [14.385095893671322, 0.0], [14.485095893671321, 0.0], [14.58509589367132, 0.0], [14.68509589367132, 0.0], [14.783864171918731, 0.0], [14.866844993184467, 0.0], [14.929825814450203, 0.0], [14.972806635715939, 0.0], [14.995787456981676, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434, 10.80639452948434, 10.90639452948434, 11.00639452948434, 11.106394529484339, 11.206394529484339, 11.306394529484338, 11.406394529484338, 11.506394529484337, 11.606394529484337, 11.706394529484337, 11.806394529484336, 11.906394529484336, 12.006394529484336, 12.106394529484335, 12.206394529484335, 12.306394529484335, 12.406394529484334, 12.506394529484334, 12.606394529484334, 12.706394529484333, 12.806394529484333, 12.906394529484333, 13.006394529484332, 13.106394529484332, 13.206394529484331, 13.306394529484331, 13.40639452948433, 13.50639452948433, 13.60639452948433, 13.70639452948433, 13.80639452948433, 13.906394529484329, 14.006394529484329, 14.106394529484328, 14.206394529484328, 14.306394529484328, 14.406394529484327, 14.506394529484327, 14.606394529484326, 14.706394529484326, 14.806394529484326, 14.906394529484325, 15.006394529484325, 15.106394529484325, 15.206394529484324, 15.306394529484324, 15.406394529484324, 15.506394529484323, 15.606394529484323, 15.706394529484323], "velocities": null}}, "time": 1740481167.8436306} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19767107924361257, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8436306} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481167.8536305, "x": 4.036580302704266, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.8736305} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24706897488242152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2207709501419795, "gear": 1, "accelerator_pedal_position": 0.24706897488242152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.8736305} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.03658030270426593, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.9136305} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24542178133015952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.22149455201880083, "gear": 1, "accelerator_pedal_position": 0.24542178133015952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.9136305} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.03658030270426593, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.19767107924361257, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.989725707482126, "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": 1740481167.9536304} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.03658030270426593, 0.0], [0.07885985477440659, 0.0], [0.14113940684454723, 0.0], [0.22341895891468794, 0.0], [0.3256985109848286, 0.0], [0.44797806305496923, 0.0], [0.5902576151251098, 0.0], [0.750521051281676, 0.0], [0.8505210512816761, 0.0], [0.9505210512816762, 0.0], [1.0505210512816763, 0.0], [1.1505210512816764, 0.0], [1.2505210512816765, 0.0], [1.3505210512816765, 0.0], [1.4505210512816766, 0.0], [1.5505210512816767, 0.0], [1.6505210512816766, 0.0], [1.7505210512816767, 0.0], [1.8505210512816768, 0.0], [1.9505210512816769, 0.0], [2.050521051281677, 0.0], [2.150521051281677, 0.0], [2.250521051281677, 0.0], [2.350521051281677, 0.0], [2.4505210512816773, 0.0], [2.5505210512816774, 0.0], [2.6505210512816775, 0.0], [2.7505210512816776, 0.0], [2.850521051281678, 0.0], [2.9505210512816777, 0.0], [3.0505210512816783, 0.0], [3.150521051281678, 0.0], [3.2505210512816785, 0.0], [3.350521051281678, 0.0], [3.4505210512816786, 0.0], [3.5505210512816783, 0.0], [3.650521051281679, 0.0], [3.7505210512816785, 0.0], [3.850521051281678, 0.0], [3.9505210512816777, 0.0], [4.050521051281677, 0.0], [4.150521051281677, 0.0], [4.250521051281677, 0.0], [4.350521051281676, 0.0], [4.450521051281676, 0.0], [4.550521051281676, 0.0], [4.650521051281675, 0.0], [4.750521051281675, 0.0], [4.8505210512816745, 0.0], [4.950521051281674, 0.0], [5.050521051281674, 0.0], [5.1505210512816735, 0.0], [5.250521051281673, 0.0], [5.350521051281673, 0.0], [5.450521051281672, 0.0], [5.550521051281672, 0.0], [5.650521051281672, 0.0], [5.750521051281671, 0.0], [5.850521051281671, 0.0], [5.950521051281671, 0.0], [6.05052105128167, 0.0], [6.15052105128167, 0.0], [6.25052105128167, 0.0], [6.350521051281669, 0.0], [6.450521051281669, 0.0], [6.5505210512816685, 0.0], [6.650521051281668, 0.0], [6.750521051281668, 0.0], [6.850521051281667, 0.0], [6.950521051281667, 0.0], [7.050521051281667, 0.0], [7.150521051281666, 0.0], [7.250521051281666, 0.0], [7.350521051281666, 0.0], [7.450521051281665, 0.0], [7.550521051281665, 0.0], [7.6505210512816655, 0.0], [7.750521051281665, 0.0], [7.850521051281665, 0.0], [7.950521051281664, 0.0], [8.050521051281663, 0.0], [8.150521051281663, 0.0], [8.250521051281662, 0.0], [8.350521051281662, 0.0], [8.450521051281662, 0.0], [8.550521051281661, 0.0], [8.650521051281661, 0.0], [8.75052105128166, 0.0], [8.85052105128166, 0.0], [8.95052105128166, 0.0], [9.05052105128166, 0.0], [9.15052105128166, 0.0], [9.250521051281659, 0.0], [9.350521051281659, 0.0], [9.450521051281658, 0.0], [9.550521051281658, 0.0], [9.650521051281657, 0.0], [9.750521051281657, 0.0], [9.850521051281657, 0.0], [9.950521051281656, 0.0], [10.050521051281656, 0.0], [10.150521051281656, 0.0], [10.250521051281655, 0.0], [10.350521051281655, 0.0], [10.450521051281655, 0.0], [10.550521051281654, 0.0], [10.650521051281654, 0.0], [10.750521051281654, 0.0], [10.850521051281653, 0.0], [10.950521051281653, 0.0], [11.050521051281653, 0.0], [11.150521051281652, 0.0], [11.250521051281652, 0.0], [11.350521051281651, 0.0], [11.450521051281651, 0.0], [11.55052105128165, 0.0], [11.65052105128165, 0.0], [11.75052105128165, 0.0], [11.85052105128165, 0.0], [11.95052105128165, 0.0], [12.050521051281649, 0.0], [12.150521051281649, 0.0], [12.250521051281648, 0.0], [12.350521051281648, 0.0], [12.450521051281648, 0.0], [12.550521051281647, 0.0], [12.650521051281647, 0.0], [12.750521051281646, 0.0], [12.850521051281646, 0.0], [12.950521051281646, 0.0], [13.050521051281645, 0.0], [13.150521051281645, 0.0], [13.250521051281645, 0.0], [13.350521051281644, 0.0], [13.450521051281644, 0.0], [13.550521051281644, 0.0], [13.650521051281643, 0.0], [13.750521051281643, 0.0], [13.850521051281643, 0.0], [13.950521051281642, 0.0], [14.050521051281642, 0.0], [14.150521051281642, 0.0], [14.250521051281641, 0.0], [14.35052105128164, 0.0], [14.45052105128164, 0.0], [14.55052105128164, 0.0], [14.65052105128164, 0.0], [14.750520779787202, 0.0], [14.840416569530873, 0.0], [14.910312359274545, 0.0], [14.960208149018218, 0.0], [14.990103938761889, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779, 15.543095213298779], "velocities": null}}, "time": 1740481167.9536304} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23401274097597255, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481167.9536304} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.0736303, "x": 4.085421049444235, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.229591660542647, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.049230537236539695, "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": 1740481168.1636302} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481168.9500866, "x": 15.0, "y": 2.3999999999999924, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.1636302} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.08542104944423468, 0.0], [0.13291321061275274, 0.0], [0.20040537178127082, 0.0], [0.2878975329497889, 0.0], [0.39538969411830704, 0.0], [0.5228818552868251, 0.0], [0.6703740164553431, 0.0], [0.8328302564060938, 0.0], [0.9328302564060938, 0.0], [1.0328302564060938, 0.0], [1.132830256406094, 0.0], [1.232830256406094, 0.0], [1.332830256406094, 0.0], [1.4328302564060942, 0.0], [1.5328302564060943, 0.0], [1.6328302564060944, 0.0], [1.7328302564060944, 0.0], [1.8328302564060945, 0.0], [1.9328302564060946, 0.0], [2.0328302564060947, 0.0], [2.132830256406095, 0.0], [2.232830256406095, 0.0], [2.332830256406095, 0.0], [2.432830256406095, 0.0], [2.532830256406095, 0.0], [2.6328302564060952, 0.0], [2.732830256406095, 0.0], [2.8328302564060954, 0.0], [2.932830256406095, 0.0], [3.0328302564060956, 0.0], [3.1328302564060952, 0.0], [3.232830256406096, 0.0], [3.3328302564060954, 0.0], [3.432830256406096, 0.0], [3.5328302564060956, 0.0], [3.632830256406096, 0.0], [3.732830256406096, 0.0], [3.8328302564060954, 0.0], [3.932830256406095, 0.0], [4.032830256406095, 0.0], [4.132830256406095, 0.0], [4.2328302564060944, 0.0], [4.332830256406094, 0.0], [4.432830256406094, 0.0], [4.532830256406093, 0.0], [4.632830256406093, 0.0], [4.732830256406093, 0.0], [4.832830256406092, 0.0], [4.932830256406092, 0.0], [5.032830256406092, 0.0], [5.132830256406091, 0.0], [5.232830256406091, 0.0], [5.3328302564060905, 0.0], [5.43283025640609, 0.0], [5.53283025640609, 0.0], [5.6328302564060895, 0.0], [5.732830256406089, 0.0], [5.832830256406089, 0.0], [5.932830256406088, 0.0], [6.032830256406088, 0.0], [6.132830256406088, 0.0], [6.232830256406087, 0.0], [6.332830256406087, 0.0], [6.432830256406087, 0.0], [6.532830256406086, 0.0], [6.632830256406086, 0.0], [6.732830256406086, 0.0], [6.832830256406085, 0.0], [6.932830256406085, 0.0], [7.0328302564060845, 0.0], [7.132830256406084, 0.0], [7.232830256406084, 0.0], [7.332830256406083, 0.0], [7.432830256406083, 0.0], [7.532830256406083, 0.0], [7.632830256406082, 0.0], [7.732830256406083, 0.0], [7.8328302564060825, 0.0], [7.932830256406082, 0.0], [8.032830256406083, 0.0], [8.132830256406082, 0.0], [8.232830256406082, 0.0], [8.332830256406082, 0.0], [8.432830256406081, 0.0], [8.532830256406081, 0.0], [8.63283025640608, 0.0], [8.73283025640608, 0.0], [8.83283025640608, 0.0], [8.93283025640608, 0.0], [9.03283025640608, 0.0], [9.132830256406079, 0.0], [9.232830256406078, 0.0], [9.332830256406078, 0.0], [9.432830256406078, 0.0], [9.532830256406077, 0.0], [9.632830256406077, 0.0], [9.732830256406077, 0.0], [9.832830256406076, 0.0], [9.932830256406076, 0.0], [10.032830256406076, 0.0], [10.132830256406075, 0.0], [10.232830256406075, 0.0], [10.332830256406075, 0.0], [10.432830256406074, 0.0], [10.532830256406074, 0.0], [10.632830256406073, 0.0], [10.732830256406073, 0.0], [10.832830256406073, 0.0], [10.932830256406072, 0.0], [11.032830256406072, 0.0], [11.132830256406072, 0.0], [11.232830256406071, 0.0], [11.332830256406071, 0.0], [11.43283025640607, 0.0], [11.53283025640607, 0.0], [11.63283025640607, 0.0], [11.73283025640607, 0.0], [11.83283025640607, 0.0], [11.932830256406069, 0.0], [12.032830256406069, 0.0], [12.132830256406068, 0.0], [12.232830256406068, 0.0], [12.332830256406067, 0.0], [12.432830256406067, 0.0], [12.532830256406067, 0.0], [12.632830256406066, 0.0], [12.732830256406066, 0.0], [12.832830256406066, 0.0], [12.932830256406065, 0.0], [13.032830256406065, 0.0], [13.132830256406065, 0.0], [13.232830256406064, 0.0], [13.332830256406064, 0.0], [13.432830256406064, 0.0], [13.532830256406063, 0.0], [13.632830256406063, 0.0], [13.732830256406062, 0.0], [13.832830256406062, 0.0], [13.932830256406062, 0.0], [14.032830256406061, 0.0], [14.132830256406061, 0.0], [14.23283025640606, 0.0], [14.33283025640606, 0.0], [14.43283025640606, 0.0], [14.53283025640606, 0.0], [14.63283025640606, 0.0], [14.732830256406059, 0.0], [14.825969405029765, 0.0], [14.899403353748554, 0.0], [14.95283730246734, 0.0], [14.98627125118613, 0.0], [14.999705199904918, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779, 15.543095213298779], "velocities": null}}, "time": 1740481168.1636302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26584749887485426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23450263084488646, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.1636302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.1836302, "x": 4.110946456891718, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.1836302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28829036169917055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2364953490607551, "gear": 1, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.1836302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2036302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2432821040609096, "gear": 1, "accelerator_pedal_position": 0.28829036169917055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2036302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2236302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2490110624396571, "gear": 1, "accelerator_pedal_position": 0.2798852046927663, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2236302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2436302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798852046927663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2547337262433775, "gear": 1, "accelerator_pedal_position": 0.2798852046927663, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2436302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2636302} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.11094645689171756, 0.0], [0.1595659856744007, 0.0], [0.22818551445708382, 0.0], [0.316805043239767, 0.0], [0.4254245720224501, 0.0], [0.5540441008051332, 0.0], [0.7026636295878164, 0.0], [0.8654154355199618, 0.0], [0.9654154355199619, 0.0], [1.065415435519962, 0.0], [1.1654154355199622, 0.0], [1.2654154355199623, 0.0], [1.3654154355199624, 0.0], [1.4654154355199625, 0.0], [1.5654154355199625, 0.0], [1.6654154355199626, 0.0], [1.7654154355199623, 0.0], [1.8654154355199624, 0.0], [1.9654154355199625, 0.0], [2.0654154355199625, 0.0], [2.1654154355199626, 0.0], [2.2654154355199627, 0.0], [2.365415435519963, 0.0], [2.465415435519963, 0.0], [2.565415435519963, 0.0], [2.665415435519963, 0.0], [2.765415435519963, 0.0], [2.8654154355199632, 0.0], [2.9654154355199633, 0.0], [3.0654154355199634, 0.0], [3.1654154355199635, 0.0], [3.2654154355199636, 0.0], [3.3654154355199637, 0.0], [3.465415435519964, 0.0], [3.565415435519964, 0.0], [3.665415435519964, 0.0], [3.765415435519964, 0.0], [3.8654154355199637, 0.0], [3.9654154355199633, 0.0], [4.065415435519963, 0.0], [4.165415435519963, 0.0], [4.265415435519962, 0.0], [4.365415435519962, 0.0], [4.465415435519962, 0.0], [4.565415435519961, 0.0], [4.665415435519961, 0.0], [4.7654154355199605, 0.0], [4.86541543551996, 0.0], [4.96541543551996, 0.0], [5.065415435519959, 0.0], [5.165415435519959, 0.0], [5.265415435519959, 0.0], [5.365415435519958, 0.0], [5.465415435519958, 0.0], [5.565415435519958, 0.0], [5.665415435519957, 0.0], [5.765415435519957, 0.0], [5.865415435519957, 0.0], [5.965415435519956, 0.0], [6.065415435519956, 0.0], [6.1654154355199555, 0.0], [6.265415435519955, 0.0], [6.365415435519955, 0.0], [6.4654154355199545, 0.0], [6.565415435519954, 0.0], [6.665415435519954, 0.0], [6.765415435519953, 0.0], [6.865415435519953, 0.0], [6.965415435519953, 0.0], [7.065415435519952, 0.0], [7.165415435519952, 0.0], [7.265415435519952, 0.0], [7.365415435519951, 0.0], [7.465415435519951, 0.0], [7.5654154355199505, 0.0], [7.66541543551995, 0.0], [7.765415435519951, 0.0], [7.86541543551995, 0.0], [7.96541543551995, 0.0], [8.065415435519949, 0.0], [8.16541543551995, 0.0], [8.26541543551995, 0.0], [8.36541543551995, 0.0], [8.46541543551995, 0.0], [8.565415435519949, 0.0], [8.665415435519948, 0.0], [8.765415435519948, 0.0], [8.865415435519948, 0.0], [8.965415435519947, 0.0], [9.065415435519947, 0.0], [9.165415435519947, 0.0], [9.265415435519946, 0.0], [9.365415435519946, 0.0], [9.465415435519946, 0.0], [9.565415435519945, 0.0], [9.665415435519945, 0.0], [9.765415435519945, 0.0], [9.865415435519944, 0.0], [9.965415435519944, 0.0], [10.065415435519943, 0.0], [10.165415435519943, 0.0], [10.265415435519943, 0.0], [10.365415435519942, 0.0], [10.465415435519942, 0.0], [10.565415435519942, 0.0], [10.665415435519941, 0.0], [10.765415435519941, 0.0], [10.86541543551994, 0.0], [10.96541543551994, 0.0], [11.06541543551994, 0.0], [11.16541543551994, 0.0], [11.26541543551994, 0.0], [11.365415435519939, 0.0], [11.465415435519938, 0.0], [11.565415435519938, 0.0], [11.665415435519938, 0.0], [11.765415435519937, 0.0], [11.865415435519937, 0.0], [11.965415435519937, 0.0], [12.065415435519936, 0.0], [12.165415435519936, 0.0], [12.265415435519936, 0.0], [12.365415435519935, 0.0], [12.465415435519935, 0.0], [12.565415435519935, 0.0], [12.665415435519934, 0.0], [12.765415435519934, 0.0], [12.865415435519933, 0.0], [12.965415435519933, 0.0], [13.065415435519933, 0.0], [13.165415435519932, 0.0], [13.265415435519932, 0.0], [13.365415435519932, 0.0], [13.465415435519931, 0.0], [13.565415435519931, 0.0], [13.66541543551993, 0.0], [13.76541543551993, 0.0], [13.86541543551993, 0.0], [13.96541543551993, 0.0], [14.06541543551993, 0.0], [14.165415435519929, 0.0], [14.265415435519929, 0.0], [14.365415435519928, 0.0], [14.465415435519928, 0.0], [14.565415435519927, 0.0], [14.665415435519927, 0.0], [14.765177799867658, 0.0], [14.852094712763671, 0.0], [14.919011625659687, 0.0], [14.965928538555701, 0.0], [14.992845451451716, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779], "velocities": null}}, "time": 1740481168.2636302} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26377969259852846, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2636302} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.11094645689171756, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.2364953490607551, "accelerator_pedal_position": 0.26584749887485426, "brake_pedal_position": 0.0, "acceleration": 0.19916280001352762, "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": 1740481168.2836301} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26377969259852846, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.2836301} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.2936301, "x": 4.138612065219516, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.30363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26472648006610955, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.30363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.32363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2844422754527114, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.32363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.34363} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.1744242, "x": 15.0, "y": 2.50999999999999, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.34363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30413615681640904, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.34363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.36363} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.1386120652195162, 0.0], [0.1917644348906054, 0.0], [0.26491680456169464, 0.0], [0.35806917423278384, 0.0], [0.47122154390387305, 0.0], [0.6043739135749622, 0.0], [0.7575262832460514, 0.0], [0.9208250595996438, 0.0], [1.0208250595996438, 0.0], [1.1208250595996438, 0.0], [1.220825059599644, 0.0], [1.320825059599644, 0.0], [1.4208250595996441, 0.0], [1.5208250595996442, 0.0], [1.6208250595996443, 0.0], [1.7208250595996444, 0.0], [1.8208250595996445, 0.0], [1.9208250595996446, 0.0], [2.0208250595996446, 0.0], [2.1208250595996447, 0.0], [2.220825059599645, 0.0], [2.320825059599645, 0.0], [2.420825059599645, 0.0], [2.520825059599645, 0.0], [2.620825059599645, 0.0], [2.7208250595996453, 0.0], [2.8208250595996454, 0.0], [2.9208250595996454, 0.0], [3.0208250595996455, 0.0], [3.1208250595996456, 0.0], [3.2208250595996457, 0.0], [3.320825059599646, 0.0], [3.420825059599646, 0.0], [3.520825059599646, 0.0], [3.620825059599646, 0.0], [3.720825059599646, 0.0], [3.8208250595996462, 0.0], [3.920825059599646, 0.0], [4.0208250595996455, 0.0], [4.120825059599645, 0.0], [4.220825059599645, 0.0], [4.3208250595996445, 0.0], [4.420825059599644, 0.0], [4.520825059599644, 0.0], [4.620825059599643, 0.0], [4.720825059599643, 0.0], [4.820825059599643, 0.0], [4.920825059599642, 0.0], [5.020825059599642, 0.0], [5.120825059599642, 0.0], [5.220825059599641, 0.0], [5.320825059599641, 0.0], [5.420825059599641, 0.0], [5.52082505959964, 0.0], [5.62082505959964, 0.0], [5.7208250595996395, 0.0], [5.820825059599639, 0.0], [5.920825059599639, 0.0], [6.020825059599638, 0.0], [6.120825059599638, 0.0], [6.220825059599638, 0.0], [6.320825059599637, 0.0], [6.420825059599637, 0.0], [6.520825059599637, 0.0], [6.620825059599636, 0.0], [6.720825059599636, 0.0], [6.820825059599636, 0.0], [6.920825059599635, 0.0], [7.020825059599635, 0.0], [7.1208250595996345, 0.0], [7.220825059599634, 0.0], [7.320825059599634, 0.0], [7.4208250595996335, 0.0], [7.520825059599633, 0.0], [7.620825059599633, 0.0], [7.720825059599632, 0.0], [7.820825059599633, 0.0], [7.920825059599633, 0.0], [8.020825059599632, 0.0], [8.120825059599632, 0.0], [8.22082505959963, 0.0], [8.32082505959963, 0.0], [8.420825059599629, 0.0], [8.520825059599629, 0.0], [8.620825059599628, 0.0], [8.720825059599628, 0.0], [8.820825059599628, 0.0], [8.920825059599627, 0.0], [9.020825059599627, 0.0], [9.120825059599627, 0.0], [9.220825059599626, 0.0], [9.320825059599626, 0.0], [9.420825059599625, 0.0], [9.520825059599625, 0.0], [9.620825059599625, 0.0], [9.720825059599624, 0.0], [9.820825059599624, 0.0], [9.920825059599624, 0.0], [10.020825059599623, 0.0], [10.120825059599623, 0.0], [10.220825059599623, 0.0], [10.320825059599622, 0.0], [10.420825059599622, 0.0], [10.520825059599622, 0.0], [10.620825059599621, 0.0], [10.72082505959962, 0.0], [10.82082505959962, 0.0], [10.92082505959962, 0.0], [11.02082505959962, 0.0], [11.12082505959962, 0.0], [11.220825059599619, 0.0], [11.320825059599619, 0.0], [11.420825059599618, 0.0], [11.520825059599618, 0.0], [11.620825059599618, 0.0], [11.720825059599617, 0.0], [11.820825059599617, 0.0], [11.920825059599617, 0.0], [12.020825059599616, 0.0], [12.120825059599616, 0.0], [12.220825059599616, 0.0], [12.320825059599615, 0.0], [12.420825059599615, 0.0], [12.520825059599614, 0.0], [12.620825059599614, 0.0], [12.720825059599614, 0.0], [12.820825059599613, 0.0], [12.920825059599613, 0.0], [13.020825059599613, 0.0], [13.120825059599612, 0.0], [13.220825059599612, 0.0], [13.320825059599612, 0.0], [13.420825059599611, 0.0], [13.520825059599611, 0.0], [13.62082505959961, 0.0], [13.72082505959961, 0.0], [13.82082505959961, 0.0], [13.92082505959961, 0.0], [14.02082505959961, 0.0], [14.120825059599609, 0.0], [14.220825059599608, 0.0], [14.320825059599608, 0.0], [14.420825059599608, 0.0], [14.520825059599607, 0.0], [14.620825059599607, 0.0], [14.720825059599607, 0.0], [14.815808870532319, 0.0], [14.891643858612397, 0.0], [14.947478846692476, 0.0], [14.983313834772554, 0.0], [14.999148822852634, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796, 10.743095213298796, 10.843095213298795, 10.943095213298795, 11.043095213298795, 11.143095213298794, 11.243095213298794, 11.343095213298794, 11.443095213298793, 11.543095213298793, 11.643095213298793, 11.743095213298792, 11.843095213298792, 11.943095213298792, 12.043095213298791, 12.14309521329879, 12.24309521329879, 12.34309521329879, 12.44309521329879, 12.54309521329879, 12.643095213298789, 12.743095213298789, 12.843095213298788, 12.943095213298788, 13.043095213298788, 13.143095213298787, 13.243095213298787, 13.343095213298787, 13.443095213298786, 13.543095213298786, 13.643095213298785, 13.743095213298785, 13.843095213298785, 13.943095213298784, 14.043095213298784, 14.143095213298784, 14.243095213298783, 14.343095213298783, 14.443095213298783, 14.543095213298782, 14.643095213298782, 14.743095213298782, 14.843095213298781, 14.94309521329878, 15.04309521329878, 15.14309521329878, 15.24309521329878, 15.34309521329878, 15.443095213298779], "velocities": null}}, "time": 1740481168.36363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3336356042600706, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.36363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.1386120652195162, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.26425321721530226, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04732628508072806, "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": 1740481168.38363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3340700276219934, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.38363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.40363, "x": 4.1718763639281535, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.40363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38534764574512076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3349381357925551, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.40363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.42363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3904883719987723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3537438749924682, "gear": 1, "accelerator_pedal_position": 0.38534764574512076, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.42363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.44363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3904883719987723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37317059575740025, "gear": 1, "accelerator_pedal_position": 0.3904883719987723, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.44363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.46363} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.17187636392815353, 0.0], [0.23657153246753906, 0.0], [0.3212667010069246, 0.0], [0.42596186954631016, 0.0], [0.5506570380856957, 0.0], [0.6953522066250812, 0.0], [0.8568007388927036, 0.0], [0.9568007388927037, 0.0], [1.0568007388927039, 0.0], [1.156800738892704, 0.0], [1.256800738892704, 0.0], [1.3568007388927041, 0.0], [1.4568007388927042, 0.0], [1.5568007388927043, 0.0], [1.6568007388927044, 0.0], [1.7568007388927045, 0.0], [1.8568007388927046, 0.0], [1.9568007388927042, 0.0], [2.0568007388927043, 0.0], [2.1568007388927044, 0.0], [2.2568007388927045, 0.0], [2.3568007388927046, 0.0], [2.4568007388927047, 0.0], [2.5568007388927048, 0.0], [2.656800738892705, 0.0], [2.756800738892705, 0.0], [2.856800738892705, 0.0], [2.956800738892705, 0.0], [3.056800738892705, 0.0], [3.1568007388927053, 0.0], [3.2568007388927054, 0.0], [3.3568007388927055, 0.0], [3.4568007388927056, 0.0], [3.5568007388927056, 0.0], [3.6568007388927057, 0.0], [3.756800738892706, 0.0], [3.856800738892706, 0.0], [3.9568007388927056, 0.0], [4.056800738892705, 0.0], [4.156800738892705, 0.0], [4.2568007388927045, 0.0], [4.356800738892704, 0.0], [4.456800738892704, 0.0], [4.556800738892703, 0.0], [4.656800738892703, 0.0], [4.756800738892703, 0.0], [4.856800738892702, 0.0], [4.956800738892702, 0.0], [5.056800738892702, 0.0], [5.156800738892701, 0.0], [5.256800738892701, 0.0], [5.356800738892701, 0.0], [5.4568007388927, 0.0], [5.5568007388927, 0.0], [5.6568007388926995, 0.0], [5.756800738892699, 0.0], [5.856800738892699, 0.0], [5.9568007388926985, 0.0], [6.056800738892698, 0.0], [6.156800738892698, 0.0], [6.256800738892697, 0.0], [6.356800738892697, 0.0], [6.456800738892697, 0.0], [6.556800738892696, 0.0], [6.656800738892696, 0.0], [6.756800738892696, 0.0], [6.856800738892695, 0.0], [6.956800738892695, 0.0], [7.0568007388926945, 0.0], [7.156800738892694, 0.0], [7.256800738892694, 0.0], [7.3568007388926935, 0.0], [7.456800738892693, 0.0], [7.556800738892693, 0.0], [7.656800738892692, 0.0], [7.756800738892692, 0.0], [7.856800738892692, 0.0], [7.956800738892691, 0.0], [8.05680073889269, 0.0], [8.15680073889269, 0.0], [8.25680073889269, 0.0], [8.356800738892689, 0.0], [8.456800738892689, 0.0], [8.556800738892688, 0.0], [8.656800738892688, 0.0], [8.756800738892688, 0.0], [8.856800738892687, 0.0], [8.956800738892687, 0.0], [9.056800738892687, 0.0], [9.156800738892686, 0.0], [9.256800738892686, 0.0], [9.356800738892685, 0.0], [9.456800738892685, 0.0], [9.556800738892685, 0.0], [9.656800738892684, 0.0], [9.756800738892684, 0.0], [9.856800738892684, 0.0], [9.956800738892683, 0.0], [10.056800738892683, 0.0], [10.156800738892683, 0.0], [10.256800738892682, 0.0], [10.356800738892682, 0.0], [10.456800738892682, 0.0], [10.556800738892681, 0.0], [10.65680073889268, 0.0], [10.75680073889268, 0.0], [10.85680073889268, 0.0], [10.95680073889268, 0.0], [11.05680073889268, 0.0], [11.156800738892679, 0.0], [11.256800738892679, 0.0], [11.356800738892678, 0.0], [11.456800738892678, 0.0], [11.556800738892678, 0.0], [11.656800738892677, 0.0], [11.756800738892677, 0.0], [11.856800738892677, 0.0], [11.956800738892676, 0.0], [12.056800738892676, 0.0], [12.156800738892676, 0.0], [12.256800738892675, 0.0], [12.356800738892675, 0.0], [12.456800738892674, 0.0], [12.556800738892674, 0.0], [12.656800738892674, 0.0], [12.756800738892673, 0.0], [12.856800738892673, 0.0], [12.956800738892673, 0.0], [13.056800738892672, 0.0], [13.156800738892672, 0.0], [13.256800738892672, 0.0], [13.356800738892671, 0.0], [13.456800738892671, 0.0], [13.55680073889267, 0.0], [13.65680073889267, 0.0], [13.75680073889267, 0.0], [13.85680073889267, 0.0], [13.95680073889267, 0.0], [14.056800738892669, 0.0], [14.156800738892668, 0.0], [14.256800738892668, 0.0], [14.356800738892668, 0.0], [14.456800738892667, 0.0], [14.556800738892667, 0.0], [14.656800738892667, 0.0], [14.75675448884318, 0.0], [14.845394341064647, 0.0], [14.914034193286113, 0.0], [14.96267404550758, 0.0], [14.991313897729047, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251, 10.47979589711325, 10.57979589711325, 10.67979589711325, 10.77979589711325, 10.87979589711325, 10.979795897113249, 11.079795897113248, 11.179795897113248, 11.279795897113248, 11.379795897113247, 11.479795897113247, 11.579795897113247, 11.679795897113246, 11.779795897113246, 11.879795897113246, 11.979795897113245, 12.079795897113245, 12.179795897113245, 12.279795897113244, 12.379795897113244, 12.479795897113243, 12.579795897113243, 12.679795897113243, 12.779795897113242, 12.879795897113242, 12.979795897113242, 13.079795897113241, 13.179795897113241, 13.27979589711324, 13.37979589711324, 13.47979589711324, 13.57979589711324, 13.67979589711324, 13.779795897113239, 13.879795897113238, 13.979795897113238, 14.079795897113238, 14.179795897113237, 14.279795897113237, 14.379795897113237, 14.479795897113236, 14.579795897113236, 14.679795897113236, 14.779795897113235, 14.879795897113235, 14.979795897113235, 15.079795897113234, 15.179795897113234, 15.279795897113233], "velocities": null}}, "time": 1740481168.46363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40226885836995085, "gear": 1, "accelerator_pedal_position": 0.3904883719987723, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.46363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.48363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40266391435302024, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.48363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.17187636392815353, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.3349381357925551, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.04336850123186986, "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": 1740481168.50363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4034533384390684, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.50363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.51363, "x": 4.213441881828219, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.52363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38576081767890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41363343506612116, "gear": 1, "accelerator_pedal_position": 0.38576081767890713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.52363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.54363} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3907724276185952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4230195601916593, "gear": 1, "accelerator_pedal_position": 0.38576081767890713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.54363} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.5636299} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.21344188182821888, 0.0], [0.2893899361829274, 0.0], [0.38533799053763584, 0.0], [0.5012860448923444, 0.0], [0.6372340992470529, 0.0], [0.7930067582545417, 0.0], [0.8930067582545417, 0.0], [0.9930067582545417, 0.0], [1.0930067582545417, 0.0], [1.1930067582545418, 0.0], [1.293006758254542, 0.0], [1.393006758254542, 0.0], [1.493006758254542, 0.0], [1.5930067582545422, 0.0], [1.6930067582545423, 0.0], [1.7930067582545424, 0.0], [1.8930067582545425, 0.0], [1.9930067582545425, 0.0], [2.0930067582545426, 0.0], [2.1930067582545427, 0.0], [2.293006758254543, 0.0], [2.393006758254543, 0.0], [2.493006758254543, 0.0], [2.593006758254543, 0.0], [2.693006758254543, 0.0], [2.7930067582545433, 0.0], [2.8930067582545433, 0.0], [2.9930067582545434, 0.0], [3.0930067582545435, 0.0], [3.1930067582545436, 0.0], [3.2930067582545437, 0.0], [3.393006758254544, 0.0], [3.493006758254544, 0.0], [3.593006758254544, 0.0], [3.693006758254544, 0.0], [3.793006758254544, 0.0], [3.8930067582545442, 0.0], [3.993006758254544, 0.0], [4.0930067582545435, 0.0], [4.193006758254543, 0.0], [4.293006758254543, 0.0], [4.3930067582545425, 0.0], [4.493006758254542, 0.0], [4.593006758254542, 0.0], [4.693006758254541, 0.0], [4.793006758254541, 0.0], [4.893006758254541, 0.0], [4.99300675825454, 0.0], [5.09300675825454, 0.0], [5.19300675825454, 0.0], [5.293006758254539, 0.0], [5.393006758254539, 0.0], [5.4930067582545385, 0.0], [5.593006758254538, 0.0], [5.693006758254538, 0.0], [5.7930067582545375, 0.0], [5.893006758254537, 0.0], [5.993006758254537, 0.0], [6.093006758254536, 0.0], [6.193006758254536, 0.0], [6.293006758254536, 0.0], [6.393006758254535, 0.0], [6.493006758254535, 0.0], [6.593006758254535, 0.0], [6.693006758254534, 0.0], [6.793006758254534, 0.0], [6.893006758254534, 0.0], [6.993006758254533, 0.0], [7.093006758254533, 0.0], [7.1930067582545325, 0.0], [7.293006758254532, 0.0], [7.393006758254532, 0.0], [7.493006758254531, 0.0], [7.593006758254531, 0.0], [7.693006758254531, 0.0], [7.79300675825453, 0.0], [7.89300675825453, 0.0], [7.9930067582545306, 0.0], [8.09300675825453, 0.0], [8.19300675825453, 0.0], [8.29300675825453, 0.0], [8.39300675825453, 0.0], [8.493006758254529, 0.0], [8.593006758254528, 0.0], [8.693006758254528, 0.0], [8.793006758254528, 0.0], [8.893006758254527, 0.0], [8.993006758254527, 0.0], [9.093006758254527, 0.0], [9.193006758254526, 0.0], [9.293006758254526, 0.0], [9.393006758254526, 0.0], [9.493006758254525, 0.0], [9.593006758254525, 0.0], [9.693006758254525, 0.0], [9.793006758254524, 0.0], [9.893006758254524, 0.0], [9.993006758254523, 0.0], [10.093006758254523, 0.0], [10.193006758254523, 0.0], [10.293006758254522, 0.0], [10.393006758254522, 0.0], [10.493006758254522, 0.0], [10.593006758254521, 0.0], [10.693006758254521, 0.0], [10.79300675825452, 0.0], [10.89300675825452, 0.0], [10.99300675825452, 0.0], [11.09300675825452, 0.0], [11.19300675825452, 0.0], [11.293006758254519, 0.0], [11.393006758254518, 0.0], [11.493006758254518, 0.0], [11.593006758254518, 0.0], [11.693006758254517, 0.0], [11.793006758254517, 0.0], [11.893006758254517, 0.0], [11.993006758254516, 0.0], [12.093006758254516, 0.0], [12.193006758254516, 0.0], [12.293006758254515, 0.0], [12.393006758254515, 0.0], [12.493006758254515, 0.0], [12.593006758254514, 0.0], [12.693006758254514, 0.0], [12.793006758254513, 0.0], [12.893006758254513, 0.0], [12.993006758254513, 0.0], [13.093006758254512, 0.0], [13.193006758254512, 0.0], [13.293006758254512, 0.0], [13.393006758254511, 0.0], [13.493006758254511, 0.0], [13.59300675825451, 0.0], [13.69300675825451, 0.0], [13.79300675825451, 0.0], [13.89300675825451, 0.0], [13.99300675825451, 0.0], [14.093006758254509, 0.0], [14.193006758254509, 0.0], [14.293006758254508, 0.0], [14.393006758254508, 0.0], [14.493006758254507, 0.0], [14.593006758254507, 0.0], [14.693006758254507, 0.0], [14.791157176998945, 0.0], [14.872555825348043, 0.0], [14.933954473697142, 0.0], [14.97535312204624, 0.0], [14.99675177039534, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769, 15.11649658092769, 15.21649658092769], "velocities": null}}, "time": 1740481168.5636299} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45245002485627767, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.5636299} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.5836298} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.3927798, "x": 15.0, "y": 2.6199999999999877, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.5836298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45245002485627767, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.5836298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.21344188182821888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.40384770674591486, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03941392852984424, "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": 1740481168.6036298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45318116155623006, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6036298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.6236298, "x": 4.26128123218118, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6236298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39014676058456527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45391143489302915, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6236298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6436298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47317895898620943, "gear": 1, "accelerator_pedal_position": 0.39014676058456527, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6436298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6636298} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.2612812321811804, 0.0], [0.34540465910801166, 0.0], [0.44952808603484296, 0.0], [0.5736515129616743, 0.0], [0.7177749398885056, 0.0], [0.878969332481846, 0.0], [0.978969332481846, 0.0], [1.078969332481846, 0.0], [1.178969332481846, 0.0], [1.278969332481846, 0.0], [1.3789693324818462, 0.0], [1.4789693324818463, 0.0], [1.5789693324818463, 0.0], [1.6789693324818464, 0.0], [1.7789693324818465, 0.0], [1.8789693324818466, 0.0], [1.9789693324818467, 0.0], [2.078969332481847, 0.0], [2.178969332481847, 0.0], [2.278969332481847, 0.0], [2.378969332481847, 0.0], [2.478969332481847, 0.0], [2.5789693324818472, 0.0], [2.6789693324818473, 0.0], [2.7789693324818474, 0.0], [2.8789693324818475, 0.0], [2.9789693324818476, 0.0], [3.0789693324818477, 0.0], [3.1789693324818478, 0.0], [3.278969332481848, 0.0], [3.378969332481848, 0.0], [3.478969332481848, 0.0], [3.578969332481848, 0.0], [3.678969332481848, 0.0], [3.7789693324818483, 0.0], [3.8789693324818484, 0.0], [3.9789693324818485, 0.0], [4.078969332481848, 0.0], [4.178969332481848, 0.0], [4.278969332481847, 0.0], [4.378969332481847, 0.0], [4.478969332481847, 0.0], [4.578969332481846, 0.0], [4.678969332481846, 0.0], [4.778969332481846, 0.0], [4.878969332481845, 0.0], [4.978969332481845, 0.0], [5.078969332481845, 0.0], [5.178969332481844, 0.0], [5.278969332481844, 0.0], [5.3789693324818435, 0.0], [5.478969332481843, 0.0], [5.578969332481843, 0.0], [5.678969332481842, 0.0], [5.778969332481842, 0.0], [5.878969332481842, 0.0], [5.978969332481841, 0.0], [6.078969332481841, 0.0], [6.178969332481841, 0.0], [6.27896933248184, 0.0], [6.37896933248184, 0.0], [6.47896933248184, 0.0], [6.578969332481839, 0.0], [6.678969332481839, 0.0], [6.7789693324818385, 0.0], [6.878969332481838, 0.0], [6.978969332481838, 0.0], [7.0789693324818375, 0.0], [7.178969332481837, 0.0], [7.278969332481837, 0.0], [7.378969332481836, 0.0], [7.478969332481836, 0.0], [7.578969332481836, 0.0], [7.678969332481835, 0.0], [7.778969332481835, 0.0], [7.878969332481835, 0.0], [7.978969332481834, 0.0], [8.078969332481835, 0.0], [8.178969332481834, 0.0], [8.278969332481834, 0.0], [8.378969332481834, 0.0], [8.478969332481833, 0.0], [8.578969332481833, 0.0], [8.678969332481833, 0.0], [8.778969332481832, 0.0], [8.878969332481832, 0.0], [8.978969332481832, 0.0], [9.078969332481831, 0.0], [9.178969332481831, 0.0], [9.27896933248183, 0.0], [9.37896933248183, 0.0], [9.47896933248183, 0.0], [9.57896933248183, 0.0], [9.67896933248183, 0.0], [9.778969332481829, 0.0], [9.878969332481828, 0.0], [9.978969332481828, 0.0], [10.078969332481828, 0.0], [10.178969332481827, 0.0], [10.278969332481827, 0.0], [10.378969332481827, 0.0], [10.478969332481826, 0.0], [10.578969332481826, 0.0], [10.678969332481826, 0.0], [10.778969332481825, 0.0], [10.878969332481825, 0.0], [10.978969332481824, 0.0], [11.078969332481824, 0.0], [11.178969332481824, 0.0], [11.278969332481823, 0.0], [11.378969332481823, 0.0], [11.478969332481823, 0.0], [11.578969332481822, 0.0], [11.678969332481822, 0.0], [11.778969332481822, 0.0], [11.878969332481821, 0.0], [11.978969332481821, 0.0], [12.07896933248182, 0.0], [12.17896933248182, 0.0], [12.27896933248182, 0.0], [12.37896933248182, 0.0], [12.47896933248182, 0.0], [12.578969332481819, 0.0], [12.678969332481818, 0.0], [12.778969332481818, 0.0], [12.878969332481818, 0.0], [12.978969332481817, 0.0], [13.078969332481817, 0.0], [13.178969332481817, 0.0], [13.278969332481816, 0.0], [13.378969332481816, 0.0], [13.478969332481816, 0.0], [13.578969332481815, 0.0], [13.678969332481815, 0.0], [13.778969332481815, 0.0], [13.878969332481814, 0.0], [13.978969332481814, 0.0], [14.078969332481813, 0.0], [14.178969332481813, 0.0], [14.278969332481813, 0.0], [14.378969332481812, 0.0], [14.478969332481812, 0.0], [14.578969332481812, 0.0], [14.678969332481811, 0.0], [14.778130110257369, 0.0], [14.862336243761007, 0.0], [14.926542377264644, 0.0], [14.970748510768283, 0.0], [14.994954644271921, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769, 15.11649658092769], "velocities": null}}, "time": 1740481168.6636298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5027205411068251, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6636298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.6836298} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5027205411068251, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.6836298} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.7036297} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5033918182110465, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7036297} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.2612812321811804, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45391143489302915, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.036481315917661766, "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": 1740481168.7236297} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5043972225712381, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7236297} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.7336297, "x": 4.315136795216979, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7436297} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39004853579169174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5047319547398345, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7436297} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7636297} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.31513679521697924, 0.0], [0.4075045167487507, 0.0], [0.5198722382805221, 0.0], [0.6522399598122935, 0.0], [0.804607681344065, 0.0], [0.9678853008146366, 0.0], [1.0678853008146367, 0.0], [1.1678853008146366, 0.0], [1.2678853008146367, 0.0], [1.3678853008146368, 0.0], [1.4678853008146369, 0.0], [1.567885300814637, 0.0], [1.667885300814637, 0.0], [1.7678853008146371, 0.0], [1.8678853008146372, 0.0], [1.9678853008146373, 0.0], [2.0678853008146376, 0.0], [2.1678853008146373, 0.0], [2.267885300814638, 0.0], [2.3678853008146374, 0.0], [2.4678853008146375, 0.0], [2.5678853008146376, 0.0], [2.6678853008146377, 0.0], [2.767885300814638, 0.0], [2.867885300814638, 0.0], [2.967885300814638, 0.0], [3.067885300814638, 0.0], [3.167885300814638, 0.0], [3.2678853008146382, 0.0], [3.3678853008146383, 0.0], [3.4678853008146384, 0.0], [3.5678853008146385, 0.0], [3.6678853008146386, 0.0], [3.7678853008146387, 0.0], [3.8678853008146388, 0.0], [3.967885300814639, 0.0], [4.067885300814639, 0.0], [4.167885300814639, 0.0], [4.267885300814639, 0.0], [4.367885300814638, 0.0], [4.467885300814638, 0.0], [4.567885300814638, 0.0], [4.667885300814637, 0.0], [4.767885300814637, 0.0], [4.8678853008146366, 0.0], [4.967885300814636, 0.0], [5.067885300814636, 0.0], [5.1678853008146355, 0.0], [5.267885300814635, 0.0], [5.367885300814635, 0.0], [5.467885300814634, 0.0], [5.567885300814634, 0.0], [5.667885300814634, 0.0], [5.767885300814633, 0.0], [5.867885300814633, 0.0], [5.967885300814633, 0.0], [6.067885300814632, 0.0], [6.167885300814632, 0.0], [6.267885300814632, 0.0], [6.367885300814631, 0.0], [6.467885300814631, 0.0], [6.5678853008146305, 0.0], [6.66788530081463, 0.0], [6.76788530081463, 0.0], [6.8678853008146294, 0.0], [6.967885300814629, 0.0], [7.067885300814629, 0.0], [7.167885300814628, 0.0], [7.267885300814628, 0.0], [7.367885300814628, 0.0], [7.467885300814627, 0.0], [7.567885300814627, 0.0], [7.667885300814627, 0.0], [7.767885300814626, 0.0], [7.867885300814626, 0.0], [7.9678853008146255, 0.0], [8.067885300814625, 0.0], [8.167885300814625, 0.0], [8.267885300814626, 0.0], [8.367885300814626, 0.0], [8.467885300814626, 0.0], [8.567885300814625, 0.0], [8.667885300814625, 0.0], [8.767885300814624, 0.0], [8.867885300814624, 0.0], [8.967885300814624, 0.0], [9.067885300814623, 0.0], [9.167885300814623, 0.0], [9.267885300814623, 0.0], [9.367885300814622, 0.0], [9.467885300814622, 0.0], [9.567885300814622, 0.0], [9.667885300814621, 0.0], [9.767885300814621, 0.0], [9.86788530081462, 0.0], [9.96788530081462, 0.0], [10.06788530081462, 0.0], [10.16788530081462, 0.0], [10.26788530081462, 0.0], [10.367885300814619, 0.0], [10.467885300814618, 0.0], [10.567885300814618, 0.0], [10.667885300814618, 0.0], [10.767885300814617, 0.0], [10.867885300814617, 0.0], [10.967885300814617, 0.0], [11.067885300814616, 0.0], [11.167885300814616, 0.0], [11.267885300814616, 0.0], [11.367885300814615, 0.0], [11.467885300814615, 0.0], [11.567885300814615, 0.0], [11.667885300814614, 0.0], [11.767885300814614, 0.0], [11.867885300814613, 0.0], [11.967885300814613, 0.0], [12.067885300814613, 0.0], [12.167885300814612, 0.0], [12.267885300814612, 0.0], [12.367885300814612, 0.0], [12.467885300814611, 0.0], [12.567885300814611, 0.0], [12.66788530081461, 0.0], [12.76788530081461, 0.0], [12.86788530081461, 0.0], [12.96788530081461, 0.0], [13.06788530081461, 0.0], [13.167885300814609, 0.0], [13.267885300814608, 0.0], [13.367885300814608, 0.0], [13.467885300814608, 0.0], [13.567885300814607, 0.0], [13.667885300814607, 0.0], [13.767885300814607, 0.0], [13.867885300814606, 0.0], [13.967885300814606, 0.0], [14.067885300814606, 0.0], [14.167885300814605, 0.0], [14.267885300814605, 0.0], [14.367885300814605, 0.0], [14.467885300814604, 0.0], [14.567885300814604, 0.0], [14.667885300814604, 0.0], [14.767565416829374, 0.0], [14.853988356666454, 0.0], [14.920411296503532, 0.0], [14.966834236340611, 0.0], [14.993257176177691, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707, 10.216496580927707, 10.316496580927707, 10.416496580927706, 10.516496580927706, 10.616496580927706, 10.716496580927705, 10.816496580927705, 10.916496580927705, 11.016496580927704, 11.116496580927704, 11.216496580927704, 11.316496580927703, 11.416496580927703, 11.516496580927702, 11.616496580927702, 11.716496580927702, 11.816496580927701, 11.916496580927701, 12.0164965809277, 12.1164965809277, 12.2164965809277, 12.3164965809277, 12.4164965809277, 12.516496580927699, 12.616496580927699, 12.716496580927698, 12.816496580927698, 12.916496580927697, 13.016496580927697, 13.116496580927697, 13.216496580927696, 13.316496580927696, 13.416496580927696, 13.516496580927695, 13.616496580927695, 13.716496580927695, 13.816496580927694, 13.916496580927694, 14.016496580927694, 14.116496580927693, 14.216496580927693, 14.316496580927693, 14.416496580927692, 14.516496580927692, 14.616496580927691, 14.716496580927691, 14.81649658092769, 14.91649658092769, 15.01649658092769], "velocities": null}}, "time": 1740481168.7636297} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5430979928271291, "gear": 1, "accelerator_pedal_position": 0.39004853579169174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7636297} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.7836297} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5430979928271291, "gear": 1, "accelerator_pedal_position": 0.39004853579169174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.7836297} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.8036296} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5437204591297793, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8036296} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.31513679521697924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5043972225712381, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.03347321685964161, "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": 1740481168.8236296} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5443421678564628, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8236296} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.8436296, "x": 4.373578366741195, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8436296} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.6127732, "x": 15.0, "y": 2.7299999999999853, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481168.8436296} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5449631197746299, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8436296} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8636296} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.37357836674119493, 0.0], [0.4725704715467334, 0.0], [0.5915625763522718, 0.0], [0.7305546811578103, 0.0], [0.8887365899065505, 0.0], [0.9887365899065506, 0.0], [1.0887365899065504, 0.0], [1.1887365899065505, 0.0], [1.2887365899065504, 0.0], [1.3887365899065505, 0.0], [1.4887365899065506, 0.0], [1.5887365899065506, 0.0], [1.6887365899065507, 0.0], [1.7887365899065508, 0.0], [1.888736589906551, 0.0], [1.988736589906551, 0.0], [2.088736589906551, 0.0], [2.188736589906551, 0.0], [2.2887365899065513, 0.0], [2.3887365899065514, 0.0], [2.4887365899065514, 0.0], [2.5887365899065515, 0.0], [2.6887365899065516, 0.0], [2.7887365899065517, 0.0], [2.888736589906552, 0.0], [2.988736589906552, 0.0], [3.088736589906552, 0.0], [3.188736589906552, 0.0], [3.288736589906552, 0.0], [3.3887365899065522, 0.0], [3.4887365899065523, 0.0], [3.5887365899065524, 0.0], [3.6887365899065525, 0.0], [3.7887365899065526, 0.0], [3.8887365899065527, 0.0], [3.9887365899065528, 0.0], [4.088736589906553, 0.0], [4.1887365899065525, 0.0], [4.288736589906552, 0.0], [4.388736589906552, 0.0], [4.488736589906551, 0.0], [4.588736589906551, 0.0], [4.688736589906551, 0.0], [4.78873658990655, 0.0], [4.88873658990655, 0.0], [4.98873658990655, 0.0], [5.088736589906549, 0.0], [5.188736589906549, 0.0], [5.288736589906549, 0.0], [5.388736589906548, 0.0], [5.488736589906548, 0.0], [5.5887365899065475, 0.0], [5.688736589906547, 0.0], [5.788736589906547, 0.0], [5.8887365899065465, 0.0], [5.988736589906546, 0.0], [6.088736589906546, 0.0], [6.188736589906545, 0.0], [6.288736589906545, 0.0], [6.388736589906545, 0.0], [6.488736589906544, 0.0], [6.588736589906544, 0.0], [6.688736589906544, 0.0], [6.788736589906543, 0.0], [6.888736589906543, 0.0], [6.988736589906543, 0.0], [7.088736589906542, 0.0], [7.188736589906542, 0.0], [7.2887365899065415, 0.0], [7.388736589906541, 0.0], [7.488736589906541, 0.0], [7.58873658990654, 0.0], [7.68873658990654, 0.0], [7.78873658990654, 0.0], [7.888736589906539, 0.0], [7.988736589906539, 0.0], [8.088736589906539, 0.0], [8.188736589906538, 0.0], [8.288736589906538, 0.0], [8.38873658990654, 0.0], [8.488736589906539, 0.0], [8.588736589906539, 0.0], [8.688736589906538, 0.0], [8.788736589906538, 0.0], [8.888736589906538, 0.0], [8.988736589906537, 0.0], [9.088736589906537, 0.0], [9.188736589906537, 0.0], [9.288736589906536, 0.0], [9.388736589906536, 0.0], [9.488736589906535, 0.0], [9.588736589906535, 0.0], [9.688736589906535, 0.0], [9.788736589906534, 0.0], [9.888736589906534, 0.0], [9.988736589906534, 0.0], [10.088736589906533, 0.0], [10.188736589906533, 0.0], [10.288736589906533, 0.0], [10.388736589906532, 0.0], [10.488736589906532, 0.0], [10.588736589906532, 0.0], [10.688736589906531, 0.0], [10.78873658990653, 0.0], [10.88873658990653, 0.0], [10.98873658990653, 0.0], [11.08873658990653, 0.0], [11.18873658990653, 0.0], [11.288736589906529, 0.0], [11.388736589906529, 0.0], [11.488736589906528, 0.0], [11.588736589906528, 0.0], [11.688736589906528, 0.0], [11.788736589906527, 0.0], [11.888736589906527, 0.0], [11.988736589906527, 0.0], [12.088736589906526, 0.0], [12.188736589906526, 0.0], [12.288736589906526, 0.0], [12.388736589906525, 0.0], [12.488736589906525, 0.0], [12.588736589906524, 0.0], [12.688736589906524, 0.0], [12.788736589906524, 0.0], [12.888736589906523, 0.0], [12.988736589906523, 0.0], [13.088736589906523, 0.0], [13.188736589906522, 0.0], [13.288736589906522, 0.0], [13.388736589906522, 0.0], [13.488736589906521, 0.0], [13.588736589906521, 0.0], [13.68873658990652, 0.0], [13.78873658990652, 0.0], [13.88873658990652, 0.0], [13.98873658990652, 0.0], [14.08873658990652, 0.0], [14.188736589906519, 0.0], [14.288736589906518, 0.0], [14.388736589906518, 0.0], [14.488736589906518, 0.0], [14.588736589906517, 0.0], [14.688736589906517, 0.0], [14.787236066508932, 0.0], [14.869488748527628, 0.0], [14.931741430546325, 0.0], [14.97399411256502, 0.0], [14.996246794583717, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161, 10.153197264742161, 10.25319726474216, 10.35319726474216, 10.45319726474216, 10.55319726474216, 10.65319726474216, 10.753197264742159, 10.853197264742159, 10.953197264742158, 11.053197264742158, 11.153197264742158, 11.253197264742157, 11.353197264742157, 11.453197264742156, 11.553197264742156, 11.653197264742156, 11.753197264742155, 11.853197264742155, 11.953197264742155, 12.053197264742154, 12.153197264742154, 12.253197264742154, 12.353197264742153, 12.453197264742153, 12.553197264742153, 12.653197264742152, 12.753197264742152, 12.853197264742152, 12.953197264742151, 13.05319726474215, 13.15319726474215, 13.25319726474215, 13.35319726474215, 13.45319726474215, 13.553197264742149, 13.653197264742149, 13.753197264742148, 13.853197264742148, 13.953197264742148, 14.053197264742147, 14.153197264742147, 14.253197264742147, 14.353197264742146, 14.453197264742146, 14.553197264742145, 14.653197264742145, 14.753197264742145, 14.853197264742144, 14.953197264742144], "velocities": null}}, "time": 1740481168.8636296} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5740388185533857, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8636296} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.8836296} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5743312195232841, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.8836296} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9036295} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5749154822197232, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9036295} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9236295} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5754990265478943, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9236295} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 0.37357836674119493, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5449631197746299, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.031019239561703216, "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": 1740481168.9436295} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5760818532548847, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9436295} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481168.9536295, "x": 4.436223012925216, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481168.9636295} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.4362230129252156, 0.0], [0.540344329322956, 0.0], [0.6644656457206964, 0.0], [0.8085869621184367, 0.0], [0.9697803863013584, 0.0], [1.0697803863013584, 0.0], [1.1697803863013583, 0.0], [1.2697803863013584, 0.0], [1.3697803863013585, 0.0], [1.4697803863013585, 0.0], [1.5697803863013586, 0.0], [1.6697803863013587, 0.0], [1.7697803863013588, 0.0], [1.869780386301359, 0.0], [1.969780386301359, 0.0], [2.069780386301359, 0.0], [2.169780386301359, 0.0], [2.2697803863013593, 0.0], [2.369780386301359, 0.0], [2.469780386301359, 0.0], [2.569780386301359, 0.0], [2.669780386301359, 0.0], [2.7697803863013593, 0.0], [2.8697803863013593, 0.0], [2.9697803863013594, 0.0], [3.0697803863013595, 0.0], [3.1697803863013596, 0.0], [3.2697803863013597, 0.0], [3.36978038630136, 0.0], [3.46978038630136, 0.0], [3.56978038630136, 0.0], [3.66978038630136, 0.0], [3.76978038630136, 0.0], [3.8697803863013602, 0.0], [3.9697803863013603, 0.0], [4.06978038630136, 0.0], [4.16978038630136, 0.0], [4.269780386301361, 0.0], [4.36978038630136, 0.0], [4.46978038630136, 0.0], [4.5697803863013595, 0.0], [4.669780386301359, 0.0], [4.769780386301359, 0.0], [4.8697803863013585, 0.0], [4.969780386301358, 0.0], [5.069780386301358, 0.0], [5.169780386301357, 0.0], [5.269780386301357, 0.0], [5.369780386301357, 0.0], [5.469780386301356, 0.0], [5.569780386301356, 0.0], [5.669780386301356, 0.0], [5.769780386301355, 0.0], [5.869780386301355, 0.0], [5.9697803863013545, 0.0], [6.069780386301354, 0.0], [6.169780386301354, 0.0], [6.2697803863013535, 0.0], [6.369780386301353, 0.0], [6.469780386301353, 0.0], [6.569780386301352, 0.0], [6.669780386301352, 0.0], [6.769780386301352, 0.0], [6.869780386301351, 0.0], [6.969780386301351, 0.0], [7.069780386301351, 0.0], [7.16978038630135, 0.0], [7.26978038630135, 0.0], [7.36978038630135, 0.0], [7.469780386301349, 0.0], [7.569780386301349, 0.0], [7.6697803863013485, 0.0], [7.769780386301348, 0.0], [7.869780386301348, 0.0], [7.969780386301347, 0.0], [8.069780386301346, 0.0], [8.169780386301346, 0.0], [8.269780386301345, 0.0], [8.369780386301345, 0.0], [8.469780386301345, 0.0], [8.569780386301344, 0.0], [8.669780386301344, 0.0], [8.769780386301344, 0.0], [8.869780386301343, 0.0], [8.969780386301343, 0.0], [9.069780386301343, 0.0], [9.169780386301342, 0.0], [9.269780386301342, 0.0], [9.369780386301342, 0.0], [9.469780386301341, 0.0], [9.56978038630134, 0.0], [9.66978038630134, 0.0], [9.76978038630134, 0.0], [9.86978038630134, 0.0], [9.96978038630134, 0.0], [10.069780386301339, 0.0], [10.169780386301339, 0.0], [10.269780386301338, 0.0], [10.369780386301338, 0.0], [10.469780386301338, 0.0], [10.569780386301337, 0.0], [10.669780386301337, 0.0], [10.769780386301337, 0.0], [10.869780386301336, 0.0], [10.969780386301336, 0.0], [11.069780386301336, 0.0], [11.169780386301335, 0.0], [11.269780386301335, 0.0], [11.369780386301334, 0.0], [11.469780386301334, 0.0], [11.569780386301334, 0.0], [11.669780386301333, 0.0], [11.769780386301333, 0.0], [11.869780386301333, 0.0], [11.969780386301332, 0.0], [12.069780386301332, 0.0], [12.169780386301332, 0.0], [12.269780386301331, 0.0], [12.369780386301331, 0.0], [12.46978038630133, 0.0], [12.56978038630133, 0.0], [12.66978038630133, 0.0], [12.76978038630133, 0.0], [12.86978038630133, 0.0], [12.969780386301329, 0.0], [13.069780386301328, 0.0], [13.169780386301328, 0.0], [13.269780386301328, 0.0], [13.369780386301327, 0.0], [13.469780386301327, 0.0], [13.569780386301327, 0.0], [13.669780386301326, 0.0], [13.769780386301326, 0.0], [13.869780386301326, 0.0], [13.969780386301325, 0.0], [14.069780386301325, 0.0], [14.169780386301325, 0.0], [14.269780386301324, 0.0], [14.369780386301324, 0.0], [14.469780386301323, 0.0], [14.569780386301323, 0.0], [14.669780386301323, 0.0], [14.769389122619092, 0.0], [14.855433045358827, 0.0], [14.921476968098563, 0.0], [14.9675208908383, 0.0], [14.993564813578034, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161, 10.153197264742161, 10.25319726474216, 10.35319726474216, 10.45319726474216, 10.55319726474216, 10.65319726474216, 10.753197264742159, 10.853197264742159, 10.953197264742158, 11.053197264742158, 11.153197264742158, 11.253197264742157, 11.353197264742157, 11.453197264742156, 11.553197264742156, 11.653197264742156, 11.753197264742155, 11.853197264742155, 11.953197264742155, 12.053197264742154, 12.153197264742154, 12.253197264742154, 12.353197264742153, 12.453197264742153, 12.553197264742153, 12.653197264742152, 12.753197264742152, 12.853197264742152, 12.953197264742151, 13.05319726474215, 13.15319726474215, 13.25319726474215, 13.35319726474215, 13.45319726474215, 13.553197264742149, 13.653197264742149, 13.753197264742148, 13.853197264742148, 13.953197264742148, 14.053197264742147, 14.153197264742147, 14.253197264742147, 14.353197264742146, 14.453197264742146, 14.553197264742145, 14.653197264742145, 14.753197264742145, 14.853197264742144], "velocities": null}}, "time": 1740481168.9636295} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5769547494088851, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9636295} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481168.9836295} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5866329843558942, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481168.9836295} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0036294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6059715434152646, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0036294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0236294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6252861213177344, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0236294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 0.4362230129252156, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5763729977337881, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.0290965353577238, "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": 1740481169.0436294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6445765986270439, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0436294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.0636294, "x": 4.503158444844102, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.0636294} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.503158444844102, 0.0], [0.6215635293837478, 0.0], [0.7599686139233935, 0.0], [0.917721976700896, 0.0], [1.017721976700896, 0.0], [1.117721976700896, 0.0], [1.2177219767008958, 0.0], [1.3177219767008959, 0.0], [1.4177219767008957, 0.0], [1.5177219767008958, 0.0], [1.617721976700896, 0.0], [1.717721976700896, 0.0], [1.817721976700896, 0.0], [1.9177219767008962, 0.0], [2.017721976700896, 0.0], [2.1177219767008966, 0.0], [2.217721976700896, 0.0], [2.3177219767008967, 0.0], [2.4177219767008964, 0.0], [2.517721976700897, 0.0], [2.617721976700897, 0.0], [2.717721976700897, 0.0], [2.817721976700897, 0.0], [2.917721976700897, 0.0], [3.017721976700897, 0.0], [3.117721976700897, 0.0], [3.217721976700897, 0.0], [3.317721976700897, 0.0], [3.4177219767008973, 0.0], [3.5177219767008974, 0.0], [3.6177219767008975, 0.0], [3.7177219767008975, 0.0], [3.8177219767008976, 0.0], [3.9177219767008977, 0.0], [4.017721976700898, 0.0], [4.1177219767008975, 0.0], [4.217721976700898, 0.0], [4.3177219767008985, 0.0], [4.417721976700898, 0.0], [4.517721976700899, 0.0], [4.617721976700898, 0.0], [4.717721976700898, 0.0], [4.817721976700898, 0.0], [4.917721976700897, 0.0], [5.017721976700897, 0.0], [5.117721976700897, 0.0], [5.217721976700896, 0.0], [5.317721976700896, 0.0], [5.4177219767008955, 0.0], [5.517721976700895, 0.0], [5.617721976700895, 0.0], [5.717721976700894, 0.0], [5.817721976700894, 0.0], [5.917721976700894, 0.0], [6.017721976700893, 0.0], [6.117721976700893, 0.0], [6.217721976700893, 0.0], [6.317721976700892, 0.0], [6.417721976700892, 0.0], [6.517721976700892, 0.0], [6.617721976700891, 0.0], [6.717721976700891, 0.0], [6.8177219767008905, 0.0], [6.91772197670089, 0.0], [7.01772197670089, 0.0], [7.1177219767008895, 0.0], [7.217721976700889, 0.0], [7.317721976700889, 0.0], [7.417721976700888, 0.0], [7.517721976700888, 0.0], [7.617721976700888, 0.0], [7.717721976700887, 0.0], [7.817721976700887, 0.0], [7.917721976700887, 0.0], [8.017721976700887, 0.0], [8.117721976700885, 0.0], [8.217721976700886, 0.0], [8.317721976700884, 0.0], [8.417721976700886, 0.0], [8.517721976700884, 0.0], [8.617721976700883, 0.0], [8.717721976700883, 0.0], [8.817721976700883, 0.0], [8.917721976700882, 0.0], [9.017721976700882, 0.0], [9.117721976700881, 0.0], [9.217721976700881, 0.0], [9.31772197670088, 0.0], [9.41772197670088, 0.0], [9.51772197670088, 0.0], [9.61772197670088, 0.0], [9.71772197670088, 0.0], [9.817721976700879, 0.0], [9.917721976700879, 0.0], [10.017721976700878, 0.0], [10.117721976700878, 0.0], [10.217721976700878, 0.0], [10.317721976700877, 0.0], [10.417721976700877, 0.0], [10.517721976700876, 0.0], [10.617721976700876, 0.0], [10.717721976700876, 0.0], [10.817721976700875, 0.0], [10.917721976700875, 0.0], [11.017721976700875, 0.0], [11.117721976700874, 0.0], [11.217721976700874, 0.0], [11.317721976700874, 0.0], [11.417721976700873, 0.0], [11.517721976700873, 0.0], [11.617721976700873, 0.0], [11.717721976700872, 0.0], [11.817721976700872, 0.0], [11.917721976700872, 0.0], [12.017721976700871, 0.0], [12.11772197670087, 0.0], [12.21772197670087, 0.0], [12.31772197670087, 0.0], [12.41772197670087, 0.0], [12.51772197670087, 0.0], [12.617721976700869, 0.0], [12.717721976700869, 0.0], [12.817721976700868, 0.0], [12.917721976700868, 0.0], [13.017721976700868, 0.0], [13.117721976700867, 0.0], [13.217721976700867, 0.0], [13.317721976700867, 0.0], [13.417721976700866, 0.0], [13.517721976700866, 0.0], [13.617721976700865, 0.0], [13.717721976700865, 0.0], [13.817721976700865, 0.0], [13.917721976700864, 0.0], [14.017721976700864, 0.0], [14.117721976700864, 0.0], [14.217721976700863, 0.0], [14.317721976700863, 0.0], [14.417721976700863, 0.0], [14.517721976700862, 0.0], [14.617721976700862, 0.0], [14.717721976700862, 0.0], [14.81313571057259, 0.0], [14.889591315232417, 0.0], [14.946046919892245, 0.0], [14.982502524552073, 0.0], [14.9989581292119, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618, 9.989897948556617, 10.089897948556617, 10.189897948556617, 10.289897948556616, 10.389897948556616, 10.489897948556616, 10.589897948556615, 10.689897948556615, 10.789897948556614, 10.889897948556614, 10.989897948556614, 11.089897948556613, 11.189897948556613, 11.289897948556613, 11.389897948556612, 11.489897948556612, 11.589897948556612, 11.689897948556611, 11.78989794855661, 11.88989794855661, 11.98989794855661, 12.08989794855661, 12.18989794855661, 12.289897948556609, 12.389897948556609, 12.489897948556608, 12.589897948556608, 12.689897948556608, 12.789897948556607, 12.889897948556607, 12.989897948556607, 13.089897948556606, 13.189897948556606, 13.289897948556606, 13.389897948556605, 13.489897948556605, 13.589897948556604, 13.689897948556604, 13.789897948556604, 13.889897948556603, 13.989897948556603, 14.089897948556603, 14.189897948556602, 14.289897948556602, 14.389897948556602, 14.489897948556601, 14.589897948556601, 14.6898979485566, 14.7898979485566], "velocities": null}}, "time": 1740481169.0636294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6734668664513794, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0636294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.0836294} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481169.8314939, "x": 15.0, "y": 2.839999999999983, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.0836294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6830847772561329, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.0836294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1036294} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7023022432446031, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1036294} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1236293} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7214951379813445, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1236293} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1436293} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7406633455834576, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1436293} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 0.503158444844102, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6638428566135138, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9624009837865564, "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": 1740481169.1636293} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.503158444844102, 0.0], [0.6215635293837478, 0.0], [0.7599686139233935, 0.0], [0.917721976700896, 0.0], [1.017721976700896, 0.0], [1.117721976700896, 0.0], [1.2177219767008958, 0.0], [1.3177219767008959, 0.0], [1.4177219767008957, 0.0], [1.5177219767008958, 0.0], [1.617721976700896, 0.0], [1.717721976700896, 0.0], [1.817721976700896, 0.0], [1.9177219767008962, 0.0], [2.017721976700896, 0.0], [2.1177219767008966, 0.0], [2.217721976700896, 0.0], [2.3177219767008967, 0.0], [2.4177219767008964, 0.0], [2.517721976700897, 0.0], [2.617721976700897, 0.0], [2.717721976700897, 0.0], [2.817721976700897, 0.0], [2.917721976700897, 0.0], [3.017721976700897, 0.0], [3.117721976700897, 0.0], [3.217721976700897, 0.0], [3.317721976700897, 0.0], [3.4177219767008973, 0.0], [3.5177219767008974, 0.0], [3.6177219767008975, 0.0], [3.7177219767008975, 0.0], [3.8177219767008976, 0.0], [3.9177219767008977, 0.0], [4.017721976700898, 0.0], [4.1177219767008975, 0.0], [4.217721976700898, 0.0], [4.3177219767008985, 0.0], [4.417721976700898, 0.0], [4.517721976700899, 0.0], [4.617721976700898, 0.0], [4.717721976700898, 0.0], [4.817721976700898, 0.0], [4.917721976700897, 0.0], [5.017721976700897, 0.0], [5.117721976700897, 0.0], [5.217721976700896, 0.0], [5.317721976700896, 0.0], [5.4177219767008955, 0.0], [5.517721976700895, 0.0], [5.617721976700895, 0.0], [5.717721976700894, 0.0], [5.817721976700894, 0.0], [5.917721976700894, 0.0], [6.017721976700893, 0.0], [6.117721976700893, 0.0], [6.217721976700893, 0.0], [6.317721976700892, 0.0], [6.417721976700892, 0.0], [6.517721976700892, 0.0], [6.617721976700891, 0.0], [6.717721976700891, 0.0], [6.8177219767008905, 0.0], [6.91772197670089, 0.0], [7.01772197670089, 0.0], [7.1177219767008895, 0.0], [7.217721976700889, 0.0], [7.317721976700889, 0.0], [7.417721976700888, 0.0], [7.517721976700888, 0.0], [7.617721976700888, 0.0], [7.717721976700887, 0.0], [7.817721976700887, 0.0], [7.917721976700887, 0.0], [8.017721976700887, 0.0], [8.117721976700885, 0.0], [8.217721976700886, 0.0], [8.317721976700884, 0.0], [8.417721976700886, 0.0], [8.517721976700884, 0.0], [8.617721976700883, 0.0], [8.717721976700883, 0.0], [8.817721976700883, 0.0], [8.917721976700882, 0.0], [9.017721976700882, 0.0], [9.117721976700881, 0.0], [9.217721976700881, 0.0], [9.31772197670088, 0.0], [9.41772197670088, 0.0], [9.51772197670088, 0.0], [9.61772197670088, 0.0], [9.71772197670088, 0.0], [9.817721976700879, 0.0], [9.917721976700879, 0.0], [10.017721976700878, 0.0], [10.117721976700878, 0.0], [10.217721976700878, 0.0], [10.317721976700877, 0.0], [10.417721976700877, 0.0], [10.517721976700876, 0.0], [10.617721976700876, 0.0], [10.717721976700876, 0.0], [10.817721976700875, 0.0], [10.917721976700875, 0.0], [11.017721976700875, 0.0], [11.117721976700874, 0.0], [11.217721976700874, 0.0], [11.317721976700874, 0.0], [11.417721976700873, 0.0], [11.517721976700873, 0.0], [11.617721976700873, 0.0], [11.717721976700872, 0.0], [11.817721976700872, 0.0], [11.917721976700872, 0.0], [12.017721976700871, 0.0], [12.11772197670087, 0.0], [12.21772197670087, 0.0], [12.31772197670087, 0.0], [12.41772197670087, 0.0], [12.51772197670087, 0.0], [12.617721976700869, 0.0], [12.717721976700869, 0.0], [12.817721976700868, 0.0], [12.917721976700868, 0.0], [13.017721976700868, 0.0], [13.117721976700867, 0.0], [13.217721976700867, 0.0], [13.317721976700867, 0.0], [13.417721976700866, 0.0], [13.517721976700866, 0.0], [13.617721976700865, 0.0], [13.717721976700865, 0.0], [13.817721976700865, 0.0], [13.917721976700864, 0.0], [14.017721976700864, 0.0], [14.117721976700864, 0.0], [14.217721976700863, 0.0], [14.317721976700863, 0.0], [14.417721976700863, 0.0], [14.517721976700862, 0.0], [14.617721976700862, 0.0], [14.717721976700862, 0.0], [14.81313571057259, 0.0], [14.889591315232417, 0.0], [14.946046919892245, 0.0], [14.982502524552073, 0.0], [14.9989581292119, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618, 9.989897948556617, 10.089897948556617, 10.189897948556617, 10.289897948556616, 10.389897948556616, 10.489897948556616, 10.589897948556615, 10.689897948556615, 10.789897948556614, 10.889897948556614, 10.989897948556614, 11.089897948556613, 11.189897948556613, 11.289897948556613, 11.389897948556612, 11.489897948556612, 11.589897948556612, 11.689897948556611, 11.78989794855661, 11.88989794855661, 11.98989794855661, 12.08989794855661, 12.18989794855661, 12.289897948556609, 12.389897948556609, 12.489897948556608, 12.589897948556608, 12.689897948556608, 12.789897948556607, 12.889897948556607, 12.989897948556607, 13.089897948556606, 13.189897948556606, 13.289897948556606, 13.389897948556605, 13.489897948556605, 13.589897948556604, 13.689897948556604, 13.789897948556604, 13.889897948556603, 13.989897948556603, 14.089897948556603, 14.189897948556602, 14.289897948556602, 14.389897948556602, 14.489897948556601, 14.589897948556601, 14.6898979485566, 14.7898979485566], "velocities": null}}, "time": 1740481169.1636293} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7693691168793342, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1636293} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.1736293, "x": 4.5814642529667085, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.1836293} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457422747644263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7789252394370938, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.1836293} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2036293} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7797424855639807, "gear": 1, "accelerator_pedal_position": 0.2457422747644263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2036293} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2236292} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.780735384815269, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2236292} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2436292} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450967527086687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7810659170531803, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2436292} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 0.5814642529667085, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7693691168793342, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9556122557759563, "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": 1740481169.2636292} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.5814642529667085, 0.0], [0.7171017036473806, 0.0], [0.8726024825051201, 0.0], [0.97260248250512, 0.0], [1.0726024825051201, 0.0], [1.17260248250512, 0.0], [1.2726024825051199, 0.0], [1.37260248250512, 0.0], [1.47260248250512, 0.0], [1.57260248250512, 0.0], [1.67260248250512, 0.0], [1.77260248250512, 0.0], [1.8726024825051202, 0.0], [1.9726024825051203, 0.0], [2.07260248250512, 0.0], [2.1726024825051207, 0.0], [2.2726024825051203, 0.0], [2.372602482505121, 0.0], [2.4726024825051205, 0.0], [2.5726024825051206, 0.0], [2.6726024825051207, 0.0], [2.7726024825051208, 0.0], [2.872602482505121, 0.0], [2.972602482505121, 0.0], [3.072602482505121, 0.0], [3.172602482505121, 0.0], [3.272602482505121, 0.0], [3.3726024825051213, 0.0], [3.4726024825051214, 0.0], [3.5726024825051215, 0.0], [3.6726024825051216, 0.0], [3.7726024825051216, 0.0], [3.8726024825051217, 0.0], [3.972602482505122, 0.0], [4.072602482505122, 0.0], [4.172602482505122, 0.0], [4.272602482505122, 0.0], [4.372602482505123, 0.0], [4.472602482505122, 0.0], [4.572602482505122, 0.0], [4.672602482505122, 0.0], [4.772602482505121, 0.0], [4.872602482505121, 0.0], [4.9726024825051205, 0.0], [5.07260248250512, 0.0], [5.17260248250512, 0.0], [5.272602482505119, 0.0], [5.372602482505119, 0.0], [5.472602482505119, 0.0], [5.572602482505118, 0.0], [5.672602482505118, 0.0], [5.772602482505118, 0.0], [5.872602482505117, 0.0], [5.972602482505117, 0.0], [6.072602482505117, 0.0], [6.172602482505116, 0.0], [6.272602482505116, 0.0], [6.3726024825051155, 0.0], [6.472602482505115, 0.0], [6.572602482505115, 0.0], [6.6726024825051145, 0.0], [6.772602482505114, 0.0], [6.872602482505114, 0.0], [6.972602482505113, 0.0], [7.072602482505113, 0.0], [7.172602482505113, 0.0], [7.272602482505112, 0.0], [7.372602482505112, 0.0], [7.472602482505112, 0.0], [7.572602482505111, 0.0], [7.672602482505111, 0.0], [7.7726024825051105, 0.0], [7.87260248250511, 0.0], [7.97260248250511, 0.0], [8.07260248250511, 0.0], [8.17260248250511, 0.0], [8.272602482505109, 0.0], [8.372602482505108, 0.0], [8.472602482505108, 0.0], [8.572602482505108, 0.0], [8.672602482505106, 0.0], [8.772602482505105, 0.0], [8.872602482505105, 0.0], [8.972602482505105, 0.0], [9.072602482505104, 0.0], [9.172602482505104, 0.0], [9.272602482505103, 0.0], [9.372602482505103, 0.0], [9.472602482505103, 0.0], [9.572602482505102, 0.0], [9.672602482505102, 0.0], [9.772602482505102, 0.0], [9.872602482505101, 0.0], [9.972602482505101, 0.0], [10.0726024825051, 0.0], [10.1726024825051, 0.0], [10.2726024825051, 0.0], [10.3726024825051, 0.0], [10.4726024825051, 0.0], [10.572602482505099, 0.0], [10.672602482505098, 0.0], [10.772602482505098, 0.0], [10.872602482505098, 0.0], [10.972602482505097, 0.0], [11.072602482505097, 0.0], [11.172602482505097, 0.0], [11.272602482505096, 0.0], [11.372602482505096, 0.0], [11.472602482505096, 0.0], [11.572602482505095, 0.0], [11.672602482505095, 0.0], [11.772602482505095, 0.0], [11.872602482505094, 0.0], [11.972602482505094, 0.0], [12.072602482505093, 0.0], [12.172602482505093, 0.0], [12.272602482505093, 0.0], [12.372602482505092, 0.0], [12.472602482505092, 0.0], [12.572602482505092, 0.0], [12.672602482505091, 0.0], [12.772602482505091, 0.0], [12.87260248250509, 0.0], [12.97260248250509, 0.0], [13.07260248250509, 0.0], [13.17260248250509, 0.0], [13.27260248250509, 0.0], [13.372602482505089, 0.0], [13.472602482505089, 0.0], [13.572602482505088, 0.0], [13.672602482505088, 0.0], [13.772602482505087, 0.0], [13.872602482505087, 0.0], [13.972602482505087, 0.0], [14.072602482505086, 0.0], [14.172602482505086, 0.0], [14.272602482505086, 0.0], [14.372602482505085, 0.0], [14.472602482505085, 0.0], [14.572602482505085, 0.0], [14.672602482505084, 0.0], [14.77209161028969, 0.0], [14.857571113788675, 0.0], [14.923050617287657, 0.0], [14.96853012078664, 0.0], [14.994009624285624, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055, 14.526598632371055, 14.626598632371055], "velocities": null}}, "time": 1740481169.2636292} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7817263309834314, "gear": 1, "accelerator_pedal_position": 0.24450967527086687, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2636292} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.2836292, "x": 4.667210850357501, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.2836292} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7820470250323956, "gear": 1, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.2836292} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3036292} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8011363821047098, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3036292} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3236291} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8202005772979156, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3236291} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.3436291} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.1610777, "x": 15.0, "y": 3.0049999999999795, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.3436291} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8392394984489674, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.3436291} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.363629} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.6672108503575007, 0.0], [0.8049185947702309, 0.0], [0.962140483197105, 0.0], [1.0621404831971049, 0.0], [1.162140483197105, 0.0], [1.262140483197105, 0.0], [1.362140483197105, 0.0], [1.4621404831971048, 0.0], [1.5621404831971049, 0.0], [1.6621404831971047, 0.0], [1.7621404831971048, 0.0], [1.862140483197105, 0.0], [1.962140483197105, 0.0], [2.062140483197105, 0.0], [2.1621404831971054, 0.0], [2.262140483197105, 0.0], [2.3621404831971056, 0.0], [2.462140483197105, 0.0], [2.5621404831971057, 0.0], [2.6621404831971054, 0.0], [2.7621404831971055, 0.0], [2.8621404831971056, 0.0], [2.962140483197106, 0.0], [3.062140483197106, 0.0], [3.1621404831971063, 0.0], [3.2621404831971064, 0.0], [3.3621404831971065, 0.0], [3.4621404831971065, 0.0], [3.5621404831971066, 0.0], [3.6621404831971067, 0.0], [3.762140483197107, 0.0], [3.862140483197107, 0.0], [3.962140483197107, 0.0], [4.062140483197107, 0.0], [4.162140483197107, 0.0], [4.262140483197108, 0.0], [4.362140483197107, 0.0], [4.462140483197107, 0.0], [4.5621404831971075, 0.0], [4.662140483197107, 0.0], [4.762140483197107, 0.0], [4.8621404831971065, 0.0], [4.962140483197105, 0.0], [5.062140483197105, 0.0], [5.1621404831971045, 0.0], [5.262140483197104, 0.0], [5.362140483197104, 0.0], [5.462140483197103, 0.0], [5.562140483197103, 0.0], [5.662140483197103, 0.0], [5.762140483197102, 0.0], [5.862140483197102, 0.0], [5.962140483197102, 0.0], [6.062140483197101, 0.0], [6.162140483197101, 0.0], [6.262140483197101, 0.0], [6.3621404831971, 0.0], [6.4621404831971, 0.0], [6.5621404831970995, 0.0], [6.662140483197099, 0.0], [6.762140483197099, 0.0], [6.8621404831970985, 0.0], [6.962140483197098, 0.0], [7.062140483197098, 0.0], [7.162140483197097, 0.0], [7.262140483197097, 0.0], [7.362140483197097, 0.0], [7.462140483197096, 0.0], [7.562140483197096, 0.0], [7.662140483197096, 0.0], [7.762140483197095, 0.0], [7.862140483197095, 0.0], [7.9621404831970946, 0.0], [8.062140483197094, 0.0], [8.162140483197094, 0.0], [8.262140483197093, 0.0], [8.362140483197093, 0.0], [8.462140483197093, 0.0], [8.562140483197092, 0.0], [8.662140483197092, 0.0], [8.762140483197092, 0.0], [8.862140483197091, 0.0], [8.962140483197093, 0.0], [9.062140483197092, 0.0], [9.162140483197092, 0.0], [9.262140483197092, 0.0], [9.362140483197091, 0.0], [9.462140483197091, 0.0], [9.56214048319709, 0.0], [9.66214048319709, 0.0], [9.76214048319709, 0.0], [9.86214048319709, 0.0], [9.96214048319709, 0.0], [10.062140483197089, 0.0], [10.162140483197089, 0.0], [10.262140483197088, 0.0], [10.362140483197088, 0.0], [10.462140483197087, 0.0], [10.562140483197087, 0.0], [10.662140483197087, 0.0], [10.762140483197086, 0.0], [10.862140483197086, 0.0], [10.962140483197086, 0.0], [11.062140483197085, 0.0], [11.162140483197085, 0.0], [11.262140483197085, 0.0], [11.362140483197084, 0.0], [11.462140483197084, 0.0], [11.562140483197084, 0.0], [11.662140483197083, 0.0], [11.762140483197083, 0.0], [11.862140483197082, 0.0], [11.962140483197082, 0.0], [12.062140483197082, 0.0], [12.162140483197081, 0.0], [12.262140483197081, 0.0], [12.36214048319708, 0.0], [12.46214048319708, 0.0], [12.56214048319708, 0.0], [12.66214048319708, 0.0], [12.76214048319708, 0.0], [12.862140483197079, 0.0], [12.962140483197079, 0.0], [13.062140483197078, 0.0], [13.162140483197078, 0.0], [13.262140483197078, 0.0], [13.362140483197077, 0.0], [13.462140483197077, 0.0], [13.562140483197076, 0.0], [13.662140483197076, 0.0], [13.762140483197076, 0.0], [13.862140483197075, 0.0], [13.962140483197075, 0.0], [14.062140483197075, 0.0], [14.162140483197074, 0.0], [14.262140483197074, 0.0], [14.362140483197074, 0.0], [14.462140483197073, 0.0], [14.562140483197073, 0.0], [14.662140483197073, 0.0], [14.761993091864813, 0.0], [14.8495649952254, 0.0], [14.917136898585985, 0.0], [14.96470880194657, 0.0], [14.992280705307156, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055, 14.526598632371055], "velocities": null}}, "time": 1740481169.363629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8677502477765686, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.363629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 0.6672108503575007, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7820470250323956, "accelerator_pedal_position": 0.24179795897113276, "brake_pedal_position": 0.0, "acceleration": 0.01601891682433973, "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": 1740481169.383629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8678534460391245, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.383629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.393629, "x": 4.758383043708155, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.403629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38180445779595534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8680596340781482, "gear": 1, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.403629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.423629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3880524310096888, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8949923941240038, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.423629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.443629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3880524310096888, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9042180737264933, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.443629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.463629} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.7583830437081547, 0.0], [0.9101197588503417, 0.0], [1.0733580319853693, 0.0], [1.1733580319853694, 0.0], [1.2733580319853692, 0.0], [1.373358031985369, 0.0], [1.4733580319853692, 0.0], [1.5733580319853693, 0.0], [1.6733580319853691, 0.0], [1.7733580319853692, 0.0], [1.8733580319853693, 0.0], [1.9733580319853694, 0.0], [2.0733580319853697, 0.0], [2.1733580319853694, 0.0], [2.27335803198537, 0.0], [2.3733580319853695, 0.0], [2.47335803198537, 0.0], [2.5733580319853697, 0.0], [2.6733580319853703, 0.0], [2.77335803198537, 0.0], [2.87335803198537, 0.0], [2.97335803198537, 0.0], [3.07335803198537, 0.0], [3.1733580319853703, 0.0], [3.2733580319853703, 0.0], [3.3733580319853704, 0.0], [3.4733580319853705, 0.0], [3.5733580319853706, 0.0], [3.6733580319853707, 0.0], [3.773358031985371, 0.0], [3.873358031985371, 0.0], [3.973358031985371, 0.0], [4.0733580319853715, 0.0], [4.173358031985371, 0.0], [4.273358031985371, 0.0], [4.373358031985371, 0.0], [4.473358031985372, 0.0], [4.5733580319853715, 0.0], [4.673358031985371, 0.0], [4.773358031985371, 0.0], [4.87335803198537, 0.0], [4.97335803198537, 0.0], [5.07335803198537, 0.0], [5.173358031985369, 0.0], [5.273358031985369, 0.0], [5.373358031985369, 0.0], [5.473358031985368, 0.0], [5.573358031985368, 0.0], [5.673358031985368, 0.0], [5.773358031985367, 0.0], [5.873358031985367, 0.0], [5.9733580319853665, 0.0], [6.073358031985366, 0.0], [6.173358031985366, 0.0], [6.2733580319853655, 0.0], [6.373358031985365, 0.0], [6.473358031985365, 0.0], [6.573358031985364, 0.0], [6.673358031985364, 0.0], [6.773358031985364, 0.0], [6.873358031985363, 0.0], [6.973358031985363, 0.0], [7.073358031985363, 0.0], [7.173358031985362, 0.0], [7.273358031985362, 0.0], [7.3733580319853615, 0.0], [7.473358031985361, 0.0], [7.573358031985361, 0.0], [7.6733580319853605, 0.0], [7.77335803198536, 0.0], [7.87335803198536, 0.0], [7.973358031985359, 0.0], [8.073358031985359, 0.0], [8.173358031985359, 0.0], [8.273358031985358, 0.0], [8.373358031985358, 0.0], [8.473358031985358, 0.0], [8.573358031985357, 0.0], [8.673358031985357, 0.0], [8.773358031985355, 0.0], [8.873358031985354, 0.0], [8.973358031985354, 0.0], [9.073358031985354, 0.0], [9.173358031985353, 0.0], [9.273358031985353, 0.0], [9.373358031985353, 0.0], [9.473358031985352, 0.0], [9.573358031985352, 0.0], [9.673358031985352, 0.0], [9.773358031985351, 0.0], [9.873358031985351, 0.0], [9.97335803198535, 0.0], [10.07335803198535, 0.0], [10.17335803198535, 0.0], [10.27335803198535, 0.0], [10.37335803198535, 0.0], [10.473358031985349, 0.0], [10.573358031985348, 0.0], [10.673358031985348, 0.0], [10.773358031985348, 0.0], [10.873358031985347, 0.0], [10.973358031985347, 0.0], [11.073358031985347, 0.0], [11.173358031985346, 0.0], [11.273358031985346, 0.0], [11.373358031985346, 0.0], [11.473358031985345, 0.0], [11.573358031985345, 0.0], [11.673358031985344, 0.0], [11.773358031985344, 0.0], [11.873358031985344, 0.0], [11.973358031985343, 0.0], [12.073358031985343, 0.0], [12.173358031985343, 0.0], [12.273358031985342, 0.0], [12.373358031985342, 0.0], [12.473358031985342, 0.0], [12.573358031985341, 0.0], [12.673358031985341, 0.0], [12.77335803198534, 0.0], [12.87335803198534, 0.0], [12.97335803198534, 0.0], [13.07335803198534, 0.0], [13.17335803198534, 0.0], [13.273358031985339, 0.0], [13.373358031985338, 0.0], [13.473358031985338, 0.0], [13.573358031985338, 0.0], [13.673358031985337, 0.0], [13.773358031985337, 0.0], [13.873358031985337, 0.0], [13.973358031985336, 0.0], [14.073358031985336, 0.0], [14.173358031985336, 0.0], [14.273358031985335, 0.0], [14.373358031985335, 0.0], [14.473358031985335, 0.0], [14.573358031985334, 0.0], [14.673358031985334, 0.0], [14.772812434327106, 0.0], [14.858140827930038, 0.0], [14.923469221532972, 0.0], [14.968797615135905, 0.0], [14.994126008738839, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072, 9.726598632371072, 9.826598632371072, 9.926598632371071, 10.026598632371071, 10.12659863237107, 10.22659863237107, 10.32659863237107, 10.42659863237107, 10.52659863237107, 10.626598632371069, 10.726598632371068, 10.826598632371068, 10.926598632371068, 11.026598632371067, 11.126598632371067, 11.226598632371067, 11.326598632371066, 11.426598632371066, 11.526598632371066, 11.626598632371065, 11.726598632371065, 11.826598632371065, 11.926598632371064, 12.026598632371064, 12.126598632371064, 12.226598632371063, 12.326598632371063, 12.426598632371062, 12.526598632371062, 12.626598632371062, 12.726598632371061, 12.826598632371061, 12.92659863237106, 13.02659863237106, 13.12659863237106, 13.22659863237106, 13.32659863237106, 13.426598632371059, 13.526598632371059, 13.626598632371058, 13.726598632371058, 13.826598632371057, 13.926598632371057, 14.026598632371057, 14.126598632371056, 14.226598632371056, 14.326598632371056, 14.426598632371055], "velocities": null}}, "time": 1740481169.463629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9318574252137378, "gear": 1, "accelerator_pedal_position": 0.3880524310096888, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.463629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 0.7583830437081547, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8679565747914205, "accelerator_pedal_position": 0.2417979589711327, "brake_pedal_position": 0.0, "acceleration": 0.010305928672771747, "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": 1740481169.483629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319170331107341, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.483629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.503629, "x": 4.857680436732315, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.503629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3395766886097067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9320361261915507, "gear": 1, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.503629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.523629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34423702406506745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505353708480782, "gear": 1, "accelerator_pedal_position": 0.3395766886097067, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.523629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.543629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34423702406506745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569845654175975, "gear": 1, "accelerator_pedal_position": 0.34423702406506745, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.543629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.563629} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.8576804367323154, 0.0], [1.0179003608224935, 0.0], [1.1179003608224936, 0.0], [1.2179003608224934, 0.0], [1.3179003608224935, 0.0], [1.4179003608224934, 0.0], [1.5179003608224932, 0.0], [1.6179003608224933, 0.0], [1.7179003608224934, 0.0], [1.8179003608224933, 0.0], [1.9179003608224934, 0.0], [2.0179003608224937, 0.0], [2.1179003608224933, 0.0], [2.217900360822494, 0.0], [2.3179003608224935, 0.0], [2.417900360822494, 0.0], [2.5179003608224937, 0.0], [2.617900360822494, 0.0], [2.717900360822494, 0.0], [2.8179003608224944, 0.0], [2.917900360822494, 0.0], [3.017900360822494, 0.0], [3.117900360822494, 0.0], [3.2179003608224943, 0.0], [3.3179003608224944, 0.0], [3.4179003608224945, 0.0], [3.5179003608224946, 0.0], [3.6179003608224947, 0.0], [3.7179003608224948, 0.0], [3.817900360822495, 0.0], [3.917900360822495, 0.0], [4.017900360822495, 0.0], [4.117900360822495, 0.0], [4.217900360822496, 0.0], [4.317900360822495, 0.0], [4.417900360822495, 0.0], [4.5179003608224955, 0.0], [4.617900360822496, 0.0], [4.717900360822496, 0.0], [4.817900360822495, 0.0], [4.917900360822496, 0.0], [5.017900360822496, 0.0], [5.117900360822496, 0.0], [5.217900360822496, 0.0], [5.317900360822495, 0.0], [5.417900360822495, 0.0], [5.517900360822495, 0.0], [5.617900360822494, 0.0], [5.717900360822494, 0.0], [5.8179003608224935, 0.0], [5.917900360822493, 0.0], [6.017900360822493, 0.0], [6.1179003608224924, 0.0], [6.217900360822492, 0.0], [6.317900360822492, 0.0], [6.417900360822491, 0.0], [6.517900360822491, 0.0], [6.617900360822491, 0.0], [6.71790036082249, 0.0], [6.81790036082249, 0.0], [6.91790036082249, 0.0], [7.017900360822489, 0.0], [7.117900360822489, 0.0], [7.2179003608224885, 0.0], [7.317900360822488, 0.0], [7.417900360822488, 0.0], [7.5179003608224875, 0.0], [7.617900360822487, 0.0], [7.717900360822487, 0.0], [7.817900360822486, 0.0], [7.917900360822486, 0.0], [8.017900360822486, 0.0], [8.117900360822485, 0.0], [8.217900360822485, 0.0], [8.317900360822485, 0.0], [8.417900360822484, 0.0], [8.517900360822484, 0.0], [8.617900360822484, 0.0], [8.717900360822483, 0.0], [8.817900360822483, 0.0], [8.917900360822482, 0.0], [9.017900360822482, 0.0], [9.117900360822482, 0.0], [9.217900360822481, 0.0], [9.317900360822481, 0.0], [9.41790036082248, 0.0], [9.51790036082248, 0.0], [9.61790036082248, 0.0], [9.71790036082248, 0.0], [9.81790036082248, 0.0], [9.917900360822479, 0.0], [10.017900360822479, 0.0], [10.117900360822478, 0.0], [10.217900360822478, 0.0], [10.317900360822478, 0.0], [10.417900360822477, 0.0], [10.517900360822477, 0.0], [10.617900360822476, 0.0], [10.717900360822476, 0.0], [10.817900360822476, 0.0], [10.917900360822475, 0.0], [11.017900360822475, 0.0], [11.117900360822475, 0.0], [11.217900360822474, 0.0], [11.317900360822474, 0.0], [11.417900360822474, 0.0], [11.517900360822473, 0.0], [11.617900360822473, 0.0], [11.717900360822473, 0.0], [11.817900360822472, 0.0], [11.917900360822472, 0.0], [12.017900360822471, 0.0], [12.117900360822471, 0.0], [12.21790036082247, 0.0], [12.31790036082247, 0.0], [12.41790036082247, 0.0], [12.51790036082247, 0.0], [12.61790036082247, 0.0], [12.717900360822469, 0.0], [12.817900360822469, 0.0], [12.917900360822468, 0.0], [13.017900360822468, 0.0], [13.117900360822468, 0.0], [13.217900360822467, 0.0], [13.317900360822467, 0.0], [13.417900360822467, 0.0], [13.517900360822466, 0.0], [13.617900360822466, 0.0], [13.717900360822465, 0.0], [13.817900360822465, 0.0], [13.917900360822465, 0.0], [14.017900360822464, 0.0], [14.117900360822464, 0.0], [14.217900360822464, 0.0], [14.317900360822463, 0.0], [14.417900360822463, 0.0], [14.517900360822463, 0.0], [14.617900360822462, 0.0], [14.717900360822462, 0.0], [14.81328990182264, 0.0], [14.889709829658148, 0.0], [14.946129757493656, 0.0], [14.982549685329165, 0.0], [14.998969613164672, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512, 14.263299316185512, 14.363299316185511], "velocities": null}}, "time": 1740481169.563629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969781650702614, "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": 1740481169.563629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.583629} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.3812554, "x": 15.0, "y": 3.114999999999977, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.583629} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969693777486553, "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": 1740481169.583629} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 0.8576804367323154, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9320361261915507, "accelerator_pedal_position": 0.24179795897113274, "brake_pedal_position": 0.0, "acceleration": 0.005948523854740484, "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": 1740481169.6036289} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23985704406870811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9695182139487789, "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": 1740481169.6036289} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.6136289, "x": 4.963020782137273, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6236289} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26132610277149815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693428939779085, "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": 1740481169.6236289} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6436288} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26404569789949384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9718505183609643, "gear": 1, "accelerator_pedal_position": 0.26132610277149815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.6436288} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6636288} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[0.9630207821372734, 0.0], [1.125697103062101, 0.0], [1.2256971030621011, 0.0], [1.325697103062101, 0.0], [1.425697103062101, 0.0], [1.5256971030621012, 0.0], [1.625697103062101, 0.0], [1.725697103062101, 0.0], [1.825697103062101, 0.0], [1.925697103062101, 0.0], [2.0256971030621007, 0.0], [2.125697103062101, 0.0], [2.225697103062101, 0.0], [2.325697103062101, 0.0], [2.425697103062101, 0.0], [2.525697103062101, 0.0], [2.6256971030621012, 0.0], [2.7256971030621013, 0.0], [2.8256971030621014, 0.0], [2.9256971030621015, 0.0], [3.025697103062102, 0.0], [3.125697103062102, 0.0], [3.2256971030621022, 0.0], [3.3256971030621023, 0.0], [3.4256971030621024, 0.0], [3.5256971030621025, 0.0], [3.6256971030621026, 0.0], [3.7256971030621027, 0.0], [3.8256971030621028, 0.0], [3.925697103062103, 0.0], [4.025697103062103, 0.0], [4.1256971030621035, 0.0], [4.225697103062103, 0.0], [4.325697103062103, 0.0], [4.425697103062103, 0.0], [4.525697103062104, 0.0], [4.6256971030621035, 0.0], [4.725697103062103, 0.0], [4.825697103062104, 0.0], [4.925697103062104, 0.0], [5.025697103062103, 0.0], [5.125697103062103, 0.0], [5.225697103062102, 0.0], [5.325697103062102, 0.0], [5.4256971030621015, 0.0], [5.525697103062101, 0.0], [5.625697103062101, 0.0], [5.7256971030621004, 0.0], [5.8256971030621, 0.0], [5.9256971030621, 0.0], [6.025697103062099, 0.0], [6.125697103062099, 0.0], [6.225697103062099, 0.0], [6.325697103062098, 0.0], [6.425697103062098, 0.0], [6.525697103062098, 0.0], [6.625697103062097, 0.0], [6.725697103062097, 0.0], [6.8256971030620965, 0.0], [6.925697103062096, 0.0], [7.025697103062096, 0.0], [7.1256971030620955, 0.0], [7.225697103062095, 0.0], [7.325697103062095, 0.0], [7.425697103062094, 0.0], [7.525697103062094, 0.0], [7.625697103062094, 0.0], [7.725697103062093, 0.0], [7.825697103062093, 0.0], [7.925697103062093, 0.0], [8.025697103062093, 0.0], [8.125697103062093, 0.0], [8.225697103062092, 0.0], [8.325697103062092, 0.0], [8.425697103062092, 0.0], [8.525697103062091, 0.0], [8.625697103062091, 0.0], [8.72569710306209, 0.0], [8.82569710306209, 0.0], [8.92569710306209, 0.0], [9.02569710306209, 0.0], [9.12569710306209, 0.0], [9.225697103062089, 0.0], [9.325697103062089, 0.0], [9.425697103062088, 0.0], [9.525697103062088, 0.0], [9.625697103062087, 0.0], [9.725697103062087, 0.0], [9.825697103062087, 0.0], [9.925697103062086, 0.0], [10.025697103062086, 0.0], [10.125697103062086, 0.0], [10.225697103062085, 0.0], [10.325697103062085, 0.0], [10.425697103062085, 0.0], [10.525697103062084, 0.0], [10.625697103062084, 0.0], [10.725697103062084, 0.0], [10.825697103062083, 0.0], [10.925697103062083, 0.0], [11.025697103062083, 0.0], [11.125697103062082, 0.0], [11.225697103062082, 0.0], [11.325697103062081, 0.0], [11.425697103062081, 0.0], [11.52569710306208, 0.0], [11.62569710306208, 0.0], [11.72569710306208, 0.0], [11.82569710306208, 0.0], [11.92569710306208, 0.0], [12.025697103062079, 0.0], [12.125697103062079, 0.0], [12.225697103062078, 0.0], [12.325697103062078, 0.0], [12.425697103062078, 0.0], [12.525697103062077, 0.0], [12.625697103062077, 0.0], [12.725697103062076, 0.0], [12.825697103062076, 0.0], [12.925697103062076, 0.0], [13.025697103062075, 0.0], [13.125697103062075, 0.0], [13.225697103062075, 0.0], [13.325697103062074, 0.0], [13.425697103062074, 0.0], [13.525697103062074, 0.0], [13.625697103062073, 0.0], [13.725697103062073, 0.0], [13.825697103062073, 0.0], [13.925697103062072, 0.0], [14.025697103062072, 0.0], [14.125697103062071, 0.0], [14.225697103062071, 0.0], [14.32569710306207, 0.0], [14.42569710306207, 0.0], [14.52569710306207, 0.0], [14.62569710306207, 0.0], [14.72569710306207, 0.0], [14.81996705165008, 0.0], [14.894827631037666, 0.0], [14.949688210425252, 0.0], [14.984548789812838, 0.0], [14.999409369200425, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512, 14.263299316185512], "velocities": null}}, "time": 1740481169.6636288} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.976114999399477, "gear": 1, "accelerator_pedal_position": 0.26404569789949384, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.6636288} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.6836288} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9757992061026549, "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": 1740481169.6836288} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 0.9630207821372734, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.969430523539381, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25786948157666745, "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": 1740481169.7036288} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23628070803332699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9751682779468382, "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": 1740481169.7036288} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.7236288, "x": 5.070086860428703, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7236288} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411960878892153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745382265586362, "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": 1740481169.7236288} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7436287} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24156755755396767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745232595693641, "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": 1740481169.7436287} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7636287} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.0700868604287033, 0.0], [1.2329539753430623, 0.0], [1.3329539753430624, 0.0], [1.4329539753430622, 0.0], [1.5329539753430623, 0.0], [1.6329539753430624, 0.0], [1.7329539753430623, 0.0], [1.8329539753430621, 0.0], [1.9329539753430622, 0.0], [2.0329539753430623, 0.0], [2.132953975343062, 0.0], [2.232953975343062, 0.0], [2.332953975343062, 0.0], [2.4329539753430622, 0.0], [2.5329539753430623, 0.0], [2.6329539753430624, 0.0], [2.7329539753430625, 0.0], [2.8329539753430626, 0.0], [2.9329539753430627, 0.0], [3.0329539753430628, 0.0], [3.1329539753430633, 0.0], [3.2329539753430634, 0.0], [3.3329539753430635, 0.0], [3.4329539753430636, 0.0], [3.5329539753430637, 0.0], [3.6329539753430637, 0.0], [3.732953975343064, 0.0], [3.832953975343064, 0.0], [3.932953975343064, 0.0], [4.032953975343064, 0.0], [4.132953975343064, 0.0], [4.232953975343064, 0.0], [4.332953975343065, 0.0], [4.4329539753430645, 0.0], [4.532953975343064, 0.0], [4.632953975343065, 0.0], [4.732953975343065, 0.0], [4.832953975343065, 0.0], [4.9329539753430645, 0.0], [5.032953975343065, 0.0], [5.132953975343065, 0.0], [5.232953975343064, 0.0], [5.332953975343064, 0.0], [5.432953975343064, 0.0], [5.532953975343063, 0.0], [5.632953975343063, 0.0], [5.7329539753430625, 0.0], [5.832953975343062, 0.0], [5.932953975343062, 0.0], [6.032953975343061, 0.0], [6.132953975343061, 0.0], [6.232953975343061, 0.0], [6.33295397534306, 0.0], [6.43295397534306, 0.0], [6.53295397534306, 0.0], [6.632953975343059, 0.0], [6.732953975343059, 0.0], [6.832953975343059, 0.0], [6.932953975343058, 0.0], [7.032953975343058, 0.0], [7.1329539753430575, 0.0], [7.232953975343057, 0.0], [7.332953975343057, 0.0], [7.4329539753430565, 0.0], [7.532953975343056, 0.0], [7.632953975343056, 0.0], [7.732953975343055, 0.0], [7.832953975343055, 0.0], [7.932953975343055, 0.0], [8.032953975343055, 0.0], [8.132953975343053, 0.0], [8.232953975343055, 0.0], [8.332953975343052, 0.0], [8.432953975343054, 0.0], [8.532953975343052, 0.0], [8.632953975343053, 0.0], [8.732953975343051, 0.0], [8.832953975343052, 0.0], [8.93295397534305, 0.0], [9.03295397534305, 0.0], [9.13295397534305, 0.0], [9.23295397534305, 0.0], [9.332953975343049, 0.0], [9.432953975343048, 0.0], [9.532953975343048, 0.0], [9.632953975343048, 0.0], [9.732953975343047, 0.0], [9.832953975343047, 0.0], [9.932953975343047, 0.0], [10.032953975343046, 0.0], [10.132953975343046, 0.0], [10.232953975343046, 0.0], [10.332953975343045, 0.0], [10.432953975343045, 0.0], [10.532953975343045, 0.0], [10.632953975343044, 0.0], [10.732953975343044, 0.0], [10.832953975343043, 0.0], [10.932953975343043, 0.0], [11.032953975343043, 0.0], [11.132953975343042, 0.0], [11.232953975343042, 0.0], [11.332953975343042, 0.0], [11.432953975343041, 0.0], [11.532953975343041, 0.0], [11.63295397534304, 0.0], [11.73295397534304, 0.0], [11.83295397534304, 0.0], [11.93295397534304, 0.0], [12.03295397534304, 0.0], [12.132953975343039, 0.0], [12.232953975343039, 0.0], [12.332953975343038, 0.0], [12.432953975343038, 0.0], [12.532953975343037, 0.0], [12.632953975343037, 0.0], [12.732953975343037, 0.0], [12.832953975343036, 0.0], [12.932953975343036, 0.0], [13.032953975343036, 0.0], [13.132953975343035, 0.0], [13.232953975343035, 0.0], [13.332953975343035, 0.0], [13.432953975343034, 0.0], [13.532953975343034, 0.0], [13.632953975343034, 0.0], [13.732953975343033, 0.0], [13.832953975343033, 0.0], [13.932953975343032, 0.0], [14.032953975343032, 0.0], [14.132953975343032, 0.0], [14.232953975343031, 0.0], [14.332953975343031, 0.0], [14.43295397534303, 0.0], [14.53295397534303, 0.0], [14.63295397534303, 0.0], [14.73295397534303, 0.0], [14.826072613317818, 0.0], [14.899481818249212, 0.0], [14.952891023180605, 0.0], [14.986300228112, 0.0], [14.999709433043394, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512, 14.163299316185512], "velocities": null}}, "time": 1740481169.7636287} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9745704502380101, "gear": 1, "accelerator_pedal_position": 0.24156755755396767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.7636287} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.7836287} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742163371765423, "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": 1740481169.7836287} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.8036287} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9735088490544168, "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": 1740481169.8036287} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 1.0700868604287033, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9745382265586362, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25822415887817235, "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": 1740481169.8236287} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23565041471838286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9724494589354963, "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": 1740481169.8236287} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.8336287, "x": 5.177234879250172, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8436286} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.601939, "x": 15.0, "y": 3.2249999999999748, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481169.8436286} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24037121837790482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9720968193309091, "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": 1740481169.8436286} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8636286} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.1772348792501717, 0.0], [1.3400281738937523, 0.0], [1.4400281738937522, 0.0], [1.5400281738937522, 0.0], [1.6400281738937523, 0.0], [1.7400281738937522, 0.0], [1.840028173893752, 0.0], [1.9400281738937522, 0.0], [2.0400281738937522, 0.0], [2.140028173893752, 0.0], [2.2400281738937524, 0.0], [2.340028173893752, 0.0], [2.4400281738937526, 0.0], [2.5400281738937522, 0.0], [2.6400281738937528, 0.0], [2.7400281738937524, 0.0], [2.840028173893753, 0.0], [2.9400281738937526, 0.0], [3.040028173893753, 0.0], [3.1400281738937528, 0.0], [3.240028173893753, 0.0], [3.340028173893753, 0.0], [3.440028173893753, 0.0], [3.540028173893753, 0.0], [3.640028173893753, 0.0], [3.7400281738937533, 0.0], [3.8400281738937534, 0.0], [3.9400281738937535, 0.0], [4.040028173893754, 0.0], [4.140028173893754, 0.0], [4.240028173893753, 0.0], [4.340028173893754, 0.0], [4.440028173893754, 0.0], [4.540028173893754, 0.0], [4.640028173893754, 0.0], [4.740028173893754, 0.0], [4.840028173893755, 0.0], [4.940028173893754, 0.0], [5.040028173893754, 0.0], [5.1400281738937545, 0.0], [5.240028173893755, 0.0], [5.340028173893755, 0.0], [5.440028173893754, 0.0], [5.540028173893754, 0.0], [5.640028173893754, 0.0], [5.740028173893753, 0.0], [5.840028173893753, 0.0], [5.940028173893753, 0.0], [6.040028173893752, 0.0], [6.140028173893752, 0.0], [6.2400281738937515, 0.0], [6.340028173893751, 0.0], [6.440028173893751, 0.0], [6.5400281738937505, 0.0], [6.64002817389375, 0.0], [6.74002817389375, 0.0], [6.840028173893749, 0.0], [6.940028173893749, 0.0], [7.040028173893749, 0.0], [7.140028173893748, 0.0], [7.240028173893748, 0.0], [7.340028173893748, 0.0], [7.440028173893747, 0.0], [7.540028173893747, 0.0], [7.6400281738937466, 0.0], [7.740028173893746, 0.0], [7.840028173893746, 0.0], [7.9400281738937455, 0.0], [8.040028173893745, 0.0], [8.140028173893745, 0.0], [8.240028173893744, 0.0], [8.340028173893744, 0.0], [8.440028173893744, 0.0], [8.540028173893743, 0.0], [8.640028173893743, 0.0], [8.740028173893743, 0.0], [8.840028173893742, 0.0], [8.940028173893742, 0.0], [9.040028173893742, 0.0], [9.140028173893741, 0.0], [9.24002817389374, 0.0], [9.34002817389374, 0.0], [9.44002817389374, 0.0], [9.54002817389374, 0.0], [9.64002817389374, 0.0], [9.740028173893739, 0.0], [9.840028173893739, 0.0], [9.940028173893738, 0.0], [10.040028173893738, 0.0], [10.140028173893738, 0.0], [10.240028173893737, 0.0], [10.340028173893737, 0.0], [10.440028173893737, 0.0], [10.540028173893736, 0.0], [10.640028173893736, 0.0], [10.740028173893736, 0.0], [10.840028173893735, 0.0], [10.940028173893735, 0.0], [11.040028173893734, 0.0], [11.140028173893734, 0.0], [11.240028173893734, 0.0], [11.340028173893733, 0.0], [11.440028173893733, 0.0], [11.540028173893733, 0.0], [11.640028173893732, 0.0], [11.740028173893732, 0.0], [11.840028173893732, 0.0], [11.940028173893731, 0.0], [12.040028173893731, 0.0], [12.14002817389373, 0.0], [12.24002817389373, 0.0], [12.34002817389373, 0.0], [12.44002817389373, 0.0], [12.54002817389373, 0.0], [12.640028173893729, 0.0], [12.740028173893728, 0.0], [12.840028173893728, 0.0], [12.940028173893728, 0.0], [13.040028173893727, 0.0], [13.140028173893727, 0.0], [13.240028173893727, 0.0], [13.340028173893726, 0.0], [13.440028173893726, 0.0], [13.540028173893726, 0.0], [13.640028173893725, 0.0], [13.740028173893725, 0.0], [13.840028173893725, 0.0], [13.940028173893724, 0.0], [14.040028173893724, 0.0], [14.140028173893723, 0.0], [14.240028173893723, 0.0], [14.340028173893723, 0.0], [14.440028173893722, 0.0], [14.540028173893722, 0.0], [14.640028173893722, 0.0], [14.740028173893721, 0.0], [14.831923101799083, 0.0], [14.903917467020339, 0.0], [14.955911832241593, 0.0], [14.98790619746285, 0.0], [14.999900562684106, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513, 14.063299316185512], "velocities": null}}, "time": 1740481169.8636286} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9719249053139879, "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": 1740481169.8636286} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.8836286} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715889971054023, "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": 1740481169.8836286} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.9036286} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9709178802187332, "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": 1740481169.9036286} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 1.1772348792501717, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9724494589354963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25807905244861423, "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": 1740481169.9236286} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23591228873965275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9702476948103237, "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": 1740481169.9236286} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481169.9436285, "x": 5.284084842700208, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9436285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24153843179010118, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9695784394077295, "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": 1740481169.9436285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9636285} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.2840848427002083, 0.0], [1.4467671779865074, 0.0], [1.5467671779865073, 0.0], [1.6467671779865074, 0.0], [1.7467671779865073, 0.0], [1.8467671779865074, 0.0], [1.9467671779865072, 0.0], [2.0467671779865073, 0.0], [2.1467671779865074, 0.0], [2.2467671779865075, 0.0], [2.346767177986507, 0.0], [2.4467671779865072, 0.0], [2.5467671779865073, 0.0], [2.6467671779865074, 0.0], [2.7467671779865075, 0.0], [2.8467671779865076, 0.0], [2.9467671779865077, 0.0], [3.0467671779865078, 0.0], [3.146767177986508, 0.0], [3.246767177986508, 0.0], [3.346767177986508, 0.0], [3.446767177986508, 0.0], [3.546767177986508, 0.0], [3.6467671779865083, 0.0], [3.7467671779865084, 0.0], [3.8467671779865085, 0.0], [3.9467671779865086, 0.0], [4.046767177986508, 0.0], [4.146767177986509, 0.0], [4.246767177986509, 0.0], [4.346767177986509, 0.0], [4.446767177986509, 0.0], [4.546767177986509, 0.0], [4.64676717798651, 0.0], [4.746767177986509, 0.0], [4.846767177986509, 0.0], [4.9467671779865094, 0.0], [5.04676717798651, 0.0], [5.14676717798651, 0.0], [5.246767177986509, 0.0], [5.34676717798651, 0.0], [5.4467671779865094, 0.0], [5.546767177986509, 0.0], [5.646767177986509, 0.0], [5.746767177986508, 0.0], [5.846767177986508, 0.0], [5.946767177986508, 0.0], [6.046767177986507, 0.0], [6.146767177986507, 0.0], [6.246767177986507, 0.0], [6.346767177986506, 0.0], [6.446767177986506, 0.0], [6.5467671779865055, 0.0], [6.646767177986505, 0.0], [6.746767177986505, 0.0], [6.8467671779865045, 0.0], [6.946767177986504, 0.0], [7.046767177986504, 0.0], [7.146767177986503, 0.0], [7.246767177986503, 0.0], [7.346767177986503, 0.0], [7.446767177986502, 0.0], [7.546767177986502, 0.0], [7.646767177986502, 0.0], [7.746767177986501, 0.0], [7.846767177986501, 0.0], [7.946767177986501, 0.0], [8.0467671779865, 0.0], [8.1467671779865, 0.0], [8.246767177986499, 0.0], [8.3467671779865, 0.0], [8.446767177986498, 0.0], [8.5467671779865, 0.0], [8.646767177986497, 0.0], [8.746767177986499, 0.0], [8.846767177986496, 0.0], [8.946767177986498, 0.0], [9.046767177986496, 0.0], [9.146767177986497, 0.0], [9.246767177986495, 0.0], [9.346767177986495, 0.0], [9.446767177986494, 0.0], [9.546767177986494, 0.0], [9.646767177986494, 0.0], [9.746767177986493, 0.0], [9.846767177986493, 0.0], [9.946767177986493, 0.0], [10.046767177986492, 0.0], [10.146767177986492, 0.0], [10.246767177986492, 0.0], [10.346767177986491, 0.0], [10.44676717798649, 0.0], [10.54676717798649, 0.0], [10.64676717798649, 0.0], [10.74676717798649, 0.0], [10.84676717798649, 0.0], [10.946767177986489, 0.0], [11.046767177986489, 0.0], [11.146767177986488, 0.0], [11.246767177986488, 0.0], [11.346767177986488, 0.0], [11.446767177986487, 0.0], [11.546767177986487, 0.0], [11.646767177986487, 0.0], [11.746767177986486, 0.0], [11.846767177986486, 0.0], [11.946767177986485, 0.0], [12.046767177986485, 0.0], [12.146767177986485, 0.0], [12.246767177986484, 0.0], [12.346767177986484, 0.0], [12.446767177986484, 0.0], [12.546767177986483, 0.0], [12.646767177986483, 0.0], [12.746767177986483, 0.0], [12.846767177986482, 0.0], [12.946767177986482, 0.0], [13.046767177986482, 0.0], [13.146767177986481, 0.0], [13.24676717798648, 0.0], [13.34676717798648, 0.0], [13.44676717798648, 0.0], [13.54676717798648, 0.0], [13.64676717798648, 0.0], [13.746767177986479, 0.0], [13.846767177986479, 0.0], [13.946767177986478, 0.0], [14.046767177986478, 0.0], [14.146767177986478, 0.0], [14.246767177986477, 0.0], [14.346767177986477, 0.0], [14.446767177986477, 0.0], [14.546767177986476, 0.0], [14.646767177986476, 0.0], [14.746767177986476, 0.0], [14.83740329125101, 0.0], [14.908049855653713, 0.0], [14.958696420056418, 0.0], [14.989342984459123, 0.0], [14.999989548861828, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513, 13.863299316185513, 13.963299316185513], "velocities": null}}, "time": 1740481169.9636285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9696304668846722, "gear": 1, "accelerator_pedal_position": 0.24153843179010118, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481169.9636285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481169.9836285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693180667233167, "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": 1740481169.9836285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0036285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9686939165492818, "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": 1740481170.0036285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0236285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9680706321081676, "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": 1740481170.0236285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 1.2840848427002083, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9695784394077295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787974547202974, "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": 1740481170.0436285} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23626293434108475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9674482120438118, "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": 1740481170.0436285} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.0536284, "x": 5.390655802977525, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.0636284} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.3906558029775251, 0.0], [1.5532351489229446, 0.0], [1.6532351489229447, 0.0], [1.7532351489229445, 0.0], [1.8532351489229446, 0.0], [1.9532351489229445, 0.0], [2.0532351489229446, 0.0], [2.1532351489229447, 0.0], [2.2532351489229443, 0.0], [2.3532351489229444, 0.0], [2.4532351489229445, 0.0], [2.5532351489229446, 0.0], [2.6532351489229447, 0.0], [2.7532351489229447, 0.0], [2.853235148922945, 0.0], [2.953235148922945, 0.0], [3.053235148922945, 0.0], [3.153235148922945, 0.0], [3.253235148922945, 0.0], [3.3532351489229453, 0.0], [3.4532351489229454, 0.0], [3.553235148922945, 0.0], [3.6532351489229455, 0.0], [3.753235148922945, 0.0], [3.8532351489229457, 0.0], [3.9532351489229454, 0.0], [4.053235148922946, 0.0], [4.1532351489229455, 0.0], [4.253235148922946, 0.0], [4.353235148922946, 0.0], [4.453235148922946, 0.0], [4.553235148922946, 0.0], [4.653235148922946, 0.0], [4.753235148922946, 0.0], [4.853235148922947, 0.0], [4.953235148922946, 0.0], [5.053235148922947, 0.0], [5.153235148922946, 0.0], [5.253235148922947, 0.0], [5.353235148922947, 0.0], [5.453235148922947, 0.0], [5.553235148922947, 0.0], [5.653235148922946, 0.0], [5.753235148922946, 0.0], [5.853235148922946, 0.0], [5.953235148922945, 0.0], [6.053235148922945, 0.0], [6.153235148922945, 0.0], [6.253235148922944, 0.0], [6.353235148922944, 0.0], [6.453235148922944, 0.0], [6.553235148922943, 0.0], [6.653235148922943, 0.0], [6.7532351489229425, 0.0], [6.853235148922942, 0.0], [6.953235148922942, 0.0], [7.0532351489229415, 0.0], [7.153235148922941, 0.0], [7.253235148922941, 0.0], [7.35323514892294, 0.0], [7.45323514892294, 0.0], [7.55323514892294, 0.0], [7.653235148922939, 0.0], [7.753235148922939, 0.0], [7.853235148922939, 0.0], [7.953235148922938, 0.0], [8.053235148922937, 0.0], [8.153235148922938, 0.0], [8.253235148922936, 0.0], [8.353235148922938, 0.0], [8.453235148922936, 0.0], [8.553235148922937, 0.0], [8.653235148922935, 0.0], [8.753235148922936, 0.0], [8.853235148922934, 0.0], [8.953235148922936, 0.0], [9.053235148922933, 0.0], [9.153235148922935, 0.0], [9.253235148922933, 0.0], [9.353235148922934, 0.0], [9.453235148922932, 0.0], [9.553235148922932, 0.0], [9.653235148922931, 0.0], [9.753235148922931, 0.0], [9.85323514892293, 0.0], [9.95323514892293, 0.0], [10.05323514892293, 0.0], [10.15323514892293, 0.0], [10.25323514892293, 0.0], [10.353235148922929, 0.0], [10.453235148922928, 0.0], [10.553235148922928, 0.0], [10.653235148922928, 0.0], [10.753235148922927, 0.0], [10.853235148922927, 0.0], [10.953235148922927, 0.0], [11.053235148922926, 0.0], [11.153235148922926, 0.0], [11.253235148922926, 0.0], [11.353235148922925, 0.0], [11.453235148922925, 0.0], [11.553235148922925, 0.0], [11.653235148922924, 0.0], [11.753235148922924, 0.0], [11.853235148922924, 0.0], [11.953235148922923, 0.0], [12.053235148922923, 0.0], [12.153235148922922, 0.0], [12.253235148922922, 0.0], [12.353235148922922, 0.0], [12.453235148922921, 0.0], [12.553235148922921, 0.0], [12.65323514892292, 0.0], [12.75323514892292, 0.0], [12.85323514892292, 0.0], [12.95323514892292, 0.0], [13.05323514892292, 0.0], [13.153235148922919, 0.0], [13.253235148922919, 0.0], [13.353235148922918, 0.0], [13.453235148922918, 0.0], [13.553235148922917, 0.0], [13.653235148922917, 0.0], [13.753235148922917, 0.0], [13.853235148922916, 0.0], [13.953235148922916, 0.0], [14.053235148922916, 0.0], [14.153235148922915, 0.0], [14.253235148922915, 0.0], [14.353235148922915, 0.0], [14.453235148922914, 0.0], [14.553235148922914, 0.0], [14.653235148922914, 0.0], [14.75322468273436, 0.0], [14.842577652949776, 0.0], [14.911930623165194, 0.0], [14.961283593380612, 0.0], [14.990636563596029, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514, 13.763299316185513], "velocities": null}}, "time": 1740481170.0636284} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243738511019591, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966516199693314, "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": 1740481170.0636284} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.0836284} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481170.9325814, "x": 15.0, "y": 3.3899999999999713, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.0836284} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666731831757649, "gear": 1, "accelerator_pedal_position": 0.243738511019591, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.0836284} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1136284} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671188102034733, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1136284} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1236284} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672671465983855, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1236284} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 1.3906558029775251, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967137325729809, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25771041235468856, "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": 1740481170.1436284} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24360684286910111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675635108685982, "gear": 1, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1436284} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.1636283, "x": 5.4970360224747195, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.1636283} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.4970360224747195, 0.0], [1.6596466626336772, 0.0], [1.7596466626336773, 0.0], [1.8596466626336774, 0.0], [1.9596466626336775, 0.0], [2.059646662633677, 0.0], [2.159646662633677, 0.0], [2.2596466626336773, 0.0], [2.3596466626336774, 0.0], [2.459646662633677, 0.0], [2.5596466626336776, 0.0], [2.659646662633677, 0.0], [2.7596466626336777, 0.0], [2.8596466626336774, 0.0], [2.959646662633678, 0.0], [3.0596466626336776, 0.0], [3.159646662633678, 0.0], [3.2596466626336777, 0.0], [3.3596466626336783, 0.0], [3.459646662633678, 0.0], [3.559646662633678, 0.0], [3.659646662633678, 0.0], [3.759646662633678, 0.0], [3.8596466626336783, 0.0], [3.9596466626336784, 0.0], [4.0596466626336785, 0.0], [4.159646662633678, 0.0], [4.259646662633679, 0.0], [4.359646662633679, 0.0], [4.459646662633679, 0.0], [4.5596466626336785, 0.0], [4.659646662633679, 0.0], [4.7596466626336795, 0.0], [4.859646662633679, 0.0], [4.959646662633679, 0.0], [5.059646662633679, 0.0], [5.15964666263368, 0.0], [5.2596466626336795, 0.0], [5.359646662633679, 0.0], [5.45964666263368, 0.0], [5.55964666263368, 0.0], [5.65964666263368, 0.0], [5.7596466626336795, 0.0], [5.859646662633679, 0.0], [5.959646662633679, 0.0], [6.0596466626336785, 0.0], [6.159646662633678, 0.0], [6.259646662633678, 0.0], [6.359646662633677, 0.0], [6.459646662633677, 0.0], [6.559646662633677, 0.0], [6.659646662633676, 0.0], [6.759646662633676, 0.0], [6.859646662633676, 0.0], [6.959646662633675, 0.0], [7.059646662633675, 0.0], [7.1596466626336746, 0.0], [7.259646662633674, 0.0], [7.359646662633674, 0.0], [7.4596466626336735, 0.0], [7.559646662633673, 0.0], [7.659646662633673, 0.0], [7.759646662633672, 0.0], [7.859646662633672, 0.0], [7.959646662633672, 0.0], [8.059646662633671, 0.0], [8.159646662633671, 0.0], [8.25964666263367, 0.0], [8.35964666263367, 0.0], [8.45964666263367, 0.0], [8.55964666263367, 0.0], [8.65964666263367, 0.0], [8.759646662633669, 0.0], [8.859646662633669, 0.0], [8.959646662633668, 0.0], [9.059646662633668, 0.0], [9.159646662633667, 0.0], [9.259646662633667, 0.0], [9.359646662633667, 0.0], [9.459646662633666, 0.0], [9.559646662633666, 0.0], [9.659646662633666, 0.0], [9.759646662633665, 0.0], [9.859646662633665, 0.0], [9.959646662633665, 0.0], [10.059646662633664, 0.0], [10.159646662633664, 0.0], [10.259646662633664, 0.0], [10.359646662633663, 0.0], [10.459646662633663, 0.0], [10.559646662633662, 0.0], [10.659646662633662, 0.0], [10.759646662633662, 0.0], [10.859646662633661, 0.0], [10.959646662633661, 0.0], [11.05964666263366, 0.0], [11.15964666263366, 0.0], [11.25964666263366, 0.0], [11.35964666263366, 0.0], [11.45964666263366, 0.0], [11.559646662633659, 0.0], [11.659646662633659, 0.0], [11.759646662633658, 0.0], [11.859646662633658, 0.0], [11.959646662633657, 0.0], [12.059646662633657, 0.0], [12.159646662633657, 0.0], [12.259646662633656, 0.0], [12.359646662633656, 0.0], [12.459646662633656, 0.0], [12.559646662633655, 0.0], [12.659646662633655, 0.0], [12.759646662633655, 0.0], [12.859646662633654, 0.0], [12.959646662633654, 0.0], [13.059646662633654, 0.0], [13.159646662633653, 0.0], [13.259646662633653, 0.0], [13.359646662633653, 0.0], [13.459646662633652, 0.0], [13.559646662633652, 0.0], [13.659646662633651, 0.0], [13.759646662633651, 0.0], [13.85964666263365, 0.0], [13.95964666263365, 0.0], [14.05964666263365, 0.0], [14.15964666263365, 0.0], [14.25964666263365, 0.0], [14.359646662633649, 0.0], [14.459646662633649, 0.0], [14.559646662633648, 0.0], [14.659646662633648, 0.0], [14.75955360453368, 0.0], [14.84762427200695, 0.0], [14.91569493948022, 0.0], [14.96376560695349, 0.0], [14.991836274426761, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514], "velocities": null}}, "time": 1740481170.1636283} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431767612778283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9679804068788609, "gear": 1, "accelerator_pedal_position": 0.2431767612778283, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1636283} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.1836283} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9681012656484755, "gear": 1, "accelerator_pedal_position": 0.2431767612778283, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.1836283} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2036283} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9683475528286227, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2036283} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2236283} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687163433157499, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2236283} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2436283} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9688391029606838, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2436283} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 1.4970360224747195, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9678594642253584, "accelerator_pedal_position": 0.24360684286910111, "brake_pedal_position": 0.0, "acceleration": 0.01478227529570797, "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": 1740481170.2636282} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.4970360224747195, 0.0], [1.6596466626336772, 0.0], [1.7596466626336773, 0.0], [1.8596466626336774, 0.0], [1.9596466626336775, 0.0], [2.059646662633677, 0.0], [2.159646662633677, 0.0], [2.2596466626336773, 0.0], [2.3596466626336774, 0.0], [2.459646662633677, 0.0], [2.5596466626336776, 0.0], [2.659646662633677, 0.0], [2.7596466626336777, 0.0], [2.8596466626336774, 0.0], [2.959646662633678, 0.0], [3.0596466626336776, 0.0], [3.159646662633678, 0.0], [3.2596466626336777, 0.0], [3.3596466626336783, 0.0], [3.459646662633678, 0.0], [3.559646662633678, 0.0], [3.659646662633678, 0.0], [3.759646662633678, 0.0], [3.8596466626336783, 0.0], [3.9596466626336784, 0.0], [4.0596466626336785, 0.0], [4.159646662633678, 0.0], [4.259646662633679, 0.0], [4.359646662633679, 0.0], [4.459646662633679, 0.0], [4.5596466626336785, 0.0], [4.659646662633679, 0.0], [4.7596466626336795, 0.0], [4.859646662633679, 0.0], [4.959646662633679, 0.0], [5.059646662633679, 0.0], [5.15964666263368, 0.0], [5.2596466626336795, 0.0], [5.359646662633679, 0.0], [5.45964666263368, 0.0], [5.55964666263368, 0.0], [5.65964666263368, 0.0], [5.7596466626336795, 0.0], [5.859646662633679, 0.0], [5.959646662633679, 0.0], [6.0596466626336785, 0.0], [6.159646662633678, 0.0], [6.259646662633678, 0.0], [6.359646662633677, 0.0], [6.459646662633677, 0.0], [6.559646662633677, 0.0], [6.659646662633676, 0.0], [6.759646662633676, 0.0], [6.859646662633676, 0.0], [6.959646662633675, 0.0], [7.059646662633675, 0.0], [7.1596466626336746, 0.0], [7.259646662633674, 0.0], [7.359646662633674, 0.0], [7.4596466626336735, 0.0], [7.559646662633673, 0.0], [7.659646662633673, 0.0], [7.759646662633672, 0.0], [7.859646662633672, 0.0], [7.959646662633672, 0.0], [8.059646662633671, 0.0], [8.159646662633671, 0.0], [8.25964666263367, 0.0], [8.35964666263367, 0.0], [8.45964666263367, 0.0], [8.55964666263367, 0.0], [8.65964666263367, 0.0], [8.759646662633669, 0.0], [8.859646662633669, 0.0], [8.959646662633668, 0.0], [9.059646662633668, 0.0], [9.159646662633667, 0.0], [9.259646662633667, 0.0], [9.359646662633667, 0.0], [9.459646662633666, 0.0], [9.559646662633666, 0.0], [9.659646662633666, 0.0], [9.759646662633665, 0.0], [9.859646662633665, 0.0], [9.959646662633665, 0.0], [10.059646662633664, 0.0], [10.159646662633664, 0.0], [10.259646662633664, 0.0], [10.359646662633663, 0.0], [10.459646662633663, 0.0], [10.559646662633662, 0.0], [10.659646662633662, 0.0], [10.759646662633662, 0.0], [10.859646662633661, 0.0], [10.959646662633661, 0.0], [11.05964666263366, 0.0], [11.15964666263366, 0.0], [11.25964666263366, 0.0], [11.35964666263366, 0.0], [11.45964666263366, 0.0], [11.559646662633659, 0.0], [11.659646662633659, 0.0], [11.759646662633658, 0.0], [11.859646662633658, 0.0], [11.959646662633657, 0.0], [12.059646662633657, 0.0], [12.159646662633657, 0.0], [12.259646662633656, 0.0], [12.359646662633656, 0.0], [12.459646662633656, 0.0], [12.559646662633655, 0.0], [12.659646662633655, 0.0], [12.759646662633655, 0.0], [12.859646662633654, 0.0], [12.959646662633654, 0.0], [13.059646662633654, 0.0], [13.159646662633653, 0.0], [13.259646662633653, 0.0], [13.359646662633653, 0.0], [13.459646662633652, 0.0], [13.559646662633652, 0.0], [13.659646662633651, 0.0], [13.759646662633651, 0.0], [13.85964666263365, 0.0], [13.95964666263365, 0.0], [14.05964666263365, 0.0], [14.15964666263365, 0.0], [14.25964666263365, 0.0], [14.359646662633649, 0.0], [14.459646662633649, 0.0], [14.559646662633648, 0.0], [14.659646662633648, 0.0], [14.75955360453368, 0.0], [14.84762427200695, 0.0], [14.91569493948022, 0.0], [14.96376560695349, 0.0], [14.991836274426761, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514, 13.663299316185514], "velocities": null}}, "time": 1740481170.2636282} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321534323155913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9692068711286386, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2636282} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.2736282, "x": 5.60356781046298, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.2836282} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23713561756426965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9693292904491424, "gear": 1, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.2836282} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3036282} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9688141722664042, "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": 1740481170.3036282} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3236282} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9682736880331717, "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": 1740481170.3236282} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3436282} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.1513095, "x": 15.0, "y": 3.499999999999969, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.3436282} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692690061941898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677339533879816, "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": 1740481170.3436282} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 1.6035678104629802, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9692068711286386, "accelerator_pedal_position": 0.24321534323155913, "brake_pedal_position": 0.0, "acceleration": 0.012241932050382931, "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": 1740481170.3636281} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.6035678104629802, 0.0], [1.7662349821247334, 0.0], [1.8662349821247333, 0.0], [1.9662349821247334, 0.0], [2.066234982124733, 0.0], [2.1662349821247333, 0.0], [2.2662349821247334, 0.0], [2.366234982124733, 0.0], [2.466234982124733, 0.0], [2.566234982124733, 0.0], [2.6662349821247333, 0.0], [2.7662349821247334, 0.0], [2.8662349821247335, 0.0], [2.9662349821247336, 0.0], [3.0662349821247337, 0.0], [3.1662349821247338, 0.0], [3.266234982124734, 0.0], [3.366234982124734, 0.0], [3.466234982124734, 0.0], [3.566234982124734, 0.0], [3.6662349821247338, 0.0], [3.766234982124734, 0.0], [3.866234982124734, 0.0], [3.966234982124734, 0.0], [4.066234982124734, 0.0], [4.166234982124735, 0.0], [4.266234982124734, 0.0], [4.366234982124734, 0.0], [4.4662349821247345, 0.0], [4.566234982124735, 0.0], [4.666234982124735, 0.0], [4.766234982124734, 0.0], [4.866234982124735, 0.0], [4.966234982124735, 0.0], [5.066234982124735, 0.0], [5.166234982124735, 0.0], [5.266234982124735, 0.0], [5.366234982124736, 0.0], [5.466234982124735, 0.0], [5.566234982124735, 0.0], [5.666234982124736, 0.0], [5.766234982124736, 0.0], [5.866234982124736, 0.0], [5.966234982124735, 0.0], [6.066234982124735, 0.0], [6.166234982124735, 0.0], [6.266234982124734, 0.0], [6.366234982124734, 0.0], [6.466234982124734, 0.0], [6.566234982124733, 0.0], [6.666234982124733, 0.0], [6.7662349821247325, 0.0], [6.866234982124732, 0.0], [6.966234982124732, 0.0], [7.0662349821247314, 0.0], [7.166234982124731, 0.0], [7.266234982124731, 0.0], [7.36623498212473, 0.0], [7.46623498212473, 0.0], [7.56623498212473, 0.0], [7.666234982124729, 0.0], [7.766234982124729, 0.0], [7.866234982124729, 0.0], [7.966234982124728, 0.0], [8.066234982124728, 0.0], [8.166234982124728, 0.0], [8.266234982124727, 0.0], [8.366234982124727, 0.0], [8.466234982124726, 0.0], [8.566234982124726, 0.0], [8.666234982124726, 0.0], [8.766234982124725, 0.0], [8.866234982124725, 0.0], [8.966234982124725, 0.0], [9.066234982124724, 0.0], [9.166234982124724, 0.0], [9.266234982124724, 0.0], [9.366234982124723, 0.0], [9.466234982124723, 0.0], [9.566234982124723, 0.0], [9.666234982124722, 0.0], [9.766234982124722, 0.0], [9.866234982124721, 0.0], [9.966234982124721, 0.0], [10.06623498212472, 0.0], [10.16623498212472, 0.0], [10.26623498212472, 0.0], [10.36623498212472, 0.0], [10.46623498212472, 0.0], [10.566234982124719, 0.0], [10.666234982124719, 0.0], [10.766234982124718, 0.0], [10.866234982124718, 0.0], [10.966234982124718, 0.0], [11.066234982124717, 0.0], [11.166234982124717, 0.0], [11.266234982124717, 0.0], [11.366234982124716, 0.0], [11.466234982124716, 0.0], [11.566234982124715, 0.0], [11.666234982124715, 0.0], [11.766234982124715, 0.0], [11.866234982124714, 0.0], [11.966234982124714, 0.0], [12.066234982124714, 0.0], [12.166234982124713, 0.0], [12.266234982124713, 0.0], [12.366234982124713, 0.0], [12.466234982124712, 0.0], [12.566234982124712, 0.0], [12.666234982124712, 0.0], [12.766234982124711, 0.0], [12.86623498212471, 0.0], [12.96623498212471, 0.0], [13.06623498212471, 0.0], [13.16623498212471, 0.0], [13.26623498212471, 0.0], [13.366234982124709, 0.0], [13.466234982124709, 0.0], [13.566234982124708, 0.0], [13.666234982124708, 0.0], [13.766234982124708, 0.0], [13.866234982124707, 0.0], [13.966234982124707, 0.0], [14.066234982124707, 0.0], [14.166234982124706, 0.0], [14.266234982124706, 0.0], [14.366234982124706, 0.0], [14.466234982124705, 0.0], [14.566234982124705, 0.0], [14.666234982124704, 0.0], [14.765971407480114, 0.0], [14.852724411055174, 0.0], [14.919477414630233, 0.0], [14.966230418205292, 0.0], [14.992983421780352, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514, 13.563299316185514], "velocities": null}}, "time": 1740481170.3636281} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23630752800862376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966925754369432, "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": 1740481170.3636281} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.3836281, "x": 5.7100734331534495, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.3836281} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24310375115192775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666180174513399, "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": 1740481170.3836281} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.403628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668524169626367, "gear": 1, "accelerator_pedal_position": 0.24310375115192775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.403628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.423628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967062964644355, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.423628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.443628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24291547070492964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672732204389127, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.443628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.463628} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.7100734331534495, 0.0], [1.8726298448330754, 0.0], [1.9726298448330755, 0.0], [2.0726298448330756, 0.0], [2.172629844833075, 0.0], [2.2726298448330753, 0.0], [2.3726298448330754, 0.0], [2.472629844833075, 0.0], [2.572629844833075, 0.0], [2.672629844833075, 0.0], [2.7726298448330753, 0.0], [2.8726298448330754, 0.0], [2.9726298448330755, 0.0], [3.0726298448330756, 0.0], [3.1726298448330756, 0.0], [3.2726298448330757, 0.0], [3.372629844833076, 0.0], [3.472629844833076, 0.0], [3.572629844833076, 0.0], [3.672629844833076, 0.0], [3.772629844833076, 0.0], [3.8726298448330763, 0.0], [3.9726298448330764, 0.0], [4.072629844833076, 0.0], [4.172629844833077, 0.0], [4.272629844833077, 0.0], [4.372629844833076, 0.0], [4.472629844833077, 0.0], [4.572629844833077, 0.0], [4.672629844833077, 0.0], [4.772629844833077, 0.0], [4.872629844833077, 0.0], [4.972629844833078, 0.0], [5.072629844833077, 0.0], [5.172629844833077, 0.0], [5.2726298448330775, 0.0], [5.372629844833078, 0.0], [5.472629844833078, 0.0], [5.572629844833077, 0.0], [5.672629844833078, 0.0], [5.7726298448330775, 0.0], [5.872629844833077, 0.0], [5.972629844833077, 0.0], [6.072629844833076, 0.0], [6.172629844833076, 0.0], [6.272629844833076, 0.0], [6.372629844833075, 0.0], [6.472629844833075, 0.0], [6.572629844833075, 0.0], [6.672629844833074, 0.0], [6.772629844833074, 0.0], [6.872629844833074, 0.0], [6.972629844833073, 0.0], [7.072629844833073, 0.0], [7.1726298448330725, 0.0], [7.272629844833072, 0.0], [7.372629844833072, 0.0], [7.4726298448330715, 0.0], [7.572629844833071, 0.0], [7.672629844833071, 0.0], [7.77262984483307, 0.0], [7.87262984483307, 0.0], [7.97262984483307, 0.0], [8.07262984483307, 0.0], [8.172629844833068, 0.0], [8.27262984483307, 0.0], [8.372629844833067, 0.0], [8.472629844833069, 0.0], [8.572629844833067, 0.0], [8.672629844833068, 0.0], [8.772629844833066, 0.0], [8.872629844833067, 0.0], [8.972629844833065, 0.0], [9.072629844833067, 0.0], [9.172629844833066, 0.0], [9.272629844833066, 0.0], [9.372629844833066, 0.0], [9.472629844833065, 0.0], [9.572629844833065, 0.0], [9.672629844833065, 0.0], [9.772629844833064, 0.0], [9.872629844833064, 0.0], [9.972629844833063, 0.0], [10.072629844833063, 0.0], [10.172629844833063, 0.0], [10.272629844833062, 0.0], [10.372629844833062, 0.0], [10.472629844833062, 0.0], [10.572629844833061, 0.0], [10.672629844833061, 0.0], [10.77262984483306, 0.0], [10.87262984483306, 0.0], [10.97262984483306, 0.0], [11.07262984483306, 0.0], [11.17262984483306, 0.0], [11.272629844833059, 0.0], [11.372629844833058, 0.0], [11.472629844833058, 0.0], [11.572629844833058, 0.0], [11.672629844833057, 0.0], [11.772629844833057, 0.0], [11.872629844833057, 0.0], [11.972629844833056, 0.0], [12.072629844833056, 0.0], [12.172629844833056, 0.0], [12.272629844833055, 0.0], [12.372629844833055, 0.0], [12.472629844833055, 0.0], [12.572629844833054, 0.0], [12.672629844833054, 0.0], [12.772629844833054, 0.0], [12.872629844833053, 0.0], [12.972629844833053, 0.0], [13.072629844833052, 0.0], [13.172629844833052, 0.0], [13.272629844833052, 0.0], [13.372629844833051, 0.0], [13.472629844833051, 0.0], [13.57262984483305, 0.0], [13.67262984483305, 0.0], [13.77262984483305, 0.0], [13.87262984483305, 0.0], [13.97262984483305, 0.0], [14.072629844833049, 0.0], [14.172629844833049, 0.0], [14.272629844833048, 0.0], [14.372629844833048, 0.0], [14.472629844833047, 0.0], [14.572629844833047, 0.0], [14.672629844833047, 0.0], [14.772117734955879, 0.0], [14.85759176598927, 0.0], [14.92306579702266, 0.0], [14.96853982805605, 0.0], [14.994013859089442, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515, 13.463299316185514], "velocities": null}}, "time": 1740481170.463628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366132224209389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9674831847332829, "gear": 1, "accelerator_pedal_position": 0.24291547070492964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.463628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 1.7100734331534495, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666180174513399, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576744047891826, "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": 1740481170.483628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366132224209389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966905350032973, "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": 1740481170.483628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.493628, "x": 5.816449719899462, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.503628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24389246917826207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663283164075166, "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": 1740481170.503628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.523628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2438923757754336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666616730601639, "gear": 1, "accelerator_pedal_position": 0.24389246917826207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.523628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.543628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2438923757754336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669945559589695, "gear": 1, "accelerator_pedal_position": 0.2438923757754336, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.543628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.563628} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.8164497198994622, 0.0], [1.9790060744152305, 0.0], [2.0790060744152306, 0.0], [2.1790060744152306, 0.0], [2.2790060744152303, 0.0], [2.3790060744152304, 0.0], [2.4790060744152305, 0.0], [2.5790060744152306, 0.0], [2.6790060744152306, 0.0], [2.7790060744152303, 0.0], [2.8790060744152304, 0.0], [2.9790060744152305, 0.0], [3.0790060744152306, 0.0], [3.1790060744152306, 0.0], [3.2790060744152307, 0.0], [3.379006074415231, 0.0], [3.479006074415231, 0.0], [3.579006074415231, 0.0], [3.679006074415231, 0.0], [3.779006074415231, 0.0], [3.8790060744152313, 0.0], [3.9790060744152314, 0.0], [4.079006074415231, 0.0], [4.1790060744152315, 0.0], [4.279006074415232, 0.0], [4.379006074415232, 0.0], [4.479006074415231, 0.0], [4.579006074415232, 0.0], [4.679006074415232, 0.0], [4.779006074415232, 0.0], [4.879006074415232, 0.0], [4.979006074415232, 0.0], [5.079006074415233, 0.0], [5.179006074415232, 0.0], [5.279006074415232, 0.0], [5.379006074415233, 0.0], [5.479006074415233, 0.0], [5.579006074415233, 0.0], [5.679006074415232, 0.0], [5.779006074415233, 0.0], [5.8790060744152335, 0.0], [5.979006074415233, 0.0], [6.079006074415233, 0.0], [6.179006074415232, 0.0], [6.279006074415232, 0.0], [6.379006074415232, 0.0], [6.479006074415231, 0.0], [6.579006074415231, 0.0], [6.679006074415231, 0.0], [6.77900607441523, 0.0], [6.87900607441523, 0.0], [6.97900607441523, 0.0], [7.079006074415229, 0.0], [7.179006074415229, 0.0], [7.2790060744152285, 0.0], [7.379006074415228, 0.0], [7.479006074415228, 0.0], [7.5790060744152274, 0.0], [7.679006074415227, 0.0], [7.779006074415227, 0.0], [7.879006074415226, 0.0], [7.979006074415226, 0.0], [8.079006074415226, 0.0], [8.179006074415225, 0.0], [8.279006074415225, 0.0], [8.379006074415225, 0.0], [8.479006074415224, 0.0], [8.579006074415224, 0.0], [8.679006074415224, 0.0], [8.779006074415223, 0.0], [8.879006074415223, 0.0], [8.979006074415222, 0.0], [9.079006074415222, 0.0], [9.179006074415222, 0.0], [9.279006074415221, 0.0], [9.379006074415221, 0.0], [9.47900607441522, 0.0], [9.57900607441522, 0.0], [9.67900607441522, 0.0], [9.77900607441522, 0.0], [9.87900607441522, 0.0], [9.979006074415219, 0.0], [10.079006074415219, 0.0], [10.179006074415218, 0.0], [10.279006074415218, 0.0], [10.379006074415217, 0.0], [10.479006074415217, 0.0], [10.579006074415217, 0.0], [10.679006074415216, 0.0], [10.779006074415216, 0.0], [10.879006074415216, 0.0], [10.979006074415215, 0.0], [11.079006074415215, 0.0], [11.179006074415215, 0.0], [11.279006074415214, 0.0], [11.379006074415214, 0.0], [11.479006074415214, 0.0], [11.579006074415213, 0.0], [11.679006074415213, 0.0], [11.779006074415213, 0.0], [11.879006074415212, 0.0], [11.979006074415212, 0.0], [12.079006074415211, 0.0], [12.179006074415211, 0.0], [12.27900607441521, 0.0], [12.37900607441521, 0.0], [12.47900607441521, 0.0], [12.57900607441521, 0.0], [12.67900607441521, 0.0], [12.779006074415209, 0.0], [12.879006074415209, 0.0], [12.979006074415208, 0.0], [13.079006074415208, 0.0], [13.179006074415208, 0.0], [13.279006074415207, 0.0], [13.379006074415207, 0.0], [13.479006074415206, 0.0], [13.579006074415206, 0.0], [13.679006074415206, 0.0], [13.779006074415205, 0.0], [13.879006074415205, 0.0], [13.979006074415205, 0.0], [14.079006074415204, 0.0], [14.179006074415204, 0.0], [14.279006074415204, 0.0], [14.379006074415203, 0.0], [14.479006074415203, 0.0], [14.579006074415203, 0.0], [14.679006074415202, 0.0], [14.778164722062222, 0.0], [14.86236350717918, 0.0], [14.92656229229614, 0.0], [14.9707610774131, 0.0], [14.99495986253006, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515, 13.363299316185515], "velocities": null}}, "time": 1740481170.563628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23661337189805243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967326977387624, "gear": 1, "accelerator_pedal_position": 0.2438923757754336, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.563628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 1.8164497198994622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666167331636729, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576743157465038, "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": 1740481170.583628} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.37304, "x": 15.0, "y": 3.6099999999999666, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.583628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23661337189805243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667493779349889, "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": 1740481170.583628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.603628, "x": 5.922796326289891, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.603628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24399624662824665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661725791950498, "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": 1740481170.603628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.623628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396394449063197, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666901904425138, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.623628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.643628} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396394449063197, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668611428855273, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.643628} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.6636279} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[1.922796326289891, 0.0], [2.085332779543226, 0.0], [2.1853327795432262, 0.0], [2.2853327795432263, 0.0], [2.385332779543226, 0.0], [2.485332779543226, 0.0], [2.585332779543226, 0.0], [2.6853327795432262, 0.0], [2.785332779543226, 0.0], [2.885332779543226, 0.0], [2.985332779543226, 0.0], [3.085332779543226, 0.0], [3.1853327795432262, 0.0], [3.2853327795432263, 0.0], [3.3853327795432264, 0.0], [3.4853327795432265, 0.0], [3.5853327795432266, 0.0], [3.6853327795432267, 0.0], [3.7853327795432268, 0.0], [3.885332779543227, 0.0], [3.985332779543227, 0.0], [4.085332779543227, 0.0], [4.185332779543227, 0.0], [4.285332779543227, 0.0], [4.385332779543227, 0.0], [4.485332779543227, 0.0], [4.5853327795432275, 0.0], [4.685332779543227, 0.0], [4.785332779543228, 0.0], [4.885332779543227, 0.0], [4.985332779543228, 0.0], [5.0853327795432275, 0.0], [5.185332779543228, 0.0], [5.285332779543228, 0.0], [5.385332779543228, 0.0], [5.485332779543228, 0.0], [5.585332779543228, 0.0], [5.685332779543228, 0.0], [5.7853327795432286, 0.0], [5.885332779543228, 0.0], [5.985332779543229, 0.0], [6.085332779543228, 0.0], [6.185332779543228, 0.0], [6.285332779543228, 0.0], [6.385332779543227, 0.0], [6.485332779543227, 0.0], [6.585332779543227, 0.0], [6.685332779543226, 0.0], [6.785332779543226, 0.0], [6.8853327795432255, 0.0], [6.985332779543225, 0.0], [7.085332779543225, 0.0], [7.1853327795432245, 0.0], [7.285332779543224, 0.0], [7.385332779543224, 0.0], [7.485332779543223, 0.0], [7.585332779543223, 0.0], [7.685332779543223, 0.0], [7.785332779543222, 0.0], [7.885332779543222, 0.0], [7.985332779543222, 0.0], [8.085332779543222, 0.0], [8.18533277954322, 0.0], [8.285332779543221, 0.0], [8.38533277954322, 0.0], [8.48533277954322, 0.0], [8.585332779543219, 0.0], [8.68533277954322, 0.0], [8.785332779543218, 0.0], [8.88533277954322, 0.0], [8.985332779543217, 0.0], [9.085332779543219, 0.0], [9.185332779543216, 0.0], [9.285332779543218, 0.0], [9.385332779543216, 0.0], [9.485332779543217, 0.0], [9.585332779543215, 0.0], [9.685332779543216, 0.0], [9.785332779543214, 0.0], [9.885332779543216, 0.0], [9.985332779543215, 0.0], [10.085332779543215, 0.0], [10.185332779543215, 0.0], [10.285332779543214, 0.0], [10.385332779543214, 0.0], [10.485332779543214, 0.0], [10.585332779543213, 0.0], [10.685332779543213, 0.0], [10.785332779543213, 0.0], [10.885332779543212, 0.0], [10.985332779543212, 0.0], [11.085332779543212, 0.0], [11.185332779543211, 0.0], [11.28533277954321, 0.0], [11.38533277954321, 0.0], [11.48533277954321, 0.0], [11.58533277954321, 0.0], [11.68533277954321, 0.0], [11.785332779543209, 0.0], [11.885332779543209, 0.0], [11.985332779543208, 0.0], [12.085332779543208, 0.0], [12.185332779543208, 0.0], [12.285332779543207, 0.0], [12.385332779543207, 0.0], [12.485332779543207, 0.0], [12.585332779543206, 0.0], [12.685332779543206, 0.0], [12.785332779543205, 0.0], [12.885332779543205, 0.0], [12.985332779543205, 0.0], [13.085332779543204, 0.0], [13.185332779543204, 0.0], [13.285332779543204, 0.0], [13.385332779543203, 0.0], [13.485332779543203, 0.0], [13.585332779543203, 0.0], [13.685332779543202, 0.0], [13.785332779543202, 0.0], [13.885332779543202, 0.0], [13.985332779543201, 0.0], [14.0853327795432, 0.0], [14.1853327795432, 0.0], [14.2853327795432, 0.0], [14.3853327795432, 0.0], [14.4853327795432, 0.0], [14.585332779543199, 0.0], [14.685332779543199, 0.0], [14.78408437423295, 0.0], [14.86701781832431, 0.0], [14.92995126241567, 0.0], [14.972884706507031, 0.0], [14.99581815059839, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515, 13.263299316185515], "velocities": null}}, "time": 1740481170.6636279} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673732893353835, "gear": 1, "accelerator_pedal_position": 0.24396394449063197, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.6636279} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.6836278} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670875801674834, "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": 1740481170.6836278} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 1.922796326289891, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661725791950498, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764352348763664, "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": 1740481170.7036278} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366649373577528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665167560496994, "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": 1740481170.7036278} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.7136278, "x": 6.029142359340086, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7236278} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441256918195378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965946723198658, "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": 1740481170.7236278} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7436278} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24412998721254417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663097514679029, "gear": 1, "accelerator_pedal_position": 0.2441256918195378, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.7436278} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7636278} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.029142359340086, 0.0], [2.1916814741365895, 0.0], [2.291681474136589, 0.0], [2.3916814741365893, 0.0], [2.4916814741365894, 0.0], [2.5916814741365894, 0.0], [2.6916814741365895, 0.0], [2.791681474136589, 0.0], [2.8916814741365893, 0.0], [2.9916814741365894, 0.0], [3.091681474136589, 0.0], [3.1916814741365895, 0.0], [3.291681474136589, 0.0], [3.3916814741365897, 0.0], [3.4916814741365894, 0.0], [3.59168147413659, 0.0], [3.6916814741365895, 0.0], [3.79168147413659, 0.0], [3.8916814741365897, 0.0], [3.9916814741365902, 0.0], [4.091681474136591, 0.0], [4.19168147413659, 0.0], [4.29168147413659, 0.0], [4.391681474136591, 0.0], [4.491681474136591, 0.0], [4.591681474136591, 0.0], [4.69168147413659, 0.0], [4.791681474136591, 0.0], [4.8916814741365915, 0.0], [4.991681474136591, 0.0], [5.091681474136591, 0.0], [5.191681474136591, 0.0], [5.291681474136592, 0.0], [5.3916814741365915, 0.0], [5.491681474136591, 0.0], [5.591681474136592, 0.0], [5.691681474136592, 0.0], [5.791681474136592, 0.0], [5.8916814741365915, 0.0], [5.991681474136592, 0.0], [6.091681474136592, 0.0], [6.191681474136591, 0.0], [6.291681474136591, 0.0], [6.391681474136591, 0.0], [6.49168147413659, 0.0], [6.59168147413659, 0.0], [6.6916814741365895, 0.0], [6.791681474136589, 0.0], [6.891681474136589, 0.0], [6.9916814741365885, 0.0], [7.091681474136588, 0.0], [7.191681474136588, 0.0], [7.291681474136587, 0.0], [7.391681474136587, 0.0], [7.491681474136587, 0.0], [7.591681474136586, 0.0], [7.691681474136586, 0.0], [7.791681474136586, 0.0], [7.891681474136585, 0.0], [7.991681474136585, 0.0], [8.091681474136585, 0.0], [8.191681474136583, 0.0], [8.291681474136585, 0.0], [8.391681474136583, 0.0], [8.491681474136584, 0.0], [8.591681474136582, 0.0], [8.691681474136583, 0.0], [8.791681474136581, 0.0], [8.891681474136583, 0.0], [8.99168147413658, 0.0], [9.091681474136582, 0.0], [9.19168147413658, 0.0], [9.291681474136581, 0.0], [9.391681474136579, 0.0], [9.49168147413658, 0.0], [9.591681474136578, 0.0], [9.69168147413658, 0.0], [9.791681474136578, 0.0], [9.891681474136579, 0.0], [9.991681474136577, 0.0], [10.091681474136577, 0.0], [10.191681474136576, 0.0], [10.291681474136576, 0.0], [10.391681474136576, 0.0], [10.491681474136575, 0.0], [10.591681474136575, 0.0], [10.691681474136574, 0.0], [10.791681474136574, 0.0], [10.891681474136574, 0.0], [10.991681474136573, 0.0], [11.091681474136573, 0.0], [11.191681474136573, 0.0], [11.291681474136572, 0.0], [11.391681474136572, 0.0], [11.491681474136572, 0.0], [11.591681474136571, 0.0], [11.69168147413657, 0.0], [11.79168147413657, 0.0], [11.89168147413657, 0.0], [11.99168147413657, 0.0], [12.09168147413657, 0.0], [12.191681474136569, 0.0], [12.291681474136569, 0.0], [12.391681474136568, 0.0], [12.491681474136568, 0.0], [12.591681474136568, 0.0], [12.691681474136567, 0.0], [12.791681474136567, 0.0], [12.891681474136567, 0.0], [12.991681474136566, 0.0], [13.091681474136566, 0.0], [13.191681474136566, 0.0], [13.291681474136565, 0.0], [13.391681474136565, 0.0], [13.491681474136564, 0.0], [13.591681474136564, 0.0], [13.691681474136564, 0.0], [13.791681474136563, 0.0], [13.891681474136563, 0.0], [13.991681474136563, 0.0], [14.091681474136562, 0.0], [14.191681474136562, 0.0], [14.291681474136562, 0.0], [14.391681474136561, 0.0], [14.491681474136561, 0.0], [14.59168147413656, 0.0], [14.69168147413656, 0.0], [14.789944128850363, 0.0], [14.87160783402305, 0.0], [14.933271539195738, 0.0], [14.974935244368426, 0.0], [14.996598949541115, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516, 13.163299316185515], "velocities": null}}, "time": 1740481170.7636278} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668541554767535, "gear": 1, "accelerator_pedal_position": 0.24412998721254417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.7636278} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.7836277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665683786576705, "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": 1740481170.7836277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 2.029142359340086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9662316407925616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25764761787631496, "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": 1740481170.8036277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366580952712274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659974192892395, "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": 1740481170.8036277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.8236277, "x": 6.1354343149822705, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8236277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442937207295742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654272512565151, "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": 1740481170.8236277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8436277} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.5911465, "x": 15.0, "y": 3.7199999999999642, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481170.8436277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24423521961661618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658119957606274, "gear": 1, "accelerator_pedal_position": 0.2442937207295742, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.8436277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8636277} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.1354343149822705, 0.0], [2.2979367811973623, 0.0], [2.3979367811973624, 0.0], [2.497936781197362, 0.0], [2.597936781197362, 0.0], [2.6979367811973622, 0.0], [2.7979367811973623, 0.0], [2.8979367811973624, 0.0], [2.997936781197362, 0.0], [3.097936781197362, 0.0], [3.1979367811973622, 0.0], [3.297936781197362, 0.0], [3.3979367811973624, 0.0], [3.497936781197362, 0.0], [3.5979367811973626, 0.0], [3.6979367811973622, 0.0], [3.7979367811973628, 0.0], [3.8979367811973624, 0.0], [3.997936781197363, 0.0], [4.097936781197363, 0.0], [4.197936781197363, 0.0], [4.297936781197363, 0.0], [4.397936781197363, 0.0], [4.497936781197364, 0.0], [4.5979367811973635, 0.0], [4.697936781197363, 0.0], [4.797936781197364, 0.0], [4.897936781197364, 0.0], [4.997936781197364, 0.0], [5.0979367811973635, 0.0], [5.197936781197364, 0.0], [5.2979367811973646, 0.0], [5.397936781197364, 0.0], [5.497936781197364, 0.0], [5.597936781197364, 0.0], [5.697936781197365, 0.0], [5.7979367811973646, 0.0], [5.897936781197364, 0.0], [5.997936781197365, 0.0], [6.097936781197365, 0.0], [6.197936781197365, 0.0], [6.2979367811973646, 0.0], [6.397936781197364, 0.0], [6.497936781197364, 0.0], [6.5979367811973635, 0.0], [6.697936781197363, 0.0], [6.797936781197363, 0.0], [6.897936781197362, 0.0], [6.997936781197362, 0.0], [7.097936781197362, 0.0], [7.197936781197361, 0.0], [7.297936781197361, 0.0], [7.397936781197361, 0.0], [7.49793678119736, 0.0], [7.59793678119736, 0.0], [7.69793678119736, 0.0], [7.797936781197359, 0.0], [7.897936781197359, 0.0], [7.9979367811973585, 0.0], [8.097936781197358, 0.0], [8.197936781197358, 0.0], [8.297936781197357, 0.0], [8.397936781197357, 0.0], [8.497936781197357, 0.0], [8.597936781197356, 0.0], [8.697936781197356, 0.0], [8.797936781197356, 0.0], [8.897936781197355, 0.0], [8.997936781197355, 0.0], [9.097936781197355, 0.0], [9.197936781197354, 0.0], [9.297936781197354, 0.0], [9.397936781197354, 0.0], [9.497936781197353, 0.0], [9.597936781197353, 0.0], [9.697936781197352, 0.0], [9.797936781197352, 0.0], [9.897936781197352, 0.0], [9.997936781197351, 0.0], [10.097936781197351, 0.0], [10.19793678119735, 0.0], [10.29793678119735, 0.0], [10.39793678119735, 0.0], [10.49793678119735, 0.0], [10.59793678119735, 0.0], [10.697936781197349, 0.0], [10.797936781197349, 0.0], [10.897936781197348, 0.0], [10.997936781197348, 0.0], [11.097936781197347, 0.0], [11.197936781197347, 0.0], [11.297936781197347, 0.0], [11.397936781197346, 0.0], [11.497936781197346, 0.0], [11.597936781197346, 0.0], [11.697936781197345, 0.0], [11.797936781197345, 0.0], [11.897936781197345, 0.0], [11.997936781197344, 0.0], [12.097936781197344, 0.0], [12.197936781197344, 0.0], [12.297936781197343, 0.0], [12.397936781197343, 0.0], [12.497936781197343, 0.0], [12.597936781197342, 0.0], [12.697936781197342, 0.0], [12.797936781197341, 0.0], [12.897936781197341, 0.0], [12.99793678119734, 0.0], [13.09793678119734, 0.0], [13.19793678119734, 0.0], [13.29793678119734, 0.0], [13.39793678119734, 0.0], [13.497936781197339, 0.0], [13.597936781197339, 0.0], [13.697936781197338, 0.0], [13.797936781197338, 0.0], [13.897936781197338, 0.0], [13.997936781197337, 0.0], [14.097936781197337, 0.0], [14.197936781197336, 0.0], [14.297936781197336, 0.0], [14.397936781197336, 0.0], [14.497936781197335, 0.0], [14.597936781197335, 0.0], [14.697936781197335, 0.0], [14.795638846205772, 0.0], [14.876051489966306, 0.0], [14.936464133726838, 0.0], [14.976876777487373, 0.0], [14.997289421247906, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516, 13.063299316185516], "velocities": null}}, "time": 1740481170.8636277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661888969789928, "gear": 1, "accelerator_pedal_position": 0.24423521961661618, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.8636277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.8836277} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656300588317035, "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": 1740481170.8836277} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.9036276} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650719951376668, "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": 1740481170.9036276} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 2.1354343149822705, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9654272512565151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25759186033751286, "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": 1740481170.9236276} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367508894672925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645147046990933, "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": 1740481170.9236276} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481170.9336276, "x": 6.24163750167411, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9436276} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24483554828289178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639581863203707, "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": 1740481170.9436276} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9636276} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.24163750167411, 0.0], [2.4040841253747556, 0.0], [2.5040841253747557, 0.0], [2.6040841253747553, 0.0], [2.7040841253747554, 0.0], [2.8040841253747555, 0.0], [2.904084125374755, 0.0], [3.004084125374755, 0.0], [3.1040841253747553, 0.0], [3.2040841253747554, 0.0], [3.3040841253747555, 0.0], [3.404084125374755, 0.0], [3.5040841253747557, 0.0], [3.6040841253747553, 0.0], [3.704084125374756, 0.0], [3.8040841253747555, 0.0], [3.904084125374756, 0.0], [4.004084125374756, 0.0], [4.104084125374756, 0.0], [4.204084125374756, 0.0], [4.3040841253747555, 0.0], [4.404084125374756, 0.0], [4.5040841253747566, 0.0], [4.604084125374756, 0.0], [4.704084125374756, 0.0], [4.804084125374756, 0.0], [4.904084125374757, 0.0], [5.0040841253747566, 0.0], [5.104084125374756, 0.0], [5.204084125374757, 0.0], [5.304084125374757, 0.0], [5.404084125374757, 0.0], [5.5040841253747566, 0.0], [5.604084125374757, 0.0], [5.704084125374758, 0.0], [5.804084125374757, 0.0], [5.904084125374757, 0.0], [6.004084125374757, 0.0], [6.104084125374758, 0.0], [6.204084125374758, 0.0], [6.304084125374758, 0.0], [6.404084125374758, 0.0], [6.504084125374757, 0.0], [6.604084125374757, 0.0], [6.704084125374757, 0.0], [6.804084125374756, 0.0], [6.904084125374756, 0.0], [7.004084125374756, 0.0], [7.104084125374755, 0.0], [7.204084125374755, 0.0], [7.304084125374755, 0.0], [7.404084125374754, 0.0], [7.504084125374754, 0.0], [7.6040841253747535, 0.0], [7.704084125374753, 0.0], [7.804084125374753, 0.0], [7.9040841253747525, 0.0], [8.004084125374753, 0.0], [8.10408412537475, 0.0], [8.204084125374752, 0.0], [8.30408412537475, 0.0], [8.404084125374752, 0.0], [8.50408412537475, 0.0], [8.60408412537475, 0.0], [8.704084125374749, 0.0], [8.80408412537475, 0.0], [8.904084125374748, 0.0], [9.00408412537475, 0.0], [9.104084125374747, 0.0], [9.204084125374749, 0.0], [9.304084125374747, 0.0], [9.404084125374748, 0.0], [9.504084125374746, 0.0], [9.604084125374747, 0.0], [9.704084125374745, 0.0], [9.804084125374747, 0.0], [9.904084125374744, 0.0], [10.004084125374744, 0.0], [10.104084125374744, 0.0], [10.204084125374743, 0.0], [10.304084125374743, 0.0], [10.404084125374743, 0.0], [10.504084125374742, 0.0], [10.604084125374742, 0.0], [10.704084125374742, 0.0], [10.804084125374741, 0.0], [10.904084125374741, 0.0], [11.00408412537474, 0.0], [11.10408412537474, 0.0], [11.20408412537474, 0.0], [11.30408412537474, 0.0], [11.40408412537474, 0.0], [11.504084125374739, 0.0], [11.604084125374738, 0.0], [11.704084125374738, 0.0], [11.804084125374738, 0.0], [11.904084125374737, 0.0], [12.004084125374737, 0.0], [12.104084125374737, 0.0], [12.204084125374736, 0.0], [12.304084125374736, 0.0], [12.404084125374736, 0.0], [12.504084125374735, 0.0], [12.604084125374735, 0.0], [12.704084125374735, 0.0], [12.804084125374734, 0.0], [12.904084125374734, 0.0], [13.004084125374733, 0.0], [13.104084125374733, 0.0], [13.204084125374733, 0.0], [13.304084125374732, 0.0], [13.404084125374732, 0.0], [13.504084125374732, 0.0], [13.604084125374731, 0.0], [13.704084125374731, 0.0], [13.80408412537473, 0.0], [13.90408412537473, 0.0], [14.00408412537473, 0.0], [14.10408412537473, 0.0], [14.20408412537473, 0.0], [14.304084125374729, 0.0], [14.404084125374728, 0.0], [14.504084125374728, 0.0], [14.604084125374728, 0.0], [14.704084125374727, 0.0], [14.801159032757178, 0.0], [14.880342207682233, 0.0], [14.939525382607286, 0.0], [14.978708557532341, 0.0], [14.997891732457395, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516, 12.963299316185516], "velocities": null}}, "time": 1740481170.9636276} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644126711010675, "gear": 1, "accelerator_pedal_position": 0.24483554828289178, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481170.9636276} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481170.9836276} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638732669429582, "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": 1740481170.9836276} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481171.0036275} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633346099261119, "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": 1740481171.0036275} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 2.24163750167411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9642363490768915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575093348226559, "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": 1740481171.0236275} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688671954949325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627966988996255, "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": 1740481171.0236275} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.0436275, "x": 6.347638877618153, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0436275} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570142474930556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622595327146718, "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": 1740481171.0436275} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0636275} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.347638877618153, 0.0], [2.509988631889755, 0.0], [2.609988631889755, 0.0], [2.7099886318897553, 0.0], [2.809988631889755, 0.0], [2.909988631889755, 0.0], [3.009988631889755, 0.0], [3.109988631889755, 0.0], [3.209988631889755, 0.0], [3.309988631889755, 0.0], [3.409988631889755, 0.0], [3.509988631889755, 0.0], [3.609988631889755, 0.0], [3.7099886318897553, 0.0], [3.8099886318897553, 0.0], [3.9099886318897554, 0.0], [4.0099886318897555, 0.0], [4.109988631889756, 0.0], [4.209988631889756, 0.0], [4.309988631889755, 0.0], [4.409988631889756, 0.0], [4.509988631889756, 0.0], [4.609988631889756, 0.0], [4.709988631889756, 0.0], [4.809988631889756, 0.0], [4.909988631889757, 0.0], [5.009988631889756, 0.0], [5.109988631889756, 0.0], [5.209988631889757, 0.0], [5.309988631889757, 0.0], [5.409988631889757, 0.0], [5.509988631889756, 0.0], [5.609988631889757, 0.0], [5.7099886318897575, 0.0], [5.809988631889757, 0.0], [5.909988631889757, 0.0], [6.009988631889757, 0.0], [6.109988631889758, 0.0], [6.2099886318897575, 0.0], [6.309988631889757, 0.0], [6.409988631889757, 0.0], [6.509988631889756, 0.0], [6.609988631889756, 0.0], [6.709988631889756, 0.0], [6.809988631889755, 0.0], [6.909988631889755, 0.0], [7.009988631889755, 0.0], [7.109988631889754, 0.0], [7.209988631889754, 0.0], [7.309988631889754, 0.0], [7.409988631889753, 0.0], [7.509988631889753, 0.0], [7.6099886318897525, 0.0], [7.709988631889752, 0.0], [7.809988631889752, 0.0], [7.909988631889751, 0.0], [8.009988631889751, 0.0], [8.10998863188975, 0.0], [8.20998863188975, 0.0], [8.30998863188975, 0.0], [8.40998863188975, 0.0], [8.50998863188975, 0.0], [8.609988631889749, 0.0], [8.709988631889749, 0.0], [8.809988631889748, 0.0], [8.909988631889748, 0.0], [9.009988631889748, 0.0], [9.109988631889747, 0.0], [9.209988631889747, 0.0], [9.309988631889746, 0.0], [9.409988631889746, 0.0], [9.509988631889746, 0.0], [9.609988631889745, 0.0], [9.709988631889745, 0.0], [9.809988631889745, 0.0], [9.909988631889744, 0.0], [10.009988631889744, 0.0], [10.109988631889744, 0.0], [10.209988631889743, 0.0], [10.309988631889743, 0.0], [10.409988631889743, 0.0], [10.509988631889742, 0.0], [10.609988631889742, 0.0], [10.709988631889741, 0.0], [10.809988631889741, 0.0], [10.90998863188974, 0.0], [11.00998863188974, 0.0], [11.10998863188974, 0.0], [11.20998863188974, 0.0], [11.30998863188974, 0.0], [11.409988631889739, 0.0], [11.509988631889739, 0.0], [11.609988631889738, 0.0], [11.709988631889738, 0.0], [11.809988631889738, 0.0], [11.909988631889737, 0.0], [12.009988631889737, 0.0], [12.109988631889737, 0.0], [12.209988631889736, 0.0], [12.309988631889736, 0.0], [12.409988631889735, 0.0], [12.509988631889735, 0.0], [12.609988631889735, 0.0], [12.709988631889734, 0.0], [12.809988631889734, 0.0], [12.909988631889734, 0.0], [13.009988631889733, 0.0], [13.109988631889733, 0.0], [13.209988631889733, 0.0], [13.309988631889732, 0.0], [13.409988631889732, 0.0], [13.509988631889732, 0.0], [13.609988631889731, 0.0], [13.70998863188973, 0.0], [13.80998863188973, 0.0], [13.90998863188973, 0.0], [14.00998863188973, 0.0], [14.10998863188973, 0.0], [14.209988631889729, 0.0], [14.309988631889729, 0.0], [14.409988631889728, 0.0], [14.509988631889728, 0.0], [14.609988631889728, 0.0], [14.709988631889727, 0.0], [14.806389995933726, 0.0], [14.88439226955578, 0.0], [14.942394543177835, 0.0], [14.980396816799889, 0.0], [14.998399090421945, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517, 12.863299316185516], "velocities": null}}, "time": 1740481171.0636275} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628245668887193, "gear": 1, "accelerator_pedal_position": 0.24570142474930556, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.0636275} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.0836275} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481171.9255316, "x": 15.0, "y": 3.8849999999999607, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.0836275} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623150248298986, "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": 1740481171.0836275} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1036274} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618061882307547, "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": 1740481171.1036274} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1236274} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612980560110505, "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": 1740481171.1236274} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 2.347638877618153, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622595327146718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573724107187362, "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": 1740481171.1436274} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710809789831586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960790627092474, "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": 1740481171.1436274} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.1536274, "x": 6.453449504191092, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.1636274} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.4534495041910924, 0.0], [2.615710610726425, 0.0], [2.7157106107264246, 0.0], [2.8157106107264247, 0.0], [2.915710610726425, 0.0], [3.015710610726425, 0.0], [3.115710610726425, 0.0], [3.2157106107264246, 0.0], [3.3157106107264247, 0.0], [3.415710610726425, 0.0], [3.5157106107264244, 0.0], [3.615710610726425, 0.0], [3.7157106107264246, 0.0], [3.815710610726425, 0.0], [3.915710610726425, 0.0], [4.015710610726425, 0.0], [4.115710610726425, 0.0], [4.2157106107264255, 0.0], [4.315710610726425, 0.0], [4.415710610726426, 0.0], [4.515710610726426, 0.0], [4.615710610726426, 0.0], [4.7157106107264255, 0.0], [4.815710610726426, 0.0], [4.915710610726427, 0.0], [5.015710610726426, 0.0], [5.115710610726426, 0.0], [5.215710610726426, 0.0], [5.315710610726427, 0.0], [5.415710610726427, 0.0], [5.515710610726426, 0.0], [5.615710610726427, 0.0], [5.715710610726427, 0.0], [5.815710610726427, 0.0], [5.915710610726427, 0.0], [6.015710610726427, 0.0], [6.115710610726428, 0.0], [6.215710610726427, 0.0], [6.315710610726427, 0.0], [6.4157106107264275, 0.0], [6.515710610726427, 0.0], [6.615710610726427, 0.0], [6.715710610726426, 0.0], [6.815710610726426, 0.0], [6.915710610726426, 0.0], [7.015710610726425, 0.0], [7.115710610726425, 0.0], [7.215710610726425, 0.0], [7.315710610726424, 0.0], [7.415710610726424, 0.0], [7.5157106107264235, 0.0], [7.615710610726423, 0.0], [7.715710610726423, 0.0], [7.8157106107264225, 0.0], [7.915710610726422, 0.0], [8.015710610726423, 0.0], [8.11571061072642, 0.0], [8.215710610726422, 0.0], [8.31571061072642, 0.0], [8.415710610726421, 0.0], [8.515710610726419, 0.0], [8.61571061072642, 0.0], [8.715710610726418, 0.0], [8.81571061072642, 0.0], [8.915710610726418, 0.0], [9.015710610726419, 0.0], [9.115710610726417, 0.0], [9.215710610726418, 0.0], [9.315710610726416, 0.0], [9.415710610726418, 0.0], [9.515710610726416, 0.0], [9.615710610726417, 0.0], [9.715710610726415, 0.0], [9.815710610726416, 0.0], [9.915710610726414, 0.0], [10.015710610726414, 0.0], [10.115710610726413, 0.0], [10.215710610726413, 0.0], [10.315710610726413, 0.0], [10.415710610726412, 0.0], [10.515710610726412, 0.0], [10.615710610726412, 0.0], [10.715710610726411, 0.0], [10.815710610726411, 0.0], [10.91571061072641, 0.0], [11.01571061072641, 0.0], [11.11571061072641, 0.0], [11.21571061072641, 0.0], [11.31571061072641, 0.0], [11.415710610726409, 0.0], [11.515710610726408, 0.0], [11.615710610726408, 0.0], [11.715710610726408, 0.0], [11.815710610726407, 0.0], [11.915710610726407, 0.0], [12.015710610726407, 0.0], [12.115710610726406, 0.0], [12.215710610726406, 0.0], [12.315710610726406, 0.0], [12.415710610726405, 0.0], [12.515710610726405, 0.0], [12.615710610726405, 0.0], [12.715710610726404, 0.0], [12.815710610726404, 0.0], [12.915710610726403, 0.0], [13.015710610726403, 0.0], [13.115710610726403, 0.0], [13.215710610726402, 0.0], [13.315710610726402, 0.0], [13.415710610726402, 0.0], [13.515710610726401, 0.0], [13.615710610726401, 0.0], [13.7157106107264, 0.0], [13.8157106107264, 0.0], [13.9157106107264, 0.0], [14.0157106107264, 0.0], [14.1157106107264, 0.0], [14.215710610726399, 0.0], [14.315710610726398, 0.0], [14.415710610726398, 0.0], [14.515710610726398, 0.0], [14.615710610726397, 0.0], [14.715710610726397, 0.0], [14.81139272636436, 0.0], [14.888250604219081, 0.0], [14.945108482073802, 0.0], [14.981966359928522, 0.0], [14.998824237783243, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517, 12.763299316185517], "velocities": null}}, "time": 1740481171.1636274} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24755493590799588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600308000501435, "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": 1740481171.1636274} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.1836274} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604308022306637, "gear": 1, "accelerator_pedal_position": 0.24755493590799588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.1836274} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2036273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612192572432331, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2036273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2236273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620066210895067, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2236273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 2.4534495041910924, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9605371760346616, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572531754671795, "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": 1740481171.2436273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24746915383504386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627928950316912, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2436273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.2636273, "x": 6.559202756307854, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.2636273} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.5592027563078537, 0.0], [2.721617701671829, 0.0], [2.821617701671829, 0.0], [2.921617701671829, 0.0], [3.021617701671829, 0.0], [3.1216177016718287, 0.0], [3.221617701671829, 0.0], [3.321617701671829, 0.0], [3.4216177016718285, 0.0], [3.5216177016718286, 0.0], [3.6216177016718287, 0.0], [3.721617701671829, 0.0], [3.821617701671829, 0.0], [3.921617701671829, 0.0], [4.021617701671829, 0.0], [4.121617701671829, 0.0], [4.221617701671829, 0.0], [4.32161770167183, 0.0], [4.421617701671829, 0.0], [4.521617701671829, 0.0], [4.62161770167183, 0.0], [4.72161770167183, 0.0], [4.82161770167183, 0.0], [4.921617701671829, 0.0], [5.02161770167183, 0.0], [5.1216177016718305, 0.0], [5.22161770167183, 0.0], [5.32161770167183, 0.0], [5.42161770167183, 0.0], [5.521617701671831, 0.0], [5.6216177016718305, 0.0], [5.72161770167183, 0.0], [5.821617701671831, 0.0], [5.921617701671831, 0.0], [6.021617701671831, 0.0], [6.1216177016718305, 0.0], [6.221617701671831, 0.0], [6.321617701671832, 0.0], [6.421617701671831, 0.0], [6.521617701671831, 0.0], [6.621617701671831, 0.0], [6.721617701671831, 0.0], [6.821617701671831, 0.0], [6.92161770167183, 0.0], [7.02161770167183, 0.0], [7.12161770167183, 0.0], [7.221617701671829, 0.0], [7.321617701671829, 0.0], [7.4216177016718285, 0.0], [7.521617701671828, 0.0], [7.621617701671828, 0.0], [7.7216177016718275, 0.0], [7.821617701671827, 0.0], [7.921617701671827, 0.0], [8.021617701671826, 0.0], [8.121617701671827, 0.0], [8.221617701671825, 0.0], [8.321617701671826, 0.0], [8.421617701671824, 0.0], [8.521617701671826, 0.0], [8.621617701671823, 0.0], [8.721617701671825, 0.0], [8.821617701671823, 0.0], [8.921617701671824, 0.0], [9.021617701671822, 0.0], [9.121617701671823, 0.0], [9.221617701671821, 0.0], [9.321617701671823, 0.0], [9.42161770167182, 0.0], [9.521617701671822, 0.0], [9.62161770167182, 0.0], [9.721617701671821, 0.0], [9.82161770167182, 0.0], [9.92161770167182, 0.0], [10.02161770167182, 0.0], [10.12161770167182, 0.0], [10.22161770167182, 0.0], [10.32161770167182, 0.0], [10.421617701671819, 0.0], [10.521617701671818, 0.0], [10.621617701671818, 0.0], [10.721617701671818, 0.0], [10.821617701671817, 0.0], [10.921617701671817, 0.0], [11.021617701671817, 0.0], [11.121617701671816, 0.0], [11.221617701671816, 0.0], [11.321617701671816, 0.0], [11.421617701671815, 0.0], [11.521617701671815, 0.0], [11.621617701671815, 0.0], [11.721617701671814, 0.0], [11.821617701671814, 0.0], [11.921617701671813, 0.0], [12.021617701671813, 0.0], [12.121617701671813, 0.0], [12.221617701671812, 0.0], [12.321617701671812, 0.0], [12.421617701671812, 0.0], [12.521617701671811, 0.0], [12.621617701671811, 0.0], [12.72161770167181, 0.0], [12.82161770167181, 0.0], [12.92161770167181, 0.0], [13.02161770167181, 0.0], [13.12161770167181, 0.0], [13.221617701671809, 0.0], [13.321617701671808, 0.0], [13.421617701671808, 0.0], [13.521617701671808, 0.0], [13.621617701671807, 0.0], [13.721617701671807, 0.0], [13.821617701671807, 0.0], [13.921617701671806, 0.0], [14.021617701671806, 0.0], [14.121617701671806, 0.0], [14.221617701671805, 0.0], [14.321617701671805, 0.0], [14.421617701671805, 0.0], [14.521617701671804, 0.0], [14.621617701671804, 0.0], [14.721617701671804, 0.0], [14.816488606479052, 0.0], [14.89216506614469, 0.0], [14.94784152581033, 0.0], [14.98351798547597, 0.0], [14.99919444514161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517], "velocities": null}}, "time": 1740481171.2636273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24547339038105365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639702651341101, "gear": 1, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2636273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.2836273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642374430331526, "gear": 1, "accelerator_pedal_position": 0.24547339038105365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.2836273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3036273} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647903173766753, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3036273} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3236272} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653424257787706, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3236272} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3436272} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.141229, "x": 15.0, "y": 3.9949999999999584, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.3436272} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658937691786719, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3436272} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 2.5592027563078537, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.963578080331275, "accelerator_pedal_position": 0.24746915383504386, "brake_pedal_position": 0.0, "acceleration": 0.03921848028351127, "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": 1740481171.3636272} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.5592027563078537, 0.0], [2.721617701671829, 0.0], [2.821617701671829, 0.0], [2.921617701671829, 0.0], [3.021617701671829, 0.0], [3.1216177016718287, 0.0], [3.221617701671829, 0.0], [3.321617701671829, 0.0], [3.4216177016718285, 0.0], [3.5216177016718286, 0.0], [3.6216177016718287, 0.0], [3.721617701671829, 0.0], [3.821617701671829, 0.0], [3.921617701671829, 0.0], [4.021617701671829, 0.0], [4.121617701671829, 0.0], [4.221617701671829, 0.0], [4.32161770167183, 0.0], [4.421617701671829, 0.0], [4.521617701671829, 0.0], [4.62161770167183, 0.0], [4.72161770167183, 0.0], [4.82161770167183, 0.0], [4.921617701671829, 0.0], [5.02161770167183, 0.0], [5.1216177016718305, 0.0], [5.22161770167183, 0.0], [5.32161770167183, 0.0], [5.42161770167183, 0.0], [5.521617701671831, 0.0], [5.6216177016718305, 0.0], [5.72161770167183, 0.0], [5.821617701671831, 0.0], [5.921617701671831, 0.0], [6.021617701671831, 0.0], [6.1216177016718305, 0.0], [6.221617701671831, 0.0], [6.321617701671832, 0.0], [6.421617701671831, 0.0], [6.521617701671831, 0.0], [6.621617701671831, 0.0], [6.721617701671831, 0.0], [6.821617701671831, 0.0], [6.92161770167183, 0.0], [7.02161770167183, 0.0], [7.12161770167183, 0.0], [7.221617701671829, 0.0], [7.321617701671829, 0.0], [7.4216177016718285, 0.0], [7.521617701671828, 0.0], [7.621617701671828, 0.0], [7.7216177016718275, 0.0], [7.821617701671827, 0.0], [7.921617701671827, 0.0], [8.021617701671826, 0.0], [8.121617701671827, 0.0], [8.221617701671825, 0.0], [8.321617701671826, 0.0], [8.421617701671824, 0.0], [8.521617701671826, 0.0], [8.621617701671823, 0.0], [8.721617701671825, 0.0], [8.821617701671823, 0.0], [8.921617701671824, 0.0], [9.021617701671822, 0.0], [9.121617701671823, 0.0], [9.221617701671821, 0.0], [9.321617701671823, 0.0], [9.42161770167182, 0.0], [9.521617701671822, 0.0], [9.62161770167182, 0.0], [9.721617701671821, 0.0], [9.82161770167182, 0.0], [9.92161770167182, 0.0], [10.02161770167182, 0.0], [10.12161770167182, 0.0], [10.22161770167182, 0.0], [10.32161770167182, 0.0], [10.421617701671819, 0.0], [10.521617701671818, 0.0], [10.621617701671818, 0.0], [10.721617701671818, 0.0], [10.821617701671817, 0.0], [10.921617701671817, 0.0], [11.021617701671817, 0.0], [11.121617701671816, 0.0], [11.221617701671816, 0.0], [11.321617701671816, 0.0], [11.421617701671815, 0.0], [11.521617701671815, 0.0], [11.621617701671815, 0.0], [11.721617701671814, 0.0], [11.821617701671814, 0.0], [11.921617701671813, 0.0], [12.021617701671813, 0.0], [12.121617701671813, 0.0], [12.221617701671812, 0.0], [12.321617701671812, 0.0], [12.421617701671812, 0.0], [12.521617701671811, 0.0], [12.621617701671811, 0.0], [12.72161770167181, 0.0], [12.82161770167181, 0.0], [12.92161770167181, 0.0], [13.02161770167181, 0.0], [13.12161770167181, 0.0], [13.221617701671809, 0.0], [13.321617701671808, 0.0], [13.421617701671808, 0.0], [13.521617701671808, 0.0], [13.621617701671807, 0.0], [13.721617701671807, 0.0], [13.821617701671807, 0.0], [13.921617701671806, 0.0], [14.021617701671806, 0.0], [14.121617701671806, 0.0], [14.221617701671805, 0.0], [14.321617701671805, 0.0], [14.421617701671805, 0.0], [14.521617701671804, 0.0], [14.621617701671804, 0.0], [14.721617701671804, 0.0], [14.816488606479052, 0.0], [14.89216506614469, 0.0], [14.94784152581033, 0.0], [14.98351798547597, 0.0], [14.99919444514161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518, 12.663299316185517], "velocities": null}}, "time": 1740481171.3636272} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562603326950588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667193519520267, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3636272} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.3736272, "x": 6.665359000707424, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.3836272} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23749031268323265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966994164724851, "gear": 1, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.3836272} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.4036272} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665266062556056, "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": 1740481171.4036272} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.4236271} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657954907743637, "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": 1740481171.4236271} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.443627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732490368767686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655521234164562, "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": 1740481171.443627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 2.665359000707424, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667193519520267, "accelerator_pedal_position": 0.24562603326950588, "brake_pedal_position": 0.0, "acceleration": 0.027481277282424887, "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": 1740481171.463627} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.665359000707424, 0.0], [2.8279199158699737, 0.0], [2.927919915869974, 0.0], [3.027919915869974, 0.0], [3.127919915869974, 0.0], [3.2279199158699736, 0.0], [3.3279199158699737, 0.0], [3.427919915869974, 0.0], [3.5279199158699734, 0.0], [3.6279199158699735, 0.0], [3.7279199158699736, 0.0], [3.8279199158699737, 0.0], [3.927919915869974, 0.0], [4.027919915869974, 0.0], [4.127919915869974, 0.0], [4.227919915869974, 0.0], [4.327919915869974, 0.0], [4.427919915869975, 0.0], [4.527919915869974, 0.0], [4.627919915869974, 0.0], [4.7279199158699745, 0.0], [4.827919915869975, 0.0], [4.927919915869975, 0.0], [5.027919915869974, 0.0], [5.127919915869975, 0.0], [5.227919915869975, 0.0], [5.327919915869975, 0.0], [5.427919915869975, 0.0], [5.527919915869975, 0.0], [5.627919915869976, 0.0], [5.727919915869975, 0.0], [5.827919915869975, 0.0], [5.927919915869976, 0.0], [6.027919915869976, 0.0], [6.127919915869976, 0.0], [6.227919915869975, 0.0], [6.327919915869976, 0.0], [6.4279199158699765, 0.0], [6.527919915869976, 0.0], [6.627919915869976, 0.0], [6.727919915869976, 0.0], [6.827919915869976, 0.0], [6.927919915869976, 0.0], [7.027919915869975, 0.0], [7.127919915869975, 0.0], [7.2279199158699745, 0.0], [7.327919915869974, 0.0], [7.427919915869974, 0.0], [7.527919915869973, 0.0], [7.627919915869973, 0.0], [7.727919915869973, 0.0], [7.827919915869972, 0.0], [7.927919915869972, 0.0], [8.027919915869973, 0.0], [8.12791991586997, 0.0], [8.227919915869972, 0.0], [8.32791991586997, 0.0], [8.427919915869971, 0.0], [8.527919915869969, 0.0], [8.62791991586997, 0.0], [8.727919915869968, 0.0], [8.82791991586997, 0.0], [8.927919915869968, 0.0], [9.027919915869969, 0.0], [9.127919915869967, 0.0], [9.227919915869968, 0.0], [9.327919915869966, 0.0], [9.427919915869968, 0.0], [9.527919915869965, 0.0], [9.627919915869967, 0.0], [9.727919915869965, 0.0], [9.827919915869966, 0.0], [9.927919915869964, 0.0], [10.027919915869965, 0.0], [10.127919915869963, 0.0], [10.227919915869965, 0.0], [10.327919915869963, 0.0], [10.427919915869964, 0.0], [10.527919915869962, 0.0], [10.627919915869963, 0.0], [10.727919915869961, 0.0], [10.82791991586996, 0.0], [10.92791991586996, 0.0], [11.02791991586996, 0.0], [11.12791991586996, 0.0], [11.22791991586996, 0.0], [11.327919915869959, 0.0], [11.427919915869959, 0.0], [11.527919915869958, 0.0], [11.627919915869958, 0.0], [11.727919915869958, 0.0], [11.827919915869957, 0.0], [11.927919915869957, 0.0], [12.027919915869957, 0.0], [12.127919915869956, 0.0], [12.227919915869956, 0.0], [12.327919915869956, 0.0], [12.427919915869955, 0.0], [12.527919915869955, 0.0], [12.627919915869954, 0.0], [12.727919915869954, 0.0], [12.827919915869954, 0.0], [12.927919915869953, 0.0], [13.027919915869953, 0.0], [13.127919915869953, 0.0], [13.227919915869952, 0.0], [13.327919915869952, 0.0], [13.427919915869952, 0.0], [13.527919915869951, 0.0], [13.62791991586995, 0.0], [13.72791991586995, 0.0], [13.82791991586995, 0.0], [13.92791991586995, 0.0], [14.02791991586995, 0.0], [14.127919915869949, 0.0], [14.227919915869949, 0.0], [14.327919915869948, 0.0], [14.427919915869948, 0.0], [14.527919915869948, 0.0], [14.627919915869947, 0.0], [14.727919915869947, 0.0], [14.821848402580766, 0.0], [14.896264419406778, 0.0], [14.950680436232789, 0.0], [14.985096453058798, 0.0], [14.99951246988481, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518, 12.563299316185518], "velocities": null}}, "time": 1740481171.463627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23660142139492057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648230329460789, "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": 1740481171.463627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.483627, "x": 6.771617677236139, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.483627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443445743727258, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964535121918298, "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": 1740481171.483627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.503627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649274570158547, "gear": 1, "accelerator_pedal_position": 0.2443445743727258, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.503627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.523627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652993987771079, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.523627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.543627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418572112786946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656708251750213, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.543627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.563627} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.771617677236139, 0.0], [2.9340784883701176, 0.0], [3.0340784883701177, 0.0], [3.134078488370118, 0.0], [3.234078488370118, 0.0], [3.3340784883701176, 0.0], [3.4340784883701176, 0.0], [3.5340784883701177, 0.0], [3.6340784883701174, 0.0], [3.7340784883701175, 0.0], [3.8340784883701176, 0.0], [3.9340784883701176, 0.0], [4.034078488370118, 0.0], [4.134078488370118, 0.0], [4.234078488370118, 0.0], [4.3340784883701176, 0.0], [4.434078488370118, 0.0], [4.534078488370119, 0.0], [4.634078488370118, 0.0], [4.734078488370118, 0.0], [4.834078488370118, 0.0], [4.934078488370119, 0.0], [5.034078488370119, 0.0], [5.134078488370118, 0.0], [5.234078488370119, 0.0], [5.334078488370119, 0.0], [5.434078488370119, 0.0], [5.534078488370119, 0.0], [5.634078488370119, 0.0], [5.73407848837012, 0.0], [5.834078488370119, 0.0], [5.934078488370119, 0.0], [6.0340784883701195, 0.0], [6.13407848837012, 0.0], [6.23407848837012, 0.0], [6.334078488370119, 0.0], [6.43407848837012, 0.0], [6.53407848837012, 0.0], [6.63407848837012, 0.0], [6.73407848837012, 0.0], [6.83407848837012, 0.0], [6.93407848837012, 0.0], [7.0340784883701195, 0.0], [7.134078488370119, 0.0], [7.234078488370119, 0.0], [7.334078488370118, 0.0], [7.434078488370118, 0.0], [7.534078488370118, 0.0], [7.634078488370117, 0.0], [7.734078488370117, 0.0], [7.834078488370117, 0.0], [7.934078488370116, 0.0], [8.034078488370117, 0.0], [8.134078488370115, 0.0], [8.234078488370116, 0.0], [8.334078488370114, 0.0], [8.434078488370115, 0.0], [8.534078488370113, 0.0], [8.634078488370115, 0.0], [8.734078488370113, 0.0], [8.834078488370114, 0.0], [8.934078488370112, 0.0], [9.034078488370113, 0.0], [9.134078488370111, 0.0], [9.234078488370113, 0.0], [9.33407848837011, 0.0], [9.434078488370112, 0.0], [9.53407848837011, 0.0], [9.634078488370111, 0.0], [9.734078488370109, 0.0], [9.83407848837011, 0.0], [9.934078488370108, 0.0], [10.03407848837011, 0.0], [10.13407848837011, 0.0], [10.234078488370109, 0.0], [10.334078488370109, 0.0], [10.434078488370108, 0.0], [10.534078488370108, 0.0], [10.634078488370108, 0.0], [10.734078488370107, 0.0], [10.834078488370107, 0.0], [10.934078488370107, 0.0], [11.034078488370106, 0.0], [11.134078488370106, 0.0], [11.234078488370105, 0.0], [11.334078488370105, 0.0], [11.434078488370105, 0.0], [11.534078488370104, 0.0], [11.634078488370104, 0.0], [11.734078488370104, 0.0], [11.834078488370103, 0.0], [11.934078488370103, 0.0], [12.034078488370103, 0.0], [12.134078488370102, 0.0], [12.234078488370102, 0.0], [12.334078488370102, 0.0], [12.434078488370101, 0.0], [12.5340784883701, 0.0], [12.6340784883701, 0.0], [12.7340784883701, 0.0], [12.8340784883701, 0.0], [12.9340784883701, 0.0], [13.034078488370099, 0.0], [13.134078488370099, 0.0], [13.234078488370098, 0.0], [13.334078488370098, 0.0], [13.434078488370098, 0.0], [13.534078488370097, 0.0], [13.634078488370097, 0.0], [13.734078488370097, 0.0], [13.834078488370096, 0.0], [13.934078488370096, 0.0], [14.034078488370096, 0.0], [14.134078488370095, 0.0], [14.234078488370095, 0.0], [14.334078488370094, 0.0], [14.434078488370094, 0.0], [14.534078488370094, 0.0], [14.634078488370093, 0.0], [14.734078488370093, 0.0], [14.827009296163492, 0.0], [14.900193598489475, 0.0], [14.953377900815456, 0.0], [14.986562203141437, 0.0], [14.999746505467419, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518, 12.463299316185518], "velocities": null}}, "time": 1740481171.563627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368528166838385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662269999068399, "gear": 1, "accelerator_pedal_position": 0.24418572112786946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.563627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 2.771617677236139, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964535121918298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753003611005437, "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": 1740481171.583627} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.3612564, "x": 15.0, "y": 4.104999999999956, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.583627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368528166838385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659538279880915, "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": 1740481171.583627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.593627, "x": 6.877816094627512, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.603627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24480181358689196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654080521075539, "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": 1740481171.603627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.623627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448851390131761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965856312812888, "gear": 1, "accelerator_pedal_position": 0.24480181358689196, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.623627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.643627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448851390131761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663143643789391, "gear": 1, "accelerator_pedal_position": 0.2448851390131761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.643627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.663627} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.877816094627512, 0.0], [3.0403302078997805, 0.0], [3.1403302078997806, 0.0], [3.2403302078997807, 0.0], [3.3403302078997807, 0.0], [3.4403302078997804, 0.0], [3.5403302078997805, 0.0], [3.6403302078997806, 0.0], [3.7403302078997807, 0.0], [3.8403302078997807, 0.0], [3.9403302078997804, 0.0], [4.04033020789978, 0.0], [4.140330207899781, 0.0], [4.240330207899781, 0.0], [4.340330207899781, 0.0], [4.44033020789978, 0.0], [4.540330207899781, 0.0], [4.6403302078997815, 0.0], [4.740330207899781, 0.0], [4.840330207899781, 0.0], [4.940330207899781, 0.0], [5.040330207899782, 0.0], [5.1403302078997815, 0.0], [5.240330207899782, 0.0], [5.340330207899782, 0.0], [5.440330207899782, 0.0], [5.540330207899782, 0.0], [5.640330207899782, 0.0], [5.740330207899782, 0.0], [5.8403302078997825, 0.0], [5.940330207899782, 0.0], [6.040330207899783, 0.0], [6.140330207899782, 0.0], [6.240330207899783, 0.0], [6.3403302078997825, 0.0], [6.440330207899783, 0.0], [6.540330207899783, 0.0], [6.640330207899783, 0.0], [6.740330207899783, 0.0], [6.840330207899783, 0.0], [6.940330207899783, 0.0], [7.040330207899783, 0.0], [7.140330207899782, 0.0], [7.240330207899782, 0.0], [7.340330207899782, 0.0], [7.440330207899781, 0.0], [7.540330207899781, 0.0], [7.640330207899781, 0.0], [7.74033020789978, 0.0], [7.84033020789978, 0.0], [7.9403302078997795, 0.0], [8.040330207899778, 0.0], [8.14033020789978, 0.0], [8.240330207899778, 0.0], [8.340330207899779, 0.0], [8.440330207899777, 0.0], [8.540330207899778, 0.0], [8.640330207899776, 0.0], [8.740330207899778, 0.0], [8.840330207899775, 0.0], [8.940330207899777, 0.0], [9.040330207899775, 0.0], [9.140330207899776, 0.0], [9.240330207899774, 0.0], [9.340330207899775, 0.0], [9.440330207899773, 0.0], [9.540330207899775, 0.0], [9.640330207899773, 0.0], [9.740330207899774, 0.0], [9.840330207899772, 0.0], [9.940330207899773, 0.0], [10.040330207899771, 0.0], [10.140330207899773, 0.0], [10.24033020789977, 0.0], [10.340330207899772, 0.0], [10.44033020789977, 0.0], [10.540330207899771, 0.0], [10.640330207899769, 0.0], [10.74033020789977, 0.0], [10.840330207899768, 0.0], [10.940330207899768, 0.0], [11.040330207899768, 0.0], [11.140330207899767, 0.0], [11.240330207899767, 0.0], [11.340330207899767, 0.0], [11.440330207899766, 0.0], [11.540330207899766, 0.0], [11.640330207899765, 0.0], [11.740330207899765, 0.0], [11.840330207899765, 0.0], [11.940330207899764, 0.0], [12.040330207899764, 0.0], [12.140330207899764, 0.0], [12.240330207899763, 0.0], [12.340330207899763, 0.0], [12.440330207899763, 0.0], [12.540330207899762, 0.0], [12.640330207899762, 0.0], [12.740330207899762, 0.0], [12.840330207899761, 0.0], [12.94033020789976, 0.0], [13.04033020789976, 0.0], [13.14033020789976, 0.0], [13.24033020789976, 0.0], [13.34033020789976, 0.0], [13.440330207899759, 0.0], [13.540330207899759, 0.0], [13.640330207899758, 0.0], [13.740330207899758, 0.0], [13.840330207899758, 0.0], [13.940330207899757, 0.0], [14.040330207899757, 0.0], [14.140330207899757, 0.0], [14.240330207899756, 0.0], [14.340330207899756, 0.0], [14.440330207899756, 0.0], [14.540330207899755, 0.0], [14.640330207899755, 0.0], [14.740330207899754, 0.0], [14.832170661440541, 0.0], [14.90410461986059, 0.0], [14.956038578280639, 0.0], [14.987972536700688, 0.0], [14.999906495120738, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519, 12.363299316185518], "velocities": null}}, "time": 1740481171.663627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367217261372408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670002516159308, "gear": 1, "accelerator_pedal_position": 0.2448851390131761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.663627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 2.877816094627512, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9656808454370569, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760943722429314, "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": 1740481171.683627} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367217261372408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667183504250378, "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": 1740481171.683627} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.7036269, "x": 6.98410056895514, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7036269} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24430473208399844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661551342789061, "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": 1740481171.7036269} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7236269} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24433922585084694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665402459707456, "gear": 1, "accelerator_pedal_position": 0.24430473208399844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7236269} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7436268} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24433922585084694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669291340865508, "gear": 1, "accelerator_pedal_position": 0.24433922585084694, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7436268} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7636268} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[2.9841005689551396, 0.0], [3.1466362351835655, 0.0], [3.2466362351835656, 0.0], [3.3466362351835657, 0.0], [3.4466362351835658, 0.0], [3.5466362351835654, 0.0], [3.6466362351835655, 0.0], [3.7466362351835656, 0.0], [3.8466362351835657, 0.0], [3.9466362351835658, 0.0], [4.046636235183565, 0.0], [4.146636235183566, 0.0], [4.246636235183566, 0.0], [4.346636235183565, 0.0], [4.446636235183566, 0.0], [4.546636235183566, 0.0], [4.646636235183566, 0.0], [4.746636235183566, 0.0], [4.846636235183566, 0.0], [4.946636235183567, 0.0], [5.046636235183566, 0.0], [5.146636235183566, 0.0], [5.2466362351835665, 0.0], [5.346636235183567, 0.0], [5.446636235183567, 0.0], [5.546636235183566, 0.0], [5.646636235183567, 0.0], [5.746636235183567, 0.0], [5.846636235183567, 0.0], [5.946636235183567, 0.0], [6.046636235183567, 0.0], [6.146636235183568, 0.0], [6.246636235183567, 0.0], [6.346636235183567, 0.0], [6.4466362351835675, 0.0], [6.546636235183568, 0.0], [6.646636235183568, 0.0], [6.746636235183567, 0.0], [6.846636235183568, 0.0], [6.946636235183568, 0.0], [7.046636235183568, 0.0], [7.146636235183568, 0.0], [7.246636235183567, 0.0], [7.346636235183567, 0.0], [7.446636235183567, 0.0], [7.546636235183566, 0.0], [7.646636235183566, 0.0], [7.746636235183566, 0.0], [7.846636235183565, 0.0], [7.946636235183565, 0.0], [8.046636235183565, 0.0], [8.146636235183564, 0.0], [8.246636235183564, 0.0], [8.346636235183563, 0.0], [8.446636235183563, 0.0], [8.546636235183563, 0.0], [8.646636235183562, 0.0], [8.746636235183562, 0.0], [8.846636235183562, 0.0], [8.946636235183561, 0.0], [9.046636235183561, 0.0], [9.14663623518356, 0.0], [9.24663623518356, 0.0], [9.34663623518356, 0.0], [9.44663623518356, 0.0], [9.54663623518356, 0.0], [9.646636235183559, 0.0], [9.746636235183558, 0.0], [9.846636235183558, 0.0], [9.946636235183558, 0.0], [10.046636235183557, 0.0], [10.146636235183557, 0.0], [10.246636235183557, 0.0], [10.346636235183556, 0.0], [10.446636235183556, 0.0], [10.546636235183556, 0.0], [10.646636235183555, 0.0], [10.746636235183555, 0.0], [10.846636235183555, 0.0], [10.946636235183554, 0.0], [11.046636235183552, 0.0], [11.146636235183554, 0.0], [11.246636235183551, 0.0], [11.346636235183553, 0.0], [11.44663623518355, 0.0], [11.546636235183552, 0.0], [11.64663623518355, 0.0], [11.746636235183551, 0.0], [11.84663623518355, 0.0], [11.94663623518355, 0.0], [12.046636235183549, 0.0], [12.14663623518355, 0.0], [12.246636235183548, 0.0], [12.34663623518355, 0.0], [12.446636235183547, 0.0], [12.546636235183549, 0.0], [12.646636235183546, 0.0], [12.746636235183548, 0.0], [12.846636235183546, 0.0], [12.946636235183547, 0.0], [13.046636235183545, 0.0], [13.146636235183546, 0.0], [13.246636235183544, 0.0], [13.346636235183546, 0.0], [13.446636235183544, 0.0], [13.546636235183545, 0.0], [13.646636235183543, 0.0], [13.746636235183544, 0.0], [13.846636235183542, 0.0], [13.946636235183544, 0.0], [14.046636235183541, 0.0], [14.146636235183543, 0.0], [14.24663623518354, 0.0], [14.346636235183542, 0.0], [14.44663623518354, 0.0], [14.546636235183541, 0.0], [14.64663623518354, 0.0], [14.74663623518354, 0.0], [14.837297673233092, 0.0], [14.907970426196384, 0.0], [14.958643179159676, 0.0], [14.989315932122967, 0.0], [14.99998868508626, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552, 12.163299316185519, 12.263299316185519], "velocities": null}}, "time": 1740481171.7636268} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675114556682429, "gear": 1, "accelerator_pedal_position": 0.24433922585084694, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.7636268} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.7836268} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672257769375088, "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": 1740481171.7836268} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 2.9841005689551396, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9661551342789061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576423141488802, "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": 1740481171.8036268} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23666695742055877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666550136544296, "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": 1740481171.8036268} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.8136268, "x": 7.090455373258246, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8236268} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24409917981193316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660850415853046, "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": 1740481171.8236268} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8436267} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.6929522, "x": 15.0, "y": 4.2699999999999525, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481171.8436267} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24411480124617194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664445652982776, "gear": 1, "accelerator_pedal_position": 0.24409917981193316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.8436267} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8636267} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.090455373258246, 0.0], [3.2530007016509486, 0.0], [3.3530007016509487, 0.0], [3.4530007016509487, 0.0], [3.553000701650949, 0.0], [3.6530007016509485, 0.0], [3.7530007016509486, 0.0], [3.8530007016509487, 0.0], [3.9530007016509487, 0.0], [4.053000701650949, 0.0], [4.1530007016509485, 0.0], [4.253000701650949, 0.0], [4.353000701650949, 0.0], [4.453000701650948, 0.0], [4.553000701650949, 0.0], [4.653000701650949, 0.0], [4.753000701650949, 0.0], [4.853000701650949, 0.0], [4.953000701650949, 0.0], [5.05300070165095, 0.0], [5.153000701650949, 0.0], [5.25300070165095, 0.0], [5.3530007016509495, 0.0], [5.45300070165095, 0.0], [5.55300070165095, 0.0], [5.65300070165095, 0.0], [5.75300070165095, 0.0], [5.85300070165095, 0.0], [5.95300070165095, 0.0], [6.053000701650951, 0.0], [6.15300070165095, 0.0], [6.253000701650951, 0.0], [6.35300070165095, 0.0], [6.453000701650951, 0.0], [6.553000701650951, 0.0], [6.653000701650951, 0.0], [6.753000701650951, 0.0], [6.853000701650951, 0.0], [6.953000701650951, 0.0], [7.0530007016509515, 0.0], [7.153000701650951, 0.0], [7.253000701650951, 0.0], [7.35300070165095, 0.0], [7.45300070165095, 0.0], [7.55300070165095, 0.0], [7.653000701650949, 0.0], [7.753000701650949, 0.0], [7.853000701650949, 0.0], [7.953000701650948, 0.0], [8.053000701650948, 0.0], [8.153000701650948, 0.0], [8.253000701650947, 0.0], [8.353000701650947, 0.0], [8.453000701650947, 0.0], [8.553000701650946, 0.0], [8.653000701650946, 0.0], [8.753000701650945, 0.0], [8.853000701650945, 0.0], [8.953000701650945, 0.0], [9.053000701650944, 0.0], [9.153000701650944, 0.0], [9.253000701650944, 0.0], [9.353000701650943, 0.0], [9.453000701650943, 0.0], [9.553000701650943, 0.0], [9.653000701650942, 0.0], [9.753000701650942, 0.0], [9.853000701650942, 0.0], [9.953000701650941, 0.0], [10.05300070165094, 0.0], [10.15300070165094, 0.0], [10.25300070165094, 0.0], [10.35300070165094, 0.0], [10.45300070165094, 0.0], [10.553000701650939, 0.0], [10.653000701650939, 0.0], [10.753000701650938, 0.0], [10.853000701650938, 0.0], [10.953000701650938, 0.0], [11.053000701650937, 0.0], [11.153000701650937, 0.0], [11.253000701650937, 0.0], [11.353000701650936, 0.0], [11.453000701650936, 0.0], [11.553000701650936, 0.0], [11.653000701650935, 0.0], [11.753000701650935, 0.0], [11.853000701650934, 0.0], [11.953000701650934, 0.0], [12.053000701650934, 0.0], [12.153000701650933, 0.0], [12.253000701650933, 0.0], [12.353000701650933, 0.0], [12.453000701650932, 0.0], [12.553000701650932, 0.0], [12.653000701650932, 0.0], [12.753000701650931, 0.0], [12.853000701650931, 0.0], [12.95300070165093, 0.0], [13.05300070165093, 0.0], [13.15300070165093, 0.0], [13.25300070165093, 0.0], [13.35300070165093, 0.0], [13.453000701650929, 0.0], [13.553000701650928, 0.0], [13.653000701650928, 0.0], [13.753000701650928, 0.0], [13.853000701650927, 0.0], [13.953000701650927, 0.0], [14.053000701650927, 0.0], [14.153000701650926, 0.0], [14.253000701650926, 0.0], [14.353000701650926, 0.0], [14.453000701650925, 0.0], [14.553000701650925, 0.0], [14.653000701650924, 0.0], [14.752991697440526, 0.0], [14.842391557110341, 0.0], [14.911791416780156, 0.0], [14.961191276449972, 0.0], [14.990591136119786, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552, 12.06329931618552], "velocities": null}}, "time": 1740481171.8636267} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669858437025295, "gear": 1, "accelerator_pedal_position": 0.24411480124617194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.8636267} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.8836267} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666989731964188, "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": 1740481171.8836267} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 3.090455373258246, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.966369928794845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576572048325318, "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": 1740481171.9036267} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23664205724692405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661258287507418, "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": 1740481171.9036267} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481171.9236267, "x": 7.196761948882999, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9236267} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24421960896673525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655534786987786, "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": 1740481171.9236267} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9436266} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416023072130294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659287875229806, "gear": 1, "accelerator_pedal_position": 0.24421960896673525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481171.9436266} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9636266} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.1967619488829992, 0.0], [3.359270223182041, 0.0], [3.459270223182041, 0.0], [3.559270223182041, 0.0], [3.6592702231820406, 0.0], [3.7592702231820407, 0.0], [3.859270223182041, 0.0], [3.959270223182041, 0.0], [4.059270223182041, 0.0], [4.159270223182041, 0.0], [4.259270223182041, 0.0], [4.35927022318204, 0.0], [4.459270223182041, 0.0], [4.5592702231820414, 0.0], [4.659270223182041, 0.0], [4.759270223182041, 0.0], [4.859270223182041, 0.0], [4.959270223182042, 0.0], [5.0592702231820414, 0.0], [5.159270223182041, 0.0], [5.259270223182042, 0.0], [5.359270223182041, 0.0], [5.459270223182042, 0.0], [5.5592702231820414, 0.0], [5.659270223182042, 0.0], [5.759270223182042, 0.0], [5.859270223182042, 0.0], [5.959270223182042, 0.0], [6.059270223182042, 0.0], [6.159270223182042, 0.0], [6.2592702231820425, 0.0], [6.359270223182042, 0.0], [6.459270223182043, 0.0], [6.559270223182042, 0.0], [6.659270223182043, 0.0], [6.7592702231820425, 0.0], [6.859270223182043, 0.0], [6.959270223182043, 0.0], [7.059270223182043, 0.0], [7.159270223182043, 0.0], [7.259270223182043, 0.0], [7.359270223182043, 0.0], [7.459270223182043, 0.0], [7.559270223182042, 0.0], [7.659270223182042, 0.0], [7.759270223182042, 0.0], [7.859270223182041, 0.0], [7.959270223182041, 0.0], [8.05927022318204, 0.0], [8.159270223182041, 0.0], [8.259270223182039, 0.0], [8.35927022318204, 0.0], [8.459270223182038, 0.0], [8.55927022318204, 0.0], [8.659270223182038, 0.0], [8.759270223182039, 0.0], [8.859270223182037, 0.0], [8.959270223182038, 0.0], [9.059270223182036, 0.0], [9.159270223182038, 0.0], [9.259270223182035, 0.0], [9.359270223182037, 0.0], [9.459270223182035, 0.0], [9.559270223182036, 0.0], [9.659270223182034, 0.0], [9.759270223182035, 0.0], [9.859270223182033, 0.0], [9.959270223182035, 0.0], [10.059270223182033, 0.0], [10.159270223182034, 0.0], [10.259270223182032, 0.0], [10.359270223182033, 0.0], [10.459270223182031, 0.0], [10.559270223182033, 0.0], [10.65927022318203, 0.0], [10.759270223182032, 0.0], [10.85927022318203, 0.0], [10.959270223182031, 0.0], [11.059270223182029, 0.0], [11.15927022318203, 0.0], [11.25927022318203, 0.0], [11.35927022318203, 0.0], [11.45927022318203, 0.0], [11.559270223182029, 0.0], [11.659270223182029, 0.0], [11.759270223182028, 0.0], [11.859270223182028, 0.0], [11.959270223182028, 0.0], [12.059270223182027, 0.0], [12.159270223182027, 0.0], [12.259270223182027, 0.0], [12.359270223182026, 0.0], [12.459270223182026, 0.0], [12.559270223182025, 0.0], [12.659270223182025, 0.0], [12.759270223182025, 0.0], [12.859270223182024, 0.0], [12.959270223182024, 0.0], [13.059270223182024, 0.0], [13.159270223182023, 0.0], [13.259270223182023, 0.0], [13.359270223182023, 0.0], [13.459270223182022, 0.0], [13.559270223182022, 0.0], [13.659270223182022, 0.0], [13.759270223182021, 0.0], [13.85927022318202, 0.0], [13.95927022318202, 0.0], [14.05927022318202, 0.0], [14.15927022318202, 0.0], [14.25927022318202, 0.0], [14.359270223182019, 0.0], [14.459270223182019, 0.0], [14.559270223182018, 0.0], [14.659270223182018, 0.0], [14.759184286144173, 0.0], [14.84733024150777, 0.0], [14.915476196871365, 0.0], [14.963622152234962, 0.0], [14.991768107598558, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552, 11.96329931618552], "velocities": null}}, "time": 1740481171.9636266} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660156595999737, "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": 1740481171.9636266} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481171.9836266} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657353571330491, "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": 1740481171.9836266} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481172.0036266} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651753349448925, "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": 1740481172.0036266} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 3.1967619488829992, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655534786987786, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25760060913721206, "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": 1740481172.0236266} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23673638381335443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646160887491395, "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": 1740481172.0236266} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.0336266, "x": 7.302977203492276, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0436265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447701443379183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640576173454803, "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": 1740481172.0436265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0636265} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.3029772034922757, 0.0], [3.4654286083757446, 0.0], [3.5654286083757443, 0.0], [3.6654286083757444, 0.0], [3.7654286083757444, 0.0], [3.8654286083757445, 0.0], [3.9654286083757446, 0.0], [4.065428608375744, 0.0], [4.165428608375745, 0.0], [4.2654286083757444, 0.0], [4.365428608375744, 0.0], [4.465428608375744, 0.0], [4.565428608375744, 0.0], [4.665428608375745, 0.0], [4.7654286083757444, 0.0], [4.865428608375744, 0.0], [4.965428608375745, 0.0], [5.065428608375745, 0.0], [5.165428608375745, 0.0], [5.2654286083757444, 0.0], [5.365428608375746, 0.0], [5.4654286083757455, 0.0], [5.565428608375745, 0.0], [5.665428608375746, 0.0], [5.765428608375746, 0.0], [5.865428608375746, 0.0], [5.9654286083757455, 0.0], [6.065428608375746, 0.0], [6.165428608375747, 0.0], [6.265428608375746, 0.0], [6.365428608375746, 0.0], [6.465428608375746, 0.0], [6.565428608375747, 0.0], [6.665428608375747, 0.0], [6.765428608375746, 0.0], [6.865428608375747, 0.0], [6.965428608375747, 0.0], [7.065428608375747, 0.0], [7.165428608375747, 0.0], [7.265428608375747, 0.0], [7.365428608375747, 0.0], [7.465428608375746, 0.0], [7.565428608375746, 0.0], [7.665428608375746, 0.0], [7.765428608375745, 0.0], [7.865428608375745, 0.0], [7.965428608375745, 0.0], [8.065428608375743, 0.0], [8.165428608375745, 0.0], [8.265428608375743, 0.0], [8.365428608375744, 0.0], [8.465428608375742, 0.0], [8.565428608375743, 0.0], [8.665428608375741, 0.0], [8.765428608375743, 0.0], [8.86542860837574, 0.0], [8.965428608375742, 0.0], [9.06542860837574, 0.0], [9.165428608375741, 0.0], [9.26542860837574, 0.0], [9.36542860837574, 0.0], [9.465428608375738, 0.0], [9.56542860837574, 0.0], [9.665428608375738, 0.0], [9.76542860837574, 0.0], [9.865428608375737, 0.0], [9.965428608375738, 0.0], [10.065428608375736, 0.0], [10.165428608375738, 0.0], [10.265428608375736, 0.0], [10.365428608375737, 0.0], [10.465428608375735, 0.0], [10.565428608375736, 0.0], [10.665428608375734, 0.0], [10.765428608375736, 0.0], [10.865428608375733, 0.0], [10.965428608375735, 0.0], [11.065428608375733, 0.0], [11.165428608375734, 0.0], [11.265428608375732, 0.0], [11.365428608375733, 0.0], [11.465428608375733, 0.0], [11.565428608375733, 0.0], [11.665428608375732, 0.0], [11.765428608375732, 0.0], [11.865428608375732, 0.0], [11.965428608375731, 0.0], [12.065428608375731, 0.0], [12.16542860837573, 0.0], [12.26542860837573, 0.0], [12.36542860837573, 0.0], [12.46542860837573, 0.0], [12.56542860837573, 0.0], [12.665428608375729, 0.0], [12.765428608375728, 0.0], [12.865428608375728, 0.0], [12.965428608375728, 0.0], [13.065428608375727, 0.0], [13.165428608375727, 0.0], [13.265428608375727, 0.0], [13.365428608375726, 0.0], [13.465428608375726, 0.0], [13.565428608375726, 0.0], [13.665428608375725, 0.0], [13.765428608375725, 0.0], [13.865428608375725, 0.0], [13.965428608375724, 0.0], [14.065428608375724, 0.0], [14.165428608375723, 0.0], [14.265428608375723, 0.0], [14.365428608375723, 0.0], [14.465428608375722, 0.0], [14.565428608375722, 0.0], [14.665428608375722, 0.0], [14.76519056641931, 0.0], [14.852104844744165, 0.0], [14.91901912306902, 0.0], [14.965933401393876, 0.0], [14.992847679718732, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552, 11.86329931618552], "velocities": null}}, "time": 1740481172.0636265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647266471053665, "gear": 1, "accelerator_pedal_position": 0.2447701443379183, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.0636265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.0836265} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481172.913456, "x": 15.0, "y": 4.37999999999995, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.0836265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644559227177874, "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": 1740481172.0836265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.1036265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639150365676138, "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": 1740481172.1036265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 3.3029772034922757, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643367562732322, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575162916086574, "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": 1740481172.1236265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687533898139249, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633748996205559, "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": 1740481172.1236265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.1436265, "x": 7.409023071746164, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1436265} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2455325200171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628355107222036, "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": 1740481172.1436265} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1636264} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.409023071746164, 0.0], [3.5714015884228565, 0.0], [3.6714015884228566, 0.0], [3.771401588422856, 0.0], [3.8714015884228563, 0.0], [3.9714015884228564, 0.0], [4.071401588422856, 0.0], [4.171401588422857, 0.0], [4.271401588422856, 0.0], [4.371401588422856, 0.0], [4.471401588422856, 0.0], [4.571401588422856, 0.0], [4.671401588422857, 0.0], [4.771401588422856, 0.0], [4.871401588422857, 0.0], [4.971401588422856, 0.0], [5.071401588422857, 0.0], [5.171401588422857, 0.0], [5.271401588422857, 0.0], [5.371401588422857, 0.0], [5.471401588422857, 0.0], [5.571401588422857, 0.0], [5.671401588422857, 0.0], [5.771401588422857, 0.0], [5.871401588422858, 0.0], [5.971401588422857, 0.0], [6.071401588422857, 0.0], [6.1714015884228575, 0.0], [6.271401588422858, 0.0], [6.371401588422858, 0.0], [6.471401588422857, 0.0], [6.571401588422858, 0.0], [6.671401588422858, 0.0], [6.771401588422858, 0.0], [6.871401588422858, 0.0], [6.971401588422858, 0.0], [7.071401588422859, 0.0], [7.171401588422858, 0.0], [7.271401588422858, 0.0], [7.3714015884228585, 0.0], [7.471401588422859, 0.0], [7.571401588422859, 0.0], [7.671401588422858, 0.0], [7.771401588422858, 0.0], [7.871401588422858, 0.0], [7.971401588422857, 0.0], [8.071401588422857, 0.0], [8.171401588422857, 0.0], [8.271401588422856, 0.0], [8.371401588422856, 0.0], [8.471401588422856, 0.0], [8.571401588422855, 0.0], [8.671401588422855, 0.0], [8.771401588422854, 0.0], [8.871401588422854, 0.0], [8.971401588422854, 0.0], [9.071401588422853, 0.0], [9.171401588422853, 0.0], [9.271401588422853, 0.0], [9.371401588422852, 0.0], [9.471401588422852, 0.0], [9.571401588422852, 0.0], [9.671401588422851, 0.0], [9.771401588422851, 0.0], [9.87140158842285, 0.0], [9.97140158842285, 0.0], [10.07140158842285, 0.0], [10.17140158842285, 0.0], [10.27140158842285, 0.0], [10.371401588422849, 0.0], [10.471401588422848, 0.0], [10.571401588422848, 0.0], [10.671401588422848, 0.0], [10.771401588422847, 0.0], [10.871401588422847, 0.0], [10.971401588422847, 0.0], [11.071401588422846, 0.0], [11.171401588422846, 0.0], [11.271401588422846, 0.0], [11.371401588422845, 0.0], [11.471401588422845, 0.0], [11.571401588422844, 0.0], [11.671401588422844, 0.0], [11.771401588422844, 0.0], [11.871401588422843, 0.0], [11.971401588422843, 0.0], [12.071401588422843, 0.0], [12.171401588422842, 0.0], [12.271401588422842, 0.0], [12.371401588422842, 0.0], [12.471401588422841, 0.0], [12.571401588422841, 0.0], [12.67140158842284, 0.0], [12.77140158842284, 0.0], [12.87140158842284, 0.0], [12.97140158842284, 0.0], [13.07140158842284, 0.0], [13.171401588422839, 0.0], [13.271401588422838, 0.0], [13.371401588422838, 0.0], [13.471401588422838, 0.0], [13.571401588422837, 0.0], [13.671401588422837, 0.0], [13.771401588422837, 0.0], [13.871401588422836, 0.0], [13.971401588422836, 0.0], [14.071401588422836, 0.0], [14.171401588422835, 0.0], [14.271401588422835, 0.0], [14.371401588422835, 0.0], [14.471401588422834, 0.0], [14.571401588422834, 0.0], [14.671401588422833, 0.0], [14.770943560435812, 0.0], [14.856663242751246, 0.0], [14.92238292506668, 0.0], [14.968102607382113, 0.0], [14.993822289697546, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552, 11.76329931618552], "velocities": null}}, "time": 1740481172.1636264} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963649924959213, "gear": 1, "accelerator_pedal_position": 0.2455325200171985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.1636264} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.1836264} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633904955479216, "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": 1740481172.1836264} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2036264} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628721757108132, "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": 1740481172.2036264} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2236264} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620960413517221, "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": 1740481172.2236264} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 3.409023071746164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9628355107222036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574122977431871, "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": 1740481172.2436264} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704412270360958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618376881207433, "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": 1740481172.2436264} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.2536263, "x": 7.514935739273505, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.2636263} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.514935739273505, 0.0], [3.6772509662843778, 0.0], [3.7772509662843774, 0.0], [3.8772509662843775, 0.0], [3.9772509662843776, 0.0], [4.077250966284377, 0.0], [4.177250966284378, 0.0], [4.277250966284377, 0.0], [4.377250966284377, 0.0], [4.477250966284378, 0.0], [4.577250966284377, 0.0], [4.677250966284378, 0.0], [4.777250966284377, 0.0], [4.877250966284377, 0.0], [4.977250966284378, 0.0], [5.077250966284378, 0.0], [5.177250966284378, 0.0], [5.277250966284377, 0.0], [5.377250966284378, 0.0], [5.4772509662843785, 0.0], [5.577250966284378, 0.0], [5.677250966284379, 0.0], [5.777250966284379, 0.0], [5.877250966284379, 0.0], [5.9772509662843785, 0.0], [6.077250966284379, 0.0], [6.1772509662843795, 0.0], [6.277250966284379, 0.0], [6.377250966284379, 0.0], [6.477250966284379, 0.0], [6.57725096628438, 0.0], [6.6772509662843795, 0.0], [6.777250966284379, 0.0], [6.87725096628438, 0.0], [6.97725096628438, 0.0], [7.07725096628438, 0.0], [7.1772509662843795, 0.0], [7.27725096628438, 0.0], [7.377250966284381, 0.0], [7.47725096628438, 0.0], [7.57725096628438, 0.0], [7.6772509662843795, 0.0], [7.777250966284379, 0.0], [7.877250966284379, 0.0], [7.9772509662843785, 0.0], [8.077250966284378, 0.0], [8.177250966284378, 0.0], [8.277250966284377, 0.0], [8.377250966284377, 0.0], [8.477250966284377, 0.0], [8.577250966284376, 0.0], [8.677250966284376, 0.0], [8.777250966284376, 0.0], [8.877250966284375, 0.0], [8.977250966284375, 0.0], [9.077250966284375, 0.0], [9.177250966284374, 0.0], [9.277250966284374, 0.0], [9.377250966284373, 0.0], [9.477250966284373, 0.0], [9.577250966284373, 0.0], [9.677250966284372, 0.0], [9.777250966284372, 0.0], [9.877250966284372, 0.0], [9.977250966284371, 0.0], [10.077250966284371, 0.0], [10.17725096628437, 0.0], [10.27725096628437, 0.0], [10.37725096628437, 0.0], [10.47725096628437, 0.0], [10.57725096628437, 0.0], [10.677250966284369, 0.0], [10.777250966284369, 0.0], [10.877250966284368, 0.0], [10.977250966284368, 0.0], [11.077250966284367, 0.0], [11.177250966284367, 0.0], [11.277250966284367, 0.0], [11.377250966284366, 0.0], [11.477250966284366, 0.0], [11.577250966284364, 0.0], [11.677250966284364, 0.0], [11.777250966284363, 0.0], [11.877250966284363, 0.0], [11.977250966284362, 0.0], [12.077250966284362, 0.0], [12.177250966284362, 0.0], [12.277250966284361, 0.0], [12.377250966284361, 0.0], [12.47725096628436, 0.0], [12.57725096628436, 0.0], [12.67725096628436, 0.0], [12.77725096628436, 0.0], [12.87725096628436, 0.0], [12.977250966284359, 0.0], [13.077250966284359, 0.0], [13.177250966284358, 0.0], [13.277250966284358, 0.0], [13.377250966284358, 0.0], [13.477250966284357, 0.0], [13.577250966284357, 0.0], [13.677250966284356, 0.0], [13.777250966284356, 0.0], [13.877250966284356, 0.0], [13.977250966284355, 0.0], [14.077250966284355, 0.0], [14.177250966284355, 0.0], [14.277250966284354, 0.0], [14.377250966284354, 0.0], [14.477250966284354, 0.0], [14.577250966284353, 0.0], [14.677250966284353, 0.0], [14.776508351120922, 0.0], [14.86105815786405, 0.0], [14.925607964607181, 0.0], [14.97015777135031, 0.0], [14.99470757809344, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521, 11.66329931618552], "velocities": null}}, "time": 1740481172.2636263} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24688829511344537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961678961947166, "gear": 1, "accelerator_pedal_position": 0.24688829511344537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.2636263} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.2836263} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620361582681975, "gear": 1, "accelerator_pedal_position": 0.24688829511344537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.2836263} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3036263} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627419170399103, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3036263} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3236263} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634466986557209, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3236263} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 3.514935739273505, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615795137718296, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732532730164814, "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": 1740481172.3436263} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.1312976, "x": 15.0, "y": 4.489999999999948, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.3436263} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24682513661813998, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964150504269929, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3436263} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.3636262, "x": 7.620843135540897, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.3636262} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.6208431355408974, 0.0], [3.7833189263543843, 0.0], [3.8833189263543844, 0.0], [3.9833189263543844, 0.0], [4.0833189263543845, 0.0], [4.183318926354384, 0.0], [4.283318926354385, 0.0], [4.383318926354384, 0.0], [4.483318926354384, 0.0], [4.5833189263543845, 0.0], [4.683318926354384, 0.0], [4.783318926354385, 0.0], [4.883318926354384, 0.0], [4.983318926354384, 0.0], [5.0833189263543845, 0.0], [5.183318926354385, 0.0], [5.283318926354385, 0.0], [5.383318926354384, 0.0], [5.483318926354385, 0.0], [5.583318926354385, 0.0], [5.683318926354385, 0.0], [5.783318926354386, 0.0], [5.883318926354385, 0.0], [5.983318926354386, 0.0], [6.083318926354385, 0.0], [6.183318926354386, 0.0], [6.283318926354386, 0.0], [6.383318926354386, 0.0], [6.483318926354386, 0.0], [6.583318926354386, 0.0], [6.683318926354386, 0.0], [6.7833189263543865, 0.0], [6.883318926354386, 0.0], [6.983318926354387, 0.0], [7.083318926354386, 0.0], [7.183318926354387, 0.0], [7.2833189263543865, 0.0], [7.383318926354387, 0.0], [7.483318926354387, 0.0], [7.583318926354387, 0.0], [7.683318926354387, 0.0], [7.7833189263543865, 0.0], [7.883318926354386, 0.0], [7.983318926354386, 0.0], [8.083318926354385, 0.0], [8.183318926354385, 0.0], [8.283318926354385, 0.0], [8.383318926354384, 0.0], [8.483318926354384, 0.0], [8.583318926354384, 0.0], [8.683318926354383, 0.0], [8.783318926354383, 0.0], [8.883318926354383, 0.0], [8.983318926354382, 0.0], [9.083318926354382, 0.0], [9.183318926354382, 0.0], [9.283318926354381, 0.0], [9.38331892635438, 0.0], [9.48331892635438, 0.0], [9.58331892635438, 0.0], [9.68331892635438, 0.0], [9.78331892635438, 0.0], [9.883318926354379, 0.0], [9.983318926354379, 0.0], [10.083318926354378, 0.0], [10.183318926354378, 0.0], [10.283318926354378, 0.0], [10.383318926354377, 0.0], [10.483318926354377, 0.0], [10.583318926354377, 0.0], [10.683318926354376, 0.0], [10.783318926354376, 0.0], [10.883318926354375, 0.0], [10.983318926354375, 0.0], [11.083318926354375, 0.0], [11.183318926354374, 0.0], [11.283318926354374, 0.0], [11.383318926354374, 0.0], [11.483318926354373, 0.0], [11.583318926354373, 0.0], [11.683318926354373, 0.0], [11.783318926354372, 0.0], [11.883318926354372, 0.0], [11.983318926354372, 0.0], [12.083318926354371, 0.0], [12.18331892635437, 0.0], [12.28331892635437, 0.0], [12.38331892635437, 0.0], [12.48331892635437, 0.0], [12.58331892635437, 0.0], [12.683318926354369, 0.0], [12.783318926354369, 0.0], [12.883318926354368, 0.0], [12.983318926354368, 0.0], [13.083318926354368, 0.0], [13.183318926354367, 0.0], [13.283318926354367, 0.0], [13.383318926354367, 0.0], [13.483318926354366, 0.0], [13.583318926354366, 0.0], [13.683318926354366, 0.0], [13.783318926354365, 0.0], [13.883318926354365, 0.0], [13.983318926354364, 0.0], [14.083318926354364, 0.0], [14.183318926354364, 0.0], [14.283318926354363, 0.0], [14.383318926354363, 0.0], [14.483318926354363, 0.0], [14.583318926354362, 0.0], [14.683318926354362, 0.0], [14.782208775500955, 0.0], [14.865544990230081, 0.0], [14.92888120495921, 0.0], [14.972217419688336, 0.0], [14.995553634417465, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521], "velocities": null}}, "time": 1740481172.3636262} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24471886014937735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648533350360611, "gear": 1, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3636262} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.3836262} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652919987800211, "gear": 1, "accelerator_pedal_position": 0.24471886014937735, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.3836262} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4036262} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657508709072564, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4036262} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4236262} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662091071414193, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4236262} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4436262} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666667082797507, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4436262} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 3.6208431355408974, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648533350360611, "accelerator_pedal_position": 0.24682513661813998, "brake_pedal_position": 0.0, "acceleration": 0.03510501753026968, "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": 1740481172.4636261} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.6208431355408974, 0.0], [3.7833189263543843, 0.0], [3.8833189263543844, 0.0], [3.9833189263543844, 0.0], [4.0833189263543845, 0.0], [4.183318926354384, 0.0], [4.283318926354385, 0.0], [4.383318926354384, 0.0], [4.483318926354384, 0.0], [4.5833189263543845, 0.0], [4.683318926354384, 0.0], [4.783318926354385, 0.0], [4.883318926354384, 0.0], [4.983318926354384, 0.0], [5.0833189263543845, 0.0], [5.183318926354385, 0.0], [5.283318926354385, 0.0], [5.383318926354384, 0.0], [5.483318926354385, 0.0], [5.583318926354385, 0.0], [5.683318926354385, 0.0], [5.783318926354386, 0.0], [5.883318926354385, 0.0], [5.983318926354386, 0.0], [6.083318926354385, 0.0], [6.183318926354386, 0.0], [6.283318926354386, 0.0], [6.383318926354386, 0.0], [6.483318926354386, 0.0], [6.583318926354386, 0.0], [6.683318926354386, 0.0], [6.7833189263543865, 0.0], [6.883318926354386, 0.0], [6.983318926354387, 0.0], [7.083318926354386, 0.0], [7.183318926354387, 0.0], [7.2833189263543865, 0.0], [7.383318926354387, 0.0], [7.483318926354387, 0.0], [7.583318926354387, 0.0], [7.683318926354387, 0.0], [7.7833189263543865, 0.0], [7.883318926354386, 0.0], [7.983318926354386, 0.0], [8.083318926354385, 0.0], [8.183318926354385, 0.0], [8.283318926354385, 0.0], [8.383318926354384, 0.0], [8.483318926354384, 0.0], [8.583318926354384, 0.0], [8.683318926354383, 0.0], [8.783318926354383, 0.0], [8.883318926354383, 0.0], [8.983318926354382, 0.0], [9.083318926354382, 0.0], [9.183318926354382, 0.0], [9.283318926354381, 0.0], [9.38331892635438, 0.0], [9.48331892635438, 0.0], [9.58331892635438, 0.0], [9.68331892635438, 0.0], [9.78331892635438, 0.0], [9.883318926354379, 0.0], [9.983318926354379, 0.0], [10.083318926354378, 0.0], [10.183318926354378, 0.0], [10.283318926354378, 0.0], [10.383318926354377, 0.0], [10.483318926354377, 0.0], [10.583318926354377, 0.0], [10.683318926354376, 0.0], [10.783318926354376, 0.0], [10.883318926354375, 0.0], [10.983318926354375, 0.0], [11.083318926354375, 0.0], [11.183318926354374, 0.0], [11.283318926354374, 0.0], [11.383318926354374, 0.0], [11.483318926354373, 0.0], [11.583318926354373, 0.0], [11.683318926354373, 0.0], [11.783318926354372, 0.0], [11.883318926354372, 0.0], [11.983318926354372, 0.0], [12.083318926354371, 0.0], [12.18331892635437, 0.0], [12.28331892635437, 0.0], [12.38331892635437, 0.0], [12.48331892635437, 0.0], [12.58331892635437, 0.0], [12.683318926354369, 0.0], [12.783318926354369, 0.0], [12.883318926354368, 0.0], [12.983318926354368, 0.0], [13.083318926354368, 0.0], [13.183318926354367, 0.0], [13.283318926354367, 0.0], [13.383318926354367, 0.0], [13.483318926354366, 0.0], [13.583318926354366, 0.0], [13.683318926354366, 0.0], [13.783318926354365, 0.0], [13.883318926354365, 0.0], [13.983318926354364, 0.0], [14.083318926354364, 0.0], [14.183318926354364, 0.0], [14.283318926354363, 0.0], [14.383318926354363, 0.0], [14.483318926354363, 0.0], [14.583318926354362, 0.0], [14.683318926354362, 0.0], [14.782208775500955, 0.0], [14.865544990230081, 0.0], [14.92888120495921, 0.0], [14.972217419688336, 0.0], [14.995553634417465, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521, 11.563299316185521], "velocities": null}}, "time": 1740481172.4636261} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24488544742063412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673519209246686, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4636261} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.4736261, "x": 7.72710116833111, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.4836261} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23740874420968505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675800084541042, "gear": 1, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.4836261} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.503626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671014452547584, "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": 1740481172.503626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.523626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966600422113699, "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": 1740481172.523626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.543626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722369265205417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966100093495708, "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": 1740481172.543626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 3.72710116833111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9673519209246686, "accelerator_pedal_position": 0.24488544742063412, "brake_pedal_position": 0.0, "acceleration": 0.02280875294356327, "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": 1740481172.563626} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.72710116833111, 0.0], [3.889689886471783, 0.0], [3.9896898864717825, 0.0], [4.089689886471783, 0.0], [4.189689886471783, 0.0], [4.289689886471782, 0.0], [4.389689886471783, 0.0], [4.4896898864717825, 0.0], [4.589689886471783, 0.0], [4.689689886471783, 0.0], [4.789689886471782, 0.0], [4.889689886471783, 0.0], [4.9896898864717825, 0.0], [5.089689886471783, 0.0], [5.189689886471783, 0.0], [5.289689886471783, 0.0], [5.389689886471783, 0.0], [5.489689886471783, 0.0], [5.589689886471783, 0.0], [5.6896898864717835, 0.0], [5.789689886471783, 0.0], [5.889689886471784, 0.0], [5.989689886471783, 0.0], [6.089689886471784, 0.0], [6.1896898864717835, 0.0], [6.289689886471784, 0.0], [6.389689886471784, 0.0], [6.489689886471784, 0.0], [6.589689886471784, 0.0], [6.689689886471784, 0.0], [6.789689886471784, 0.0], [6.889689886471785, 0.0], [6.989689886471784, 0.0], [7.089689886471785, 0.0], [7.189689886471784, 0.0], [7.289689886471785, 0.0], [7.389689886471785, 0.0], [7.489689886471785, 0.0], [7.589689886471785, 0.0], [7.689689886471785, 0.0], [7.789689886471785, 0.0], [7.889689886471785, 0.0], [7.989689886471784, 0.0], [8.089689886471785, 0.0], [8.189689886471783, 0.0], [8.289689886471784, 0.0], [8.389689886471782, 0.0], [8.489689886471783, 0.0], [8.589689886471781, 0.0], [8.689689886471783, 0.0], [8.78968988647178, 0.0], [8.889689886471782, 0.0], [8.98968988647178, 0.0], [9.089689886471781, 0.0], [9.189689886471779, 0.0], [9.28968988647178, 0.0], [9.389689886471778, 0.0], [9.48968988647178, 0.0], [9.589689886471778, 0.0], [9.689689886471779, 0.0], [9.789689886471777, 0.0], [9.889689886471778, 0.0], [9.989689886471776, 0.0], [10.089689886471778, 0.0], [10.189689886471776, 0.0], [10.289689886471777, 0.0], [10.389689886471775, 0.0], [10.489689886471776, 0.0], [10.589689886471774, 0.0], [10.689689886471776, 0.0], [10.789689886471773, 0.0], [10.889689886471775, 0.0], [10.989689886471773, 0.0], [11.089689886471774, 0.0], [11.189689886471772, 0.0], [11.289689886471773, 0.0], [11.389689886471771, 0.0], [11.489689886471773, 0.0], [11.58968988647177, 0.0], [11.689689886471772, 0.0], [11.789689886471772, 0.0], [11.88968988647177, 0.0], [11.989689886471771, 0.0], [12.089689886471769, 0.0], [12.18968988647177, 0.0], [12.289689886471768, 0.0], [12.38968988647177, 0.0], [12.489689886471767, 0.0], [12.589689886471769, 0.0], [12.689689886471767, 0.0], [12.789689886471768, 0.0], [12.889689886471766, 0.0], [12.989689886471767, 0.0], [13.089689886471765, 0.0], [13.189689886471767, 0.0], [13.289689886471765, 0.0], [13.389689886471766, 0.0], [13.489689886471764, 0.0], [13.589689886471765, 0.0], [13.689689886471763, 0.0], [13.789689886471765, 0.0], [13.889689886471762, 0.0], [13.989689886471764, 0.0], [14.089689886471762, 0.0], [14.189689886471763, 0.0], [14.289689886471761, 0.0], [14.389689886471762, 0.0], [14.48968988647176, 0.0], [14.589689886471762, 0.0], [14.68968988647176, 0.0], [14.78811459938362, 0.0], [14.870176622089268, 0.0], [14.932238644794914, 0.0], [14.974300667500563, 0.0], [14.99636269020621, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522, 11.463299316185521], "velocities": null}}, "time": 1740481172.563626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365274516031902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656004583379342, "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": 1740481172.563626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.583626, "x": 7.8334215041811595, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.583626} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.3513753, "x": 15.0, "y": 4.5999999999999455, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.583626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403384021874364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650145156071125, "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": 1740481172.583626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.603626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965367358209814, "gear": 1, "accelerator_pedal_position": 0.24403384021874364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.603626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.623626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656984701072164, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.623626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.643626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24386384694262134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660291231610603, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.643626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.663626} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.8334215041811595, 0.0], [3.995904830954568, 0.0], [4.095904830954568, 0.0], [4.195904830954568, 0.0], [4.2959048309545675, 0.0], [4.395904830954568, 0.0], [4.495904830954568, 0.0], [4.595904830954568, 0.0], [4.695904830954568, 0.0], [4.7959048309545675, 0.0], [4.895904830954568, 0.0], [4.995904830954568, 0.0], [5.095904830954568, 0.0], [5.195904830954568, 0.0], [5.295904830954568, 0.0], [5.395904830954568, 0.0], [5.495904830954569, 0.0], [5.595904830954568, 0.0], [5.695904830954569, 0.0], [5.795904830954568, 0.0], [5.895904830954569, 0.0], [5.995904830954569, 0.0], [6.095904830954569, 0.0], [6.195904830954569, 0.0], [6.295904830954569, 0.0], [6.395904830954569, 0.0], [6.4959048309545695, 0.0], [6.595904830954569, 0.0], [6.69590483095457, 0.0], [6.795904830954569, 0.0], [6.89590483095457, 0.0], [6.9959048309545695, 0.0], [7.09590483095457, 0.0], [7.19590483095457, 0.0], [7.29590483095457, 0.0], [7.39590483095457, 0.0], [7.49590483095457, 0.0], [7.59590483095457, 0.0], [7.695904830954571, 0.0], [7.79590483095457, 0.0], [7.89590483095457, 0.0], [7.9959048309545695, 0.0], [8.09590483095457, 0.0], [8.195904830954568, 0.0], [8.29590483095457, 0.0], [8.395904830954567, 0.0], [8.495904830954569, 0.0], [8.595904830954566, 0.0], [8.695904830954568, 0.0], [8.795904830954566, 0.0], [8.895904830954567, 0.0], [8.995904830954565, 0.0], [9.095904830954566, 0.0], [9.195904830954564, 0.0], [9.295904830954566, 0.0], [9.395904830954564, 0.0], [9.495904830954565, 0.0], [9.595904830954563, 0.0], [9.695904830954564, 0.0], [9.795904830954562, 0.0], [9.895904830954564, 0.0], [9.995904830954562, 0.0], [10.095904830954563, 0.0], [10.19590483095456, 0.0], [10.295904830954562, 0.0], [10.39590483095456, 0.0], [10.495904830954562, 0.0], [10.59590483095456, 0.0], [10.69590483095456, 0.0], [10.795904830954559, 0.0], [10.89590483095456, 0.0], [10.995904830954558, 0.0], [11.09590483095456, 0.0], [11.195904830954559, 0.0], [11.295904830954559, 0.0], [11.395904830954558, 0.0], [11.495904830954558, 0.0], [11.595904830954558, 0.0], [11.695904830954557, 0.0], [11.795904830954557, 0.0], [11.895904830954557, 0.0], [11.995904830954556, 0.0], [12.095904830954556, 0.0], [12.195904830954555, 0.0], [12.295904830954555, 0.0], [12.395904830954555, 0.0], [12.495904830954554, 0.0], [12.595904830954554, 0.0], [12.695904830954554, 0.0], [12.795904830954553, 0.0], [12.895904830954553, 0.0], [12.995904830954553, 0.0], [13.095904830954552, 0.0], [13.195904830954552, 0.0], [13.295904830954552, 0.0], [13.395904830954551, 0.0], [13.49590483095455, 0.0], [13.59590483095455, 0.0], [13.69590483095455, 0.0], [13.79590483095455, 0.0], [13.89590483095455, 0.0], [13.995904830954549, 0.0], [14.095904830954549, 0.0], [14.195904830954548, 0.0], [14.295904830954548, 0.0], [14.395904830954548, 0.0], [14.495904830954547, 0.0], [14.595904830954547, 0.0], [14.695904830954547, 0.0], [14.793797577449581, 0.0], [14.874616611258672, 0.0], [14.935435645067763, 0.0], [14.976254678876852, 0.0], [14.997073712685944, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522, 11.363299316185522], "velocities": null}}, "time": 1740481172.663626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367981744247628, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665242437052686, "gear": 1, "accelerator_pedal_position": 0.24386384694262134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.663626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 3.8334215041811595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650145156071125, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25756325593367996, "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": 1740481172.683626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367981744247628, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662474505735966, "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": 1740481172.683626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.693626, "x": 7.939661729988151, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.703626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24457064019881902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656944398449863, "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": 1740481172.703626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.723626} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446401918090883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663270347864465, "gear": 1, "accelerator_pedal_position": 0.2446401918090883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.723626} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7436259} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446401918090883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665405044633054, "gear": 1, "accelerator_pedal_position": 0.2446401918090883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.7436259} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7636259} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[3.939661729988151, 0.0], [4.102189057443767, 0.0], [4.202189057443767, 0.0], [4.3021890574437665, 0.0], [4.402189057443767, 0.0], [4.502189057443767, 0.0], [4.602189057443767, 0.0], [4.702189057443767, 0.0], [4.8021890574437665, 0.0], [4.902189057443767, 0.0], [5.002189057443767, 0.0], [5.102189057443766, 0.0], [5.202189057443767, 0.0], [5.302189057443767, 0.0], [5.402189057443767, 0.0], [5.502189057443767, 0.0], [5.602189057443767, 0.0], [5.702189057443768, 0.0], [5.802189057443767, 0.0], [5.902189057443767, 0.0], [6.0021890574437675, 0.0], [6.102189057443768, 0.0], [6.202189057443768, 0.0], [6.302189057443767, 0.0], [6.402189057443768, 0.0], [6.502189057443768, 0.0], [6.602189057443768, 0.0], [6.702189057443768, 0.0], [6.802189057443768, 0.0], [6.902189057443769, 0.0], [7.002189057443768, 0.0], [7.102189057443768, 0.0], [7.202189057443769, 0.0], [7.302189057443769, 0.0], [7.402189057443769, 0.0], [7.502189057443768, 0.0], [7.602189057443769, 0.0], [7.7021890574437695, 0.0], [7.802189057443769, 0.0], [7.902189057443769, 0.0], [8.002189057443768, 0.0], [8.10218905744377, 0.0], [8.202189057443768, 0.0], [8.30218905744377, 0.0], [8.402189057443767, 0.0], [8.502189057443768, 0.0], [8.602189057443766, 0.0], [8.702189057443768, 0.0], [8.802189057443766, 0.0], [8.902189057443767, 0.0], [9.002189057443765, 0.0], [9.102189057443766, 0.0], [9.202189057443764, 0.0], [9.302189057443766, 0.0], [9.402189057443763, 0.0], [9.502189057443765, 0.0], [9.602189057443763, 0.0], [9.702189057443764, 0.0], [9.802189057443762, 0.0], [9.902189057443763, 0.0], [10.002189057443761, 0.0], [10.102189057443763, 0.0], [10.20218905744376, 0.0], [10.302189057443762, 0.0], [10.40218905744376, 0.0], [10.502189057443761, 0.0], [10.60218905744376, 0.0], [10.70218905744376, 0.0], [10.802189057443758, 0.0], [10.90218905744376, 0.0], [11.002189057443758, 0.0], [11.10218905744376, 0.0], [11.202189057443757, 0.0], [11.302189057443758, 0.0], [11.402189057443756, 0.0], [11.502189057443758, 0.0], [11.602189057443756, 0.0], [11.702189057443757, 0.0], [11.802189057443755, 0.0], [11.902189057443756, 0.0], [12.002189057443756, 0.0], [12.102189057443756, 0.0], [12.202189057443755, 0.0], [12.302189057443755, 0.0], [12.402189057443755, 0.0], [12.502189057443754, 0.0], [12.602189057443754, 0.0], [12.702189057443753, 0.0], [12.802189057443753, 0.0], [12.902189057443753, 0.0], [13.002189057443752, 0.0], [13.102189057443752, 0.0], [13.202189057443752, 0.0], [13.302189057443751, 0.0], [13.402189057443751, 0.0], [13.50218905744375, 0.0], [13.60218905744375, 0.0], [13.70218905744375, 0.0], [13.80218905744375, 0.0], [13.90218905744375, 0.0], [14.002189057443749, 0.0], [14.102189057443749, 0.0], [14.202189057443748, 0.0], [14.302189057443748, 0.0], [14.402189057443747, 0.0], [14.502189057443747, 0.0], [14.602189057443747, 0.0], [14.702189057443746, 0.0], [14.799465359726879, 0.0], [14.87902754823813, 0.0], [14.93858973674938, 0.0], [14.978151925260631, 0.0], [14.997714113771883, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523, 11.263299316185522], "velocities": null}}, "time": 1740481172.7636259} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366882727159926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9666830309503179, "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": 1740481172.7636259} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 3.939661729988151, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9659708493362835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576295392844888, "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": 1740481172.7836258} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366882727159926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663992588713596, "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": 1740481172.7836258} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.8036258, "x": 8.045956420447522, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8036258} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24428442972307024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658323047855043, "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": 1740481172.8036258} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8236258} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24427435374613163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662153269891404, "gear": 1, "accelerator_pedal_position": 0.24428442972307024, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8236258} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8436258} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.6819758, "x": 15.0, "y": 4.764999999999942, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481172.8436258} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24427435374613163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665965592760195, "gear": 1, "accelerator_pedal_position": 0.24427435374613163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8436258} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8636258} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.0459564204475225, 0.0], [4.208477449035554, 0.0], [4.3084774490355535, 0.0], [4.408477449035554, 0.0], [4.508477449035554, 0.0], [4.608477449035554, 0.0], [4.708477449035554, 0.0], [4.8084774490355535, 0.0], [4.908477449035554, 0.0], [5.008477449035554, 0.0], [5.108477449035554, 0.0], [5.208477449035554, 0.0], [5.3084774490355535, 0.0], [5.408477449035554, 0.0], [5.508477449035555, 0.0], [5.608477449035554, 0.0], [5.708477449035554, 0.0], [5.808477449035554, 0.0], [5.908477449035555, 0.0], [6.008477449035555, 0.0], [6.108477449035554, 0.0], [6.208477449035555, 0.0], [6.308477449035555, 0.0], [6.408477449035555, 0.0], [6.508477449035555, 0.0], [6.608477449035555, 0.0], [6.708477449035556, 0.0], [6.808477449035555, 0.0], [6.908477449035555, 0.0], [7.0084774490355555, 0.0], [7.108477449035556, 0.0], [7.208477449035556, 0.0], [7.308477449035555, 0.0], [7.408477449035556, 0.0], [7.508477449035556, 0.0], [7.608477449035556, 0.0], [7.708477449035556, 0.0], [7.808477449035556, 0.0], [7.908477449035557, 0.0], [8.008477449035556, 0.0], [8.108477449035558, 0.0], [8.208477449035556, 0.0], [8.308477449035557, 0.0], [8.408477449035555, 0.0], [8.508477449035556, 0.0], [8.608477449035554, 0.0], [8.708477449035556, 0.0], [8.808477449035554, 0.0], [8.908477449035555, 0.0], [9.008477449035553, 0.0], [9.108477449035554, 0.0], [9.208477449035552, 0.0], [9.308477449035554, 0.0], [9.408477449035551, 0.0], [9.508477449035553, 0.0], [9.60847744903555, 0.0], [9.708477449035552, 0.0], [9.80847744903555, 0.0], [9.908477449035551, 0.0], [10.00847744903555, 0.0], [10.10847744903555, 0.0], [10.208477449035549, 0.0], [10.30847744903555, 0.0], [10.408477449035548, 0.0], [10.50847744903555, 0.0], [10.608477449035547, 0.0], [10.708477449035549, 0.0], [10.808477449035546, 0.0], [10.908477449035548, 0.0], [11.008477449035546, 0.0], [11.108477449035547, 0.0], [11.208477449035545, 0.0], [11.308477449035546, 0.0], [11.408477449035544, 0.0], [11.508477449035546, 0.0], [11.608477449035544, 0.0], [11.708477449035545, 0.0], [11.808477449035543, 0.0], [11.908477449035544, 0.0], [12.008477449035542, 0.0], [12.108477449035542, 0.0], [12.208477449035541, 0.0], [12.308477449035541, 0.0], [12.40847744903554, 0.0], [12.50847744903554, 0.0], [12.60847744903554, 0.0], [12.70847744903554, 0.0], [12.80847744903554, 0.0], [12.908477449035539, 0.0], [13.008477449035539, 0.0], [13.108477449035538, 0.0], [13.208477449035538, 0.0], [13.308477449035538, 0.0], [13.408477449035537, 0.0], [13.508477449035537, 0.0], [13.608477449035536, 0.0], [13.708477449035536, 0.0], [13.808477449035536, 0.0], [13.908477449035535, 0.0], [14.008477449035535, 0.0], [14.108477449035535, 0.0], [14.208477449035534, 0.0], [14.308477449035534, 0.0], [14.408477449035534, 0.0], [14.508477449035533, 0.0], [14.608477449035533, 0.0], [14.708477449035533, 0.0], [14.805057836989828, 0.0], [14.883362347182722, 0.0], [14.941666857375616, 0.0], [14.97997136756851, 0.0], [14.998275877761403, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523, 11.163299316185523], "velocities": null}}, "time": 1740481172.8636258} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9671674171040967, "gear": 1, "accelerator_pedal_position": 0.24427435374613163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.8636258} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.8836257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668843088792427, "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": 1740481172.8836257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 4.0459564204475225, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9658323047855043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25761993564894803, "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": 1740481172.9036257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23670426823950116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663186812035224, "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": 1740481172.9036257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481172.9136257, "x": 8.152274521718127, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9236257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442824551683253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965753837546247, "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": 1740481172.9236257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9436257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429728112159324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661367217618756, "gear": 1, "accelerator_pedal_position": 0.2442824551683253, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.9436257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9636257} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.152274521718127, 0.0], [4.314804809684238, 0.0], [4.414804809684238, 0.0], [4.514804809684239, 0.0], [4.614804809684238, 0.0], [4.714804809684238, 0.0], [4.814804809684238, 0.0], [4.914804809684238, 0.0], [5.014804809684238, 0.0], [5.114804809684238, 0.0], [5.214804809684238, 0.0], [5.314804809684238, 0.0], [5.414804809684238, 0.0], [5.514804809684239, 0.0], [5.614804809684238, 0.0], [5.714804809684239, 0.0], [5.814804809684238, 0.0], [5.914804809684239, 0.0], [6.014804809684239, 0.0], [6.114804809684239, 0.0], [6.214804809684239, 0.0], [6.314804809684238, 0.0], [6.414804809684239, 0.0], [6.5148048096842395, 0.0], [6.614804809684239, 0.0], [6.714804809684239, 0.0], [6.814804809684239, 0.0], [6.91480480968424, 0.0], [7.0148048096842395, 0.0], [7.114804809684239, 0.0], [7.21480480968424, 0.0], [7.31480480968424, 0.0], [7.41480480968424, 0.0], [7.5148048096842395, 0.0], [7.61480480968424, 0.0], [7.7148048096842405, 0.0], [7.81480480968424, 0.0], [7.91480480968424, 0.0], [8.01480480968424, 0.0], [8.114804809684241, 0.0], [8.21480480968424, 0.0], [8.31480480968424, 0.0], [8.41480480968424, 0.0], [8.51480480968424, 0.0], [8.61480480968424, 0.0], [8.714804809684239, 0.0], [8.814804809684238, 0.0], [8.914804809684238, 0.0], [9.014804809684238, 0.0], [9.114804809684237, 0.0], [9.214804809684237, 0.0], [9.314804809684237, 0.0], [9.414804809684236, 0.0], [9.514804809684236, 0.0], [9.614804809684236, 0.0], [9.714804809684235, 0.0], [9.814804809684235, 0.0], [9.914804809684234, 0.0], [10.014804809684234, 0.0], [10.114804809684234, 0.0], [10.214804809684233, 0.0], [10.314804809684233, 0.0], [10.414804809684233, 0.0], [10.514804809684232, 0.0], [10.614804809684232, 0.0], [10.714804809684232, 0.0], [10.814804809684231, 0.0], [10.914804809684231, 0.0], [11.01480480968423, 0.0], [11.11480480968423, 0.0], [11.21480480968423, 0.0], [11.31480480968423, 0.0], [11.41480480968423, 0.0], [11.514804809684229, 0.0], [11.614804809684228, 0.0], [11.714804809684228, 0.0], [11.814804809684228, 0.0], [11.914804809684227, 0.0], [12.014804809684227, 0.0], [12.114804809684227, 0.0], [12.214804809684226, 0.0], [12.314804809684226, 0.0], [12.414804809684226, 0.0], [12.514804809684225, 0.0], [12.614804809684225, 0.0], [12.714804809684225, 0.0], [12.814804809684224, 0.0], [12.914804809684224, 0.0], [13.014804809684223, 0.0], [13.114804809684223, 0.0], [13.214804809684223, 0.0], [13.314804809684222, 0.0], [13.414804809684222, 0.0], [13.514804809684222, 0.0], [13.614804809684221, 0.0], [13.714804809684221, 0.0], [13.81480480968422, 0.0], [13.91480480968422, 0.0], [14.01480480968422, 0.0], [14.11480480968422, 0.0], [14.21480480968422, 0.0], [14.314804809684219, 0.0], [14.414804809684219, 0.0], [14.514804809684218, 0.0], [14.614804809684218, 0.0], [14.714804809684217, 0.0], [14.81060514632601, 0.0], [14.887644184389165, 0.0], [14.944683222452323, 0.0], [14.981722260515479, 0.0], [14.998761298578636, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529, 9.463299316185529, 9.563299316185528, 9.663299316185528, 9.763299316185527, 9.863299316185527, 9.963299316185527, 10.063299316185526, 10.163299316185526, 10.263299316185526, 10.363299316185525, 10.463299316185525, 10.563299316185525, 10.663299316185524, 10.763299316185524, 10.863299316185524, 10.963299316185523, 11.063299316185523], "velocities": null}}, "time": 1740481172.9636257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665209279263068, "gear": 1, "accelerator_pedal_position": 0.24429728112159324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481172.9636257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481172.9836257} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659528618733125, "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": 1740481172.9836257} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 4.152274521718127, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660361614485251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25763406672468825, "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": 1740481173.0036256} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366807234740707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653855831356786, "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": 1740481173.0036256} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.0236256, "x": 8.258525206621915, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0236256} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449887610420004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648190904935419, "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": 1740481173.0236256} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0436256} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24441036176851466, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652303132057505, "gear": 1, "accelerator_pedal_position": 0.24449887610420004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0436256} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0636256} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.258525206621915, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0], [4.316704948958214, 0]], "times": [0.0, 0.7414747933780852, 1.7414747933780852, 2.741474793378085, 3.741474793378085, 4.741474793378085, 5.741474793378085, 6.741474793378085, 7.741474793378085, 8.741474793378085, 10.741474793378085], "velocities": [0.9648190904935419, -4.96697925653114, -12.96697925653114, -20.96697925653114, -28.96697925653114, -36.96697925653114, -44.96697925653114, -52.96697925653114, -60.96697925653114, -68.96697925653115, -84.96697925653115]}}, "time": 1740481173.0636256} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965829494228328, "gear": 1, "accelerator_pedal_position": 0.24441036176851466, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0636256} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.0836256} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481173.9011161, "x": 15.0, "y": 4.87499999999994, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.0836256} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9563897548722172, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.0836256} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.1036255} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9375298570171524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1036255} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 4.258525206621915, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648190904935419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257549713298485, "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": 1740481173.1236255} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5428971371737781, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9186959183898268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1236255} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.1336255, "x": 8.363321661517297, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1436255} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5378489118302194, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8998877614208954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1436255} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1636255} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.363321661517297, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0], [4.414997024610411, 0]], "times": [0.0, 0.636678338482703, 1.636678338482703, 2.636678338482703, 3.636678338482703, 4.636678338482703, 5.636678338482703, 6.636678338482703, 7.636678338482703, 8.636678338482703, 10.636678338482703], "velocities": [0.9092886282637808, -4.184138079597844, -12.184138079597844, -20.184138079597844, -28.184138079597844, -36.184138079597844, -44.184138079597844, -52.184138079597844, -60.184138079597844, -68.18413807959784, -84.18413807959784]}}, "time": 1740481173.1636255} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8741449882848346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5378489118302194, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1636255} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.1836255} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8653502566001433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.1836255} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.2036254} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8477785553980083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2036254} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 4.363321661517297, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9092886282637808, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5428971371737781, "acceleration": -0.9400866842885366, "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": 1740481173.2236254} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5392577890280904, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8214651179490172, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2236254} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.2436254, "x": 8.458498959719952, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2436254} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5304775164466151, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8127056586515475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2436254} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2636254} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.458498959719952, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0], [4.499779615195217, 0]], "times": [0.0, 0.541501040280048, 1.541501040280048, 2.541501040280048, 3.541501040280048, 4.541501040280048, 5.541501040280048, 6.541501040280048, 7.541501040280048, 8.541501040280048, 10.541501040280048], "velocities": [0.8127056586515475, -3.519302663588836, -11.519302663588837, -19.519302663588835, -27.519302663588835, -35.51930266358884, -43.51930266358884, -51.51930266358884, -59.51930266358884, -67.51930266358883, -83.51930266358883]}}, "time": 1740481173.2636254} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7906738215682549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5304775164466151, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2636254} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.2836254} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7828512490718237, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.2836254} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3036253} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7672215150351948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3036253} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3236253} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7438152077843841, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3236253} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 4.458498959719952, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8127056586515475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5392577890280904, "acceleration": -0.8753648122580664, "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": 1740481173.3436253} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.1212618, "x": 15.0, "y": 4.984999999999937, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.3436253} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5335294942277238, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.736023254997723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3436253} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.3536253, "x": 8.543726168125094, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.3636253} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.543726168125094, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0], [4.576871679582089, 0]], "times": [0.0, 0.4562738318749062, 1.4562738318749062, 2.456273831874906, 3.456273831874906, 4.456273831874906, 5.456273831874906, 6.456273831874906, 7.456273831874906, 8.456273831874906, 10.456273831874906], "velocities": [0.7282363512705986, -2.921954303728651, -10.92195430372865, -18.92195430372865, -26.92195430372865, -34.921954303728654, -42.921954303728654, -50.921954303728654, -58.921954303728654, -66.92195430372865, -82.92195430372865]}}, "time": 1740481173.3636253} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5261768140166697, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7126776294172122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3636253} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.3836253} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7060822094194893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5261768140166697, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.3836253} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4036252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.692169025072058, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4036252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4236252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6782736196995813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4236252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 4.543726168125094, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7282363512705986, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5335294942277238, "acceleration": -0.7781870070402295, "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": 1740481173.4436252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5284745280891229, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6643958933747952, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4436252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.4636252, "x": 8.619880446984732, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.4636252} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.619880446984732, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0]], "times": [0.0, 0.3801195530152679, 1.380119553015268, 2.380119553015268, 3.380119553015268, 4.380119553015268, 5.380119553015268, 6.380119553015268, 7.380119553015268, 8.380119553015268, 10.380119553015268], "velocities": [0.6505357465925913, -2.390420677529552, -10.390420677529551, -18.39042067752955, -26.39042067752955, -34.390420677529555, -42.390420677529555, -50.390420677529555, -58.390420677529555, -66.39042067752955, -82.39042067752955]}}, "time": 1740481173.4636252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5216891132467573, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6436122345492759, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4636252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.4836252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6377787466416739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5216891132467573, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.4836252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.5036252} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6254444250260436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.5036252} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.5236251} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6131255338944347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.5236251} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.543625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6008219932598556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.543625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 4.619880446984732, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6505357465925913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5284745280891229, "acceleration": -0.6923512043315434, "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": 1740481173.563625} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.619880446984732, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0], [4.646330244334406, 0]], "times": [0.0, 0.3801195530152679, 1.380119553015268, 2.380119553015268, 3.380119553015268, 4.380119553015268, 5.380119553015268, 6.380119553015268, 7.380119553015268, 8.380119553015268, 10.380119553015268], "velocities": [0.6505357465925913, -2.390420677529552, -10.390420677529551, -18.39042067752955, -26.39042067752955, -34.390420677529555, -42.390420677529555, -50.390420677529555, -58.390420677529555, -66.39042067752955, -82.39042067752955]}}, "time": 1740481173.563625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5238095567752676, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5885337234620626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.563625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.573625, "x": 8.688004376137906, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.583625} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.3413217, "x": 15.0, "y": 5.094999999999935, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.583625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.517614967995438, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5762606451653008, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.583625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.603625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5659843390852461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.517614967995438, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.603625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.623625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5551013728091306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.623625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.643625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5195507782583509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5442317137362668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.643625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 4.688004376137906, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5823952903219235, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5238095567752676, "acceleration": -0.61346451566227, "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": 1740481173.663625} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.688004376137906, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0], [4.709203393274729, 0]], "times": [0.0, 0.311995623862094, 1.311995623862094, 2.311995623862094, 3.311995623862094, 4.311995623862094, 5.311995623862094, 6.311995623862094, 7.311995623862094, 8.311995623862094, 10.311995623862094], "velocities": [0.5823952903219235, -1.9135697005748287, -9.91356970057483, -17.91356970057483, -25.91356970057483, -33.913569700574826, -41.913569700574826, -49.913569700574826, -57.913569700574826, -65.91356970057483, -81.91356970057483]}}, "time": 1740481173.663625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5196530480970096, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5333752983497857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5195507782583509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.663625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.683625, "x": 8.7490585078663, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.683625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5142079607126203, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5224993469440395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.683625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.703625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5133784545965003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5142079607126203, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.703625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.723625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49890145168484795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5159095516358919, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.723625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.743625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5159095516358919, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4940815824314135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5159095516358919, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.743625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.763625} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.7490585078663, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0], [4.766121355838609, 0]], "times": [0.0, 0.2509414921337001, 1.2509414921337, 2.2509414921337, 3.2509414921337, 4.2509414921337, 5.2509414921337, 6.2509414921337, 7.2509414921337, 8.2509414921337, 10.2509414921337], "velocities": [0.5224993469440395, -1.4850325901255612, -9.485032590125561, -17.485032590125563, -25.485032590125563, -33.48503259012556, -41.48503259012556, -49.48503259012556, -57.48503259012556, -65.48503259012556, -81.48503259012556]}}, "time": 1740481173.763625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.515906501456509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.479639768456166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.763625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 4.7490585078663, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5224993469440395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5196530480970096, "acceleration": -0.5433037925749256, "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": 1740481173.783625} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.515906501456509, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47483190290814803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.783625} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.7936249, "x": 8.803931100187649, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8036249} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5111362776026898, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4652247539782239, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8036249} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8236248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5126269735343847, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.457155025513187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5111362776026898, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8236248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8436248} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.671118, "x": 15.0, "y": 5.259999999999931, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481173.8436248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5126269735343847, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44861796427766876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5126269735343847, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8436248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8636248} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.803931100187649, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0], [4.81773893061904, 0]], "times": [0.0, 0.1960688998123512, 1.1960688998123512, 2.196068899812351, 3.196068899812351, 4.196068899812351, 5.196068899812351, 6.196068899812351, 7.196068899812351, 8.196068899812351, 10.196068899812351], "velocities": [0.47002690019005056, -1.098524298308759, -9.098524298308758, -17.09852429830876, -25.09852429830876, -33.09852429830876, -41.09852429830876, -49.09852429830876, -57.09852429830876, -65.09852429830876, -81.09852429830876]}}, "time": 1740481173.8636248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5124752213526939, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44009097637202393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5126269735343847, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8636248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 4.803931100187649, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.47002690019005056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.515906501456509, "acceleration": -0.48021462118266856, "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": 1740481173.8836248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5124752213526939, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.43162256727641535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.8836248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481173.9036248, "x": 8.853275229652686, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9036248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5522295639676532, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4231640929105453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9036248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9236248} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5535608949895681, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4031640929105453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5522295639676532, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9236248} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9436247} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5535608949895681, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.38316409291054526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5535608949895681, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9436247} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9636247} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.853275229652686, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0], [4.864466970248237, 0]], "times": [0.0, 0.1467247703473138, 1.1467247703473138, 2.146724770347314, 3.146724770347314, 4.146724770347314, 5.146724770347314, 6.146724770347314, 7.146724770347314, 8.146724770347314, 10.146724770347314], "velocities": [0.4231640929105453, -0.750634069867965, -8.750634069867965, -16.750634069867964, -24.750634069867964, -32.750634069867964, -40.750634069867964, -48.750634069867964, -56.750634069867964, -64.75063406986797, -80.75063406986797]}}, "time": 1740481173.9636247} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36316409291054524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5535608949895681, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9636247} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481173.9836247} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3558389079903203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481173.9836247} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 4.853275229652686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4231640929105453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5124752213526939, "acceleration": -0.42255242478391697, "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": 1740481174.0036247} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.509180436794815, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.348522093863923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0036247} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.0136247, "x": 8.89495712526174, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0236247} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5497356905448343, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3412136195574876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0236247} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0436246} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5519600471191494, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.32121361955748756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5497356905448343, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0436246} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0636246} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.89495712526174, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0], [4.90239044531747, 0]], "times": [0.0, 0.10504287473825968, 1.1050428747382597, 2.1050428747382597, 3.1050428747382597, 4.10504287473826, 5.10504287473826, 6.10504287473826, 7.10504287473826, 8.10504287473826, 10.10504287473826], "velocities": [0.34486681616482956, -0.4954761817412479, -8.495476181741248, -16.49547618174125, -24.49547618174125, -32.495476181741246, -40.495476181741246, -48.495476181741246, -56.495476181741246, -64.49547618174125, -80.49547618174125]}}, "time": 1740481174.0636246} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29121361955748754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5519600471191494, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0636246} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.0836246} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481174.8934753, "x": 15.0, "y": 5.369999999999929, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.0836246} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2883185103384375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.0836246} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 4.89495712526174, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34486681616482956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.509180436794815, "acceleration": -0.3653196607341973, "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": 1740481174.1036246} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.504631386700311, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2825331353305991, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1036246} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.1236246, "x": 8.928737805862013, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1236246} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5048724789422753, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27675420107622084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1236246} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1436245} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5047971375672639, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2709045589328769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5048724789422753, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1436245} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1636245} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9287378058620135, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0], [4.933524861350347, 0]], "times": [0.0, 0.07126219413798651, 1.0712621941379865, 2.0712621941379865, 3.0712621941379865, 4.0712621941379865, 5.0712621941379865, 6.0712621941379865, 7.0712621941379865, 8.071262194137987, 10.071262194137987], "velocities": [0.27675420107622084, -0.29334335202767126, -8.293343352027671, -16.293343352027673, -24.293343352027673, -32.29334335202767, -40.29334335202767, -48.29334335202767, -56.29334335202767, -64.29334335202768, -80.29334335202768]}}, "time": 1740481174.1636245} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26508550450052204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5047971375672639, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1636245} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.1836245} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24718467954384973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.1836245} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.2036245} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2293035519672457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2036245} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 4.9287378058620135, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.27675420107622084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.504631386700311, "acceleration": -0.2887058261369212, "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": 1740481174.2236245} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5425832139680766, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.20251846624569364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2236245} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.2336245, "x": 8.956310224595983, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2436244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19359979140476147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2436244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2636244} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.956310224595983, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0], [4.95887358266914, 0]], "times": [0.0, 0.043689775404017084, 1.043689775404017, 2.043689775404017, 3.043689775404017, 4.043689775404017, 5.043689775404017, 6.043689775404017, 7.043689775404017, 8.043689775404017, 10.043689775404017], "velocities": [0.20251846624569364, -0.14699973698644303, -8.146999736986443, -16.146999736986444, -24.146999736986444, -32.146999736986444, -40.146999736986444, -48.146999736986444, -56.146999736986444, -64.14699973698644, -80.14699973698644]}}, "time": 1740481174.2636244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.18939982660340224, "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": 1740481174.2636244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.2836244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17459593466774637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.2836244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.3036244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15980789817746538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3036244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 4.956310224595983, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.20251846624569364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5425832139680766, "acceleration": -0.8918674840932158, "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": 1740481174.3236244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.53316029561364, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14503561269971094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3236244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.3436244, "x": 8.975267502031452, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3436244} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.114363, "x": 15.0, "y": 5.479999999999927, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.3436244} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13027897419269516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3436244} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3636243} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.975267502031452, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0], [4.976328290226245, 0]], "times": [0.0, 0.024732497968548373, 1.0247324979685484, 2.0247324979685484, 3.0247324979685484, 4.024732497968548, 5.024732497968548, 6.024732497968548, 7.024732497968548, 8.024732497968548, 10.024732497968548], "velocities": [0.13027897419269516, -0.06758100955569182, -8.067581009555692, -16.067581009555692, -24.067581009555692, -32.06758100955569, -40.06758100955569, -48.06758100955569, -56.06758100955569, -64.0675810095557, -80.0675810095557]}}, "time": 1740481174.3636243} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1261463875405461, "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": 1740481174.3636243} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.3836243} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11569393938614364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.3836243} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4036243} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.10525243545580168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4036243} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4236243} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09482182069173653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4236243} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 4.975267502031452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.13027897419269516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.53316029561364, "acceleration": -0.7372484046390414, "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": 1740481174.4436243} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5197683191815762, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08440204023012354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4436243} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.4536242, "x": 8.98732594902868, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.4636242} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.98732594902868, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0], [4.987717951367713, 0]], "times": [0.0, 0.012674050971320128, 1.0126740509713201, 2.01267405097132, 3.01267405097132, 4.01267405097132, 5.01267405097132, 6.01267405097132, 7.01267405097132, 8.01267405097132, 10.01267405097132], "velocities": [0.07919619577051679, -0.022196212000044235, -8.022196212000043, -16.022196212000043, -24.022196212000043, -32.02219621200005, -40.02219621200005, -48.02219621200005, -56.02219621200005, -64.02219621200004, -80.02219621200004]}}, "time": 1740481174.4636242} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07399303939983688, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.4636242} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.4836242} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06991899987612585, "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": 1740481174.4836242} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5036242} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06584914891612209, "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": 1740481174.5036242} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5236242} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05975220213216229, "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": 1740481174.5236242} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 4.98732594902868, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.07919619577051679, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5197683191815762, "acceleration": -0.5203156370679899, "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": 1740481174.5436242} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05772196899853024, "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": 1740481174.5436242} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.5636241, "x": 8.99460157546006, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.5636241} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9946015754600595, 0], [4.994774707902231, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0]], "times": [0.0, 0.0053984245399405495, 1.0053984245399405, 2.0053984245399405, 3.0053984245399405, 4.0053984245399405, 5.0053984245399405, 6.0053984245399405, 7.0053984245399405, 8.00539842453994, 10.00539842453994], "velocities": [0.053664618275527896, 0.0104772219560035, -7.989522778043996, -15.989522778043996, -23.989522778043998, -31.989522778043998, -39.989522778044, -47.989522778044, -55.989522778044, -63.989522778044, -79.98952277804399]}}, "time": 1740481174.5636241} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.053664618275527896, "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": 1740481174.5636241} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.5836241} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.3317926, "x": 15.0, "y": 5.589999999999924, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.5836241} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0496114125851563, "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": 1740481174.5836241} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.603624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04556234112309009, "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": 1740481174.603624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.623624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04151739311613538, "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": 1740481174.623624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.643624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03747655782210765, "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": 1740481174.643624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 4.9946015754600595, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.053664618275527896, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.202712029826323, "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": 1740481174.663624} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.9946015754600595, 0], [4.994774707902231, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0], [4.994781568663475, 0]], "times": [0.0, 0.0053984245399405495, 1.0053984245399405, 2.0053984245399405, 3.0053984245399405, 4.0053984245399405, 5.0053984245399405, 6.0053984245399405, 7.0053984245399405, 8.00539842453994, 10.00539842453994], "velocities": [0.053664618275527896, 0.0104772219560035, -7.989522778043996, -15.989522778043996, -23.989522778043998, -31.989522778043998, -39.989522778044, -47.989522778044, -55.989522778044, -63.989522778044, -79.98952277804399]}}, "time": 1740481174.663624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.033439824529710324, "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": 1740481174.663624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.673624, "x": 8.999391470456887, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.683624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.029407182558413757, "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": 1740481174.683624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.703624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02537862125833487, "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": 1740481174.703624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.723624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02135413001011728, "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": 1740481174.723624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.743624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.017333698224811987, "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": 1740481174.743624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 4.999391470456887, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.03142299279525901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.20158102368452507, "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": 1740481174.763624} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[4.999391470456887, 0], [4.999409111043517, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0], [4.999453183236651, 0]], "times": [0.0, 0.0006085295431130788, 1.000608529543113, 2.000608529543113, 3.000608529543113, 4.000608529543113, 5.000608529543113, 6.000608529543113, 7.000608529543113, 8.000608529543113, 10.000608529543113], "velocities": [0.03142299279525901, 0.026554756450354378, -7.973445243549645, -15.973445243549646, -23.973445243549644, -31.973445243549644, -39.97344524354965, -47.97344524354965, -55.97344524354965, -63.97344524354965, -79.97344524354965]}}, "time": 1740481174.763624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5057426339044122, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.010391817526291966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.763624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.783624, "x": 9.001731794721099, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.783624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0074677893938357165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.783624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.803624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0034613149118056246, "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": 1740481174.803624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.823624} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.823624} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8436239} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.6614075, "x": 15.0, "y": 5.754999999999921, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481174.8436239} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8436239} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8636239} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001731794721099, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0], [5.0017352802135004, 0]], "times": [0.0, 0.9982682052789009, 1.998268205278901, 2.998268205278901, 3.998268205278901, 4.998268205278901, 5.998268205278901, 6.998268205278901, 7.998268205278901, 9.998268205278901], "velocities": [0.0074677893938357165, -7.978677852837372, -15.978677852837372, -23.97867785283737, -31.97867785283737, -39.97867785283737, -47.97867785283737, -55.97867785283737, -63.97867785283737, -79.97867785283738]}}, "time": 1740481174.8636239} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8636239} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 5.001731794721099, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0074677893938357165, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5057426339044122, "acceleration": -0.29225608961907146, "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": 1740481174.8836238} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.8836238} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481174.8936238, "x": 9.001910322093941, "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": 1740481174.9036238} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2325436711201126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.9036238} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9236238} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23200055864624486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794190017610891e-05, "gear": 1, "accelerator_pedal_position": 0.2325436711201126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9236238} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9436238} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23200055864624486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794378766131621e-05, "gear": 1, "accelerator_pedal_position": 0.23200055864624486, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9436238} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9636238} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0], [5.001910322093941, 0]], "times": [0.0, 0.9980896779060586, 1.9980896779060586, 2.9980896779060586, 3.9980896779060586, 4.998089677906059, 5.998089677906059, 6.998089677906059, 7.998089677906059, 9.998089677906059], "velocities": [0.0, -7.984717423248469, -15.984717423248469, -23.98471742324847, -31.98471742324847, -39.98471742324847, -47.98471742324847, -55.98471742324847, -63.98471742324847, -79.98471742324847]}}, "time": 1740481174.9636238} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.794567325945883e-05, "gear": 1, "accelerator_pedal_position": 0.23200055864624486, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481174.9636238} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 5.001910322093941, "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": 1740481174.9836237} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481174.9836237} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.0036237, "x": 9.001914059077752, "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": 1740481175.0036237} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0036237} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0236237} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0236237} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0436237} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0436237} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0636237} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.0636237} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0636237} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.0836236} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481175.8811684, "x": 15.0, "y": 5.8649999999999185, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.0836236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.0836236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 5.001914059077752, "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": 1740481175.1036236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1036236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.1136236, "x": 9.001914059077752, "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": 1740481175.1236236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1236236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1436236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1436236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1636236} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.1636236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1636236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.1836236} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.1836236} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 5.001914059077752, "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": 1740481175.2036235} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2036235} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.2236235, "x": 9.001914059077752, "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": 1740481175.2236235} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2236235} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2436235} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2436235} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2636235} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.2636235} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2636235} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.2836235} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.2836235} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.3036234} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3036234} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 5.001914059077752, "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": 1740481175.3236234} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3236234} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.3336234, "x": 9.001914059077752, "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": 1740481175.3436234} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.1014144, "x": 15.0, "y": 5.974999999999916, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.3436234} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3436234} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.3636234} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.3636234} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3636234} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.3836234} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.3836234} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.4036233} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4036233} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 5.001914059077752, "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": 1740481175.4236233} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4236233} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.4436233, "x": 9.001914059077752, "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": 1740481175.4436233} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4436233} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.4636233} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.4636233} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4636233} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.4836233} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.4836233} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5036232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5036232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5236232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5236232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 5.001914059077752, "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": 1740481175.5436232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5436232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.5536232, "x": 9.001914059077752, "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": 1740481175.5636232} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.5636232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5636232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.5836232} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.4315019, "x": 15.0, "y": 6.139999999999913, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.5836232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.5836232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.6036232} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.6036232} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.6236231} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.6236231} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 5.001914059077752, "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": 1740481175.643623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.643623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.663623, "x": 9.001914059077752, "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": 1740481175.663623} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.663623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.663623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.683623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.683623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.703623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.703623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.723623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.723623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.743623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.743623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 5.001914059077752, "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": 1740481175.763623} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.763623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.763623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.773623, "x": 9.001914059077752, "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": 1740481175.783623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.783623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.803623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.803623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.823623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.823623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.843623} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.6514893, "x": 15.0, "y": 6.24999999999991, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481175.843623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.843623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 5.001914059077752, "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": 1740481175.863623} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.863623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.863623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.883623, "x": 9.001914059077752, "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": 1740481175.883623} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.883623} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9036229} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9036229} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9236228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9236228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9436228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9436228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9636228} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481175.9636228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9636228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 5.001914059077752, "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": 1740481175.9836228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481175.9836228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481175.9936228, "x": 9.001914059077752, "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": 1740481176.0036228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0036228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0236228} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0236228} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0436227} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0436227} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0636227} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.0636227} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0636227} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 5.001914059077752, "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": 1740481176.0836227} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481176.8721457, "x": 15.0, "y": 6.359999999999908, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.0836227} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.0836227} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.1036227, "x": 9.001914059077752, "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": 1740481176.1036227} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1036227} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1236227} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1236227} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1436226} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1436226} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1636226} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.1636226} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1636226} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.1836226} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.1836226} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 5.001914059077752, "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": 1740481176.2036226} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2036226} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.2136226, "x": 9.001914059077752, "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": 1740481176.2236226} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2236226} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2436225} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2436225} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2636225} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.2636225} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2636225} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.2836225} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.2836225} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 5.001914059077752, "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": 1740481176.3036225} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3036225} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.3236225, "x": 9.001914059077752, "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": 1740481176.3236225} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3236225} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3436224} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.0918632, "x": 15.0, "y": 6.469999999999906, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.3436224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3436224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3636224} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.3636224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3636224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.3836224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.3836224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.4036224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4036224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 5.001914059077752, "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": 1740481176.4236224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4236224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.4336224, "x": 9.001914059077752, "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": 1740481176.4436224} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4436224} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.4636223} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.4636223} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4636223} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.4836223} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.4836223} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.5036223} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5036223} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 5.001914059077752, "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": 1740481176.5236223} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5236223} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.5436223, "x": 9.001914059077752, "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": 1740481176.5436223} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5436223} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.5636222} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.5636222} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5636222} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.5836222} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.421288, "x": 15.0, "y": 6.634999999999902, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.5836222} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.5836222} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6036222} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6036222} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6236222} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6236222} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 5.001914059077752, "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": 1740481176.6436222} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6436222} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.6536222, "x": 9.001914059077752, "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": 1740481176.6636221} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.6636221} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6636221} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.6836221} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.6836221} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.703622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.703622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.723622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.723622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 5.001914059077752, "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": 1740481176.743622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.743622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.763622, "x": 9.001914059077752, "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": 1740481176.763622} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.763622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.763622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.783622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.783622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.803622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.803622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.823622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.823622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.843622} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.641529, "x": 15.0, "y": 6.7449999999999, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481176.843622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.843622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 5.001914059077752, "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": 1740481176.863622} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.863622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.863622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.873622, "x": 9.001914059077752, "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": 1740481176.883622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.883622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.903622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.903622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.923622} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.923622} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.9436219} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9436219} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 5.001914059077752, "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": 1740481176.9636219} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481176.9636219} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9636219} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481176.9836218, "x": 9.001914059077752, "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": 1740481176.9836218} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481176.9836218} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0036218} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0036218} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0236218} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0236218} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0436218} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0436218} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0636218} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.0636218} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0636218} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 5.001914059077752, "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": 1740481177.0836217} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481177.861419, "x": 15.0, "y": 6.854999999999897, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.0836217} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.0836217} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.0936217, "x": 9.001914059077752, "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": 1740481177.1036217} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1036217} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1236217} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1236217} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1436217} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1436217} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1636217} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.1636217} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1636217} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 5.001914059077752, "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": 1740481177.1836216} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.1836216} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.2036216, "x": 9.001914059077752, "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": 1740481177.2036216} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2036216} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2236216} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2236216} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2436216} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2436216} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2636216} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.2636216} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2636216} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.2836215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.2836215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 5.001914059077752, "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": 1740481177.3036215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3036215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.3136215, "x": 9.001914059077752, "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": 1740481177.3236215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3236215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3536215} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.1914217, "x": 15.0, "y": 7.019999999999894, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.3536215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3536215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3636215} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.3636215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3636215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.3836215} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.3836215} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 5.001914059077752, "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": 1740481177.4036214} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4036214} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.4236214, "x": 9.001914059077752, "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": 1740481177.4236214} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4236214} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4436214} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4436214} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4636214} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.4636214} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4636214} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.4836214} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.4836214} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.5036213} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5036213} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 5.001914059077752, "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": 1740481177.5236213} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5236213} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.5336213, "x": 9.001914059077752, "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": 1740481177.5436213} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5436213} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.5636213} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.5636213} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5636213} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.5836213} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.4143004, "x": 15.0, "y": 7.1299999999998915, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.5836213} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.5836213} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.6036212} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6036212} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 5.001914059077752, "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": 1740481177.6236212} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6236212} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.6436212, "x": 9.001914059077752, "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": 1740481177.6436212} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6436212} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.6636212} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.6636212} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6636212} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.6836212} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.6836212} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.7036211} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.7036211} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.7236211} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.7236211} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 5.001914059077752, "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": 1740481177.743621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.743621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.753621, "x": 9.001914059077752, "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": 1740481177.763621} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.763621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.763621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.783621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.783621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.803621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.803621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.823621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.823621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 5.001914059077752, "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": 1740481177.843621} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.6313984, "x": 15.0, "y": 7.239999999999889, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481177.843621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.843621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.863621, "x": 9.001914059077752, "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": 1740481177.863621} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.863621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.863621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.883621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.883621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.903621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.903621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.923621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.923621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.943621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.943621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 5.001914059077752, "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": 1740481177.963621} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481177.963621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.963621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481177.973621, "x": 9.001914059077752, "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": 1740481177.983621} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481177.983621} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0036209} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0036209} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0236208} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0236208} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0436208} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0436208} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 5.001914059077752, "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": 1740481178.0636208} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.0636208} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0636208} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.0836208, "x": 9.001914059077752, "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": 1740481178.0836208} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481178.8525784, "x": 15.0, "y": 7.349999999999887, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.0836208} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.0836208} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1036208} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1036208} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1236207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1236207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1436207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1436207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1636207} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.1636207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1636207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 5.001914059077752, "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": 1740481178.1836207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.1836207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.1936207, "x": 9.001914059077752, "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": 1740481178.2036207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2036207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2236207} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2236207} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2436206} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2436206} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2636206} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.2636206} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2636206} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 5.001914059077752, "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": 1740481178.2836206} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.2836206} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.3036206, "x": 9.001914059077752, "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": 1740481178.3036206} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3036206} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3236206} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3236206} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3436205} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.181927, "x": 15.0, "y": 7.514999999999883, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.3436205} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3436205} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3636205} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.3636205} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3636205} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.3836205} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.3836205} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 5.001914059077752, "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": 1740481178.4036205} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4036205} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.4136205, "x": 9.001914059077752, "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": 1740481178.4236205} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4236205} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4436204} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4436204} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4636204} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.4636204} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4636204} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.4836204} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.4836204} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 5.001914059077752, "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": 1740481178.5036204} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5036204} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.5236204, "x": 9.001914059077752, "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": 1740481178.5236204} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5236204} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5436203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5436203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5636203} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.5636203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5636203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.5836203} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.4017591, "x": 15.0, "y": 7.624999999999881, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.5836203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.5836203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.6036203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6036203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 5.001914059077752, "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": 1740481178.6236203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6236203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.6336203, "x": 9.001914059077752, "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": 1740481178.6436203} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6436203} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.6636202} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.6636202} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6636202} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.6836202} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.6836202} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.7036202} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7036202} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 5.001914059077752, "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": 1740481178.7236202} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7236202} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.7436202, "x": 9.001914059077752, "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": 1740481178.7436202} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7436202} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.7636201} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.7636201} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.7636201} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.78362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.78362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.80362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.80362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.82362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.82362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 5.001914059077752, "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": 1740481178.84362} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.6210592, "x": 15.0, "y": 7.734999999999879, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481178.84362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.84362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.85362, "x": 9.001914059077752, "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": 1740481178.86362} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.86362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.86362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.88362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.88362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.90362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.90362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.92362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.92362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 5.001914059077752, "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": 1740481178.94362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.94362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481178.96362, "x": 9.001914059077752, "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": 1740481178.96362} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481178.96362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.96362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481178.98362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481178.98362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.00362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.00362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.02362} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.02362} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.0436199} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0436199} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 5.001914059077752, "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": 1740481179.0636199} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0], [5.001914059077752, 0]], "times": [0.0, 0.9980859409222482, 1.9980859409222482, 2.9980859409222482, 3.9980859409222482, 4.998085940922248, 5.998085940922248, 6.998085940922248, 7.998085940922248, 9.998085940922248], "velocities": [0.0, -7.984687527377986, -15.984687527377986, -23.984687527377986, -31.984687527377986, -39.984687527377986, -47.984687527377986, -55.984687527377986, -63.984687527377986, -79.98468752737799]}}, "time": 1740481179.0636199} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0636199} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.0736198, "x": 9.001914059077752, "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": 1740481179.0836198} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481179.8461602, "x": 15.0, "y": 7.844999999999876, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.0836198} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.0836198} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1036198} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1036198} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1236198} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1236198} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1436198} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1436198} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 5.001914059077752, "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": 1740481179.1636198} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.001914059077752, 0.0], [5.011914059077752, 0.0], [5.041914059077752, 0.0], [5.091914059077752, 0.0], [5.161914059077752, 0.0], [5.251914059077752, 0.0], [5.361914059077752, 0.0], [5.491914059077752, 0.0], [5.6419140590777515, 0.0], [5.804941238080992, 0.0], [5.904941238080992, 0.0], [6.004941238080992, 0.0], [6.1049412380809915, 0.0], [6.204941238080992, 0.0], [6.304941238080993, 0.0], [6.404941238080992, 0.0], [6.504941238080992, 0.0], [6.604941238080992, 0.0], [6.704941238080993, 0.0], [6.804941238080993, 0.0], [6.904941238080992, 0.0], [7.004941238080993, 0.0], [7.104941238080993, 0.0], [7.204941238080993, 0.0], [7.304941238080993, 0.0], [7.404941238080993, 0.0], [7.504941238080994, 0.0], [7.604941238080993, 0.0], [7.704941238080993, 0.0], [7.804941238080993, 0.0], [7.904941238080994, 0.0], [8.004941238080994, 0.0], [8.104941238080993, 0.0], [8.204941238080993, 0.0], [8.304941238080994, 0.0], [8.404941238080994, 0.0], [8.504941238080994, 0.0], [8.604941238080993, 0.0], [8.704941238080993, 0.0], [8.804941238080993, 0.0], [8.904941238080992, 0.0], [9.004941238080992, 0.0], [9.104941238080992, 0.0], [9.204941238080991, 0.0], [9.30494123808099, 0.0], [9.40494123808099, 0.0], [9.50494123808099, 0.0], [9.60494123808099, 0.0], [9.70494123808099, 0.0], [9.804941238080989, 0.0], [9.904941238080989, 0.0], [10.004941238080988, 0.0], [10.104941238080988, 0.0], [10.204941238080988, 0.0], [10.304941238080987, 0.0], [10.404941238080987, 0.0], [10.504941238080987, 0.0], [10.604941238080986, 0.0], [10.704941238080986, 0.0], [10.804941238080985, 0.0], [10.904941238080985, 0.0], [11.004941238080985, 0.0], [11.104941238080984, 0.0], [11.204941238080984, 0.0], [11.304941238080984, 0.0], [11.404941238080983, 0.0], [11.504941238080983, 0.0], [11.604941238080983, 0.0], [11.704941238080982, 0.0], [11.804941238080982, 0.0], [11.904941238080982, 0.0], [12.004941238080981, 0.0], [12.10494123808098, 0.0], [12.20494123808098, 0.0], [12.30494123808098, 0.0], [12.40494123808098, 0.0], [12.50494123808098, 0.0], [12.604941238080979, 0.0], [12.704941238080979, 0.0], [12.804941238080978, 0.0], [12.904941238080978, 0.0], [13.004941238080978, 0.0], [13.104941238080977, 0.0], [13.204941238080977, 0.0], [13.304941238080977, 0.0], [13.404941238080976, 0.0], [13.504941238080976, 0.0], [13.604941238080976, 0.0], [13.704941238080973, 0.0], [13.804941238080973, 0.0], [13.904941238080973, 0.0], [14.004941238080972, 0.0], [14.104941238080972, 0.0], [14.204941238080972, 0.0], [14.304941238080971, 0.0], [14.404941238080971, 0.0], [14.50494123808097, 0.0], [14.60494123808097, 0.0], [14.70494123808097, 0.0], [14.8019226984391, 0.0], [14.880934450822906, 0.0], [14.939946203206711, 0.0], [14.978957955590518, 0.0], [14.997969707974324, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884], "velocities": null}}, "time": 1740481179.1636198} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481179.1636198} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.1836197, "x": 9.00192018280211, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.1836197} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.001224438647673715, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.1836197} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2036197} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02121820176785803, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2036197} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2236197} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04119184648083958, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2236197} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2436197} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06114523349238528, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2436197} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2636197} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.00192018280211, 0.0], [5.012120132795986, 0.0], [5.042320082789862, 0.0], [5.092520032783739, 0.0], [5.162719982777615, 0.0], [5.252919932771491, 0.0], [5.363119882765368, 0.0], [5.493319832759243, 0.0], [5.64351978275312, 0.0], [5.806578947168913, 0.0], [5.906578947168914, 0.0], [6.006578947168913, 0.0], [6.106578947168914, 0.0], [6.206578947168914, 0.0], [6.306578947168914, 0.0], [6.406578947168914, 0.0], [6.506578947168913, 0.0], [6.606578947168914, 0.0], [6.706578947168914, 0.0], [6.806578947168914, 0.0], [6.906578947168914, 0.0], [7.006578947168914, 0.0], [7.106578947168915, 0.0], [7.206578947168914, 0.0], [7.306578947168914, 0.0], [7.4065789471689145, 0.0], [7.506578947168915, 0.0], [7.606578947168915, 0.0], [7.706578947168914, 0.0], [7.806578947168916, 0.0], [7.906578947168915, 0.0], [8.006578947168915, 0.0], [8.106578947168915, 0.0], [8.206578947168916, 0.0], [8.306578947168916, 0.0], [8.406578947168915, 0.0], [8.506578947168915, 0.0], [8.606578947168915, 0.0], [8.706578947168914, 0.0], [8.806578947168914, 0.0], [8.906578947168914, 0.0], [9.006578947168911, 0.0], [9.106578947168913, 0.0], [9.20657894716891, 0.0], [9.306578947168912, 0.0], [9.40657894716891, 0.0], [9.506578947168911, 0.0], [9.60657894716891, 0.0], [9.70657894716891, 0.0], [9.806578947168909, 0.0], [9.90657894716891, 0.0], [10.006578947168908, 0.0], [10.10657894716891, 0.0], [10.206578947168907, 0.0], [10.306578947168909, 0.0], [10.406578947168907, 0.0], [10.506578947168908, 0.0], [10.606578947168906, 0.0], [10.706578947168907, 0.0], [10.806578947168905, 0.0], [10.906578947168907, 0.0], [11.006578947168904, 0.0], [11.106578947168906, 0.0], [11.206578947168904, 0.0], [11.306578947168905, 0.0], [11.406578947168903, 0.0], [11.506578947168904, 0.0], [11.606578947168902, 0.0], [11.706578947168904, 0.0], [11.806578947168902, 0.0], [11.906578947168903, 0.0], [12.0065789471689, 0.0], [12.106578947168902, 0.0], [12.2065789471689, 0.0], [12.306578947168902, 0.0], [12.4065789471689, 0.0], [12.5065789471689, 0.0], [12.606578947168899, 0.0], [12.7065789471689, 0.0], [12.806578947168898, 0.0], [12.9065789471689, 0.0], [13.006578947168899, 0.0], [13.106578947168899, 0.0], [13.206578947168898, 0.0], [13.306578947168898, 0.0], [13.406578947168898, 0.0], [13.506578947168897, 0.0], [13.606578947168897, 0.0], [13.706578947168897, 0.0], [13.806578947168896, 0.0], [13.906578947168896, 0.0], [14.006578947168896, 0.0], [14.106578947168895, 0.0], [14.206578947168895, 0.0], [14.306578947168894, 0.0], [14.406578947168894, 0.0], [14.506578947168894, 0.0], [14.606578947168893, 0.0], [14.706578947168893, 0.0], [14.803377769906152, 0.0], [14.882061980472374, 0.0], [14.940746191038595, 0.0], [14.979430401604816, 0.0], [14.998114612171038, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4696938456699067, 1.5696938456699068, 1.6696938456699069, 1.769693845669907, 1.869693845669907, 1.9696938456699071, 2.069693845669907, 2.169693845669907, 2.269693845669907, 2.3696938456699073, 2.4696938456699074, 2.5696938456699074, 2.6696938456699075, 2.7696938456699076, 2.8696938456699077, 2.969693845669908, 3.069693845669908, 3.169693845669908, 3.269693845669908, 3.369693845669908, 3.4696938456699082, 3.5696938456699083, 3.6696938456699084, 3.7696938456699085, 3.8696938456699086, 3.9696938456699087, 4.069693845669908, 4.169693845669908, 4.269693845669908, 4.369693845669907, 4.469693845669907, 4.5696938456699066, 4.669693845669906, 4.769693845669906, 4.8696938456699055, 4.969693845669905, 5.069693845669905, 5.169693845669904, 5.269693845669904, 5.369693845669904, 5.469693845669903, 5.569693845669903, 5.669693845669903, 5.769693845669902, 5.869693845669902, 5.969693845669902, 6.069693845669901, 6.169693845669901, 6.2696938456699005, 6.3696938456699, 6.4696938456699, 6.5696938456698994, 6.669693845669899, 6.769693845669899, 6.869693845669898, 6.969693845669898, 7.069693845669898, 7.169693845669897, 7.269693845669897, 7.369693845669897, 7.469693845669896, 7.569693845669896, 7.6696938456698955, 7.769693845669895, 7.869693845669895, 7.9696938456698945, 8.069693845669894, 8.169693845669894, 8.269693845669893, 8.369693845669893, 8.469693845669893, 8.569693845669892, 8.669693845669892, 8.769693845669892, 8.869693845669891, 8.969693845669891, 9.06969384566989, 9.16969384566989, 9.26969384566989, 9.36969384566989, 9.46969384566989, 9.569693845669889, 9.669693845669888, 9.769693845669888, 9.869693845669888, 9.969693845669887, 10.069693845669887, 10.169693845669887, 10.269693845669886, 10.369693845669886, 10.469693845669886, 10.569693845669885, 10.669693845669885, 10.769693845669885, 10.869693845669884], "velocities": null}}, "time": 1740481179.2636197} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09103702765408891, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2636197} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 5.00192018280211, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.001224438647673715, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.06117600664469444, "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": 1740481179.2836196} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09160305280191727, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.2836196} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.2936196, "x": 9.007452330469965, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3036196} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3806327230601132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09273422313419458, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3036196} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3236196} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3872468636188754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11121405824940593, "gear": 1, "accelerator_pedal_position": 0.3806327230601132, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3236196} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3436196} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.1714432, "x": 15.0, "y": 8.009999999999874, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.3436196} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3872468636188754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1305011815268707, "gear": 1, "accelerator_pedal_position": 0.3872468636188754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3436196} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3636196} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.007452330469965, 0.0], [5.032503429968681, 0.0], [5.077554529467396, 0.0], [5.142605628966113, 0.0], [5.2276567284648285, 0.0], [5.332707827963544, 0.0], [5.45775892746226, 0.0], [5.6028100269609755, 0.0], [5.764408516183699, 0.0], [5.864408516183699, 0.0], [5.964408516183699, 0.0], [6.064408516183699, 0.0], [6.164408516183699, 0.0], [6.2644085161837, 0.0], [6.364408516183699, 0.0], [6.464408516183699, 0.0], [6.5644085161837, 0.0], [6.6644085161837, 0.0], [6.7644085161837, 0.0], [6.864408516183699, 0.0], [6.9644085161837, 0.0], [7.0644085161837005, 0.0], [7.1644085161837, 0.0], [7.2644085161837, 0.0], [7.3644085161837, 0.0], [7.464408516183701, 0.0], [7.5644085161837005, 0.0], [7.6644085161837, 0.0], [7.7644085161837, 0.0], [7.864408516183701, 0.0], [7.964408516183701, 0.0], [8.0644085161837, 0.0], [8.1644085161837, 0.0], [8.264408516183702, 0.0], [8.364408516183701, 0.0], [8.4644085161837, 0.0], [8.5644085161837, 0.0], [8.6644085161837, 0.0], [8.7644085161837, 0.0], [8.8644085161837, 0.0], [8.964408516183699, 0.0], [9.064408516183699, 0.0], [9.164408516183698, 0.0], [9.264408516183698, 0.0], [9.364408516183698, 0.0], [9.464408516183697, 0.0], [9.564408516183697, 0.0], [9.664408516183697, 0.0], [9.764408516183696, 0.0], [9.864408516183696, 0.0], [9.964408516183695, 0.0], [10.064408516183695, 0.0], [10.164408516183695, 0.0], [10.264408516183694, 0.0], [10.364408516183694, 0.0], [10.464408516183694, 0.0], [10.564408516183693, 0.0], [10.664408516183693, 0.0], [10.764408516183693, 0.0], [10.864408516183692, 0.0], [10.964408516183692, 0.0], [11.064408516183692, 0.0], [11.164408516183691, 0.0], [11.26440851618369, 0.0], [11.36440851618369, 0.0], [11.46440851618369, 0.0], [11.56440851618369, 0.0], [11.66440851618369, 0.0], [11.764408516183689, 0.0], [11.864408516183689, 0.0], [11.964408516183688, 0.0], [12.064408516183688, 0.0], [12.164408516183688, 0.0], [12.264408516183687, 0.0], [12.364408516183687, 0.0], [12.464408516183688, 0.0], [12.564408516183686, 0.0], [12.664408516183688, 0.0], [12.764408516183686, 0.0], [12.864408516183687, 0.0], [12.964408516183685, 0.0], [13.064408516183684, 0.0], [13.164408516183684, 0.0], [13.264408516183684, 0.0], [13.364408516183683, 0.0], [13.464408516183683, 0.0], [13.564408516183683, 0.0], [13.664408516183682, 0.0], [13.764408516183682, 0.0], [13.864408516183682, 0.0], [13.964408516183681, 0.0], [14.064408516183681, 0.0], [14.16440851618368, 0.0], [14.26440851618368, 0.0], [14.36440851618368, 0.0], [14.46440851618368, 0.0], [14.56440851618368, 0.0], [14.664408516183679, 0.0], [14.764200910845062, 0.0], [14.851319207608327, 0.0], [14.91843750437159, 0.0], [14.965555801134856, 0.0], [14.99267409789812, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.3063945294843615, 1.4063945294843616, 1.5063945294843617, 1.6063945294843618, 1.7063945294843619, 1.806394529484362, 1.906394529484362, 2.006394529484362, 2.106394529484362, 2.206394529484362, 2.306394529484362, 2.4063945294843623, 2.5063945294843624, 2.6063945294843625, 2.7063945294843625, 2.8063945294843626, 2.9063945294843627, 3.006394529484363, 3.106394529484363, 3.206394529484363, 3.306394529484363, 3.406394529484363, 3.5063945294843633, 3.6063945294843633, 3.7063945294843634, 3.8063945294843635, 3.9063945294843636, 4.006394529484363, 4.106394529484363, 4.2063945294843625, 4.306394529484362, 4.406394529484362, 4.5063945294843615, 4.606394529484361, 4.706394529484361, 4.80639452948436, 4.90639452948436, 5.00639452948436, 5.106394529484359, 5.206394529484359, 5.306394529484359, 5.406394529484358, 5.506394529484358, 5.606394529484358, 5.706394529484357, 5.806394529484357, 5.9063945294843565, 6.006394529484356, 6.106394529484356, 6.206394529484355, 6.306394529484355, 6.406394529484355, 6.506394529484354, 6.606394529484354, 6.706394529484354, 6.806394529484353, 6.906394529484353, 7.006394529484353, 7.106394529484352, 7.206394529484352, 7.3063945294843515, 7.406394529484351, 7.506394529484351, 7.6063945294843505, 7.70639452948435, 7.80639452948435, 7.906394529484349, 8.00639452948435, 8.10639452948435, 8.20639452948435, 8.306394529484349, 8.406394529484349, 8.506394529484348, 8.606394529484348, 8.706394529484347, 8.806394529484347, 8.906394529484347, 9.006394529484346, 9.106394529484346, 9.206394529484346, 9.306394529484345, 9.406394529484345, 9.506394529484345, 9.606394529484344, 9.706394529484344, 9.806394529484344, 9.906394529484343, 10.006394529484343, 10.106394529484342, 10.206394529484342, 10.306394529484342, 10.406394529484341, 10.506394529484341, 10.60639452948434, 10.70639452948434], "velocities": null}}, "time": 1740481179.3636196} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14976805341192728, "gear": 1, "accelerator_pedal_position": 0.3872468636188754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3636196} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 5.007452330469965, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.09216878459928386, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.0565438534910718, "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": 1740481179.3836195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15083826045208149, "gear": 1, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.3836195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.4036195, "x": 9.021371076871302, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4036195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38789516535171176, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15190733312924354, "gear": 1, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4036195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4236195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17123257072008768, "gear": 1, "accelerator_pedal_position": 0.38789516535171176, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4236195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4436195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19105016904852815, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4436195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4636195} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.0213710768713025, 0.0], [5.056177440494878, 0.0], [5.110983804118453, 0.0], [5.185790167742028, 0.0], [5.280596531365604, 0.0], [5.395402894989179, 0.0], [5.5302092586127545, 0.0], [5.684958842436817, 0.0], [5.784958842436818, 0.0], [5.884958842436817, 0.0], [5.984958842436818, 0.0], [6.0849588424368175, 0.0], [6.184958842436818, 0.0], [6.284958842436819, 0.0], [6.384958842436818, 0.0], [6.484958842436818, 0.0], [6.5849588424368175, 0.0], [6.684958842436818, 0.0], [6.784958842436819, 0.0], [6.884958842436818, 0.0], [6.984958842436818, 0.0], [7.084958842436818, 0.0], [7.184958842436819, 0.0], [7.284958842436819, 0.0], [7.384958842436818, 0.0], [7.484958842436819, 0.0], [7.584958842436819, 0.0], [7.684958842436819, 0.0], [7.784958842436819, 0.0], [7.88495884243682, 0.0], [7.98495884243682, 0.0], [8.08495884243682, 0.0], [8.184958842436819, 0.0], [8.28495884243682, 0.0], [8.38495884243682, 0.0], [8.48495884243682, 0.0], [8.58495884243682, 0.0], [8.684958842436819, 0.0], [8.784958842436819, 0.0], [8.884958842436818, 0.0], [8.984958842436818, 0.0], [9.084958842436818, 0.0], [9.184958842436817, 0.0], [9.284958842436817, 0.0], [9.384958842436816, 0.0], [9.484958842436816, 0.0], [9.584958842436816, 0.0], [9.684958842436815, 0.0], [9.784958842436815, 0.0], [9.884958842436815, 0.0], [9.984958842436814, 0.0], [10.084958842436814, 0.0], [10.184958842436814, 0.0], [10.284958842436813, 0.0], [10.384958842436813, 0.0], [10.484958842436813, 0.0], [10.584958842436812, 0.0], [10.684958842436812, 0.0], [10.784958842436811, 0.0], [10.884958842436811, 0.0], [10.98495884243681, 0.0], [11.08495884243681, 0.0], [11.18495884243681, 0.0], [11.28495884243681, 0.0], [11.38495884243681, 0.0], [11.484958842436809, 0.0], [11.584958842436809, 0.0], [11.684958842436808, 0.0], [11.784958842436808, 0.0], [11.884958842436808, 0.0], [11.984958842436807, 0.0], [12.084958842436807, 0.0], [12.184958842436806, 0.0], [12.284958842436806, 0.0], [12.384958842436806, 0.0], [12.484958842436805, 0.0], [12.584958842436805, 0.0], [12.684958842436806, 0.0], [12.784958842436804, 0.0], [12.884958842436806, 0.0], [12.984958842436804, 0.0], [13.084958842436805, 0.0], [13.184958842436805, 0.0], [13.284958842436804, 0.0], [13.384958842436804, 0.0], [13.484958842436804, 0.0], [13.584958842436803, 0.0], [13.684958842436803, 0.0], [13.784958842436803, 0.0], [13.884958842436802, 0.0], [13.984958842436802, 0.0], [14.084958842436802, 0.0], [14.184958842436801, 0.0], [14.2849588424368, 0.0], [14.3849588424368, 0.0], [14.4849588424368, 0.0], [14.5849588424368, 0.0], [14.6849588424368, 0.0], [14.783736721772279, 0.0], [14.866744953284918, 0.0], [14.929753184797558, 0.0], [14.972761416310199, 0.0], [14.995769647822838, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797, 10.643095213298796], "velocities": null}}, "time": 1740481179.4636195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21084648032012404, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4636195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.4836195} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2118512149962841, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.4836195} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 5.0213710768713025, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.15190733312924354, "accelerator_pedal_position": 0.24179795897113315, "brake_pedal_position": 0.0, "acceleration": 0.053411118534535534, "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": 1740481179.5036194} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2128548601925433, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5036194} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.5136194, "x": 9.042542200091958, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5236194} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38749711017683985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21385741668746241, "gear": 1, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5236194} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5436194} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3919661283551731, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23306632737226865, "gear": 1, "accelerator_pedal_position": 0.38749711017683985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5436194} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5636194} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.042542200091958, 0.0], [5.087383133818273, 0.0], [5.152224067544588, 0.0], [5.237065001270903, 0.0], [5.341905934997218, 0.0], [5.466746868723533, 0.0], [5.611587802449847, 0.0], [5.773098512789727, 0.0], [5.873098512789728, 0.0], [5.973098512789727, 0.0], [6.073098512789727, 0.0], [6.1730985127897275, 0.0], [6.273098512789728, 0.0], [6.373098512789728, 0.0], [6.473098512789727, 0.0], [6.573098512789728, 0.0], [6.673098512789728, 0.0], [6.773098512789728, 0.0], [6.873098512789728, 0.0], [6.973098512789728, 0.0], [7.073098512789729, 0.0], [7.173098512789728, 0.0], [7.273098512789728, 0.0], [7.373098512789729, 0.0], [7.473098512789729, 0.0], [7.573098512789729, 0.0], [7.673098512789728, 0.0], [7.773098512789729, 0.0], [7.8730985127897295, 0.0], [7.973098512789729, 0.0], [8.073098512789729, 0.0], [8.173098512789728, 0.0], [8.27309851278973, 0.0], [8.37309851278973, 0.0], [8.47309851278973, 0.0], [8.57309851278973, 0.0], [8.67309851278973, 0.0], [8.77309851278973, 0.0], [8.87309851278973, 0.0], [8.97309851278973, 0.0], [9.073098512789727, 0.0], [9.173098512789728, 0.0], [9.273098512789726, 0.0], [9.373098512789728, 0.0], [9.473098512789726, 0.0], [9.573098512789727, 0.0], [9.673098512789725, 0.0], [9.773098512789726, 0.0], [9.873098512789724, 0.0], [9.973098512789726, 0.0], [10.073098512789723, 0.0], [10.173098512789725, 0.0], [10.273098512789723, 0.0], [10.373098512789724, 0.0], [10.473098512789722, 0.0], [10.573098512789723, 0.0], [10.673098512789721, 0.0], [10.773098512789723, 0.0], [10.87309851278972, 0.0], [10.973098512789722, 0.0], [11.07309851278972, 0.0], [11.173098512789721, 0.0], [11.27309851278972, 0.0], [11.37309851278972, 0.0], [11.473098512789718, 0.0], [11.57309851278972, 0.0], [11.673098512789718, 0.0], [11.77309851278972, 0.0], [11.873098512789717, 0.0], [11.973098512789718, 0.0], [12.073098512789716, 0.0], [12.173098512789718, 0.0], [12.273098512789716, 0.0], [12.373098512789717, 0.0], [12.473098512789715, 0.0], [12.573098512789716, 0.0], [12.673098512789716, 0.0], [12.773098512789716, 0.0], [12.873098512789715, 0.0], [12.973098512789715, 0.0], [13.073098512789715, 0.0], [13.173098512789714, 0.0], [13.273098512789714, 0.0], [13.373098512789714, 0.0], [13.473098512789713, 0.0], [13.573098512789713, 0.0], [13.673098512789712, 0.0], [13.773098512789712, 0.0], [13.873098512789712, 0.0], [13.973098512789711, 0.0], [14.073098512789711, 0.0], [14.17309851278971, 0.0], [14.27309851278971, 0.0], [14.37309851278971, 0.0], [14.47309851278971, 0.0], [14.57309851278971, 0.0], [14.673098512789709, 0.0], [14.772564971496612, 0.0], [14.85794526893867, 0.0], [14.92332556638073, 0.0], [14.968705863822787, 0.0], [14.994086161264844, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797], "velocities": null}}, "time": 1740481179.5636194} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25281275504561174, "gear": 1, "accelerator_pedal_position": 0.3919661283551731, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5636194} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.5836194} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.3912098, "x": 15.0, "y": 8.11999999999989, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.5836194} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2537716402453045, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.5836194} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 5.042542200091958, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.21335627447899205, "accelerator_pedal_position": 0.24179795897113282, "brake_pedal_position": 0.0, "acceleration": 0.0501142208470349, "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": 1740481179.6036193} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2547294696074293, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6036193} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.6236193, "x": 9.069049716268669, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6236193} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39194661769077443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25568624392770506, "gear": 1, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6236193} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6436193} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2754053646061096, "gear": 1, "accelerator_pedal_position": 0.39194661769077443, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6436193} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6636193} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.069049716268669, 0.0], [5.120803105060114, 0.0], [5.1925564938515585, 0.0], [5.2843098826430035, 0.0], [5.396063271434448, 0.0], [5.527816660225893, 0.0], [5.679570049017338, 0.0], [5.8428096179151865, 0.0], [5.942809617915187, 0.0], [6.042809617915187, 0.0], [6.142809617915187, 0.0], [6.242809617915187, 0.0], [6.342809617915187, 0.0], [6.442809617915187, 0.0], [6.542809617915188, 0.0], [6.642809617915187, 0.0], [6.742809617915187, 0.0], [6.842809617915187, 0.0], [6.942809617915188, 0.0], [7.042809617915188, 0.0], [7.142809617915187, 0.0], [7.242809617915188, 0.0], [7.342809617915188, 0.0], [7.442809617915188, 0.0], [7.542809617915188, 0.0], [7.642809617915188, 0.0], [7.742809617915189, 0.0], [7.842809617915188, 0.0], [7.942809617915188, 0.0], [8.04280961791519, 0.0], [8.142809617915189, 0.0], [8.242809617915189, 0.0], [8.342809617915188, 0.0], [8.442809617915188, 0.0], [8.54280961791519, 0.0], [8.642809617915189, 0.0], [8.742809617915189, 0.0], [8.842809617915188, 0.0], [8.942809617915188, 0.0], [9.042809617915188, 0.0], [9.142809617915187, 0.0], [9.242809617915189, 0.0], [9.342809617915186, 0.0], [9.442809617915188, 0.0], [9.542809617915186, 0.0], [9.642809617915187, 0.0], [9.742809617915185, 0.0], [9.842809617915185, 0.0], [9.942809617915184, 0.0], [10.042809617915184, 0.0], [10.142809617915184, 0.0], [10.242809617915183, 0.0], [10.342809617915183, 0.0], [10.442809617915183, 0.0], [10.542809617915182, 0.0], [10.642809617915182, 0.0], [10.742809617915182, 0.0], [10.842809617915181, 0.0], [10.94280961791518, 0.0], [11.04280961791518, 0.0], [11.14280961791518, 0.0], [11.24280961791518, 0.0], [11.34280961791518, 0.0], [11.442809617915179, 0.0], [11.542809617915179, 0.0], [11.642809617915178, 0.0], [11.742809617915178, 0.0], [11.842809617915178, 0.0], [11.942809617915177, 0.0], [12.042809617915177, 0.0], [12.142809617915177, 0.0], [12.242809617915176, 0.0], [12.342809617915176, 0.0], [12.442809617915175, 0.0], [12.542809617915175, 0.0], [12.642809617915175, 0.0], [12.742809617915174, 0.0], [12.842809617915176, 0.0], [12.942809617915174, 0.0], [13.042809617915175, 0.0], [13.142809617915175, 0.0], [13.242809617915174, 0.0], [13.342809617915174, 0.0], [13.442809617915174, 0.0], [13.542809617915173, 0.0], [13.642809617915173, 0.0], [13.742809617915173, 0.0], [13.842809617915172, 0.0], [13.942809617915172, 0.0], [14.042809617915172, 0.0], [14.142809617915171, 0.0], [14.24280961791517, 0.0], [14.34280961791517, 0.0], [14.44280961791517, 0.0], [14.54280961791517, 0.0], [14.64280961791517, 0.0], [14.742809617915169, 0.0], [14.834195992737609, 0.0], [14.905634069154575, 0.0], [14.95707214557154, 0.0], [14.988510221988507, 0.0], [14.999948298405474, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.1430952132988164, 1.2430952132988164, 1.3430952132988165, 1.4430952132988166, 1.5430952132988167, 1.6430952132988168, 1.743095213298817, 1.843095213298817, 1.943095213298817, 2.043095213298817, 2.143095213298817, 2.243095213298817, 2.343095213298817, 2.4430952132988173, 2.5430952132988174, 2.6430952132988175, 2.7430952132988176, 2.8430952132988176, 2.9430952132988177, 3.043095213298818, 3.143095213298818, 3.243095213298818, 3.343095213298818, 3.443095213298818, 3.5430952132988183, 3.6430952132988184, 3.7430952132988184, 3.8430952132988185, 3.9430952132988186, 4.043095213298819, 4.143095213298818, 4.243095213298818, 4.343095213298818, 4.443095213298817, 4.543095213298817, 4.643095213298817, 4.743095213298816, 4.843095213298816, 4.9430952132988155, 5.043095213298815, 5.143095213298815, 5.2430952132988144, 5.343095213298814, 5.443095213298814, 5.543095213298813, 5.643095213298813, 5.743095213298813, 5.843095213298812, 5.943095213298812, 6.043095213298812, 6.143095213298811, 6.243095213298811, 6.3430952132988105, 6.44309521329881, 6.54309521329881, 6.6430952132988095, 6.743095213298809, 6.843095213298809, 6.943095213298808, 7.043095213298808, 7.143095213298808, 7.243095213298807, 7.343095213298807, 7.443095213298807, 7.543095213298806, 7.643095213298806, 7.743095213298806, 7.843095213298805, 7.943095213298805, 8.043095213298805, 8.143095213298805, 8.243095213298805, 8.343095213298804, 8.443095213298804, 8.543095213298804, 8.643095213298803, 8.743095213298803, 8.843095213298803, 8.943095213298802, 9.043095213298802, 9.143095213298801, 9.243095213298801, 9.3430952132988, 9.4430952132988, 9.5430952132988, 9.6430952132988, 9.7430952132988, 9.843095213298799, 9.943095213298799, 10.043095213298798, 10.143095213298798, 10.243095213298798, 10.343095213298797, 10.443095213298797, 10.543095213298797], "velocities": null}}, "time": 1740481179.6636193} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3049530461372646, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6636193} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.6836193} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3054036424138569, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.6836193} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.7036192} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30630407666654824, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7036192} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 5.069049716268669, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.25568624392770506, "accelerator_pedal_position": 0.24179795897113254, "brake_pedal_position": 0.0, "acceleration": 0.04779917681985449, "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": 1740481179.7236192} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30765283381337716, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7236192} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.7336192, "x": 9.101184533156012, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7436192} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38970391262979476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.30810191480555094, "gear": 1, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7436192} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7636192} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.101184533156012, 0.0], [5.161424030540282, 0.0], [5.241663527924551, 0.0], [5.341903025308821, 0.0], [5.462142522693091, 0.0], [5.60238202007736, 0.0], [5.761417364584852, 0.0], [5.8614173645848515, 0.0], [5.961417364584852, 0.0], [6.061417364584852, 0.0], [6.161417364584851, 0.0], [6.261417364584852, 0.0], [6.361417364584852, 0.0], [6.461417364584852, 0.0], [6.561417364584852, 0.0], [6.661417364584852, 0.0], [6.761417364584853, 0.0], [6.861417364584852, 0.0], [6.961417364584852, 0.0], [7.061417364584853, 0.0], [7.161417364584853, 0.0], [7.261417364584853, 0.0], [7.361417364584852, 0.0], [7.461417364584853, 0.0], [7.5614173645848535, 0.0], [7.661417364584853, 0.0], [7.761417364584853, 0.0], [7.861417364584853, 0.0], [7.961417364584854, 0.0], [8.061417364584853, 0.0], [8.161417364584853, 0.0], [8.261417364584855, 0.0], [8.361417364584854, 0.0], [8.461417364584854, 0.0], [8.561417364584853, 0.0], [8.661417364584853, 0.0], [8.761417364584855, 0.0], [8.861417364584854, 0.0], [8.961417364584854, 0.0], [9.061417364584853, 0.0], [9.161417364584853, 0.0], [9.261417364584853, 0.0], [9.361417364584852, 0.0], [9.461417364584852, 0.0], [9.561417364584852, 0.0], [9.661417364584851, 0.0], [9.761417364584851, 0.0], [9.86141736458485, 0.0], [9.96141736458485, 0.0], [10.06141736458485, 0.0], [10.16141736458485, 0.0], [10.26141736458485, 0.0], [10.361417364584849, 0.0], [10.461417364584848, 0.0], [10.561417364584848, 0.0], [10.661417364584848, 0.0], [10.761417364584847, 0.0], [10.861417364584847, 0.0], [10.961417364584847, 0.0], [11.061417364584846, 0.0], [11.161417364584846, 0.0], [11.261417364584846, 0.0], [11.361417364584845, 0.0], [11.461417364584845, 0.0], [11.561417364584845, 0.0], [11.661417364584844, 0.0], [11.761417364584844, 0.0], [11.861417364584844, 0.0], [11.961417364584843, 0.0], [12.061417364584843, 0.0], [12.161417364584842, 0.0], [12.261417364584842, 0.0], [12.361417364584842, 0.0], [12.461417364584841, 0.0], [12.561417364584841, 0.0], [12.66141736458484, 0.0], [12.76141736458484, 0.0], [12.86141736458484, 0.0], [12.96141736458484, 0.0], [13.06141736458484, 0.0], [13.161417364584839, 0.0], [13.261417364584839, 0.0], [13.361417364584838, 0.0], [13.461417364584838, 0.0], [13.561417364584837, 0.0], [13.661417364584837, 0.0], [13.761417364584835, 0.0], [13.861417364584835, 0.0], [13.961417364584834, 0.0], [14.061417364584834, 0.0], [14.161417364584834, 0.0], [14.261417364584833, 0.0], [14.361417364584833, 0.0], [14.461417364584833, 0.0], [14.561417364584832, 0.0], [14.661417364584832, 0.0], [14.761287008370768, 0.0], [14.849003535453802, 0.0], [14.916720062536836, 0.0], [14.964436589619869, 0.0], [14.992153116702903, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251], "velocities": null}}, "time": 1740481179.7636192} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34684093670559946, "gear": 1, "accelerator_pedal_position": 0.38970391262979476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7636192} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.7836192} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34684093670559946, "gear": 1, "accelerator_pedal_position": 0.38970391262979476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.7836192} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.8036191} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34769453781911985, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.8036191} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 5.101184533156012, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.30765283381337716, "accelerator_pedal_position": 0.24179795897113296, "brake_pedal_position": 0.0, "acceleration": 0.04490809921737807, "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": 1740481179.8236191} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.241797958971133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34897311730373193, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.8236191} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.843619, "x": 9.138040942771699, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.843619} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.6112149, "x": 15.0, "y": 8.229999999999908, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481179.843619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34939882495711583, "gear": 1, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.843619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.863619} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.138040942771699, 0.0], [5.205097531963229, 0.0], [5.292154121154759, 0.0], [5.399210710346289, 0.0], [5.526267299537819, 0.0], [5.67332388872935, 0.0], [5.835648913906849, 0.0], [5.935648913906849, 0.0], [6.035648913906849, 0.0], [6.1356489139068495, 0.0], [6.23564891390685, 0.0], [6.33564891390685, 0.0], [6.435648913906849, 0.0], [6.53564891390685, 0.0], [6.63564891390685, 0.0], [6.73564891390685, 0.0], [6.83564891390685, 0.0], [6.935648913906849, 0.0], [7.03564891390685, 0.0], [7.13564891390685, 0.0], [7.23564891390685, 0.0], [7.33564891390685, 0.0], [7.43564891390685, 0.0], [7.535648913906851, 0.0], [7.63564891390685, 0.0], [7.73564891390685, 0.0], [7.835648913906851, 0.0], [7.935648913906851, 0.0], [8.03564891390685, 0.0], [8.13564891390685, 0.0], [8.23564891390685, 0.0], [8.335648913906851, 0.0], [8.435648913906851, 0.0], [8.53564891390685, 0.0], [8.635648913906852, 0.0], [8.735648913906852, 0.0], [8.835648913906851, 0.0], [8.935648913906851, 0.0], [9.03564891390685, 0.0], [9.13564891390685, 0.0], [9.23564891390685, 0.0], [9.33564891390685, 0.0], [9.43564891390685, 0.0], [9.535648913906849, 0.0], [9.635648913906849, 0.0], [9.735648913906848, 0.0], [9.835648913906848, 0.0], [9.935648913906848, 0.0], [10.035648913906847, 0.0], [10.135648913906847, 0.0], [10.235648913906847, 0.0], [10.335648913906846, 0.0], [10.435648913906846, 0.0], [10.535648913906845, 0.0], [10.635648913906845, 0.0], [10.735648913906845, 0.0], [10.835648913906844, 0.0], [10.935648913906844, 0.0], [11.035648913906844, 0.0], [11.135648913906843, 0.0], [11.235648913906843, 0.0], [11.335648913906843, 0.0], [11.435648913906842, 0.0], [11.535648913906842, 0.0], [11.635648913906842, 0.0], [11.735648913906841, 0.0], [11.83564891390684, 0.0], [11.93564891390684, 0.0], [12.03564891390684, 0.0], [12.13564891390684, 0.0], [12.23564891390684, 0.0], [12.335648913906839, 0.0], [12.435648913906839, 0.0], [12.535648913906838, 0.0], [12.635648913906838, 0.0], [12.735648913906838, 0.0], [12.835648913906837, 0.0], [12.935648913906837, 0.0], [13.035648913906837, 0.0], [13.135648913906836, 0.0], [13.235648913906836, 0.0], [13.335648913906835, 0.0], [13.435648913906835, 0.0], [13.535648913906835, 0.0], [13.635648913906834, 0.0], [13.735648913906834, 0.0], [13.835648913906834, 0.0], [13.935648913906833, 0.0], [14.035648913906833, 0.0], [14.135648913906833, 0.0], [14.235648913906832, 0.0], [14.335648913906832, 0.0], [14.435648913906832, 0.0], [14.535648913906831, 0.0], [14.63564891390683, 0.0], [14.73564891390683, 0.0], [14.82831317745341, 0.0], [14.901183394672044, 0.0], [14.954053611890679, 0.0], [14.986923829109312, 0.0], [14.999794046327946, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251, 10.379795897113251], "velocities": null}}, "time": 1740481179.863619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36943365351094865, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.863619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.883619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3698476609974543, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.883619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.903619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3706749632409567, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.903619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.923619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3719141363142496, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.923619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 5.138040942771699, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34939882495711583, "accelerator_pedal_position": 0.241797958971133, "brake_pedal_position": 0.0, "acceleration": 0.04254650693291118, "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": 1740481179.943619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37232671966930925, "gear": 1, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.943619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481179.953619, "x": 9.178487725666972, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481179.963619} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.178487725666972, 0.0], [5.249355760264747, 0.0], [5.340223794862522, 0.0], [5.451091829460297, 0.0], [5.581959864058072, 0.0], [5.732827898655846, 0.0], [5.895979436587416, 0.0], [5.995979436587415, 0.0], [6.095979436587416, 0.0], [6.195979436587416, 0.0], [6.295979436587416, 0.0], [6.395979436587416, 0.0], [6.495979436587416, 0.0], [6.595979436587417, 0.0], [6.695979436587416, 0.0], [6.795979436587416, 0.0], [6.8959794365874165, 0.0], [6.995979436587417, 0.0], [7.095979436587417, 0.0], [7.195979436587416, 0.0], [7.295979436587417, 0.0], [7.395979436587417, 0.0], [7.495979436587417, 0.0], [7.595979436587417, 0.0], [7.695979436587417, 0.0], [7.795979436587418, 0.0], [7.895979436587417, 0.0], [7.995979436587417, 0.0], [8.095979436587417, 0.0], [8.195979436587418, 0.0], [8.295979436587418, 0.0], [8.395979436587417, 0.0], [8.495979436587419, 0.0], [8.595979436587418, 0.0], [8.695979436587418, 0.0], [8.795979436587418, 0.0], [8.895979436587417, 0.0], [8.995979436587419, 0.0], [9.095979436587417, 0.0], [9.195979436587418, 0.0], [9.295979436587416, 0.0], [9.395979436587417, 0.0], [9.495979436587415, 0.0], [9.595979436587417, 0.0], [9.695979436587415, 0.0], [9.795979436587414, 0.0], [9.895979436587414, 0.0], [9.995979436587414, 0.0], [10.095979436587413, 0.0], [10.195979436587413, 0.0], [10.295979436587412, 0.0], [10.395979436587412, 0.0], [10.495979436587412, 0.0], [10.595979436587411, 0.0], [10.695979436587411, 0.0], [10.79597943658741, 0.0], [10.89597943658741, 0.0], [10.99597943658741, 0.0], [11.09597943658741, 0.0], [11.19597943658741, 0.0], [11.295979436587409, 0.0], [11.395979436587409, 0.0], [11.495979436587408, 0.0], [11.595979436587408, 0.0], [11.695979436587407, 0.0], [11.795979436587407, 0.0], [11.895979436587407, 0.0], [11.995979436587406, 0.0], [12.095979436587406, 0.0], [12.195979436587406, 0.0], [12.295979436587405, 0.0], [12.395979436587405, 0.0], [12.495979436587405, 0.0], [12.595979436587404, 0.0], [12.695979436587404, 0.0], [12.795979436587404, 0.0], [12.895979436587403, 0.0], [12.995979436587403, 0.0], [13.095979436587402, 0.0], [13.195979436587402, 0.0], [13.295979436587402, 0.0], [13.395979436587401, 0.0], [13.495979436587401, 0.0], [13.5959794365874, 0.0], [13.6959794365874, 0.0], [13.795979436587402, 0.0], [13.895979436587401, 0.0], [13.995979436587401, 0.0], [14.0959794365874, 0.0], [14.1959794365874, 0.0], [14.2959794365874, 0.0], [14.3959794365874, 0.0], [14.4959794365874, 0.0], [14.595979436587399, 0.0], [14.695979436587399, 0.0], [14.793865327998503, 0.0], [14.874669440681023, 0.0], [14.935473553363543, 0.0], [14.976277666046064, 0.0], [14.997081778728585, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.9797958971132712, 1.0797958971132713, 1.1797958971132714, 1.2797958971132715, 1.3797958971132716, 1.4797958971132716, 1.5797958971132717, 1.6797958971132718, 1.779795897113272, 1.879795897113272, 1.979795897113272, 2.079795897113272, 2.179795897113272, 2.279795897113272, 2.379795897113272, 2.4797958971132723, 2.5797958971132724, 2.6797958971132725, 2.7797958971132726, 2.8797958971132727, 2.9797958971132728, 3.079795897113273, 3.179795897113273, 3.279795897113273, 3.379795897113273, 3.479795897113273, 3.5797958971132733, 3.6797958971132734, 3.7797958971132735, 3.8797958971132736, 3.9797958971132736, 4.079795897113273, 4.179795897113273, 4.279795897113273, 4.379795897113272, 4.479795897113272, 4.5797958971132715, 4.679795897113271, 4.779795897113271, 4.87979589711327, 4.97979589711327, 5.07979589711327, 5.179795897113269, 5.279795897113269, 5.379795897113269, 5.479795897113268, 5.579795897113268, 5.679795897113268, 5.779795897113267, 5.879795897113267, 5.9797958971132665, 6.079795897113266, 6.179795897113266, 6.2797958971132655, 6.379795897113265, 6.479795897113265, 6.579795897113264, 6.679795897113264, 6.779795897113264, 6.879795897113263, 6.979795897113263, 7.079795897113263, 7.179795897113262, 7.279795897113262, 7.379795897113262, 7.479795897113261, 7.579795897113261, 7.6797958971132605, 7.77979589711326, 7.87979589711326, 7.979795897113259, 8.079795897113259, 8.179795897113259, 8.279795897113258, 8.379795897113258, 8.479795897113258, 8.579795897113257, 8.679795897113257, 8.779795897113257, 8.879795897113256, 8.979795897113256, 9.079795897113256, 9.179795897113255, 9.279795897113255, 9.379795897113254, 9.479795897113254, 9.579795897113254, 9.679795897113253, 9.779795897113253, 9.879795897113253, 9.979795897113252, 10.079795897113252, 10.179795897113252, 10.279795897113251], "velocities": null}}, "time": 1740481179.963619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3829506757203799, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.963619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481179.983619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3927445352605162, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481179.983619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.003619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41231526853627576, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.003619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.023619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44162866607304435, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.023619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 5.178487725666972, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.37273906602655243, "accelerator_pedal_position": 0.24179795897113293, "brake_pedal_position": 0.0, "acceleration": 0.041210946154829675, "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": 1740481180.043619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4513883481521381, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.043619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.063619, "x": 9.223933206777517, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.063619} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.223933206777517, 0.0], [5.310829294031899, 0.0], [5.4177253812862824, 0.0], [5.544621468540665, 0.0], [5.6915175557950475, 0.0], [5.853791838461971, 0.0], [5.953791838461971, 0.0], [6.053791838461971, 0.0], [6.153791838461971, 0.0], [6.2537918384619715, 0.0], [6.353791838461971, 0.0], [6.453791838461971, 0.0], [6.553791838461971, 0.0], [6.653791838461972, 0.0], [6.7537918384619715, 0.0], [6.853791838461971, 0.0], [6.953791838461972, 0.0], [7.053791838461972, 0.0], [7.153791838461972, 0.0], [7.2537918384619715, 0.0], [7.353791838461972, 0.0], [7.453791838461973, 0.0], [7.553791838461972, 0.0], [7.653791838461972, 0.0], [7.753791838461972, 0.0], [7.853791838461973, 0.0], [7.953791838461973, 0.0], [8.053791838461972, 0.0], [8.153791838461974, 0.0], [8.253791838461973, 0.0], [8.353791838461973, 0.0], [8.453791838461973, 0.0], [8.553791838461972, 0.0], [8.653791838461974, 0.0], [8.753791838461973, 0.0], [8.853791838461973, 0.0], [8.953791838461974, 0.0], [9.053791838461972, 0.0], [9.153791838461974, 0.0], [9.253791838461972, 0.0], [9.353791838461973, 0.0], [9.45379183846197, 0.0], [9.553791838461972, 0.0], [9.65379183846197, 0.0], [9.753791838461972, 0.0], [9.85379183846197, 0.0], [9.95379183846197, 0.0], [10.053791838461969, 0.0], [10.15379183846197, 0.0], [10.253791838461968, 0.0], [10.35379183846197, 0.0], [10.453791838461967, 0.0], [10.553791838461969, 0.0], [10.653791838461967, 0.0], [10.753791838461968, 0.0], [10.853791838461966, 0.0], [10.953791838461967, 0.0], [11.053791838461965, 0.0], [11.153791838461967, 0.0], [11.253791838461964, 0.0], [11.353791838461966, 0.0], [11.453791838461964, 0.0], [11.553791838461965, 0.0], [11.653791838461963, 0.0], [11.753791838461964, 0.0], [11.853791838461962, 0.0], [11.953791838461964, 0.0], [12.053791838461962, 0.0], [12.153791838461963, 0.0], [12.25379183846196, 0.0], [12.353791838461962, 0.0], [12.45379183846196, 0.0], [12.553791838461962, 0.0], [12.65379183846196, 0.0], [12.75379183846196, 0.0], [12.853791838461959, 0.0], [12.95379183846196, 0.0], [13.05379183846196, 0.0], [13.15379183846196, 0.0], [13.253791838461959, 0.0], [13.353791838461959, 0.0], [13.453791838461958, 0.0], [13.553791838461958, 0.0], [13.653791838461958, 0.0], [13.753791838461959, 0.0], [13.853791838461957, 0.0], [13.953791838461958, 0.0], [14.053791838461956, 0.0], [14.153791838461958, 0.0], [14.253791838461956, 0.0], [14.353791838461957, 0.0], [14.453791838461955, 0.0], [14.553791838461956, 0.0], [14.653791838461954, 0.0], [14.753777460423034, 0.0], [14.843019092730643, 0.0], [14.912260725038252, 0.0], [14.96150235734586, 0.0], [14.990743989653469, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707], "velocities": null}}, "time": 1740481180.063619} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4806328234723088, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.063619} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.0836189} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481180.8789096, "x": 15.0, "y": 8.339999999999925, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.0836189} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49036940626947273, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.0836189} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1036189} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5098251152446635, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1036189} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1236188} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5292574457982978, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1236188} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1436188} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5486662750219582, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1436188} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 5.223933206777517, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.4708904424744274, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9742380997881409, "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": 1740481180.1636188} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.223933206777517, 0.0], [5.310829294031899, 0.0], [5.4177253812862824, 0.0], [5.544621468540665, 0.0], [5.6915175557950475, 0.0], [5.853791838461971, 0.0], [5.953791838461971, 0.0], [6.053791838461971, 0.0], [6.153791838461971, 0.0], [6.2537918384619715, 0.0], [6.353791838461971, 0.0], [6.453791838461971, 0.0], [6.553791838461971, 0.0], [6.653791838461972, 0.0], [6.7537918384619715, 0.0], [6.853791838461971, 0.0], [6.953791838461972, 0.0], [7.053791838461972, 0.0], [7.153791838461972, 0.0], [7.2537918384619715, 0.0], [7.353791838461972, 0.0], [7.453791838461973, 0.0], [7.553791838461972, 0.0], [7.653791838461972, 0.0], [7.753791838461972, 0.0], [7.853791838461973, 0.0], [7.953791838461973, 0.0], [8.053791838461972, 0.0], [8.153791838461974, 0.0], [8.253791838461973, 0.0], [8.353791838461973, 0.0], [8.453791838461973, 0.0], [8.553791838461972, 0.0], [8.653791838461974, 0.0], [8.753791838461973, 0.0], [8.853791838461973, 0.0], [8.953791838461974, 0.0], [9.053791838461972, 0.0], [9.153791838461974, 0.0], [9.253791838461972, 0.0], [9.353791838461973, 0.0], [9.45379183846197, 0.0], [9.553791838461972, 0.0], [9.65379183846197, 0.0], [9.753791838461972, 0.0], [9.85379183846197, 0.0], [9.95379183846197, 0.0], [10.053791838461969, 0.0], [10.15379183846197, 0.0], [10.253791838461968, 0.0], [10.35379183846197, 0.0], [10.453791838461967, 0.0], [10.553791838461969, 0.0], [10.653791838461967, 0.0], [10.753791838461968, 0.0], [10.853791838461966, 0.0], [10.953791838461967, 0.0], [11.053791838461965, 0.0], [11.153791838461967, 0.0], [11.253791838461964, 0.0], [11.353791838461966, 0.0], [11.453791838461964, 0.0], [11.553791838461965, 0.0], [11.653791838461963, 0.0], [11.753791838461964, 0.0], [11.853791838461962, 0.0], [11.953791838461964, 0.0], [12.053791838461962, 0.0], [12.153791838461963, 0.0], [12.25379183846196, 0.0], [12.353791838461962, 0.0], [12.45379183846196, 0.0], [12.553791838461962, 0.0], [12.65379183846196, 0.0], [12.75379183846196, 0.0], [12.853791838461959, 0.0], [12.95379183846196, 0.0], [13.05379183846196, 0.0], [13.15379183846196, 0.0], [13.253791838461959, 0.0], [13.353791838461959, 0.0], [13.453791838461958, 0.0], [13.553791838461958, 0.0], [13.653791838461958, 0.0], [13.753791838461959, 0.0], [13.853791838461957, 0.0], [13.953791838461958, 0.0], [14.053791838461956, 0.0], [14.153791838461958, 0.0], [14.253791838461956, 0.0], [14.353791838461957, 0.0], [14.453791838461955, 0.0], [14.553791838461956, 0.0], [14.653791838461954, 0.0], [14.753777460423034, 0.0], [14.843019092730643, 0.0], [14.912260725038252, 0.0], [14.96150235734586, 0.0], [14.990743989653469, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.816496580927726, 0.916496580927726, 1.016496580927726, 1.116496580927726, 1.2164965809277262, 1.3164965809277263, 1.4164965809277263, 1.5164965809277264, 1.6164965809277265, 1.7164965809277266, 1.8164965809277267, 1.9164965809277268, 2.016496580927727, 2.116496580927727, 2.216496580927727, 2.316496580927727, 2.4164965809277272, 2.5164965809277273, 2.6164965809277274, 2.7164965809277275, 2.8164965809277276, 2.9164965809277277, 3.0164965809277278, 3.116496580927728, 3.216496580927728, 3.316496580927728, 3.416496580927728, 3.516496580927728, 3.6164965809277283, 3.7164965809277284, 3.8164965809277285, 3.9164965809277286, 4.016496580927728, 4.116496580927728, 4.2164965809277275, 4.316496580927727, 4.416496580927727, 4.516496580927726, 4.616496580927726, 4.716496580927726, 4.816496580927725, 4.916496580927725, 5.016496580927725, 5.116496580927724, 5.216496580927724, 5.316496580927724, 5.416496580927723, 5.516496580927723, 5.6164965809277225, 5.716496580927722, 5.816496580927722, 5.9164965809277215, 6.016496580927721, 6.116496580927721, 6.21649658092772, 6.31649658092772, 6.41649658092772, 6.516496580927719, 6.616496580927719, 6.716496580927719, 6.816496580927718, 6.916496580927718, 7.0164965809277176, 7.116496580927717, 7.216496580927717, 7.3164965809277165, 7.416496580927716, 7.516496580927716, 7.616496580927715, 7.716496580927715, 7.816496580927715, 7.916496580927714, 8.016496580927715, 8.116496580927715, 8.216496580927714, 8.316496580927714, 8.416496580927713, 8.516496580927713, 8.616496580927713, 8.716496580927712, 8.816496580927712, 8.916496580927712, 9.016496580927711, 9.116496580927711, 9.21649658092771, 9.31649658092771, 9.41649658092771, 9.51649658092771, 9.61649658092771, 9.716496580927709, 9.816496580927708, 9.916496580927708, 10.016496580927708, 10.116496580927707], "velocities": null}}, "time": 1740481180.1636188} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5680514807028445, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1636188} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.1736188, "x": 9.281079846967561, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.1836188} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454354274936285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5874129413260665, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.1836188} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2036188} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5884356301587572, "gear": 1, "accelerator_pedal_position": 0.2454354274936285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2036188} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2236187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5893150112653633, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2236187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2436187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24429871783506363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5901933061108833, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2436187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 5.281079846967561, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5777351867140202, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "acceleration": 0.9677754612046241, "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": 1740481180.2636187} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.281079846967561, 0.0], [5.385423607894289, 0.0], [5.5097673688210165, 0.0], [5.654111129747744, 0.0], [5.815405396683446, 0.0], [5.915405396683447, 0.0], [6.015405396683446, 0.0], [6.115405396683446, 0.0], [6.215405396683447, 0.0], [6.315405396683446, 0.0], [6.415405396683447, 0.0], [6.515405396683446, 0.0], [6.615405396683446, 0.0], [6.715405396683447, 0.0], [6.815405396683447, 0.0], [6.915405396683447, 0.0], [7.015405396683446, 0.0], [7.115405396683447, 0.0], [7.2154053966834475, 0.0], [7.315405396683447, 0.0], [7.415405396683447, 0.0], [7.515405396683447, 0.0], [7.615405396683448, 0.0], [7.7154053966834475, 0.0], [7.815405396683447, 0.0], [7.915405396683448, 0.0], [8.015405396683448, 0.0], [8.115405396683448, 0.0], [8.215405396683447, 0.0], [8.315405396683449, 0.0], [8.415405396683449, 0.0], [8.515405396683448, 0.0], [8.615405396683448, 0.0], [8.715405396683447, 0.0], [8.815405396683449, 0.0], [8.915405396683449, 0.0], [9.015405396683448, 0.0], [9.11540539668345, 0.0], [9.215405396683447, 0.0], [9.315405396683449, 0.0], [9.415405396683447, 0.0], [9.515405396683448, 0.0], [9.615405396683446, 0.0], [9.715405396683447, 0.0], [9.815405396683445, 0.0], [9.915405396683447, 0.0], [10.015405396683445, 0.0], [10.115405396683446, 0.0], [10.215405396683444, 0.0], [10.315405396683445, 0.0], [10.415405396683443, 0.0], [10.515405396683445, 0.0], [10.615405396683443, 0.0], [10.715405396683444, 0.0], [10.815405396683442, 0.0], [10.915405396683443, 0.0], [11.015405396683441, 0.0], [11.115405396683443, 0.0], [11.21540539668344, 0.0], [11.315405396683442, 0.0], [11.41540539668344, 0.0], [11.515405396683441, 0.0], [11.615405396683439, 0.0], [11.71540539668344, 0.0], [11.815405396683438, 0.0], [11.91540539668344, 0.0], [12.015405396683438, 0.0], [12.115405396683439, 0.0], [12.215405396683437, 0.0], [12.315405396683438, 0.0], [12.415405396683436, 0.0], [12.515405396683438, 0.0], [12.615405396683435, 0.0], [12.715405396683437, 0.0], [12.815405396683435, 0.0], [12.915405396683436, 0.0], [13.015405396683434, 0.0], [13.115405396683435, 0.0], [13.215405396683433, 0.0], [13.315405396683435, 0.0], [13.415405396683433, 0.0], [13.515405396683434, 0.0], [13.615405396683432, 0.0], [13.715405396683433, 0.0], [13.815405396683431, 0.0], [13.915405396683433, 0.0], [14.01540539668343, 0.0], [14.115405396683432, 0.0], [14.21540539668343, 0.0], [14.315405396683431, 0.0], [14.415405396683429, 0.0], [14.51540539668343, 0.0], [14.615405396683428, 0.0], [14.71540539668343, 0.0], [14.811127530768111, 0.0], [14.888046451431425, 0.0], [14.944965372094739, 0.0], [14.981884292758055, 0.0], [14.998803213421368, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162, 10.053197264742161], "velocities": null}}, "time": 1740481180.2636187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5910705157286623, "gear": 1, "accelerator_pedal_position": 0.24429871783506363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2636187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.2836187, "x": 9.345806859456825, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.2836187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5916341429304511, "gear": 1, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.2836187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3036187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6109665145330997, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3036187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3236187} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6302748740379055, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3236187} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3436186} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.2090857, "x": 15.0, "y": 8.504999999999951, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.3436186} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6495591021910521, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3436186} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3636186} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.345806859456825, 0.0], [5.452420310429389, 0.0], [5.579033761401953, 0.0], [5.725647212374517, 0.0], [5.887829008718908, 0.0], [5.987829008718908, 0.0], [6.0878290087189075, 0.0], [6.187829008718908, 0.0], [6.287829008718908, 0.0], [6.387829008718908, 0.0], [6.487829008718908, 0.0], [6.587829008718908, 0.0], [6.687829008718908, 0.0], [6.787829008718909, 0.0], [6.887829008718908, 0.0], [6.987829008718909, 0.0], [7.087829008718908, 0.0], [7.187829008718909, 0.0], [7.287829008718909, 0.0], [7.387829008718908, 0.0], [7.487829008718909, 0.0], [7.587829008718909, 0.0], [7.687829008718909, 0.0], [7.787829008718909, 0.0], [7.887829008718909, 0.0], [7.98782900871891, 0.0], [8.08782900871891, 0.0], [8.187829008718909, 0.0], [8.287829008718909, 0.0], [8.38782900871891, 0.0], [8.48782900871891, 0.0], [8.58782900871891, 0.0], [8.68782900871891, 0.0], [8.78782900871891, 0.0], [8.88782900871891, 0.0], [8.98782900871891, 0.0], [9.08782900871891, 0.0], [9.18782900871891, 0.0], [9.28782900871891, 0.0], [9.38782900871891, 0.0], [9.48782900871891, 0.0], [9.58782900871891, 0.0], [9.687829008718909, 0.0], [9.787829008718909, 0.0], [9.887829008718908, 0.0], [9.987829008718908, 0.0], [10.087829008718908, 0.0], [10.187829008718907, 0.0], [10.287829008718907, 0.0], [10.387829008718906, 0.0], [10.487829008718906, 0.0], [10.587829008718906, 0.0], [10.687829008718905, 0.0], [10.787829008718905, 0.0], [10.887829008718905, 0.0], [10.987829008718904, 0.0], [11.087829008718904, 0.0], [11.187829008718904, 0.0], [11.287829008718903, 0.0], [11.387829008718903, 0.0], [11.487829008718903, 0.0], [11.587829008718902, 0.0], [11.687829008718902, 0.0], [11.787829008718901, 0.0], [11.887829008718901, 0.0], [11.9878290087189, 0.0], [12.0878290087189, 0.0], [12.1878290087189, 0.0], [12.2878290087189, 0.0], [12.3878290087189, 0.0], [12.487829008718899, 0.0], [12.587829008718899, 0.0], [12.687829008718898, 0.0], [12.787829008718898, 0.0], [12.887829008718898, 0.0], [12.987829008718897, 0.0], [13.087829008718897, 0.0], [13.187829008718897, 0.0], [13.287829008718896, 0.0], [13.387829008718896, 0.0], [13.487829008718895, 0.0], [13.587829008718895, 0.0], [13.687829008718895, 0.0], [13.787829008718893, 0.0], [13.887829008718892, 0.0], [13.987829008718892, 0.0], [14.087829008718892, 0.0], [14.187829008718891, 0.0], [14.28782900871889, 0.0], [14.38782900871889, 0.0], [14.48782900871889, 0.0], [14.58782900871889, 0.0], [14.68782900871889, 0.0], [14.786397974818236, 0.0], [14.868832173074457, 0.0], [14.931266371330679, 0.0], [14.973700569586901, 0.0], [14.996134767843124, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.6531972647421809, 0.7531972647421808, 0.8531972647421808, 0.9531972647421808, 1.0531972647421808, 1.1531972647421809, 1.253197264742181, 1.353197264742181, 1.4531972647421811, 1.5531972647421812, 1.6531972647421813, 1.7531972647421814, 1.8531972647421815, 1.9531972647421816, 2.0531972647421814, 2.1531972647421815, 2.2531972647421816, 2.3531972647421817, 2.453197264742182, 2.553197264742182, 2.653197264742182, 2.753197264742182, 2.853197264742182, 2.9531972647421822, 3.0531972647421823, 3.1531972647421824, 3.2531972647421825, 3.3531972647421826, 3.4531972647421827, 3.553197264742183, 3.653197264742183, 3.753197264742183, 3.853197264742183, 3.953197264742183, 4.053197264742183, 4.153197264742182, 4.253197264742182, 4.353197264742182, 4.453197264742181, 4.553197264742181, 4.653197264742181, 4.75319726474218, 4.85319726474218, 4.95319726474218, 5.053197264742179, 5.153197264742179, 5.2531972647421785, 5.353197264742178, 5.453197264742178, 5.5531972647421775, 5.653197264742177, 5.753197264742177, 5.853197264742176, 5.953197264742176, 6.053197264742176, 6.153197264742175, 6.253197264742175, 6.353197264742175, 6.453197264742174, 6.553197264742174, 6.6531972647421735, 6.753197264742173, 6.853197264742173, 6.9531972647421725, 7.053197264742172, 7.153197264742172, 7.253197264742171, 7.353197264742171, 7.453197264742171, 7.55319726474217, 7.65319726474217, 7.75319726474217, 7.853197264742169, 7.953197264742169, 8.053197264742169, 8.153197264742168, 8.253197264742168, 8.353197264742168, 8.453197264742167, 8.553197264742167, 8.653197264742166, 8.753197264742166, 8.853197264742166, 8.953197264742165, 9.053197264742165, 9.153197264742165, 9.253197264742164, 9.353197264742164, 9.453197264742164, 9.553197264742163, 9.653197264742163, 9.753197264742163, 9.853197264742162, 9.953197264742162], "velocities": null}}, "time": 1740481180.3636186} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6688190804458469, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3636186} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 5.345806859456825, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5916341429304511, "accelerator_pedal_position": 0.24179795897113285, "brake_pedal_position": 0.0, "acceleration": 0.028155226832247165, "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": 1740481180.3836186} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6692853946255112, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.3836186} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.3936186, "x": 9.41591316533819, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4036186} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38367217910766993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6697511178611791, "gear": 1, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4036186} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4236186} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38933648902881296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6879448987322853, "gear": 1, "accelerator_pedal_position": 0.38367217910766993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4236186} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4436185} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38933648902881296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7068233321472241, "gear": 1, "accelerator_pedal_position": 0.38933648902881296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4436185} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4636185} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.415913165338189, 0.0], [5.5352450508123, 0.0], [5.67457693628641, 0.0], [5.832999024454987, 0.0], [5.932999024454988, 0.0], [6.032999024454988, 0.0], [6.132999024454987, 0.0], [6.232999024454988, 0.0], [6.332999024454987, 0.0], [6.432999024454988, 0.0], [6.532999024454988, 0.0], [6.632999024454988, 0.0], [6.732999024454988, 0.0], [6.832999024454988, 0.0], [6.932999024454988, 0.0], [7.0329990244549885, 0.0], [7.132999024454988, 0.0], [7.232999024454989, 0.0], [7.332999024454988, 0.0], [7.432999024454988, 0.0], [7.5329990244549885, 0.0], [7.632999024454989, 0.0], [7.732999024454989, 0.0], [7.832999024454988, 0.0], [7.932999024454989, 0.0], [8.03299902445499, 0.0], [8.132999024454989, 0.0], [8.232999024454989, 0.0], [8.332999024454988, 0.0], [8.43299902445499, 0.0], [8.53299902445499, 0.0], [8.632999024454989, 0.0], [8.73299902445499, 0.0], [8.83299902445499, 0.0], [8.93299902445499, 0.0], [9.03299902445499, 0.0], [9.132999024454989, 0.0], [9.23299902445499, 0.0], [9.33299902445499, 0.0], [9.43299902445499, 0.0], [9.532999024454991, 0.0], [9.632999024454989, 0.0], [9.73299902445499, 0.0], [9.832999024454988, 0.0], [9.93299902445499, 0.0], [10.032999024454988, 0.0], [10.132999024454989, 0.0], [10.232999024454987, 0.0], [10.332999024454988, 0.0], [10.432999024454986, 0.0], [10.532999024454988, 0.0], [10.632999024454985, 0.0], [10.732999024454987, 0.0], [10.832999024454985, 0.0], [10.932999024454986, 0.0], [11.032999024454984, 0.0], [11.132999024454985, 0.0], [11.232999024454983, 0.0], [11.332999024454985, 0.0], [11.432999024454983, 0.0], [11.532999024454984, 0.0], [11.632999024454982, 0.0], [11.732999024454983, 0.0], [11.832999024454981, 0.0], [11.932999024454983, 0.0], [12.03299902445498, 0.0], [12.132999024454982, 0.0], [12.23299902445498, 0.0], [12.332999024454981, 0.0], [12.432999024454979, 0.0], [12.53299902445498, 0.0], [12.632999024454978, 0.0], [12.73299902445498, 0.0], [12.832999024454978, 0.0], [12.932999024454979, 0.0], [13.032999024454977, 0.0], [13.132999024454978, 0.0], [13.232999024454976, 0.0], [13.332999024454978, 0.0], [13.432999024454976, 0.0], [13.532999024454975, 0.0], [13.632999024454975, 0.0], [13.732999024454974, 0.0], [13.832999024454974, 0.0], [13.932999024454974, 0.0], [14.032999024454973, 0.0], [14.132999024454973, 0.0], [14.232999024454973, 0.0], [14.332999024454972, 0.0], [14.432999024454972, 0.0], [14.532999024454972, 0.0], [14.632999024454971, 0.0], [14.732999024454971, 0.0], [14.826110186394494, 0.0], [14.8995103815035, 0.0], [14.952910576612505, 0.0], [14.986310771721511, 0.0], [14.999710966830516, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618, 9.889897948556618], "velocities": null}}, "time": 1740481180.4636185} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7258744658778239, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4636185} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 5.415913165338189, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6695183300699483, "accelerator_pedal_position": 0.24179795897113252, "brake_pedal_position": 0.0, "acceleration": 0.023278779123084237, "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": 1740481180.4836185} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7260712117065594, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.4836185} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.5036185, "x": 9.493217368318382, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5036185} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38854506948249906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.726464322620177, "gear": 1, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5036185} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5236185} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7451943879823668, "gear": 1, "accelerator_pedal_position": 0.38854506948249906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5236185} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5436184} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7643319089805063, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5436184} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5636184} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.493217368318382, 0.0], [5.621848495435452, 0.0], [5.770479622552522, 0.0], [5.933234139008592, 0.0], [6.0332341390085915, 0.0], [6.133234139008591, 0.0], [6.233234139008592, 0.0], [6.333234139008591, 0.0], [6.433234139008592, 0.0], [6.5332341390085915, 0.0], [6.633234139008591, 0.0], [6.733234139008592, 0.0], [6.833234139008592, 0.0], [6.933234139008592, 0.0], [7.0332341390085915, 0.0], [7.133234139008592, 0.0], [7.233234139008593, 0.0], [7.333234139008592, 0.0], [7.433234139008592, 0.0], [7.533234139008592, 0.0], [7.633234139008593, 0.0], [7.733234139008593, 0.0], [7.833234139008592, 0.0], [7.933234139008593, 0.0], [8.033234139008593, 0.0], [8.133234139008593, 0.0], [8.233234139008593, 0.0], [8.333234139008592, 0.0], [8.433234139008594, 0.0], [8.533234139008593, 0.0], [8.633234139008593, 0.0], [8.733234139008594, 0.0], [8.833234139008594, 0.0], [8.933234139008594, 0.0], [9.033234139008593, 0.0], [9.133234139008593, 0.0], [9.233234139008594, 0.0], [9.333234139008594, 0.0], [9.433234139008594, 0.0], [9.533234139008595, 0.0], [9.633234139008593, 0.0], [9.733234139008594, 0.0], [9.833234139008592, 0.0], [9.933234139008594, 0.0], [10.033234139008592, 0.0], [10.133234139008593, 0.0], [10.23323413900859, 0.0], [10.333234139008592, 0.0], [10.43323413900859, 0.0], [10.533234139008592, 0.0], [10.63323413900859, 0.0], [10.73323413900859, 0.0], [10.833234139008589, 0.0], [10.93323413900859, 0.0], [11.033234139008588, 0.0], [11.13323413900859, 0.0], [11.233234139008587, 0.0], [11.333234139008589, 0.0], [11.433234139008587, 0.0], [11.533234139008588, 0.0], [11.633234139008586, 0.0], [11.733234139008587, 0.0], [11.833234139008585, 0.0], [11.933234139008587, 0.0], [12.033234139008584, 0.0], [12.133234139008586, 0.0], [12.233234139008584, 0.0], [12.333234139008585, 0.0], [12.433234139008583, 0.0], [12.533234139008584, 0.0], [12.633234139008582, 0.0], [12.733234139008584, 0.0], [12.833234139008582, 0.0], [12.933234139008583, 0.0], [13.03323413900858, 0.0], [13.133234139008582, 0.0], [13.23323413900858, 0.0], [13.333234139008582, 0.0], [13.43323413900858, 0.0], [13.533234139008579, 0.0], [13.633234139008579, 0.0], [13.733234139008578, 0.0], [13.83323413900858, 0.0], [13.933234139008578, 0.0], [14.033234139008579, 0.0], [14.133234139008577, 0.0], [14.233234139008578, 0.0], [14.333234139008576, 0.0], [14.433234139008578, 0.0], [14.533234139008576, 0.0], [14.633234139008577, 0.0], [14.733234139008575, 0.0], [14.826306217112077, 0.0], [14.899659389310361, 0.0], [14.953012561508645, 0.0], [14.986365733706931, 0.0], [14.999718905905215, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.48989794855663565, 0.5898979485566357, 0.6898979485566357, 0.7898979485566356, 0.8898979485566356, 0.9898979485566356, 1.0898979485566356, 1.1898979485566357, 1.2898979485566358, 1.3898979485566358, 1.489897948556636, 1.589897948556636, 1.689897948556636, 1.7898979485566362, 1.8898979485566363, 1.9898979485566364, 2.0898979485566365, 2.1898979485566366, 2.2898979485566366, 2.3898979485566367, 2.489897948556637, 2.589897948556637, 2.689897948556637, 2.789897948556637, 2.889897948556637, 2.9898979485566373, 3.0898979485566374, 3.1898979485566374, 3.2898979485566375, 3.3898979485566376, 3.4898979485566377, 3.589897948556638, 3.689897948556638, 3.789897948556638, 3.889897948556638, 3.989897948556638, 4.089897948556638, 4.189897948556638, 4.2898979485566375, 4.389897948556637, 4.489897948556637, 4.5898979485566365, 4.689897948556636, 4.789897948556636, 4.889897948556635, 4.989897948556635, 5.089897948556635, 5.189897948556634, 5.289897948556634, 5.389897948556634, 5.489897948556633, 5.589897948556633, 5.689897948556633, 5.789897948556632, 5.889897948556632, 5.9898979485566315, 6.089897948556631, 6.189897948556631, 6.28989794855663, 6.38989794855663, 6.48989794855663, 6.589897948556629, 6.689897948556629, 6.789897948556629, 6.889897948556628, 6.989897948556628, 7.089897948556628, 7.189897948556627, 7.289897948556627, 7.3898979485566265, 7.489897948556626, 7.589897948556626, 7.6898979485566255, 7.789897948556625, 7.889897948556625, 7.989897948556624, 8.089897948556624, 8.189897948556624, 8.289897948556623, 8.389897948556623, 8.489897948556623, 8.589897948556622, 8.689897948556622, 8.789897948556622, 8.889897948556621, 8.98989794855662, 9.08989794855662, 9.18989794855662, 9.28989794855662, 9.38989794855662, 9.489897948556619, 9.589897948556619, 9.689897948556618, 9.789897948556618], "velocities": null}}, "time": 1740481180.5636184} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7834444862600229, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5636184} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.5836184} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.4290733, "x": 15.0, "y": 8.614999999999968, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.5836184} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7837629249980725, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.5836184} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 5.493217368318382, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.726464322620177, "accelerator_pedal_position": 0.2417979589711328, "brake_pedal_position": 0.0, "acceleration": 0.01963652331817109, "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": 1740481180.6036184} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7840809456126807, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6036184} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.6136184, "x": 9.577410315180376, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6236184} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3883520258497558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7843985486124194, "gear": 1, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6236184} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6436183} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8030289674101166, "gear": 1, "accelerator_pedal_position": 0.3883520258497558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6436183} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6636183} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.577410315180376, 0.0], [5.715476138128722, 0.0], [5.8729739714090705, 0.0], [5.972973971409071, 0.0], [6.072973971409071, 0.0], [6.17297397140907, 0.0], [6.272973971409071, 0.0], [6.3729739714090705, 0.0], [6.47297397140907, 0.0], [6.572973971409071, 0.0], [6.67297397140907, 0.0], [6.772973971409071, 0.0], [6.8729739714090705, 0.0], [6.972973971409071, 0.0], [7.072973971409071, 0.0], [7.172973971409071, 0.0], [7.272973971409071, 0.0], [7.372973971409071, 0.0], [7.472973971409071, 0.0], [7.572973971409072, 0.0], [7.672973971409071, 0.0], [7.772973971409071, 0.0], [7.872973971409071, 0.0], [7.972973971409072, 0.0], [8.072973971409072, 0.0], [8.172973971409071, 0.0], [8.272973971409073, 0.0], [8.372973971409072, 0.0], [8.472973971409072, 0.0], [8.572973971409073, 0.0], [8.672973971409071, 0.0], [8.772973971409073, 0.0], [8.872973971409072, 0.0], [8.972973971409072, 0.0], [9.072973971409073, 0.0], [9.172973971409073, 0.0], [9.272973971409073, 0.0], [9.372973971409074, 0.0], [9.472973971409072, 0.0], [9.572973971409073, 0.0], [9.672973971409071, 0.0], [9.772973971409073, 0.0], [9.87297397140907, 0.0], [9.972973971409072, 0.0], [10.07297397140907, 0.0], [10.172973971409071, 0.0], [10.272973971409069, 0.0], [10.37297397140907, 0.0], [10.472973971409068, 0.0], [10.57297397140907, 0.0], [10.672973971409068, 0.0], [10.772973971409069, 0.0], [10.872973971409067, 0.0], [10.972973971409068, 0.0], [11.072973971409066, 0.0], [11.172973971409068, 0.0], [11.272973971409066, 0.0], [11.372973971409067, 0.0], [11.472973971409065, 0.0], [11.572973971409066, 0.0], [11.672973971409064, 0.0], [11.772973971409066, 0.0], [11.872973971409063, 0.0], [11.972973971409065, 0.0], [12.072973971409063, 0.0], [12.172973971409064, 0.0], [12.272973971409062, 0.0], [12.372973971409063, 0.0], [12.472973971409061, 0.0], [12.572973971409063, 0.0], [12.67297397140906, 0.0], [12.772973971409062, 0.0], [12.87297397140906, 0.0], [12.972973971409061, 0.0], [13.07297397140906, 0.0], [13.17297397140906, 0.0], [13.272973971409058, 0.0], [13.37297397140906, 0.0], [13.472973971409058, 0.0], [13.57297397140906, 0.0], [13.672973971409057, 0.0], [13.772973971409057, 0.0], [13.872973971409056, 0.0], [13.972973971409056, 0.0], [14.072973971409056, 0.0], [14.172973971409055, 0.0], [14.272973971409055, 0.0], [14.372973971409055, 0.0], [14.472973971409054, 0.0], [14.572973971409054, 0.0], [14.672973971409053, 0.0], [14.772446168046748, 0.0], [14.857851373764937, 0.0], [14.923256579483127, 0.0], [14.968661785201316, 0.0], [14.994066990919507, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073, 9.626598632371072], "velocities": null}}, "time": 1740481180.6636183} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8220906600328797, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6636183} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.6836183} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.822358058769981, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.6836183} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 5.577410315180376, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7842397992826429, "accelerator_pedal_position": 0.24179795897113265, "brake_pedal_position": 0.0, "acceleration": 0.015874932977658046, "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": 1740481180.7036183} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24179795897113304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8226251022745532, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7036183} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.7236183, "x": 9.66653526964325, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7236183} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8228917909899981, "gear": 1, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7236183} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7436182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8419271326108738, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7436182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7636182} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.66653526964325, 0.0], [5.8109129364066145, 0.0], [5.972222356881853, 0.0], [6.072222356881853, 0.0], [6.1722223568818535, 0.0], [6.272222356881853, 0.0], [6.372222356881853, 0.0], [6.472222356881853, 0.0], [6.572222356881853, 0.0], [6.672222356881853, 0.0], [6.772222356881853, 0.0], [6.872222356881853, 0.0], [6.972222356881853, 0.0], [7.072222356881853, 0.0], [7.1722223568818535, 0.0], [7.272222356881853, 0.0], [7.372222356881854, 0.0], [7.472222356881853, 0.0], [7.572222356881854, 0.0], [7.6722223568818535, 0.0], [7.772222356881853, 0.0], [7.872222356881854, 0.0], [7.972222356881854, 0.0], [8.072222356881854, 0.0], [8.172222356881853, 0.0], [8.272222356881855, 0.0], [8.372222356881855, 0.0], [8.472222356881854, 0.0], [8.572222356881854, 0.0], [8.672222356881853, 0.0], [8.772222356881855, 0.0], [8.872222356881855, 0.0], [8.972222356881854, 0.0], [9.072222356881856, 0.0], [9.172222356881855, 0.0], [9.272222356881855, 0.0], [9.372222356881855, 0.0], [9.472222356881854, 0.0], [9.572222356881856, 0.0], [9.672222356881855, 0.0], [9.772222356881855, 0.0], [9.872222356881855, 0.0], [9.972222356881854, 0.0], [10.072222356881852, 0.0], [10.172222356881853, 0.0], [10.272222356881851, 0.0], [10.372222356881853, 0.0], [10.47222235688185, 0.0], [10.572222356881852, 0.0], [10.67222235688185, 0.0], [10.772222356881851, 0.0], [10.87222235688185, 0.0], [10.97222235688185, 0.0], [11.072222356881849, 0.0], [11.17222235688185, 0.0], [11.272222356881848, 0.0], [11.37222235688185, 0.0], [11.472222356881847, 0.0], [11.572222356881849, 0.0], [11.672222356881846, 0.0], [11.772222356881848, 0.0], [11.872222356881846, 0.0], [11.972222356881847, 0.0], [12.072222356881845, 0.0], [12.172222356881846, 0.0], [12.272222356881844, 0.0], [12.372222356881846, 0.0], [12.472222356881844, 0.0], [12.572222356881845, 0.0], [12.672222356881843, 0.0], [12.772222356881844, 0.0], [12.872222356881842, 0.0], [12.972222356881844, 0.0], [13.072222356881841, 0.0], [13.172222356881843, 0.0], [13.27222235688184, 0.0], [13.372222356881842, 0.0], [13.47222235688184, 0.0], [13.572222356881841, 0.0], [13.672222356881841, 0.0], [13.77222235688184, 0.0], [13.87222235688184, 0.0], [13.97222235688184, 0.0], [14.07222235688184, 0.0], [14.17222235688184, 0.0], [14.272222356881839, 0.0], [14.372222356881839, 0.0], [14.472222356881838, 0.0], [14.572222356881838, 0.0], [14.672222356881838, 0.0], [14.771728523736453, 0.0], [14.857284052360086, 0.0], [14.922839580983718, 0.0], [14.96839510960735, 0.0], [14.993950638230983, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073, 9.526598632371073], "velocities": null}}, "time": 1740481180.7636182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8609370730680085, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7636182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.7836182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8611525658862832, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.7836182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.8036182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8613677690848842, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8036182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 5.66653526964325, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8228917909899981, "accelerator_pedal_position": 0.24179795897113304, "brake_pedal_position": 0.0, "acceleration": 0.013321145023294262, "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": 1740481180.8236182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8615826830345381, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8236182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.8336182, "x": 9.760310142154793, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.8436182} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.6489406, "x": 15.0, "y": 8.724999999999985, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481180.8436182} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8617973081055478, "gear": 1, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8436182} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.8636181} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.760310142154793, 0.0], [5.9110235350882405, 0.0], [6.074155676297142, 0.0], [6.174155676297143, 0.0], [6.274155676297142, 0.0], [6.374155676297143, 0.0], [6.474155676297142, 0.0], [6.574155676297142, 0.0], [6.674155676297143, 0.0], [6.774155676297142, 0.0], [6.874155676297143, 0.0], [6.974155676297142, 0.0], [7.074155676297142, 0.0], [7.174155676297143, 0.0], [7.274155676297143, 0.0], [7.374155676297143, 0.0], [7.474155676297142, 0.0], [7.574155676297143, 0.0], [7.6741556762971435, 0.0], [7.774155676297143, 0.0], [7.874155676297143, 0.0], [7.974155676297143, 0.0], [8.074155676297144, 0.0], [8.174155676297143, 0.0], [8.274155676297143, 0.0], [8.374155676297143, 0.0], [8.474155676297144, 0.0], [8.574155676297144, 0.0], [8.674155676297143, 0.0], [8.774155676297145, 0.0], [8.874155676297145, 0.0], [8.974155676297144, 0.0], [9.074155676297144, 0.0], [9.174155676297143, 0.0], [9.274155676297145, 0.0], [9.374155676297145, 0.0], [9.474155676297144, 0.0], [9.574155676297146, 0.0], [9.674155676297145, 0.0], [9.774155676297145, 0.0], [9.874155676297143, 0.0], [9.974155676297144, 0.0], [10.074155676297144, 0.0], [10.174155676297143, 0.0], [10.274155676297143, 0.0], [10.374155676297143, 0.0], [10.474155676297142, 0.0], [10.574155676297142, 0.0], [10.674155676297142, 0.0], [10.774155676297141, 0.0], [10.874155676297141, 0.0], [10.97415567629714, 0.0], [11.07415567629714, 0.0], [11.17415567629714, 0.0], [11.27415567629714, 0.0], [11.37415567629714, 0.0], [11.474155676297139, 0.0], [11.574155676297138, 0.0], [11.674155676297138, 0.0], [11.774155676297138, 0.0], [11.874155676297137, 0.0], [11.974155676297137, 0.0], [12.074155676297137, 0.0], [12.174155676297136, 0.0], [12.274155676297136, 0.0], [12.374155676297136, 0.0], [12.474155676297135, 0.0], [12.574155676297135, 0.0], [12.674155676297135, 0.0], [12.774155676297134, 0.0], [12.874155676297134, 0.0], [12.974155676297134, 0.0], [13.074155676297133, 0.0], [13.174155676297133, 0.0], [13.274155676297132, 0.0], [13.374155676297132, 0.0], [13.474155676297132, 0.0], [13.574155676297131, 0.0], [13.674155676297131, 0.0], [13.77415567629713, 0.0], [13.87415567629713, 0.0], [13.97415567629713, 0.0], [14.07415567629713, 0.0], [14.17415567629713, 0.0], [14.274155676297129, 0.0], [14.374155676297129, 0.0], [14.474155676297128, 0.0], [14.574155676297128, 0.0], [14.674155676297127, 0.0], [14.773572179599755, 0.0], [14.85874104434033, 0.0], [14.923909909080905, 0.0], [14.96907877382148, 0.0], [14.994247638562054, 0.0]], "times": [0, 0.16329931618554522, 0.32659863237109044, 0.4265986323710904, 0.5265986323710904, 0.6265986323710904, 0.7265986323710903, 0.8265986323710903, 0.9265986323710903, 1.0265986323710903, 1.1265986323710904, 1.2265986323710905, 1.3265986323710905, 1.4265986323710906, 1.5265986323710907, 1.6265986323710908, 1.726598632371091, 1.826598632371091, 1.926598632371091, 2.026598632371091, 2.126598632371091, 2.226598632371091, 2.326598632371091, 2.4265986323710913, 2.5265986323710914, 2.6265986323710915, 2.7265986323710916, 2.8265986323710917, 2.9265986323710917, 3.026598632371092, 3.126598632371092, 3.226598632371092, 3.326598632371092, 3.426598632371092, 3.5265986323710923, 3.6265986323710924, 3.7265986323710925, 3.8265986323710925, 3.9265986323710926, 4.026598632371092, 4.126598632371092, 4.226598632371092, 4.326598632371091, 4.426598632371091, 4.5265986323710905, 4.62659863237109, 4.72659863237109, 4.826598632371089, 4.926598632371089, 5.026598632371089, 5.126598632371088, 5.226598632371088, 5.326598632371088, 5.426598632371087, 5.526598632371087, 5.626598632371087, 5.726598632371086, 5.826598632371086, 5.9265986323710855, 6.026598632371085, 6.126598632371085, 6.2265986323710845, 6.326598632371084, 6.426598632371084, 6.526598632371083, 6.626598632371083, 6.726598632371083, 6.826598632371082, 6.926598632371082, 7.026598632371082, 7.126598632371081, 7.226598632371081, 7.3265986323710806, 7.42659863237108, 7.52659863237108, 7.6265986323710795, 7.726598632371079, 7.826598632371079, 7.926598632371078, 8.026598632371078, 8.126598632371078, 8.226598632371077, 8.326598632371077, 8.426598632371077, 8.526598632371076, 8.626598632371076, 8.726598632371076, 8.826598632371075, 8.926598632371075, 9.026598632371075, 9.126598632371074, 9.226598632371074, 9.326598632371073, 9.426598632371073], "velocities": null}}, "time": 1740481180.8636181} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8902626111898707, "gear": 1, "accelerator_pedal_position": 0.392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.8636181} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.883618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8903505955682833, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.883618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.903618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8905263853876026, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.903618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 5.760310142154793, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8616900316567461, "accelerator_pedal_position": 0.2417979589711324, "brake_pedal_position": 0.0, "acceleration": 0.010727644880174081, "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": 1740481180.923618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417979589711325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8907019368828357, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.923618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481180.943618, "x": 9.857402581377343, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.943618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35668368121407473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8908772503647633, "gear": 1, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.943618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.963618} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.857402581377343, 0.0], [6.012763381237585, 0.0], [6.112763381237586, 0.0], [6.212763381237585, 0.0], [6.312763381237586, 0.0], [6.4127633812375855, 0.0], [6.512763381237585, 0.0], [6.612763381237586, 0.0], [6.712763381237585, 0.0], [6.812763381237585, 0.0], [6.9127633812375855, 0.0], [7.012763381237585, 0.0], [7.112763381237585, 0.0], [7.212763381237585, 0.0], [7.312763381237586, 0.0], [7.4127633812375855, 0.0], [7.512763381237585, 0.0], [7.612763381237586, 0.0], [7.712763381237586, 0.0], [7.812763381237586, 0.0], [7.9127633812375855, 0.0], [8.012763381237587, 0.0], [8.112763381237587, 0.0], [8.212763381237586, 0.0], [8.312763381237588, 0.0], [8.412763381237587, 0.0], [8.512763381237587, 0.0], [8.612763381237587, 0.0], [8.712763381237586, 0.0], [8.812763381237588, 0.0], [8.912763381237587, 0.0], [9.012763381237587, 0.0], [9.112763381237588, 0.0], [9.212763381237588, 0.0], [9.312763381237588, 0.0], [9.412763381237587, 0.0], [9.512763381237587, 0.0], [9.612763381237588, 0.0], [9.712763381237588, 0.0], [9.812763381237588, 0.0], [9.912763381237589, 0.0], [10.012763381237587, 0.0], [10.112763381237587, 0.0], [10.212763381237586, 0.0], [10.312763381237586, 0.0], [10.412763381237585, 0.0], [10.512763381237585, 0.0], [10.612763381237585, 0.0], [10.712763381237584, 0.0], [10.812763381237584, 0.0], [10.912763381237584, 0.0], [11.012763381237583, 0.0], [11.112763381237583, 0.0], [11.212763381237583, 0.0], [11.312763381237582, 0.0], [11.412763381237582, 0.0], [11.512763381237582, 0.0], [11.612763381237581, 0.0], [11.71276338123758, 0.0], [11.81276338123758, 0.0], [11.91276338123758, 0.0], [12.01276338123758, 0.0], [12.11276338123758, 0.0], [12.212763381237579, 0.0], [12.312763381237579, 0.0], [12.412763381237578, 0.0], [12.512763381237578, 0.0], [12.612763381237578, 0.0], [12.712763381237577, 0.0], [12.812763381237577, 0.0], [12.912763381237577, 0.0], [13.012763381237576, 0.0], [13.112763381237576, 0.0], [13.212763381237576, 0.0], [13.312763381237575, 0.0], [13.412763381237575, 0.0], [13.512763381237574, 0.0], [13.612763381237574, 0.0], [13.712763381237574, 0.0], [13.812763381237573, 0.0], [13.912763381237573, 0.0], [14.012763381237574, 0.0], [14.112763381237574, 0.0], [14.212763381237574, 0.0], [14.312763381237573, 0.0], [14.412763381237573, 0.0], [14.512763381237573, 0.0], [14.612763381237572, 0.0], [14.712763381237572, 0.0], [14.808824139213199, 0.0], [14.886271462965684, 0.0], [14.94371878671817, 0.0], [14.981166110470655, 0.0], [14.998613434223142, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553, 9.363299316185529], "velocities": null}}, "time": 1740481180.963618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9054785807608252, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.963618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481180.983618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9055489469629818, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481180.983618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.003618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9057597581363629, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.003618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.023618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9059000597073356, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.023618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 5.857402581377343, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8908772503647633, "accelerator_pedal_position": 0.2417979589711325, "brake_pedal_position": 0.0, "acceleration": 0.008756758299165002, "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": 1740481181.043618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168151421693906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9059701388242228, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.043618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.053618, "x": 9.956804849483587, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.063618} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[5.9568048494835875, 0.0], [6.114218532592286, 0.0], [6.2142185325922865, 0.0], [6.314218532592286, 0.0], [6.414218532592286, 0.0], [6.514218532592286, 0.0], [6.614218532592286, 0.0], [6.7142185325922865, 0.0], [6.814218532592286, 0.0], [6.914218532592286, 0.0], [7.014218532592286, 0.0], [7.114218532592286, 0.0], [7.214218532592286, 0.0], [7.314218532592286, 0.0], [7.414218532592287, 0.0], [7.514218532592286, 0.0], [7.614218532592286, 0.0], [7.7142185325922865, 0.0], [7.814218532592287, 0.0], [7.914218532592287, 0.0], [8.014218532592286, 0.0], [8.114218532592288, 0.0], [8.214218532592287, 0.0], [8.314218532592287, 0.0], [8.414218532592287, 0.0], [8.514218532592288, 0.0], [8.614218532592288, 0.0], [8.714218532592287, 0.0], [8.814218532592289, 0.0], [8.914218532592288, 0.0], [9.014218532592288, 0.0], [9.114218532592288, 0.0], [9.214218532592287, 0.0], [9.314218532592289, 0.0], [9.414218532592288, 0.0], [9.514218532592288, 0.0], [9.61421853259229, 0.0], [9.71421853259229, 0.0], [9.814218532592289, 0.0], [9.914218532592288, 0.0], [10.014218532592288, 0.0], [10.11421853259229, 0.0], [10.214218532592287, 0.0], [10.314218532592289, 0.0], [10.414218532592287, 0.0], [10.514218532592288, 0.0], [10.614218532592286, 0.0], [10.714218532592287, 0.0], [10.814218532592285, 0.0], [10.914218532592287, 0.0], [11.014218532592285, 0.0], [11.114218532592286, 0.0], [11.214218532592284, 0.0], [11.314218532592285, 0.0], [11.414218532592283, 0.0], [11.514218532592285, 0.0], [11.614218532592282, 0.0], [11.714218532592284, 0.0], [11.814218532592282, 0.0], [11.914218532592283, 0.0], [12.014218532592281, 0.0], [12.114218532592282, 0.0], [12.21421853259228, 0.0], [12.314218532592282, 0.0], [12.41421853259228, 0.0], [12.514218532592281, 0.0], [12.614218532592279, 0.0], [12.71421853259228, 0.0], [12.814218532592278, 0.0], [12.91421853259228, 0.0], [13.014218532592277, 0.0], [13.114218532592279, 0.0], [13.214218532592277, 0.0], [13.314218532592278, 0.0], [13.414218532592276, 0.0], [13.514218532592277, 0.0], [13.614218532592275, 0.0], [13.714218532592277, 0.0], [13.814218532592275, 0.0], [13.914218532592276, 0.0], [14.014218532592274, 0.0], [14.114218532592274, 0.0], [14.214218532592273, 0.0], [14.314218532592273, 0.0], [14.414218532592272, 0.0], [14.514218532592272, 0.0], [14.614218532592272, 0.0], [14.714218532592271, 0.0], [14.810094512663966, 0.0], [14.887250806145513, 0.0], [14.944407099627059, 0.0], [14.981563393108603, 0.0], [14.99871968659015, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553, 9.26329931618553], "velocities": null}}, "time": 1740481181.063618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.298745562766616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9061800898791028, "gear": 1, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.063618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.083618} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481181.9801464, "x": 15.0, "y": 8.890000000000011, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.083618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9098164812715475, "gear": 1, "accelerator_pedal_position": 0.298745562766616, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.083618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.103618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9171053796555569, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.103618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.123618} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9243843239813849, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.123618} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 5.9568048494835875, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9060401702041253, "accelerator_pedal_position": 0.24168151421693906, "brake_pedal_position": 0.0, "acceleration": 0.0069983674454276446, "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": 1740481181.1436179} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2989340450328247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9316533066567959, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1436179} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.1636178, "x": 10.057792872457066, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.1636178} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.057792872457066, 0.0], [6.218604385559311, 0.0], [6.318604385559311, 0.0], [6.418604385559311, 0.0], [6.5186043855593105, 0.0], [6.618604385559311, 0.0], [6.718604385559311, 0.0], [6.818604385559311, 0.0], [6.918604385559311, 0.0], [7.0186043855593105, 0.0], [7.11860438555931, 0.0], [7.218604385559311, 0.0], [7.318604385559311, 0.0], [7.418604385559311, 0.0], [7.5186043855593105, 0.0], [7.618604385559311, 0.0], [7.718604385559312, 0.0], [7.818604385559311, 0.0], [7.918604385559311, 0.0], [8.01860438555931, 0.0], [8.118604385559312, 0.0], [8.218604385559312, 0.0], [8.318604385559311, 0.0], [8.418604385559313, 0.0], [8.518604385559312, 0.0], [8.618604385559312, 0.0], [8.718604385559312, 0.0], [8.818604385559311, 0.0], [8.918604385559313, 0.0], [9.018604385559312, 0.0], [9.118604385559312, 0.0], [9.218604385559313, 0.0], [9.318604385559313, 0.0], [9.418604385559313, 0.0], [9.518604385559312, 0.0], [9.618604385559312, 0.0], [9.718604385559313, 0.0], [9.818604385559313, 0.0], [9.918604385559313, 0.0], [10.018604385559314, 0.0], [10.118604385559314, 0.0], [10.218604385559313, 0.0], [10.318604385559313, 0.0], [10.418604385559313, 0.0], [10.518604385559312, 0.0], [10.618604385559312, 0.0], [10.718604385559312, 0.0], [10.818604385559311, 0.0], [10.918604385559311, 0.0], [11.01860438555931, 0.0], [11.11860438555931, 0.0], [11.21860438555931, 0.0], [11.31860438555931, 0.0], [11.41860438555931, 0.0], [11.518604385559309, 0.0], [11.618604385559308, 0.0], [11.718604385559308, 0.0], [11.818604385559308, 0.0], [11.918604385559307, 0.0], [12.018604385559307, 0.0], [12.118604385559307, 0.0], [12.218604385559306, 0.0], [12.318604385559306, 0.0], [12.418604385559306, 0.0], [12.518604385559305, 0.0], [12.618604385559305, 0.0], [12.718604385559305, 0.0], [12.818604385559304, 0.0], [12.918604385559304, 0.0], [13.018604385559303, 0.0], [13.118604385559303, 0.0], [13.218604385559303, 0.0], [13.318604385559302, 0.0], [13.418604385559302, 0.0], [13.518604385559302, 0.0], [13.618604385559301, 0.0], [13.718604385559301, 0.0], [13.8186043855593, 0.0], [13.9186043855593, 0.0], [14.0186043855593, 0.0], [14.1186043855593, 0.0], [14.2186043855593, 0.0], [14.318604385559299, 0.0], [14.418604385559298, 0.0], [14.518604385559298, 0.0], [14.618604385559298, 0.0], [14.718604385559297, 0.0], [14.813897823841328, 0.0], [14.890176946729468, 0.0], [14.946456069617609, 0.0], [14.98273519250575, 0.0], [14.999014315393891, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553], "velocities": null}}, "time": 1740481181.1636178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628344429858715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389123201868808, "gear": 1, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1636178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.1836178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9416504598371546, "gear": 1, "accelerator_pedal_position": 0.2628344429858715, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.1836178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2036178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.944494474166722, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2036178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2236178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9473345721779124, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2236178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2436178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9501707560382973, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2436178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 6.057792872457066, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9389123201868808, "accelerator_pedal_position": 0.2989340450328247, "brake_pedal_position": 0.0, "acceleration": 0.3625766019958233, "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": 1740481181.2636178} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.057792872457066, 0.0], [6.218604385559311, 0.0], [6.318604385559311, 0.0], [6.418604385559311, 0.0], [6.5186043855593105, 0.0], [6.618604385559311, 0.0], [6.718604385559311, 0.0], [6.818604385559311, 0.0], [6.918604385559311, 0.0], [7.0186043855593105, 0.0], [7.11860438555931, 0.0], [7.218604385559311, 0.0], [7.318604385559311, 0.0], [7.418604385559311, 0.0], [7.5186043855593105, 0.0], [7.618604385559311, 0.0], [7.718604385559312, 0.0], [7.818604385559311, 0.0], [7.918604385559311, 0.0], [8.01860438555931, 0.0], [8.118604385559312, 0.0], [8.218604385559312, 0.0], [8.318604385559311, 0.0], [8.418604385559313, 0.0], [8.518604385559312, 0.0], [8.618604385559312, 0.0], [8.718604385559312, 0.0], [8.818604385559311, 0.0], [8.918604385559313, 0.0], [9.018604385559312, 0.0], [9.118604385559312, 0.0], [9.218604385559313, 0.0], [9.318604385559313, 0.0], [9.418604385559313, 0.0], [9.518604385559312, 0.0], [9.618604385559312, 0.0], [9.718604385559313, 0.0], [9.818604385559313, 0.0], [9.918604385559313, 0.0], [10.018604385559314, 0.0], [10.118604385559314, 0.0], [10.218604385559313, 0.0], [10.318604385559313, 0.0], [10.418604385559313, 0.0], [10.518604385559312, 0.0], [10.618604385559312, 0.0], [10.718604385559312, 0.0], [10.818604385559311, 0.0], [10.918604385559311, 0.0], [11.01860438555931, 0.0], [11.11860438555931, 0.0], [11.21860438555931, 0.0], [11.31860438555931, 0.0], [11.41860438555931, 0.0], [11.518604385559309, 0.0], [11.618604385559308, 0.0], [11.718604385559308, 0.0], [11.818604385559308, 0.0], [11.918604385559307, 0.0], [12.018604385559307, 0.0], [12.118604385559307, 0.0], [12.218604385559306, 0.0], [12.318604385559306, 0.0], [12.418604385559306, 0.0], [12.518604385559305, 0.0], [12.618604385559305, 0.0], [12.718604385559305, 0.0], [12.818604385559304, 0.0], [12.918604385559304, 0.0], [13.018604385559303, 0.0], [13.118604385559303, 0.0], [13.218604385559303, 0.0], [13.318604385559302, 0.0], [13.418604385559302, 0.0], [13.518604385559302, 0.0], [13.618604385559301, 0.0], [13.718604385559301, 0.0], [13.8186043855593, 0.0], [13.9186043855593, 0.0], [14.0186043855593, 0.0], [14.1186043855593, 0.0], [14.2186043855593, 0.0], [14.318604385559299, 0.0], [14.418604385559298, 0.0], [14.518604385559298, 0.0], [14.618604385559298, 0.0], [14.718604385559297, 0.0], [14.813897823841328, 0.0], [14.890176946729468, 0.0], [14.946456069617609, 0.0], [14.98273519250575, 0.0], [14.999014315393891, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553, 9.16329931618553], "velocities": null}}, "time": 1740481181.2636178} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263711882054697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9544176975631254, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2636178} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.2736177, "x": 10.161844632204554, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.2836177} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2392734769500379, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558313900286203, "gear": 1, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.2836177} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3036177} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556020997930303, "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": 1740481181.3036177} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3236177} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553755869669408, "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": 1740481181.3236177} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3436177} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.1993787, "x": 15.0, "y": 9.000000000000028, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.3436177} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23929316838988757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955149387112557, "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": 1740481181.3436177} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 6.161844632204554, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9544176975631254, "accelerator_pedal_position": 0.263711882054697, "brake_pedal_position": 0.0, "acceleration": 0.14136924654948274, "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": 1740481181.3636177} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.161844632204554, 0.0], [6.323758784193135, 0.0], [6.423758784193135, 0.0], [6.523758784193134, 0.0], [6.623758784193135, 0.0], [6.7237587841931346, 0.0], [6.823758784193135, 0.0], [6.923758784193135, 0.0], [7.023758784193134, 0.0], [7.123758784193135, 0.0], [7.2237587841931346, 0.0], [7.323758784193135, 0.0], [7.423758784193135, 0.0], [7.523758784193134, 0.0], [7.623758784193135, 0.0], [7.723758784193135, 0.0], [7.823758784193135, 0.0], [7.923758784193135, 0.0], [8.023758784193134, 0.0], [8.123758784193136, 0.0], [8.223758784193135, 0.0], [8.323758784193135, 0.0], [8.423758784193137, 0.0], [8.523758784193136, 0.0], [8.623758784193136, 0.0], [8.723758784193135, 0.0], [8.823758784193135, 0.0], [8.923758784193137, 0.0], [9.023758784193136, 0.0], [9.123758784193136, 0.0], [9.223758784193137, 0.0], [9.323758784193137, 0.0], [9.423758784193137, 0.0], [9.523758784193136, 0.0], [9.623758784193136, 0.0], [9.723758784193137, 0.0], [9.823758784193137, 0.0], [9.923758784193137, 0.0], [10.023758784193138, 0.0], [10.123758784193138, 0.0], [10.223758784193137, 0.0], [10.323758784193137, 0.0], [10.423758784193137, 0.0], [10.523758784193136, 0.0], [10.623758784193136, 0.0], [10.723758784193135, 0.0], [10.823758784193135, 0.0], [10.923758784193135, 0.0], [11.023758784193134, 0.0], [11.123758784193134, 0.0], [11.223758784193134, 0.0], [11.323758784193133, 0.0], [11.423758784193133, 0.0], [11.523758784193133, 0.0], [11.623758784193132, 0.0], [11.723758784193132, 0.0], [11.823758784193132, 0.0], [11.923758784193131, 0.0], [12.02375878419313, 0.0], [12.12375878419313, 0.0], [12.22375878419313, 0.0], [12.32375878419313, 0.0], [12.42375878419313, 0.0], [12.523758784193129, 0.0], [12.623758784193129, 0.0], [12.723758784193128, 0.0], [12.823758784193128, 0.0], [12.923758784193128, 0.0], [13.023758784193127, 0.0], [13.123758784193127, 0.0], [13.223758784193127, 0.0], [13.323758784193126, 0.0], [13.423758784193126, 0.0], [13.523758784193125, 0.0], [13.623758784193125, 0.0], [13.723758784193125, 0.0], [13.823758784193124, 0.0], [13.923758784193124, 0.0], [14.023758784193124, 0.0], [14.123758784193123, 0.0], [14.223758784193123, 0.0], [14.323758784193123, 0.0], [14.423758784193122, 0.0], [14.523758784193122, 0.0], [14.623758784193122, 0.0], [14.723758784193121, 0.0], [14.818318425947474, 0.0], [14.89356666910885, 0.0], [14.948814912270224, 0.0], [14.9840631554316, 0.0], [14.999311398592976, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553, 9.06329931618553], "velocities": null}}, "time": 1740481181.3636177} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23793599019288636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547258495251123, "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": 1740481181.3636177} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.3836176, "x": 10.266919930930852, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.3836176} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25148202361029387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95452833584263, "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": 1740481181.3836176} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4036176} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558263869767193, "gear": 1, "accelerator_pedal_position": 0.25148202361029387, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4036176} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4236176} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571236500194377, "gear": 1, "accelerator_pedal_position": 0.25149007003829515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4236176} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4436176} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25149007003829515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958419119931069, "gear": 1, "accelerator_pedal_position": 0.25149007003829515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.4436176} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4636176} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.266919930930852, 0.0], [6.42884079895557, 0.0], [6.52884079895557, 0.0], [6.62884079895557, 0.0], [6.72884079895557, 0.0], [6.82884079895557, 0.0], [6.92884079895557, 0.0], [7.02884079895557, 0.0], [7.12884079895557, 0.0], [7.22884079895557, 0.0], [7.32884079895557, 0.0], [7.42884079895557, 0.0], [7.528840798955571, 0.0], [7.62884079895557, 0.0], [7.72884079895557, 0.0], [7.828840798955571, 0.0], [7.928840798955571, 0.0], [8.02884079895557, 0.0], [8.12884079895557, 0.0], [8.22884079895557, 0.0], [8.328840798955572, 0.0], [8.428840798955571, 0.0], [8.52884079895557, 0.0], [8.628840798955572, 0.0], [8.728840798955572, 0.0], [8.828840798955572, 0.0], [8.928840798955571, 0.0], [9.02884079895557, 0.0], [9.128840798955572, 0.0], [9.228840798955572, 0.0], [9.328840798955572, 0.0], [9.428840798955573, 0.0], [9.528840798955573, 0.0], [9.628840798955572, 0.0], [9.728840798955572, 0.0], [9.828840798955572, 0.0], [9.928840798955573, 0.0], [10.028840798955573, 0.0], [10.128840798955572, 0.0], [10.228840798955574, 0.0], [10.328840798955572, 0.0], [10.428840798955573, 0.0], [10.52884079895557, 0.0], [10.628840798955572, 0.0], [10.72884079895557, 0.0], [10.828840798955572, 0.0], [10.92884079895557, 0.0], [11.02884079895557, 0.0], [11.128840798955569, 0.0], [11.22884079895557, 0.0], [11.328840798955568, 0.0], [11.42884079895557, 0.0], [11.528840798955567, 0.0], [11.628840798955569, 0.0], [11.728840798955567, 0.0], [11.828840798955568, 0.0], [11.928840798955566, 0.0], [12.028840798955567, 0.0], [12.128840798955565, 0.0], [12.228840798955567, 0.0], [12.328840798955564, 0.0], [12.428840798955566, 0.0], [12.528840798955564, 0.0], [12.628840798955565, 0.0], [12.728840798955563, 0.0], [12.828840798955564, 0.0], [12.928840798955562, 0.0], [13.028840798955564, 0.0], [13.128840798955562, 0.0], [13.228840798955563, 0.0], [13.32884079895556, 0.0], [13.428840798955562, 0.0], [13.52884079895556, 0.0], [13.628840798955562, 0.0], [13.72884079895556, 0.0], [13.82884079895556, 0.0], [13.928840798955559, 0.0], [14.02884079895556, 0.0], [14.128840798955558, 0.0], [14.22884079895556, 0.0], [14.328840798955559, 0.0], [14.428840798955559, 0.0], [14.528840798955558, 0.0], [14.628840798955558, 0.0], [14.728840798955558, 0.0], [14.822624927375607, 0.0], [14.896856767584495, 0.0], [14.951088607793384, 0.0], [14.985320448002271, 0.0], [14.999552288211161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553, 8.96329931618553], "velocities": null}}, "time": 1740481181.4636176} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23792486841281754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595111415300663, "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": 1740481181.4636176} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 6.266919930930852, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.95452833584263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25683766023139654, "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": 1740481181.4836175} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23792486841281754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593096240720304, "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": 1740481181.4836175} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.4936175, "x": 10.37224914770476, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5036175} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649766091315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9589070073303304, "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": 1740481181.5036175} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5236175} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250698061304799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600594230883468, "gear": 1, "accelerator_pedal_position": 0.2503649766091315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5236175} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5436175} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250698061304799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612518657385496, "gear": 1, "accelerator_pedal_position": 0.250698061304799, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5436175} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5636175} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.3722491477047605, 0.0], [6.534433706862372, 0.0], [6.634433706862373, 0.0], [6.734433706862372, 0.0], [6.834433706862373, 0.0], [6.9344337068623725, 0.0], [7.034433706862372, 0.0], [7.134433706862373, 0.0], [7.234433706862372, 0.0], [7.334433706862372, 0.0], [7.4344337068623725, 0.0], [7.534433706862373, 0.0], [7.634433706862373, 0.0], [7.734433706862372, 0.0], [7.834433706862373, 0.0], [7.934433706862373, 0.0], [8.034433706862373, 0.0], [8.134433706862373, 0.0], [8.234433706862372, 0.0], [8.334433706862374, 0.0], [8.434433706862373, 0.0], [8.534433706862373, 0.0], [8.634433706862374, 0.0], [8.734433706862374, 0.0], [8.834433706862374, 0.0], [8.934433706862373, 0.0], [9.034433706862373, 0.0], [9.134433706862374, 0.0], [9.234433706862374, 0.0], [9.334433706862374, 0.0], [9.434433706862375, 0.0], [9.534433706862375, 0.0], [9.634433706862374, 0.0], [9.734433706862374, 0.0], [9.834433706862374, 0.0], [9.934433706862375, 0.0], [10.034433706862375, 0.0], [10.134433706862374, 0.0], [10.234433706862376, 0.0], [10.334433706862376, 0.0], [10.434433706862375, 0.0], [10.534433706862375, 0.0], [10.634433706862374, 0.0], [10.734433706862374, 0.0], [10.834433706862374, 0.0], [10.934433706862373, 0.0], [11.034433706862373, 0.0], [11.134433706862373, 0.0], [11.234433706862372, 0.0], [11.334433706862372, 0.0], [11.434433706862372, 0.0], [11.534433706862371, 0.0], [11.63443370686237, 0.0], [11.73443370686237, 0.0], [11.83443370686237, 0.0], [11.93443370686237, 0.0], [12.03443370686237, 0.0], [12.134433706862369, 0.0], [12.234433706862369, 0.0], [12.334433706862368, 0.0], [12.434433706862368, 0.0], [12.534433706862368, 0.0], [12.634433706862367, 0.0], [12.734433706862367, 0.0], [12.834433706862367, 0.0], [12.934433706862366, 0.0], [13.034433706862366, 0.0], [13.134433706862366, 0.0], [13.234433706862365, 0.0], [13.334433706862365, 0.0], [13.434433706862364, 0.0], [13.534433706862364, 0.0], [13.634433706862364, 0.0], [13.734433706862363, 0.0], [13.834433706862363, 0.0], [13.934433706862363, 0.0], [14.034433706862362, 0.0], [14.134433706862362, 0.0], [14.234433706862362, 0.0], [14.334433706862361, 0.0], [14.434433706862361, 0.0], [14.53443370686236, 0.0], [14.63443370686236, 0.0], [14.73443370686236, 0.0], [14.82730465600784, 0.0], [14.90041791463537, 0.0], [14.953531173262897, 0.0], [14.986644431890424, 0.0], [14.999757690517953, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531, 8.86329931618553], "velocities": null}}, "time": 1740481181.5636175} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23745044627130266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624426581645872, "gear": 1, "accelerator_pedal_position": 0.250698061304799, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.5636175} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 6.3722491477047605, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9591082460403118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715429857824085, "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": 1740481181.5836174} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.4189186, "x": 15.0, "y": 9.110000000000046, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.5836174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23745044627130266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619764235978037, "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": 1740481181.5836174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.6036174, "x": 10.477946001365115, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6036174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24781364187524182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615108344664631, "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": 1740481181.6036174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6236174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24798837574560112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627663338994108, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6236174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6436174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24798837574560112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631915323151922, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6436174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6636174} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.477946001365115, 0.0], [6.6402577069750155, 0.0], [6.740257706975015, 0.0], [6.840257706975015, 0.0], [6.940257706975015, 0.0], [7.040257706975015, 0.0], [7.1402577069750155, 0.0], [7.240257706975015, 0.0], [7.340257706975015, 0.0], [7.440257706975015, 0.0], [7.540257706975015, 0.0], [7.6402577069750155, 0.0], [7.740257706975015, 0.0], [7.840257706975015, 0.0], [7.940257706975015, 0.0], [8.040257706975016, 0.0], [8.140257706975015, 0.0], [8.240257706975015, 0.0], [8.340257706975017, 0.0], [8.440257706975016, 0.0], [8.540257706975016, 0.0], [8.640257706975017, 0.0], [8.740257706975017, 0.0], [8.840257706975017, 0.0], [8.940257706975016, 0.0], [9.040257706975016, 0.0], [9.140257706975017, 0.0], [9.240257706975017, 0.0], [9.340257706975017, 0.0], [9.440257706975018, 0.0], [9.540257706975018, 0.0], [9.640257706975017, 0.0], [9.740257706975017, 0.0], [9.840257706975017, 0.0], [9.940257706975018, 0.0], [10.040257706975018, 0.0], [10.140257706975017, 0.0], [10.240257706975019, 0.0], [10.340257706975018, 0.0], [10.440257706975018, 0.0], [10.540257706975018, 0.0], [10.640257706975017, 0.0], [10.740257706975017, 0.0], [10.840257706975017, 0.0], [10.940257706975016, 0.0], [11.040257706975016, 0.0], [11.140257706975015, 0.0], [11.240257706975015, 0.0], [11.340257706975015, 0.0], [11.440257706975014, 0.0], [11.540257706975014, 0.0], [11.640257706975014, 0.0], [11.740257706975013, 0.0], [11.840257706975013, 0.0], [11.940257706975013, 0.0], [12.040257706975012, 0.0], [12.140257706975012, 0.0], [12.240257706975012, 0.0], [12.340257706975011, 0.0], [12.44025770697501, 0.0], [12.54025770697501, 0.0], [12.64025770697501, 0.0], [12.74025770697501, 0.0], [12.84025770697501, 0.0], [12.940257706975009, 0.0], [13.040257706975009, 0.0], [13.140257706975008, 0.0], [13.240257706975008, 0.0], [13.340257706975008, 0.0], [13.440257706975007, 0.0], [13.540257706975007, 0.0], [13.640257706975007, 0.0], [13.740257706975006, 0.0], [13.840257706975006, 0.0], [13.940257706975006, 0.0], [14.040257706975005, 0.0], [14.140257706975005, 0.0], [14.240257706975004, 0.0], [14.340257706975004, 0.0], [14.440257706975004, 0.0], [14.540257706975003, 0.0], [14.640257706975003, 0.0], [14.740257706975003, 0.0], [14.832111253306618, 0.0], [14.904059711911616, 0.0], [14.956008170516617, 0.0], [14.987956629121616, 0.0], [14.999905087726615, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531, 8.763299316185531], "velocities": null}}, "time": 1740481181.6636174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644653612900748, "gear": 1, "accelerator_pedal_position": 0.24798837574560112, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.6636174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.6836174} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642145223720796, "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": 1740481181.6836174} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 6.477946001365115, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615108344664631, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573205725712871, "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": 1740481181.7036173} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371906096954032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637133657978686, "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": 1740481181.7036173} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.7136173, "x": 10.583903502481709, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7236173} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464128441570876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635393217517758, "gear": 1, "accelerator_pedal_position": 0.2464128441570876, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.7236173} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7436173} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465548234495316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638655140482617, "gear": 1, "accelerator_pedal_position": 0.2464128441570876, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.7436173} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7636173} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.583903502481709, 0.0], [6.74631285275357, 0.0], [6.84631285275357, 0.0], [6.94631285275357, 0.0], [7.0463128527535694, 0.0], [7.14631285275357, 0.0], [7.24631285275357, 0.0], [7.346312852753569, 0.0], [7.44631285275357, 0.0], [7.5463128527535694, 0.0], [7.646312852753569, 0.0], [7.74631285275357, 0.0], [7.84631285275357, 0.0], [7.94631285275357, 0.0], [8.04631285275357, 0.0], [8.14631285275357, 0.0], [8.24631285275357, 0.0], [8.34631285275357, 0.0], [8.44631285275357, 0.0], [8.54631285275357, 0.0], [8.64631285275357, 0.0], [8.74631285275357, 0.0], [8.84631285275357, 0.0], [8.946312852753572, 0.0], [9.046312852753571, 0.0], [9.14631285275357, 0.0], [9.24631285275357, 0.0], [9.34631285275357, 0.0], [9.446312852753572, 0.0], [9.546312852753571, 0.0], [9.64631285275357, 0.0], [9.746312852753572, 0.0], [9.846312852753572, 0.0], [9.946312852753572, 0.0], [10.046312852753571, 0.0], [10.14631285275357, 0.0], [10.246312852753572, 0.0], [10.346312852753572, 0.0], [10.446312852753572, 0.0], [10.546312852753573, 0.0], [10.646312852753573, 0.0], [10.746312852753572, 0.0], [10.846312852753572, 0.0], [10.946312852753572, 0.0], [11.046312852753571, 0.0], [11.14631285275357, 0.0], [11.24631285275357, 0.0], [11.34631285275357, 0.0], [11.44631285275357, 0.0], [11.54631285275357, 0.0], [11.646312852753569, 0.0], [11.746312852753569, 0.0], [11.846312852753568, 0.0], [11.946312852753568, 0.0], [12.046312852753568, 0.0], [12.146312852753567, 0.0], [12.246312852753567, 0.0], [12.346312852753567, 0.0], [12.446312852753566, 0.0], [12.546312852753566, 0.0], [12.646312852753566, 0.0], [12.746312852753565, 0.0], [12.846312852753565, 0.0], [12.946312852753564, 0.0], [13.046312852753564, 0.0], [13.146312852753564, 0.0], [13.246312852753563, 0.0], [13.346312852753563, 0.0], [13.446312852753563, 0.0], [13.546312852753562, 0.0], [13.646312852753562, 0.0], [13.746312852753562, 0.0], [13.846312852753561, 0.0], [13.946312852753561, 0.0], [14.04631285275356, 0.0], [14.14631285275356, 0.0], [14.24631285275356, 0.0], [14.34631285275356, 0.0], [14.44631285275356, 0.0], [14.546312852753559, 0.0], [14.646312852753558, 0.0], [14.746312852753558, 0.0], [14.837036687148029, 0.0], [14.907774116597318, 0.0], [14.958511546046607, 0.0], [14.989248975495894, 0.0], [14.999986404945183, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532, 8.563299316185532, 8.663299316185531], "velocities": null}}, "time": 1740481181.7636173} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642705323516163, "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": 1740481181.7636173} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.7836173} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640062857813015, "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": 1740481181.7836173} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 6.583903502481709, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634630478757906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25745576284001065, "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": 1740481181.8036172} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697392738907475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634783417318964, "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": 1740481181.8036172} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.8236172, "x": 10.689918783775488, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8236172} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24581291444754838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629511288661443, "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": 1740481181.8236172} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8436172} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.639108, "x": 15.0, "y": 9.220000000000063, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481181.8436172} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457756839386138, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635291368288722, "gear": 1, "accelerator_pedal_position": 0.24581291444754838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.8436172} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8636172} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.689918783775488, 0.0], [6.852303020726171, 0.0], [6.952303020726171, 0.0], [7.052303020726171, 0.0], [7.152303020726171, 0.0], [7.2523030207261705, 0.0], [7.352303020726171, 0.0], [7.452303020726171, 0.0], [7.552303020726171, 0.0], [7.652303020726171, 0.0], [7.7523030207261705, 0.0], [7.852303020726171, 0.0], [7.952303020726171, 0.0], [8.052303020726171, 0.0], [8.15230302072617, 0.0], [8.25230302072617, 0.0], [8.352303020726172, 0.0], [8.452303020726172, 0.0], [8.552303020726171, 0.0], [8.65230302072617, 0.0], [8.75230302072617, 0.0], [8.852303020726172, 0.0], [8.952303020726172, 0.0], [9.052303020726171, 0.0], [9.152303020726173, 0.0], [9.252303020726172, 0.0], [9.352303020726172, 0.0], [9.452303020726173, 0.0], [9.552303020726171, 0.0], [9.652303020726173, 0.0], [9.752303020726172, 0.0], [9.852303020726172, 0.0], [9.952303020726173, 0.0], [10.052303020726173, 0.0], [10.152303020726173, 0.0], [10.252303020726174, 0.0], [10.352303020726172, 0.0], [10.452303020726173, 0.0], [10.552303020726173, 0.0], [10.652303020726173, 0.0], [10.752303020726174, 0.0], [10.852303020726172, 0.0], [10.952303020726173, 0.0], [11.052303020726171, 0.0], [11.152303020726173, 0.0], [11.25230302072617, 0.0], [11.352303020726172, 0.0], [11.45230302072617, 0.0], [11.552303020726171, 0.0], [11.652303020726169, 0.0], [11.75230302072617, 0.0], [11.852303020726168, 0.0], [11.95230302072617, 0.0], [12.052303020726168, 0.0], [12.152303020726169, 0.0], [12.252303020726167, 0.0], [12.352303020726168, 0.0], [12.452303020726166, 0.0], [12.552303020726168, 0.0], [12.652303020726166, 0.0], [12.752303020726167, 0.0], [12.852303020726165, 0.0], [12.952303020726166, 0.0], [13.052303020726164, 0.0], [13.152303020726166, 0.0], [13.252303020726163, 0.0], [13.352303020726165, 0.0], [13.452303020726163, 0.0], [13.552303020726164, 0.0], [13.652303020726162, 0.0], [13.752303020726163, 0.0], [13.852303020726161, 0.0], [13.952303020726163, 0.0], [14.05230302072616, 0.0], [14.152303020726162, 0.0], [14.25230302072616, 0.0], [14.352303020726161, 0.0], [14.45230302072616, 0.0], [14.55230302072616, 0.0], [14.652303020726158, 0.0], [14.752297716821694, 0.0], [14.841837112676462, 0.0], [14.91137650853123, 0.0], [14.960915904385999, 0.0], [14.990455300240766, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532, 8.463299316185532], "velocities": null}}, "time": 1740481181.8636172} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9641016921217608, "gear": 1, "accelerator_pedal_position": 0.2457756839386138, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481181.8636172} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.8836172} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635807760841378, "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": 1740481181.8836172} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.9036171} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630605815175858, "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": 1740481181.9036171} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 6.689918783775488, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629511288661443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742030520915304, "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": 1740481181.9236171} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703122850156574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625411073146605, "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": 1740481181.9236171} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481181.933617, "x": 10.795886610338917, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.943617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24615294566350834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620223523699009, "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": 1740481181.943617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.963617} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.795886610338917, 0.0], [6.958237476737271, 0.0], [7.058237476737271, 0.0], [7.158237476737271, 0.0], [7.258237476737271, 0.0], [7.358237476737271, 0.0], [7.458237476737271, 0.0], [7.558237476737271, 0.0], [7.658237476737271, 0.0], [7.758237476737271, 0.0], [7.858237476737271, 0.0], [7.9582374767372706, 0.0], [8.058237476737272, 0.0], [8.158237476737272, 0.0], [8.258237476737271, 0.0], [8.358237476737271, 0.0], [8.45823747673727, 0.0], [8.558237476737272, 0.0], [8.658237476737272, 0.0], [8.758237476737271, 0.0], [8.858237476737273, 0.0], [8.958237476737272, 0.0], [9.058237476737272, 0.0], [9.158237476737272, 0.0], [9.258237476737271, 0.0], [9.358237476737273, 0.0], [9.458237476737272, 0.0], [9.558237476737272, 0.0], [9.658237476737273, 0.0], [9.758237476737273, 0.0], [9.858237476737273, 0.0], [9.958237476737272, 0.0], [10.058237476737272, 0.0], [10.158237476737273, 0.0], [10.258237476737273, 0.0], [10.358237476737273, 0.0], [10.458237476737274, 0.0], [10.558237476737274, 0.0], [10.658237476737273, 0.0], [10.758237476737273, 0.0], [10.858237476737273, 0.0], [10.958237476737274, 0.0], [11.058237476737272, 0.0], [11.158237476737273, 0.0], [11.258237476737271, 0.0], [11.358237476737273, 0.0], [11.45823747673727, 0.0], [11.558237476737272, 0.0], [11.65823747673727, 0.0], [11.758237476737271, 0.0], [11.85823747673727, 0.0], [11.95823747673727, 0.0], [12.058237476737268, 0.0], [12.15823747673727, 0.0], [12.258237476737268, 0.0], [12.35823747673727, 0.0], [12.458237476737267, 0.0], [12.558237476737268, 0.0], [12.658237476737266, 0.0], [12.758237476737268, 0.0], [12.858237476737266, 0.0], [12.958237476737267, 0.0], [13.058237476737265, 0.0], [13.158237476737266, 0.0], [13.258237476737264, 0.0], [13.358237476737266, 0.0], [13.458237476737263, 0.0], [13.558237476737265, 0.0], [13.658237476737263, 0.0], [13.758237476737264, 0.0], [13.858237476737262, 0.0], [13.958237476737263, 0.0], [14.058237476737261, 0.0], [14.158237476737263, 0.0], [14.25823747673726, 0.0], [14.358237476737262, 0.0], [14.45823747673726, 0.0], [14.558237476737261, 0.0], [14.65823747673726, 0.0], [14.758169620714263, 0.0], [14.84652212536681, 0.0], [14.914874630019359, 0.0], [14.963227134671907, 0.0], [14.991579639324454, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533, 8.363299316185532], "velocities": null}}, "time": 1740481181.963617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623892481856829, "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": 1740481181.963617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481181.983617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621345374044158, "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": 1740481181.983617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481182.003617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616256448320473, "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": 1740481182.003617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 6.795886610338917, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9622816400040239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573739415470896, "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": 1740481182.023617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23710565038924908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611174566798791, "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": 1740481182.023617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.043617, "x": 10.90169324492635, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.043617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24678756537209398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9606099718695712, "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": 1740481182.043617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.063617} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[6.901693244926349, 0.0], [7.063958178234484, 0.0], [7.163958178234484, 0.0], [7.263958178234484, 0.0], [7.363958178234483, 0.0], [7.463958178234484, 0.0], [7.563958178234484, 0.0], [7.663958178234484, 0.0], [7.763958178234484, 0.0], [7.863958178234483, 0.0], [7.963958178234484, 0.0], [8.063958178234484, 0.0], [8.163958178234484, 0.0], [8.263958178234484, 0.0], [8.363958178234483, 0.0], [8.463958178234485, 0.0], [8.563958178234484, 0.0], [8.663958178234484, 0.0], [8.763958178234484, 0.0], [8.863958178234485, 0.0], [8.963958178234485, 0.0], [9.063958178234484, 0.0], [9.163958178234484, 0.0], [9.263958178234486, 0.0], [9.363958178234485, 0.0], [9.463958178234485, 0.0], [9.563958178234484, 0.0], [9.663958178234484, 0.0], [9.763958178234486, 0.0], [9.863958178234485, 0.0], [9.963958178234485, 0.0], [10.063958178234486, 0.0], [10.163958178234486, 0.0], [10.263958178234486, 0.0], [10.363958178234485, 0.0], [10.463958178234485, 0.0], [10.563958178234486, 0.0], [10.663958178234486, 0.0], [10.763958178234486, 0.0], [10.863958178234487, 0.0], [10.963958178234487, 0.0], [11.063958178234486, 0.0], [11.163958178234486, 0.0], [11.263958178234486, 0.0], [11.363958178234485, 0.0], [11.463958178234485, 0.0], [11.563958178234484, 0.0], [11.663958178234484, 0.0], [11.763958178234484, 0.0], [11.863958178234483, 0.0], [11.963958178234483, 0.0], [12.063958178234483, 0.0], [12.163958178234482, 0.0], [12.263958178234482, 0.0], [12.363958178234482, 0.0], [12.463958178234481, 0.0], [12.563958178234481, 0.0], [12.66395817823448, 0.0], [12.76395817823448, 0.0], [12.86395817823448, 0.0], [12.96395817823448, 0.0], [13.06395817823448, 0.0], [13.163958178234479, 0.0], [13.263958178234478, 0.0], [13.363958178234478, 0.0], [13.463958178234478, 0.0], [13.563958178234477, 0.0], [13.663958178234477, 0.0], [13.763958178234477, 0.0], [13.863958178234476, 0.0], [13.963958178234476, 0.0], [14.063958178234476, 0.0], [14.163958178234475, 0.0], [14.263958178234475, 0.0], [14.363958178234475, 0.0], [14.463958178234474, 0.0], [14.563958178234474, 0.0], [14.663958178234473, 0.0], [14.763763347494848, 0.0], [14.850971711847953, 0.0], [14.918180076201057, 0.0], [14.965388440554163, 0.0], [14.992596804907269, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533, 8.263299316185533], "velocities": null}}, "time": 1740481182.063617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610704986248391, "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": 1740481182.063617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.083617} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481182.9689176, "x": 15.0, "y": 9.385000000000089, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.083617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96082815525029, "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": 1740481182.083617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.103617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603439716162283, "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": 1740481182.103617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.123617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598604579504653, "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": 1740481182.123617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 6.901693244926349, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9606099718695712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572582137740312, "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": 1740481182.143617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372889204015372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593776132324794, "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": 1740481182.143617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.153617, "x": 11.007339968463826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.163617} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.0073399684638265, 0.0], [7.169526064368973, 0.0], [7.269526064368972, 0.0], [7.369526064368972, 0.0], [7.4695260643689725, 0.0], [7.569526064368972, 0.0], [7.669526064368973, 0.0], [7.769526064368972, 0.0], [7.869526064368972, 0.0], [7.9695260643689725, 0.0], [8.069526064368972, 0.0], [8.169526064368972, 0.0], [8.269526064368971, 0.0], [8.369526064368973, 0.0], [8.469526064368972, 0.0], [8.569526064368972, 0.0], [8.669526064368974, 0.0], [8.769526064368973, 0.0], [8.869526064368973, 0.0], [8.969526064368972, 0.0], [9.069526064368972, 0.0], [9.169526064368974, 0.0], [9.269526064368973, 0.0], [9.369526064368973, 0.0], [9.469526064368974, 0.0], [9.569526064368974, 0.0], [9.669526064368974, 0.0], [9.769526064368973, 0.0], [9.869526064368973, 0.0], [9.969526064368974, 0.0], [10.069526064368974, 0.0], [10.169526064368974, 0.0], [10.269526064368975, 0.0], [10.369526064368975, 0.0], [10.469526064368974, 0.0], [10.569526064368974, 0.0], [10.669526064368974, 0.0], [10.769526064368975, 0.0], [10.869526064368975, 0.0], [10.969526064368974, 0.0], [11.069526064368976, 0.0], [11.169526064368975, 0.0], [11.269526064368975, 0.0], [11.369526064368975, 0.0], [11.469526064368974, 0.0], [11.569526064368974, 0.0], [11.669526064368974, 0.0], [11.769526064368973, 0.0], [11.869526064368973, 0.0], [11.969526064368972, 0.0], [12.069526064368972, 0.0], [12.169526064368972, 0.0], [12.269526064368971, 0.0], [12.369526064368971, 0.0], [12.46952606436897, 0.0], [12.56952606436897, 0.0], [12.66952606436897, 0.0], [12.76952606436897, 0.0], [12.86952606436897, 0.0], [12.969526064368969, 0.0], [13.069526064368969, 0.0], [13.169526064368968, 0.0], [13.269526064368968, 0.0], [13.369526064368968, 0.0], [13.469526064368967, 0.0], [13.569526064368967, 0.0], [13.669526064368966, 0.0], [13.769526064368966, 0.0], [13.869526064368966, 0.0], [13.969526064368965, 0.0], [14.069526064368965, 0.0], [14.169526064368965, 0.0], [14.269526064368964, 0.0], [14.369526064368964, 0.0], [14.469526064368964, 0.0], [14.569526064368963, 0.0], [14.669526064368963, 0.0], [14.769144797179223, 0.0], [14.85523958430543, 0.0], [14.921334371431637, 0.0], [14.967429158557843, 0.0], [14.993523945684052, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534, 8.163299316185533], "velocities": null}}, "time": 1740481182.163617} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24842678209901897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586545982046197, "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": 1740481182.163617} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.1836169} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591100429228402, "gear": 1, "accelerator_pedal_position": 0.24842678209901897, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.1836169} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2036169} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600109836096028, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2036169} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2236168} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609106779030688, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2236168} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 7.0073399684638265, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.959136441410482, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571562492029397, "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": 1740481182.2436168} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24835472734418063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618091272038749, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2436168} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.2636168, "x": 11.112961637532111, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.2636168} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.112961637532111, 0.0], [7.275333741981079, 0.0], [7.375333741981079, 0.0], [7.475333741981079, 0.0], [7.575333741981079, 0.0], [7.6753337419810785, 0.0], [7.775333741981079, 0.0], [7.875333741981079, 0.0], [7.975333741981078, 0.0], [8.075333741981078, 0.0], [8.17533374198108, 0.0], [8.275333741981079, 0.0], [8.375333741981079, 0.0], [8.475333741981078, 0.0], [8.57533374198108, 0.0], [8.67533374198108, 0.0], [8.775333741981079, 0.0], [8.87533374198108, 0.0], [8.97533374198108, 0.0], [9.07533374198108, 0.0], [9.17533374198108, 0.0], [9.275333741981079, 0.0], [9.37533374198108, 0.0], [9.47533374198108, 0.0], [9.57533374198108, 0.0], [9.67533374198108, 0.0], [9.775333741981079, 0.0], [9.87533374198108, 0.0], [9.97533374198108, 0.0], [10.07533374198108, 0.0], [10.175333741981081, 0.0], [10.27533374198108, 0.0], [10.37533374198108, 0.0], [10.47533374198108, 0.0], [10.57533374198108, 0.0], [10.675333741981081, 0.0], [10.77533374198108, 0.0], [10.87533374198108, 0.0], [10.975333741981082, 0.0], [11.075333741981082, 0.0], [11.175333741981081, 0.0], [11.275333741981083, 0.0], [11.37533374198108, 0.0], [11.475333741981082, 0.0], [11.57533374198108, 0.0], [11.675333741981081, 0.0], [11.775333741981079, 0.0], [11.87533374198108, 0.0], [11.975333741981078, 0.0], [12.07533374198108, 0.0], [12.175333741981078, 0.0], [12.275333741981079, 0.0], [12.375333741981077, 0.0], [12.475333741981078, 0.0], [12.575333741981076, 0.0], [12.675333741981078, 0.0], [12.775333741981076, 0.0], [12.875333741981077, 0.0], [12.975333741981075, 0.0], [13.075333741981076, 0.0], [13.175333741981074, 0.0], [13.275333741981076, 0.0], [13.375333741981073, 0.0], [13.475333741981075, 0.0], [13.575333741981073, 0.0], [13.675333741981074, 0.0], [13.775333741981072, 0.0], [13.875333741981073, 0.0], [13.975333741981071, 0.0], [14.075333741981073, 0.0], [14.17533374198107, 0.0], [14.275333741981072, 0.0], [14.37533374198107, 0.0], [14.475333741981071, 0.0], [14.57533374198107, 0.0], [14.67533374198107, 0.0], [14.774691943498306, 0.0], [14.859625195102092, 0.0], [14.924558446705877, 0.0], [14.969491698309664, 0.0], [14.994424949913451, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534], "velocities": null}}, "time": 1740481182.2636168} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24596650348448013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627063329120633, "gear": 1, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2636168} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.2836168} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633038718272395, "gear": 1, "accelerator_pedal_position": 0.24596650348448013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.2836168} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3036168} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639226740705839, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3036168} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3236167} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645406192559522, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3236167} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3436167} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.1888819, "x": 15.0, "y": 9.495000000000106, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.3436167} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651577084177039, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3436167} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 7.112961637532111, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9627063329120633, "accelerator_pedal_position": 0.24835472734418063, "brake_pedal_position": 0.0, "acceleration": 0.04481369442123573, "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": 1740481182.3636167} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.112961637532111, 0.0], [7.275333741981079, 0.0], [7.375333741981079, 0.0], [7.475333741981079, 0.0], [7.575333741981079, 0.0], [7.6753337419810785, 0.0], [7.775333741981079, 0.0], [7.875333741981079, 0.0], [7.975333741981078, 0.0], [8.075333741981078, 0.0], [8.17533374198108, 0.0], [8.275333741981079, 0.0], [8.375333741981079, 0.0], [8.475333741981078, 0.0], [8.57533374198108, 0.0], [8.67533374198108, 0.0], [8.775333741981079, 0.0], [8.87533374198108, 0.0], [8.97533374198108, 0.0], [9.07533374198108, 0.0], [9.17533374198108, 0.0], [9.275333741981079, 0.0], [9.37533374198108, 0.0], [9.47533374198108, 0.0], [9.57533374198108, 0.0], [9.67533374198108, 0.0], [9.775333741981079, 0.0], [9.87533374198108, 0.0], [9.97533374198108, 0.0], [10.07533374198108, 0.0], [10.175333741981081, 0.0], [10.27533374198108, 0.0], [10.37533374198108, 0.0], [10.47533374198108, 0.0], [10.57533374198108, 0.0], [10.675333741981081, 0.0], [10.77533374198108, 0.0], [10.87533374198108, 0.0], [10.975333741981082, 0.0], [11.075333741981082, 0.0], [11.175333741981081, 0.0], [11.275333741981083, 0.0], [11.37533374198108, 0.0], [11.475333741981082, 0.0], [11.57533374198108, 0.0], [11.675333741981081, 0.0], [11.775333741981079, 0.0], [11.87533374198108, 0.0], [11.975333741981078, 0.0], [12.07533374198108, 0.0], [12.175333741981078, 0.0], [12.275333741981079, 0.0], [12.375333741981077, 0.0], [12.475333741981078, 0.0], [12.575333741981076, 0.0], [12.675333741981078, 0.0], [12.775333741981076, 0.0], [12.875333741981077, 0.0], [12.975333741981075, 0.0], [13.075333741981076, 0.0], [13.175333741981074, 0.0], [13.275333741981076, 0.0], [13.375333741981073, 0.0], [13.475333741981075, 0.0], [13.575333741981073, 0.0], [13.675333741981074, 0.0], [13.775333741981072, 0.0], [13.875333741981073, 0.0], [13.975333741981071, 0.0], [14.075333741981073, 0.0], [14.17533374198107, 0.0], [14.275333741981072, 0.0], [14.37533374198107, 0.0], [14.475333741981071, 0.0], [14.57533374198107, 0.0], [14.67533374198107, 0.0], [14.774691943498306, 0.0], [14.859625195102092, 0.0], [14.924558446705877, 0.0], [14.969491698309664, 0.0], [14.994424949913451, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534, 8.063299316185534], "velocities": null}}, "time": 1740481182.3636167} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461432910313453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660817393767452, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3636167} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.3736167, "x": 11.219027344451137, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.3836167} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375943824143945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663893228038002, "gear": 1, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.3836167} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4036167} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659356069431163, "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": 1740481182.4036167} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4236166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654615945702626, "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": 1740481182.4236166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4436166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23742692169973525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649882390608345, "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": 1740481182.4436166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 7.219027344451137, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9660817393767452, "accelerator_pedal_position": 0.2461432910313453, "brake_pedal_position": 0.0, "acceleration": 0.03075834270549882, "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": 1740481182.4636166} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.219027344451137, 0.0], [7.381559695034211, 0.0], [7.4815596950342105, 0.0], [7.58155969503421, 0.0], [7.681559695034211, 0.0], [7.78155969503421, 0.0], [7.881559695034211, 0.0], [7.9815596950342105, 0.0], [8.08155969503421, 0.0], [8.18155969503421, 0.0], [8.281559695034211, 0.0], [8.38155969503421, 0.0], [8.48155969503421, 0.0], [8.58155969503421, 0.0], [8.68155969503421, 0.0], [8.781559695034211, 0.0], [8.88155969503421, 0.0], [8.98155969503421, 0.0], [9.081559695034212, 0.0], [9.181559695034212, 0.0], [9.281559695034211, 0.0], [9.38155969503421, 0.0], [9.48155969503421, 0.0], [9.581559695034212, 0.0], [9.681559695034212, 0.0], [9.781559695034211, 0.0], [9.881559695034213, 0.0], [9.981559695034212, 0.0], [10.081559695034212, 0.0], [10.181559695034212, 0.0], [10.281559695034211, 0.0], [10.381559695034213, 0.0], [10.481559695034212, 0.0], [10.581559695034212, 0.0], [10.681559695034213, 0.0], [10.781559695034213, 0.0], [10.881559695034213, 0.0], [10.981559695034212, 0.0], [11.081559695034212, 0.0], [11.181559695034213, 0.0], [11.281559695034213, 0.0], [11.381559695034213, 0.0], [11.481559695034212, 0.0], [11.581559695034212, 0.0], [11.681559695034212, 0.0], [11.781559695034211, 0.0], [11.88155969503421, 0.0], [11.98155969503421, 0.0], [12.08155969503421, 0.0], [12.18155969503421, 0.0], [12.28155969503421, 0.0], [12.381559695034209, 0.0], [12.481559695034209, 0.0], [12.581559695034208, 0.0], [12.681559695034208, 0.0], [12.781559695034208, 0.0], [12.881559695034207, 0.0], [12.981559695034207, 0.0], [13.081559695034207, 0.0], [13.181559695034206, 0.0], [13.281559695034206, 0.0], [13.381559695034206, 0.0], [13.481559695034205, 0.0], [13.581559695034205, 0.0], [13.681559695034204, 0.0], [13.781559695034204, 0.0], [13.881559695034204, 0.0], [13.981559695034203, 0.0], [14.081559695034203, 0.0], [14.181559695034203, 0.0], [14.281559695034202, 0.0], [14.381559695034202, 0.0], [14.481559695034202, 0.0], [14.581559695034201, 0.0], [14.6815596950342, 0.0], [14.78056368068355, 0.0], [14.864251741676709, 0.0], [14.927939802669869, 0.0], [14.971627863663027, 0.0], [14.995315924656188, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534, 7.963299316185534], "velocities": null}}, "time": 1740481182.4636166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23667545194919273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645155394149875, "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": 1740481182.4636166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.4836166, "x": 11.325221765025375, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.4836166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468635810733996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639495934568613, "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": 1740481182.4836166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5036166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643854478282493, "gear": 1, "accelerator_pedal_position": 0.24468635810733996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5036166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5236166} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650090429731459, "gear": 1, "accelerator_pedal_position": 0.24453129280164843, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5236166} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5436165} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453129280164843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652166200064604, "gear": 1, "accelerator_pedal_position": 0.24453129280164843, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.5436165} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5636165} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.3252217650253755, 0.0], [7.4876546600029705, 0.0], [7.58765466000297, 0.0], [7.687654660002971, 0.0], [7.78765466000297, 0.0], [7.88765466000297, 0.0], [7.9876546600029705, 0.0], [8.08765466000297, 0.0], [8.18765466000297, 0.0], [8.28765466000297, 0.0], [8.38765466000297, 0.0], [8.48765466000297, 0.0], [8.58765466000297, 0.0], [8.68765466000297, 0.0], [8.787654660002971, 0.0], [8.88765466000297, 0.0], [8.98765466000297, 0.0], [9.08765466000297, 0.0], [9.187654660002972, 0.0], [9.287654660002971, 0.0], [9.38765466000297, 0.0], [9.48765466000297, 0.0], [9.587654660002972, 0.0], [9.687654660002972, 0.0], [9.787654660002971, 0.0], [9.88765466000297, 0.0], [9.98765466000297, 0.0], [10.087654660002972, 0.0], [10.187654660002972, 0.0], [10.287654660002971, 0.0], [10.387654660002973, 0.0], [10.487654660002972, 0.0], [10.587654660002972, 0.0], [10.687654660002972, 0.0], [10.787654660002971, 0.0], [10.887654660002973, 0.0], [10.987654660002972, 0.0], [11.087654660002972, 0.0], [11.187654660002973, 0.0], [11.287654660002973, 0.0], [11.387654660002973, 0.0], [11.487654660002972, 0.0], [11.587654660002972, 0.0], [11.687654660002972, 0.0], [11.787654660002971, 0.0], [11.88765466000297, 0.0], [11.98765466000297, 0.0], [12.08765466000297, 0.0], [12.18765466000297, 0.0], [12.28765466000297, 0.0], [12.387654660002969, 0.0], [12.487654660002969, 0.0], [12.587654660002968, 0.0], [12.687654660002968, 0.0], [12.787654660002968, 0.0], [12.887654660002967, 0.0], [12.987654660002967, 0.0], [13.087654660002967, 0.0], [13.187654660002966, 0.0], [13.287654660002966, 0.0], [13.387654660002966, 0.0], [13.487654660002965, 0.0], [13.587654660002965, 0.0], [13.687654660002964, 0.0], [13.787654660002964, 0.0], [13.887654660002964, 0.0], [13.987654660002963, 0.0], [14.087654660002963, 0.0], [14.187654660002963, 0.0], [14.287654660002962, 0.0], [14.387654660002962, 0.0], [14.487654660002962, 0.0], [14.587654660002961, 0.0], [14.687654660002961, 0.0], [14.786236786583022, 0.0], [14.86870585458243, 0.0], [14.931174922581837, 0.0], [14.973643990581245, 0.0], [14.996113058580654, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535, 7.863299316185534], "velocities": null}}, "time": 1740481182.5636165} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23691914910218073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653627293560777, "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": 1740481182.5636165} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 7.3252217650253755, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639495934568613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574894678600996, "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": 1740481182.5836165} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.4100251, "x": 15.0, "y": 9.605000000000123, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.5836165} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23691914910218073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965094302290363, "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": 1740481182.5836165} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.5936165, "x": 11.431358120093588, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6036165} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452043305278692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645580061122826, "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": 1740481182.6036165} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6236165} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24526807370138753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650577417901438, "gear": 1, "accelerator_pedal_position": 0.2452043305278692, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6236165} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6436164} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24526807370138753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655647502233509, "gear": 1, "accelerator_pedal_position": 0.24526807370138753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6436164} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6636164} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.431358120093588, 0.0], [7.593832632301329, 0.0], [7.69383263230133, 0.0], [7.79383263230133, 0.0], [7.893832632301329, 0.0], [7.99383263230133, 0.0], [8.09383263230133, 0.0], [8.19383263230133, 0.0], [8.29383263230133, 0.0], [8.39383263230133, 0.0], [8.493832632301329, 0.0], [8.593832632301329, 0.0], [8.69383263230133, 0.0], [8.79383263230133, 0.0], [8.89383263230133, 0.0], [8.99383263230133, 0.0], [9.09383263230133, 0.0], [9.19383263230133, 0.0], [9.29383263230133, 0.0], [9.39383263230133, 0.0], [9.49383263230133, 0.0], [9.59383263230133, 0.0], [9.69383263230133, 0.0], [9.793832632301331, 0.0], [9.893832632301331, 0.0], [9.99383263230133, 0.0], [10.09383263230133, 0.0], [10.19383263230133, 0.0], [10.293832632301331, 0.0], [10.393832632301331, 0.0], [10.49383263230133, 0.0], [10.593832632301332, 0.0], [10.693832632301332, 0.0], [10.793832632301331, 0.0], [10.893832632301331, 0.0], [10.99383263230133, 0.0], [11.093832632301332, 0.0], [11.193832632301332, 0.0], [11.293832632301331, 0.0], [11.393832632301333, 0.0], [11.49383263230133, 0.0], [11.593832632301332, 0.0], [11.69383263230133, 0.0], [11.793832632301331, 0.0], [11.89383263230133, 0.0], [11.99383263230133, 0.0], [12.093832632301329, 0.0], [12.19383263230133, 0.0], [12.293832632301328, 0.0], [12.39383263230133, 0.0], [12.493832632301327, 0.0], [12.593832632301329, 0.0], [12.693832632301326, 0.0], [12.793832632301328, 0.0], [12.893832632301326, 0.0], [12.993832632301327, 0.0], [13.093832632301325, 0.0], [13.193832632301326, 0.0], [13.293832632301324, 0.0], [13.393832632301326, 0.0], [13.493832632301324, 0.0], [13.593832632301325, 0.0], [13.693832632301323, 0.0], [13.793832632301324, 0.0], [13.893832632301322, 0.0], [13.993832632301324, 0.0], [14.093832632301321, 0.0], [14.193832632301323, 0.0], [14.29383263230132, 0.0], [14.393832632301322, 0.0], [14.49383263230132, 0.0], [14.593832632301321, 0.0], [14.69383263230132, 0.0], [14.791911332646858, 0.0], [14.873144806186595, 0.0], [14.934378279726328, 0.0], [14.975611753266065, 0.0], [14.996845226805801, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535, 7.763299316185535], "velocities": null}}, "time": 1740481182.6636164} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23681969064552566, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660710560976027, "gear": 1, "accelerator_pedal_position": 0.24526807370138753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.6636164} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 7.431358120093588, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9648260612568728, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755019634764814, "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": 1740481182.6836164} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23681969064552566, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655209784344714, "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": 1740481182.6836164} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.7036164, "x": 11.537543900360738, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7036164} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448672006587275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964971663059607, "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": 1740481182.7036164} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7236164} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487778989084322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654286989950118, "gear": 1, "accelerator_pedal_position": 0.2448672006587275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7236164} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7436163} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487778989084322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658864248359456, "gear": 1, "accelerator_pedal_position": 0.24487778989084322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7436163} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7636163} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.537543900360738, 0.0], [7.700025226953744, 0.0], [7.800025226953744, 0.0], [7.900025226953744, 0.0], [8.000025226953744, 0.0], [8.100025226953743, 0.0], [8.200025226953743, 0.0], [8.300025226953743, 0.0], [8.400025226953744, 0.0], [8.500025226953744, 0.0], [8.600025226953743, 0.0], [8.700025226953743, 0.0], [8.800025226953744, 0.0], [8.900025226953744, 0.0], [9.000025226953744, 0.0], [9.100025226953743, 0.0], [9.200025226953745, 0.0], [9.300025226953744, 0.0], [9.400025226953744, 0.0], [9.500025226953744, 0.0], [9.600025226953743, 0.0], [9.700025226953745, 0.0], [9.800025226953744, 0.0], [9.900025226953744, 0.0], [10.000025226953746, 0.0], [10.100025226953745, 0.0], [10.200025226953745, 0.0], [10.300025226953744, 0.0], [10.400025226953744, 0.0], [10.500025226953746, 0.0], [10.600025226953745, 0.0], [10.700025226953745, 0.0], [10.800025226953746, 0.0], [10.900025226953746, 0.0], [11.000025226953746, 0.0], [11.100025226953745, 0.0], [11.200025226953745, 0.0], [11.300025226953746, 0.0], [11.400025226953746, 0.0], [11.500025226953746, 0.0], [11.600025226953747, 0.0], [11.700025226953745, 0.0], [11.800025226953746, 0.0], [11.900025226953744, 0.0], [12.000025226953746, 0.0], [12.100025226953743, 0.0], [12.200025226953745, 0.0], [12.300025226953743, 0.0], [12.400025226953744, 0.0], [12.500025226953742, 0.0], [12.600025226953743, 0.0], [12.700025226953741, 0.0], [12.800025226953743, 0.0], [12.90002522695374, 0.0], [13.000025226953742, 0.0], [13.10002522695374, 0.0], [13.200025226953741, 0.0], [13.30002522695374, 0.0], [13.40002522695374, 0.0], [13.500025226953738, 0.0], [13.60002522695374, 0.0], [13.700025226953738, 0.0], [13.80002522695374, 0.0], [13.900025226953737, 0.0], [14.000025226953738, 0.0], [14.100025226953736, 0.0], [14.200025226953738, 0.0], [14.300025226953736, 0.0], [14.400025226953737, 0.0], [14.500025226953735, 0.0], [14.600025226953736, 0.0], [14.700025226953734, 0.0], [14.797522703621961, 0.0], [14.877517658231215, 0.0], [14.937512612840468, 0.0], [14.97750756744972, 0.0], [14.997502522058973, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535, 7.663299316185535], "velocities": null}}, "time": 1740481182.7636163} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663435163474468, "gear": 1, "accelerator_pedal_position": 0.24487778989084322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.7636163} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.7836163} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657909843411046, "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": 1740481182.7836163} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 7.537543900360738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.964971663059607, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575602862580606, "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": 1740481182.8036163} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23680307106381127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652392180839853, "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": 1740481182.8036163} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.8136163, "x": 11.64376605653184, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8236163} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24481957096488366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646882163931076, "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": 1740481182.8236163} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8436162} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.740566, "x": 15.0, "y": 9.770000000000149, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481182.8436162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448189861411995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651396933943354, "gear": 1, "accelerator_pedal_position": 0.24481957096488366, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.8436162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8636162} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.64376605653184, 0.0], [7.806247007516409, 0.0], [7.906247007516409, 0.0], [8.006247007516409, 0.0], [8.106247007516409, 0.0], [8.206247007516408, 0.0], [8.30624700751641, 0.0], [8.40624700751641, 0.0], [8.506247007516409, 0.0], [8.606247007516409, 0.0], [8.706247007516408, 0.0], [8.806247007516408, 0.0], [8.90624700751641, 0.0], [9.006247007516409, 0.0], [9.106247007516409, 0.0], [9.20624700751641, 0.0], [9.30624700751641, 0.0], [9.40624700751641, 0.0], [9.506247007516409, 0.0], [9.606247007516409, 0.0], [9.70624700751641, 0.0], [9.80624700751641, 0.0], [9.90624700751641, 0.0], [10.00624700751641, 0.0], [10.10624700751641, 0.0], [10.20624700751641, 0.0], [10.306247007516411, 0.0], [10.40624700751641, 0.0], [10.50624700751641, 0.0], [10.60624700751641, 0.0], [10.70624700751641, 0.0], [10.806247007516411, 0.0], [10.906247007516411, 0.0], [11.00624700751641, 0.0], [11.106247007516412, 0.0], [11.20624700751641, 0.0], [11.306247007516411, 0.0], [11.406247007516411, 0.0], [11.50624700751641, 0.0], [11.606247007516412, 0.0], [11.706247007516412, 0.0], [11.806247007516411, 0.0], [11.906247007516411, 0.0], [12.00624700751641, 0.0], [12.10624700751641, 0.0], [12.20624700751641, 0.0], [12.30624700751641, 0.0], [12.40624700751641, 0.0], [12.506247007516409, 0.0], [12.606247007516409, 0.0], [12.706247007516408, 0.0], [12.806247007516408, 0.0], [12.906247007516408, 0.0], [13.006247007516407, 0.0], [13.106247007516407, 0.0], [13.206247007516406, 0.0], [13.306247007516406, 0.0], [13.406247007516406, 0.0], [13.506247007516405, 0.0], [13.606247007516405, 0.0], [13.706247007516405, 0.0], [13.806247007516404, 0.0], [13.906247007516404, 0.0], [14.006247007516404, 0.0], [14.106247007516403, 0.0], [14.206247007516403, 0.0], [14.306247007516403, 0.0], [14.406247007516402, 0.0], [14.506247007516402, 0.0], [14.606247007516401, 0.0], [14.706247007516401, 0.0], [14.80308328166185, 0.0], [14.88183388015857, 0.0], [14.940584478655289, 0.0], [14.97933507715201, 0.0], [14.998085675648731, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536, 7.563299316185535], "velocities": null}}, "time": 1740481182.8636162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655904717827993, "gear": 1, "accelerator_pedal_position": 0.2448189861411995, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.8636162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.8836162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650390981682134, "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": 1740481182.8836162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 7.64376605653184, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9649636217416188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25755972899992796, "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": 1740481182.9036162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368039896550841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644884885316686, "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": 1740481182.9036162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481182.9236162, "x": 11.749910862942164, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9236162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245060839199979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639386416933776, "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": 1740481182.9236162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9436162} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24498629512537978, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644213051552657, "gear": 1, "accelerator_pedal_position": 0.245060839199979, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481182.9436162} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.9636161} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.749910862942164, 0.0], [7.912343231419096, 0.0], [8.012343231419097, 0.0], [8.112343231419096, 0.0], [8.212343231419096, 0.0], [8.312343231419096, 0.0], [8.412343231419097, 0.0], [8.512343231419097, 0.0], [8.612343231419096, 0.0], [8.712343231419096, 0.0], [8.812343231419096, 0.0], [8.912343231419097, 0.0], [9.012343231419097, 0.0], [9.112343231419096, 0.0], [9.212343231419096, 0.0], [9.312343231419097, 0.0], [9.412343231419097, 0.0], [9.512343231419097, 0.0], [9.612343231419096, 0.0], [9.712343231419098, 0.0], [9.812343231419097, 0.0], [9.912343231419097, 0.0], [10.012343231419099, 0.0], [10.112343231419098, 0.0], [10.212343231419098, 0.0], [10.312343231419097, 0.0], [10.412343231419097, 0.0], [10.512343231419099, 0.0], [10.612343231419098, 0.0], [10.712343231419098, 0.0], [10.8123432314191, 0.0], [10.912343231419099, 0.0], [11.012343231419099, 0.0], [11.112343231419098, 0.0], [11.212343231419098, 0.0], [11.3123432314191, 0.0], [11.412343231419099, 0.0], [11.512343231419099, 0.0], [11.6123432314191, 0.0], [11.7123432314191, 0.0], [11.8123432314191, 0.0], [11.912343231419099, 0.0], [12.012343231419099, 0.0], [12.112343231419098, 0.0], [12.212343231419098, 0.0], [12.312343231419097, 0.0], [12.412343231419097, 0.0], [12.512343231419097, 0.0], [12.612343231419096, 0.0], [12.712343231419096, 0.0], [12.812343231419096, 0.0], [12.912343231419095, 0.0], [13.012343231419095, 0.0], [13.112343231419095, 0.0], [13.212343231419094, 0.0], [13.312343231419094, 0.0], [13.412343231419094, 0.0], [13.512343231419093, 0.0], [13.612343231419093, 0.0], [13.712343231419093, 0.0], [13.812343231419092, 0.0], [13.912343231419092, 0.0], [14.012343231419091, 0.0], [14.112343231419091, 0.0], [14.21234323141909, 0.0], [14.31234323141909, 0.0], [14.41234323141909, 0.0], [14.51234323141909, 0.0], [14.61234323141909, 0.0], [14.712343231419089, 0.0], [14.808456552915315, 0.0], [14.885987906631495, 0.0], [14.943519260347678, 0.0], [14.98105061406386, 0.0], [14.998581967780044, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536, 7.463299316185536], "velocities": null}}, "time": 1740481182.9636161} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646259602935622, "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": 1740481182.9636161} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481182.983616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96435812108416, "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": 1740481182.983616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481183.003616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638229992785167, "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": 1740481183.003616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 7.749910862942164, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639386416933776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25748870913416566, "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": 1740481183.023616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23692038552114902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632886186715688, "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": 1740481183.023616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.033616, "x": 11.855969198936354, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.043616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24562809961611756, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627549781224947, "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": 1740481183.043616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.063616} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.855969198936354, 0.0], [8.018356918968543, 0.0], [8.118356918968543, 0.0], [8.218356918968544, 0.0], [8.318356918968544, 0.0], [8.418356918968543, 0.0], [8.518356918968543, 0.0], [8.618356918968543, 0.0], [8.718356918968544, 0.0], [8.818356918968544, 0.0], [8.918356918968543, 0.0], [9.018356918968543, 0.0], [9.118356918968543, 0.0], [9.218356918968544, 0.0], [9.318356918968544, 0.0], [9.418356918968543, 0.0], [9.518356918968543, 0.0], [9.618356918968544, 0.0], [9.718356918968544, 0.0], [9.818356918968544, 0.0], [9.918356918968545, 0.0], [10.018356918968545, 0.0], [10.118356918968544, 0.0], [10.218356918968544, 0.0], [10.318356918968544, 0.0], [10.418356918968545, 0.0], [10.518356918968545, 0.0], [10.618356918968544, 0.0], [10.718356918968546, 0.0], [10.818356918968545, 0.0], [10.918356918968545, 0.0], [11.018356918968545, 0.0], [11.118356918968544, 0.0], [11.218356918968546, 0.0], [11.318356918968545, 0.0], [11.418356918968545, 0.0], [11.518356918968546, 0.0], [11.618356918968546, 0.0], [11.718356918968546, 0.0], [11.818356918968545, 0.0], [11.918356918968545, 0.0], [12.018356918968546, 0.0], [12.118356918968544, 0.0], [12.218356918968546, 0.0], [12.318356918968544, 0.0], [12.418356918968545, 0.0], [12.518356918968543, 0.0], [12.618356918968544, 0.0], [12.718356918968542, 0.0], [12.818356918968544, 0.0], [12.918356918968541, 0.0], [13.018356918968543, 0.0], [13.11835691896854, 0.0], [13.218356918968542, 0.0], [13.31835691896854, 0.0], [13.418356918968541, 0.0], [13.51835691896854, 0.0], [13.61835691896854, 0.0], [13.718356918968539, 0.0], [13.81835691896854, 0.0], [13.918356918968538, 0.0], [14.01835691896854, 0.0], [14.118356918968537, 0.0], [14.218356918968539, 0.0], [14.318356918968536, 0.0], [14.418356918968538, 0.0], [14.518356918968536, 0.0], [14.618356918968537, 0.0], [14.718356918968535, 0.0], [14.813684250597664, 0.0], [14.890012866803957, 0.0], [14.94634148301025, 0.0], [14.982670099216543, 0.0], [14.998998715422836, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536, 7.363299316185536], "velocities": null}}, "time": 1740481183.063616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963310163845287, "gear": 1, "accelerator_pedal_position": 0.24562809961611756, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.063616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.083616} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481183.9589896, "x": 15.0, "y": 9.878400000000156, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, 0.4800000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.083616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627893594229341, "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": 1740481183.083616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.103616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622692761523036, "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": 1740481183.103616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 7.855969198936354, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9630217059610185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25742519335957165, "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": 1740481183.123616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702334887535464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961749912926668, "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": 1740481183.123616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.143616, "x": 11.96184926861933, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.143616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24637181430276553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612312686412813, "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": 1740481183.143616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.163616} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[7.96184926861933, 0.0], [8.124146575117432, 0.0], [8.224146575117432, 0.0], [8.324146575117432, 0.0], [8.424146575117433, 0.0], [8.524146575117433, 0.0], [8.624146575117432, 0.0], [8.724146575117432, 0.0], [8.824146575117432, 0.0], [8.924146575117433, 0.0], [9.024146575117433, 0.0], [9.124146575117432, 0.0], [9.224146575117432, 0.0], [9.324146575117432, 0.0], [9.424146575117433, 0.0], [9.524146575117433, 0.0], [9.624146575117432, 0.0], [9.724146575117434, 0.0], [9.824146575117433, 0.0], [9.924146575117433, 0.0], [10.024146575117433, 0.0], [10.124146575117432, 0.0], [10.224146575117434, 0.0], [10.324146575117433, 0.0], [10.424146575117433, 0.0], [10.524146575117435, 0.0], [10.624146575117434, 0.0], [10.724146575117434, 0.0], [10.824146575117433, 0.0], [10.924146575117433, 0.0], [11.024146575117435, 0.0], [11.124146575117434, 0.0], [11.224146575117434, 0.0], [11.324146575117435, 0.0], [11.424146575117435, 0.0], [11.524146575117435, 0.0], [11.624146575117434, 0.0], [11.724146575117434, 0.0], [11.824146575117435, 0.0], [11.924146575117435, 0.0], [12.024146575117435, 0.0], [12.124146575117434, 0.0], [12.224146575117434, 0.0], [12.324146575117433, 0.0], [12.424146575117433, 0.0], [12.524146575117433, 0.0], [12.624146575117432, 0.0], [12.724146575117432, 0.0], [12.824146575117432, 0.0], [12.924146575117431, 0.0], [13.024146575117431, 0.0], [13.12414657511743, 0.0], [13.22414657511743, 0.0], [13.32414657511743, 0.0], [13.42414657511743, 0.0], [13.52414657511743, 0.0], [13.624146575117429, 0.0], [13.724146575117429, 0.0], [13.824146575117428, 0.0], [13.924146575117428, 0.0], [14.024146575117427, 0.0], [14.124146575117427, 0.0], [14.224146575117427, 0.0], [14.324146575117426, 0.0], [14.424146575117426, 0.0], [14.524146575117426, 0.0], [14.624146575117425, 0.0], [14.724146575117425, 0.0], [14.818648860515781, 0.0], [14.893819545492295, 0.0], [14.94899023046881, 0.0], [14.984160915445326, 0.0], [14.99933160042184, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537, 7.263299316185536], "velocities": null}}, "time": 1740481183.163616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622062719476795, "gear": 1, "accelerator_pedal_position": 0.24637181430276553, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.163616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.183616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619589117230263, "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": 1740481183.183616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.203616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614647049718171, "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": 1740481183.203616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.223616} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609711822798559, "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": 1740481183.223616} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 7.96184926861933, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9612312686412813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730121895020136, "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": 1740481183.2436159} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23722123203677054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604783426029057, "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": 1740481183.2436159} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.2536159, "x": 12.067603297929363, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.2636158} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.067603297929363, 0.0], [8.229848294367342, 0.0], [8.329848294367343, 0.0], [8.429848294367343, 0.0], [8.529848294367342, 0.0], [8.629848294367342, 0.0], [8.729848294367342, 0.0], [8.829848294367343, 0.0], [8.929848294367343, 0.0], [9.029848294367342, 0.0], [9.129848294367342, 0.0], [9.229848294367342, 0.0], [9.329848294367343, 0.0], [9.429848294367343, 0.0], [9.529848294367342, 0.0], [9.629848294367342, 0.0], [9.729848294367343, 0.0], [9.829848294367343, 0.0], [9.929848294367343, 0.0], [10.029848294367342, 0.0], [10.129848294367344, 0.0], [10.229848294367343, 0.0], [10.329848294367343, 0.0], [10.429848294367343, 0.0], [10.529848294367344, 0.0], [10.629848294367344, 0.0], [10.729848294367343, 0.0], [10.829848294367345, 0.0], [10.929848294367345, 0.0], [11.029848294367344, 0.0], [11.129848294367344, 0.0], [11.229848294367343, 0.0], [11.329848294367345, 0.0], [11.429848294367345, 0.0], [11.529848294367344, 0.0], [11.629848294367346, 0.0], [11.729848294367345, 0.0], [11.829848294367345, 0.0], [11.929848294367345, 0.0], [12.029848294367344, 0.0], [12.129848294367346, 0.0], [12.229848294367345, 0.0], [12.329848294367345, 0.0], [12.429848294367345, 0.0], [12.529848294367344, 0.0], [12.629848294367344, 0.0], [12.729848294367343, 0.0], [12.829848294367343, 0.0], [12.929848294367343, 0.0], [13.029848294367342, 0.0], [13.129848294367342, 0.0], [13.229848294367342, 0.0], [13.329848294367341, 0.0], [13.429848294367341, 0.0], [13.52984829436734, 0.0], [13.62984829436734, 0.0], [13.72984829436734, 0.0], [13.82984829436734, 0.0], [13.92984829436734, 0.0], [14.029848294367339, 0.0], [14.129848294367338, 0.0], [14.229848294367338, 0.0], [14.329848294367338, 0.0], [14.429848294367337, 0.0], [14.529848294367337, 0.0], [14.629848294367337, 0.0], [14.729848294367336, 0.0], [14.823472544253963, 0.0], [14.897502885380495, 0.0], [14.951533226507028, 0.0], [14.985563567633562, 0.0], [14.999593908760094, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537, 7.163299316185537], "velocities": null}}, "time": 1740481183.2636158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770937913733085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959986184898579, "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": 1740481183.2636158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.2836158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960805272892612, "gear": 1, "accelerator_pedal_position": 0.24770937913733085, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.2836158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3036158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616170590699857, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3036158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3236158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962427721665183, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3236158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 8.067603297929363, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602321785692415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572320672960604, "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": 1740481183.3436158} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.1787477, "x": 15.0, "y": 9.81740000000014, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.3436158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766001489514453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632372619705599, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3436158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.3636158, "x": 12.173387394235935, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.3636158} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.173387394235935, 0.0], [8.335824901731627, 0.0], [8.435824901731626, 0.0], [8.535824901731626, 0.0], [8.635824901731628, 0.0], [8.735824901731627, 0.0], [8.835824901731627, 0.0], [8.935824901731626, 0.0], [9.035824901731626, 0.0], [9.135824901731628, 0.0], [9.235824901731627, 0.0], [9.335824901731627, 0.0], [9.435824901731626, 0.0], [9.535824901731626, 0.0], [9.635824901731628, 0.0], [9.735824901731627, 0.0], [9.835824901731627, 0.0], [9.935824901731628, 0.0], [10.035824901731628, 0.0], [10.135824901731628, 0.0], [10.235824901731627, 0.0], [10.335824901731627, 0.0], [10.435824901731628, 0.0], [10.535824901731628, 0.0], [10.635824901731628, 0.0], [10.735824901731629, 0.0], [10.835824901731629, 0.0], [10.935824901731628, 0.0], [11.035824901731628, 0.0], [11.135824901731628, 0.0], [11.235824901731629, 0.0], [11.335824901731629, 0.0], [11.435824901731628, 0.0], [11.53582490173163, 0.0], [11.63582490173163, 0.0], [11.735824901731629, 0.0], [11.835824901731629, 0.0], [11.935824901731628, 0.0], [12.03582490173163, 0.0], [12.13582490173163, 0.0], [12.235824901731629, 0.0], [12.33582490173163, 0.0], [12.435824901731628, 0.0], [12.53582490173163, 0.0], [12.635824901731628, 0.0], [12.735824901731629, 0.0], [12.835824901731627, 0.0], [12.935824901731628, 0.0], [13.035824901731626, 0.0], [13.135824901731628, 0.0], [13.235824901731625, 0.0], [13.335824901731627, 0.0], [13.435824901731625, 0.0], [13.535824901731626, 0.0], [13.635824901731624, 0.0], [13.735824901731625, 0.0], [13.835824901731623, 0.0], [13.935824901731625, 0.0], [14.035824901731623, 0.0], [14.135824901731624, 0.0], [14.235824901731622, 0.0], [14.335824901731623, 0.0], [14.435824901731621, 0.0], [14.535824901731623, 0.0], [14.63582490173162, 0.0], [14.735824901731622, 0.0], [14.82845898797438, 0.0], [14.901294007628053, 0.0], [14.95412902728173, 0.0], [14.986964046935405, 0.0], [14.999799066589082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537], "velocities": null}}, "time": 1740481183.3636158} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516065179269803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644494709605235, "gear": 1, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3636158} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.3836157} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646967706838833, "gear": 1, "accelerator_pedal_position": 0.24516065179269803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.3836157} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4036157} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652147989614736, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4036157} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4236157} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657321094830018, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4236157} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4436157} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662487031359507, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4436157} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 8.173387394235935, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640456812777749, "accelerator_pedal_position": 0.24766001489514453, "brake_pedal_position": 0.0, "acceleration": 0.04037896827486115, "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": 1740481183.4636157} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.173387394235935, 0.0], [8.335824901731627, 0.0], [8.435824901731626, 0.0], [8.535824901731626, 0.0], [8.635824901731628, 0.0], [8.735824901731627, 0.0], [8.835824901731627, 0.0], [8.935824901731626, 0.0], [9.035824901731626, 0.0], [9.135824901731628, 0.0], [9.235824901731627, 0.0], [9.335824901731627, 0.0], [9.435824901731626, 0.0], [9.535824901731626, 0.0], [9.635824901731628, 0.0], [9.735824901731627, 0.0], [9.835824901731627, 0.0], [9.935824901731628, 0.0], [10.035824901731628, 0.0], [10.135824901731628, 0.0], [10.235824901731627, 0.0], [10.335824901731627, 0.0], [10.435824901731628, 0.0], [10.535824901731628, 0.0], [10.635824901731628, 0.0], [10.735824901731629, 0.0], [10.835824901731629, 0.0], [10.935824901731628, 0.0], [11.035824901731628, 0.0], [11.135824901731628, 0.0], [11.235824901731629, 0.0], [11.335824901731629, 0.0], [11.435824901731628, 0.0], [11.53582490173163, 0.0], [11.63582490173163, 0.0], [11.735824901731629, 0.0], [11.835824901731629, 0.0], [11.935824901731628, 0.0], [12.03582490173163, 0.0], [12.13582490173163, 0.0], [12.235824901731629, 0.0], [12.33582490173163, 0.0], [12.435824901731628, 0.0], [12.53582490173163, 0.0], [12.635824901731628, 0.0], [12.735824901731629, 0.0], [12.835824901731627, 0.0], [12.935824901731628, 0.0], [13.035824901731626, 0.0], [13.135824901731628, 0.0], [13.235824901731625, 0.0], [13.335824901731627, 0.0], [13.435824901731625, 0.0], [13.535824901731626, 0.0], [13.635824901731624, 0.0], [13.735824901731625, 0.0], [13.835824901731623, 0.0], [13.935824901731625, 0.0], [14.035824901731623, 0.0], [14.135824901731624, 0.0], [14.235824901731622, 0.0], [14.335824901731623, 0.0], [14.435824901731621, 0.0], [14.535824901731623, 0.0], [14.63582490173162, 0.0], [14.735824901731622, 0.0], [14.82845898797438, 0.0], [14.901294007628053, 0.0], [14.95412902728173, 0.0], [14.986964046935405, 0.0], [14.999799066589082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537, 7.063299316185537], "velocities": null}}, "time": 1740481183.4636157} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24535226056127973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967022251426224, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4636157} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.4736156, "x": 12.279588181846634, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.4836156} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744377874714676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672797433821155, "gear": 1, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.4836156} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5036156} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668059742820948, "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": 1740481183.5036156} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5236156} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663119518421894, "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": 1740481183.5236156} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5436156} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23727643977180443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965818614163603, "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": 1740481183.5436156} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 8.279588181846634, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.967022251426224, "accelerator_pedal_position": 0.24535226056127973, "brake_pedal_position": 0.0, "acceleration": 0.025749195589152618, "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": 1740481183.5636156} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.279588181846634, 0.0], [8.44216247676485, 0.0], [8.54216247676485, 0.0], [8.642162476764849, 0.0], [8.742162476764848, 0.0], [8.84216247676485, 0.0], [8.94216247676485, 0.0], [9.04216247676485, 0.0], [9.142162476764849, 0.0], [9.242162476764848, 0.0], [9.34216247676485, 0.0], [9.44216247676485, 0.0], [9.54216247676485, 0.0], [9.642162476764849, 0.0], [9.74216247676485, 0.0], [9.84216247676485, 0.0], [9.94216247676485, 0.0], [10.04216247676485, 0.0], [10.14216247676485, 0.0], [10.24216247676485, 0.0], [10.34216247676485, 0.0], [10.44216247676485, 0.0], [10.542162476764851, 0.0], [10.64216247676485, 0.0], [10.74216247676485, 0.0], [10.84216247676485, 0.0], [10.94216247676485, 0.0], [11.042162476764851, 0.0], [11.14216247676485, 0.0], [11.24216247676485, 0.0], [11.342162476764852, 0.0], [11.442162476764851, 0.0], [11.542162476764851, 0.0], [11.64216247676485, 0.0], [11.74216247676485, 0.0], [11.842162476764852, 0.0], [11.942162476764851, 0.0], [12.042162476764851, 0.0], [12.142162476764852, 0.0], [12.242162476764852, 0.0], [12.342162476764852, 0.0], [12.442162476764851, 0.0], [12.542162476764851, 0.0], [12.64216247676485, 0.0], [12.74216247676485, 0.0], [12.84216247676485, 0.0], [12.94216247676485, 0.0], [13.04216247676485, 0.0], [13.142162476764849, 0.0], [13.242162476764848, 0.0], [13.342162476764848, 0.0], [13.442162476764848, 0.0], [13.542162476764847, 0.0], [13.642162476764847, 0.0], [13.742162476764847, 0.0], [13.842162476764846, 0.0], [13.942162476764846, 0.0], [14.042162476764846, 0.0], [14.142162476764845, 0.0], [14.242162476764845, 0.0], [14.342162476764845, 0.0], [14.442162476764844, 0.0], [14.542162476764844, 0.0], [14.642162476764844, 0.0], [14.742162476764843, 0.0], [14.833668554641413, 0.0], [14.905236059288445, 0.0], [14.956803563935475, 0.0], [14.988371068582506, 0.0], [14.999938573229539, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538, 6.963299316185537], "velocities": null}}, "time": 1740481183.5636156} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23656606690875456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653259601998734, "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": 1740481183.5636156} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.5836155, "x": 12.385876572242696, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.5836155} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.3999505, "x": 15.0, "y": 9.707400000000122, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.5836155} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419972229712852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647452230670487, "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": 1740481183.5836155} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6036155} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651191668516375, "gear": 1, "accelerator_pedal_position": 0.24419972229712852, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6036155} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6236155} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654718994216099, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6236155} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6436155} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24403412007671246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965824143219542, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6436155} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6636155} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.385876572242696, 0.0], [8.54834728889718, 0.0], [8.64834728889718, 0.0], [8.748347288897179, 0.0], [8.848347288897179, 0.0], [8.94834728889718, 0.0], [9.04834728889718, 0.0], [9.14834728889718, 0.0], [9.248347288897179, 0.0], [9.348347288897179, 0.0], [9.448347288897178, 0.0], [9.54834728889718, 0.0], [9.64834728889718, 0.0], [9.748347288897179, 0.0], [9.84834728889718, 0.0], [9.94834728889718, 0.0], [10.04834728889718, 0.0], [10.14834728889718, 0.0], [10.248347288897179, 0.0], [10.34834728889718, 0.0], [10.44834728889718, 0.0], [10.54834728889718, 0.0], [10.648347288897181, 0.0], [10.74834728889718, 0.0], [10.84834728889718, 0.0], [10.94834728889718, 0.0], [11.04834728889718, 0.0], [11.148347288897181, 0.0], [11.24834728889718, 0.0], [11.34834728889718, 0.0], [11.448347288897182, 0.0], [11.548347288897181, 0.0], [11.648347288897181, 0.0], [11.74834728889718, 0.0], [11.84834728889718, 0.0], [11.948347288897182, 0.0], [12.048347288897181, 0.0], [12.148347288897181, 0.0], [12.248347288897182, 0.0], [12.348347288897182, 0.0], [12.448347288897182, 0.0], [12.548347288897183, 0.0], [12.648347288897181, 0.0], [12.748347288897182, 0.0], [12.84834728889718, 0.0], [12.948347288897182, 0.0], [13.04834728889718, 0.0], [13.148347288897181, 0.0], [13.248347288897179, 0.0], [13.34834728889718, 0.0], [13.448347288897178, 0.0], [13.54834728889718, 0.0], [13.648347288897178, 0.0], [13.748347288897179, 0.0], [13.848347288897177, 0.0], [13.948347288897178, 0.0], [14.048347288897176, 0.0], [14.148347288897178, 0.0], [14.248347288897175, 0.0], [14.348347288897177, 0.0], [14.448347288897175, 0.0], [14.548347288897176, 0.0], [14.648347288897174, 0.0], [14.748347288897175, 0.0], [14.83867509966375, 0.0], [14.909005641884313, 0.0], [14.95933618410488, 0.0], [14.989666726325446, 0.0], [14.99999726854601, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385, 6.763299316185538, 6.863299316185538], "velocities": null}}, "time": 1740481183.6636155} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682890588838856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661758988730988, "gear": 1, "accelerator_pedal_position": 0.24403412007671246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.6636155} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 8.385876572242696, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9647452230670487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575445946076593, "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": 1740481183.6836154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682890588838856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656268274130334, "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": 1740481183.6836154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.6936154, "x": 12.4920839766951, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7036154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24480614220733946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650785168700318, "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": 1740481183.7036154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7236154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485031345188774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655277750898226, "gear": 1, "accelerator_pedal_position": 0.24480614220733946, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7236154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7436154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485031345188774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659819302708612, "gear": 1, "accelerator_pedal_position": 0.24485031345188774, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7436154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7636154} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.4920839766951, 0.0], [8.654582996938256, 0.0], [8.754582996938256, 0.0], [8.854582996938255, 0.0], [8.954582996938255, 0.0], [9.054582996938256, 0.0], [9.154582996938256, 0.0], [9.254582996938256, 0.0], [9.354582996938255, 0.0], [9.454582996938255, 0.0], [9.554582996938255, 0.0], [9.654582996938256, 0.0], [9.754582996938256, 0.0], [9.854582996938255, 0.0], [9.954582996938255, 0.0], [10.054582996938256, 0.0], [10.154582996938256, 0.0], [10.254582996938256, 0.0], [10.354582996938255, 0.0], [10.454582996938257, 0.0], [10.554582996938256, 0.0], [10.654582996938256, 0.0], [10.754582996938257, 0.0], [10.854582996938257, 0.0], [10.954582996938257, 0.0], [11.054582996938256, 0.0], [11.154582996938256, 0.0], [11.254582996938257, 0.0], [11.354582996938257, 0.0], [11.454582996938257, 0.0], [11.554582996938258, 0.0], [11.654582996938258, 0.0], [11.754582996938257, 0.0], [11.854582996938257, 0.0], [11.954582996938257, 0.0], [12.054582996938258, 0.0], [12.154582996938258, 0.0], [12.254582996938257, 0.0], [12.354582996938259, 0.0], [12.454582996938258, 0.0], [12.554582996938258, 0.0], [12.654582996938258, 0.0], [12.754582996938257, 0.0], [12.854582996938257, 0.0], [12.954582996938257, 0.0], [13.054582996938256, 0.0], [13.154582996938256, 0.0], [13.254582996938256, 0.0], [13.354582996938255, 0.0], [13.454582996938255, 0.0], [13.554582996938255, 0.0], [13.654582996938254, 0.0], [13.754582996938254, 0.0], [13.854582996938253, 0.0], [13.954582996938253, 0.0], [14.054582996938253, 0.0], [14.154582996938252, 0.0], [14.254582996938252, 0.0], [14.354582996938252, 0.0], [14.454582996938251, 0.0], [14.554582996938251, 0.0], [14.65458299693825, 0.0], [14.754561993077314, 0.0], [14.843645393689663, 0.0], [14.912728794302014, 0.0], [14.961812194914364, 0.0], [14.990895595526712, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539, 6.6632993161855385], "velocities": null}}, "time": 1740481183.7636154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23675946098311074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664354560532891, "gear": 1, "accelerator_pedal_position": 0.24485031345188774, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.7636154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 8.4920839766951, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653525771003691, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575866848361617, "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": 1740481183.7836154} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23675946098311074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658773472460883, "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": 1740481183.7836154} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.8036153, "x": 12.598316730870444, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8036153} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446083065954322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653200119365273, "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": 1740481183.8036153} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8236153} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460593821762142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657442146486548, "gear": 1, "accelerator_pedal_position": 0.2446083065954322, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.8236153} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8436153} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.728798, "x": 15.0, "y": 9.542400000000097, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481183.8436153} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460593821762142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661675335667255, "gear": 1, "accelerator_pedal_position": 0.24460593821762142, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.8436153} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8636153} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.598316730870444, 0.0], [8.760814246007934, 0.0], [8.860814246007934, 0.0], [8.960814246007933, 0.0], [9.060814246007935, 0.0], [9.160814246007934, 0.0], [9.260814246007934, 0.0], [9.360814246007934, 0.0], [9.460814246007933, 0.0], [9.560814246007935, 0.0], [9.660814246007934, 0.0], [9.760814246007934, 0.0], [9.860814246007934, 0.0], [9.960814246007935, 0.0], [10.060814246007935, 0.0], [10.160814246007934, 0.0], [10.260814246007934, 0.0], [10.360814246007934, 0.0], [10.460814246007935, 0.0], [10.560814246007935, 0.0], [10.660814246007934, 0.0], [10.760814246007936, 0.0], [10.860814246007935, 0.0], [10.960814246007935, 0.0], [11.060814246007935, 0.0], [11.160814246007934, 0.0], [11.260814246007936, 0.0], [11.360814246007935, 0.0], [11.460814246007935, 0.0], [11.560814246007936, 0.0], [11.660814246007936, 0.0], [11.760814246007936, 0.0], [11.860814246007935, 0.0], [11.960814246007935, 0.0], [12.060814246007936, 0.0], [12.160814246007936, 0.0], [12.260814246007936, 0.0], [12.360814246007937, 0.0], [12.460814246007937, 0.0], [12.560814246007936, 0.0], [12.660814246007936, 0.0], [12.760814246007936, 0.0], [12.860814246007935, 0.0], [12.960814246007935, 0.0], [13.060814246007935, 0.0], [13.160814246007934, 0.0], [13.260814246007934, 0.0], [13.360814246007934, 0.0], [13.460814246007933, 0.0], [13.560814246007933, 0.0], [13.660814246007932, 0.0], [13.760814246007932, 0.0], [13.860814246007932, 0.0], [13.960814246007931, 0.0], [14.060814246007931, 0.0], [14.16081424600793, 0.0], [14.26081424600793, 0.0], [14.36081424600793, 0.0], [14.46081424600793, 0.0], [14.56081424600793, 0.0], [14.660814246007929, 0.0], [14.760697298091209, 0.0], [14.848534448889623, 0.0], [14.916371599688038, 0.0], [14.964208750486451, 0.0], [14.992045901284865, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539, 6.563299316185539], "velocities": null}}, "time": 1740481183.8636153} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966311240775904, "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": 1740481183.8636153} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.8836153} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660324092086717, "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": 1740481183.8836153} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 8.598316730870444, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9653200119365273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575844278512778, "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": 1740481183.9036152} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23676319671297014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965475325811548, "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": 1740481183.9036152} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481183.9136152, "x": 12.704569349669976, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9236152} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24464782157786638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649190144013424, "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": 1740481183.9236152} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9436152} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24463888060542693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653487104008933, "gear": 1, "accelerator_pedal_position": 0.24464782157786638, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.9436152} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9636152} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.704569349669976, 0.0], [8.867061170068691, 0.0], [8.96706117006869, 0.0], [9.06706117006869, 0.0], [9.16706117006869, 0.0], [9.26706117006869, 0.0], [9.367061170068691, 0.0], [9.46706117006869, 0.0], [9.56706117006869, 0.0], [9.66706117006869, 0.0], [9.76706117006869, 0.0], [9.867061170068691, 0.0], [9.96706117006869, 0.0], [10.06706117006869, 0.0], [10.167061170068692, 0.0], [10.267061170068692, 0.0], [10.367061170068691, 0.0], [10.46706117006869, 0.0], [10.56706117006869, 0.0], [10.667061170068692, 0.0], [10.767061170068692, 0.0], [10.867061170068691, 0.0], [10.967061170068693, 0.0], [11.06706117006869, 0.0], [11.167061170068692, 0.0], [11.267061170068692, 0.0], [11.367061170068691, 0.0], [11.467061170068693, 0.0], [11.567061170068692, 0.0], [11.667061170068692, 0.0], [11.767061170068693, 0.0], [11.867061170068691, 0.0], [11.967061170068693, 0.0], [12.067061170068692, 0.0], [12.167061170068692, 0.0], [12.267061170068693, 0.0], [12.367061170068693, 0.0], [12.467061170068693, 0.0], [12.567061170068694, 0.0], [12.667061170068692, 0.0], [12.767061170068693, 0.0], [12.867061170068693, 0.0], [12.967061170068693, 0.0], [13.067061170068692, 0.0], [13.167061170068692, 0.0], [13.267061170068692, 0.0], [13.367061170068691, 0.0], [13.46706117006869, 0.0], [13.56706117006869, 0.0], [13.66706117006869, 0.0], [13.76706117006869, 0.0], [13.86706117006869, 0.0], [13.967061170068689, 0.0], [14.067061170068689, 0.0], [14.167061170068688, 0.0], [14.267061170068688, 0.0], [14.367061170068688, 0.0], [14.467061170068687, 0.0], [14.567061170068687, 0.0], [14.667061170068687, 0.0], [14.766770086544573, 0.0], [14.853357852530836, 0.0], [14.919945618517099, 0.0], [14.96653338450336, 0.0], [14.993121150489625, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554, 6.463299316185539], "velocities": null}}, "time": 1740481183.9636152} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965776693772477, "gear": 1, "accelerator_pedal_position": 0.24463888060542693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481183.9636152} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481183.9836152} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652217254468489, "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": 1740481183.9836152} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 8.704569349669976, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651970736827278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575759075945934, "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": 1740481184.0036151} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677728715189142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646675261207717, "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": 1740481184.0036151} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.0236151, "x": 12.810735967815697, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.0236151} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24494113658270075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9641140946058581, "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": 1740481184.0236151} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.043615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486237439290584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96458155739058, "gear": 1, "accelerator_pedal_position": 0.24494113658270075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.043615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.063615} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.810735967815697, 0.0], [8.973176751863937, 0.0], [9.073176751863938, 0.0], [9.173176751863938, 0.0], [9.273176751863938, 0.0], [9.373176751863937, 0.0], [9.473176751863937, 0.0], [9.573176751863937, 0.0], [9.673176751863938, 0.0], [9.773176751863938, 0.0], [9.873176751863937, 0.0], [9.973176751863937, 0.0], [10.073176751863937, 0.0], [10.173176751863938, 0.0], [10.273176751863938, 0.0], [10.373176751863937, 0.0], [10.473176751863939, 0.0], [10.573176751863938, 0.0], [10.673176751863938, 0.0], [10.773176751863938, 0.0], [10.873176751863937, 0.0], [10.973176751863939, 0.0], [11.073176751863938, 0.0], [11.173176751863938, 0.0], [11.27317675186394, 0.0], [11.373176751863939, 0.0], [11.473176751863939, 0.0], [11.573176751863938, 0.0], [11.673176751863938, 0.0], [11.77317675186394, 0.0], [11.873176751863939, 0.0], [11.973176751863939, 0.0], [12.07317675186394, 0.0], [12.17317675186394, 0.0], [12.27317675186394, 0.0], [12.373176751863939, 0.0], [12.473176751863939, 0.0], [12.57317675186394, 0.0], [12.67317675186394, 0.0], [12.77317675186394, 0.0], [12.87317675186394, 0.0], [12.973176751863939, 0.0], [13.07317675186394, 0.0], [13.173176751863938, 0.0], [13.27317675186394, 0.0], [13.373176751863937, 0.0], [13.473176751863939, 0.0], [13.573176751863937, 0.0], [13.673176751863938, 0.0], [13.773176751863936, 0.0], [13.873176751863937, 0.0], [13.973176751863935, 0.0], [14.073176751863937, 0.0], [14.173176751863934, 0.0], [14.273176751863936, 0.0], [14.373176751863934, 0.0], [14.473176751863935, 0.0], [14.573176751863933, 0.0], [14.673176751863934, 0.0], [14.772639590036972, 0.0], [14.858004239664185, 0.0], [14.923368889291398, 0.0], [14.96873353891861, 0.0], [14.994098188545824, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554, 6.36329931618554], "velocities": null}}, "time": 1740481184.063615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647691664442822, "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": 1740481184.063615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.083615} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481184.9488657, "x": 15.0, "y": 9.43240000000008, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.083615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644999888189448, "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": 1740481184.083615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.103615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639621929858138, "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": 1740481184.103615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 8.810735967815697, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641140946058581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25750086460446964, "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": 1740481184.123615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236900558597391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634251420852472, "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": 1740481184.123615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.133615, "x": 12.916810700570888, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.143615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24553518762853593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628888349700659, "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": 1740481184.143615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.163615} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[8.916810700570888, 0.0], [9.079205073863163, 0.0], [9.179205073863162, 0.0], [9.279205073863164, 0.0], [9.379205073863163, 0.0], [9.479205073863163, 0.0], [9.579205073863163, 0.0], [9.679205073863162, 0.0], [9.779205073863162, 0.0], [9.879205073863163, 0.0], [9.979205073863163, 0.0], [10.079205073863163, 0.0], [10.179205073863162, 0.0], [10.279205073863164, 0.0], [10.379205073863163, 0.0], [10.479205073863163, 0.0], [10.579205073863163, 0.0], [10.679205073863164, 0.0], [10.779205073863164, 0.0], [10.879205073863163, 0.0], [10.979205073863163, 0.0], [11.079205073863164, 0.0], [11.179205073863164, 0.0], [11.279205073863164, 0.0], [11.379205073863163, 0.0], [11.479205073863163, 0.0], [11.579205073863164, 0.0], [11.679205073863164, 0.0], [11.779205073863164, 0.0], [11.879205073863165, 0.0], [11.979205073863165, 0.0], [12.079205073863164, 0.0], [12.179205073863164, 0.0], [12.279205073863164, 0.0], [12.379205073863165, 0.0], [12.479205073863165, 0.0], [12.579205073863164, 0.0], [12.679205073863166, 0.0], [12.779205073863166, 0.0], [12.879205073863165, 0.0], [12.979205073863165, 0.0], [13.079205073863164, 0.0], [13.179205073863164, 0.0], [13.279205073863164, 0.0], [13.379205073863163, 0.0], [13.479205073863163, 0.0], [13.579205073863163, 0.0], [13.679205073863162, 0.0], [13.779205073863162, 0.0], [13.879205073863162, 0.0], [13.979205073863161, 0.0], [14.079205073863161, 0.0], [14.17920507386316, 0.0], [14.27920507386316, 0.0], [14.37920507386316, 0.0], [14.47920507386316, 0.0], [14.57920507386316, 0.0], [14.679205073863159, 0.0], [14.778352137523807, 0.0], [14.862511122751174, 0.0], [14.926670107978541, 0.0], [14.97082909320591, 0.0], [14.994988078433279, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554, 6.26329931618554], "velocities": null}}, "time": 1740481184.163615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634322253643347, "gear": 1, "accelerator_pedal_position": 0.24553518762853593, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.163615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.183615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629093636246496, "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": 1740481184.183615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.203615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623872259106184, "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": 1740481184.203615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 8.916810700570888, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631568956261013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743455683722616, "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": 1740481184.223615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2370082373658752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616053744565964, "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": 1740481184.223615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.243615, "x": 13.022704217489116, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.243615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2462964808699367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613451181151169, "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": 1740481184.243615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.263615} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.022704217489116, 0.0], [9.185007400412305, 0.0], [9.285007400412304, 0.0], [9.385007400412304, 0.0], [9.485007400412306, 0.0], [9.585007400412305, 0.0], [9.685007400412305, 0.0], [9.785007400412304, 0.0], [9.885007400412304, 0.0], [9.985007400412304, 0.0], [10.085007400412305, 0.0], [10.185007400412305, 0.0], [10.285007400412304, 0.0], [10.385007400412304, 0.0], [10.485007400412306, 0.0], [10.585007400412305, 0.0], [10.685007400412305, 0.0], [10.785007400412304, 0.0], [10.885007400412306, 0.0], [10.985007400412306, 0.0], [11.085007400412305, 0.0], [11.185007400412307, 0.0], [11.285007400412306, 0.0], [11.385007400412306, 0.0], [11.485007400412306, 0.0], [11.585007400412305, 0.0], [11.685007400412307, 0.0], [11.785007400412306, 0.0], [11.885007400412306, 0.0], [11.985007400412307, 0.0], [12.085007400412307, 0.0], [12.185007400412307, 0.0], [12.285007400412306, 0.0], [12.385007400412306, 0.0], [12.485007400412307, 0.0], [12.585007400412307, 0.0], [12.685007400412307, 0.0], [12.785007400412308, 0.0], [12.885007400412308, 0.0], [12.985007400412307, 0.0], [13.085007400412307, 0.0], [13.185007400412307, 0.0], [13.285007400412306, 0.0], [13.385007400412306, 0.0], [13.485007400412306, 0.0], [13.585007400412305, 0.0], [13.685007400412305, 0.0], [13.785007400412304, 0.0], [13.885007400412304, 0.0], [13.985007400412304, 0.0], [14.085007400412303, 0.0], [14.185007400412303, 0.0], [14.285007400412303, 0.0], [14.385007400412302, 0.0], [14.485007400412302, 0.0], [14.585007400412302, 0.0], [14.685007400412301, 0.0], [14.783781882328674, 0.0], [14.866780402246214, 0.0], [14.929778922163752, 0.0], [14.972777442081293, 0.0], [14.995775961998833, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541, 6.16329931618554], "velocities": null}}, "time": 1740481184.263615} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961737788191656, "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": 1740481184.263615} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.2836149} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614899737038708, "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": 1740481184.2836149} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3036149} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960994859300093, "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": 1740481184.3036149} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3236148} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605004301189541, "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": 1740481184.3236148} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 9.022704217489116, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9613451181151169, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730910026699355, "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": 1740481184.3436148} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.169243, "x": 15.0, "y": 9.322400000000062, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.3436148} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23720877381814676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600066851143777, "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": 1740481184.3436148} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.3536148, "x": 13.128423912970664, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.3636148} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.128423912970664, 0.0], [9.290643727783674, 0.0], [9.390643727783674, 0.0], [9.490643727783674, 0.0], [9.590643727783673, 0.0], [9.690643727783673, 0.0], [9.790643727783674, 0.0], [9.890643727783674, 0.0], [9.990643727783674, 0.0], [10.090643727783673, 0.0], [10.190643727783673, 0.0], [10.290643727783674, 0.0], [10.390643727783674, 0.0], [10.490643727783674, 0.0], [10.590643727783673, 0.0], [10.690643727783675, 0.0], [10.790643727783674, 0.0], [10.890643727783674, 0.0], [10.990643727783674, 0.0], [11.090643727783675, 0.0], [11.190643727783675, 0.0], [11.290643727783674, 0.0], [11.390643727783676, 0.0], [11.490643727783675, 0.0], [11.590643727783675, 0.0], [11.690643727783675, 0.0], [11.790643727783674, 0.0], [11.890643727783676, 0.0], [11.990643727783675, 0.0], [12.090643727783675, 0.0], [12.190643727783677, 0.0], [12.290643727783676, 0.0], [12.390643727783676, 0.0], [12.490643727783675, 0.0], [12.590643727783675, 0.0], [12.690643727783677, 0.0], [12.790643727783676, 0.0], [12.890643727783676, 0.0], [12.990643727783677, 0.0], [13.090643727783677, 0.0], [13.190643727783677, 0.0], [13.290643727783676, 0.0], [13.390643727783676, 0.0], [13.490643727783675, 0.0], [13.590643727783675, 0.0], [13.690643727783675, 0.0], [13.790643727783674, 0.0], [13.890643727783674, 0.0], [13.990643727783674, 0.0], [14.090643727783673, 0.0], [14.190643727783673, 0.0], [14.290643727783673, 0.0], [14.390643727783672, 0.0], [14.490643727783672, 0.0], [14.590643727783672, 0.0], [14.690643727783671, 0.0], [14.788991815175518, 0.0], [14.870863069618784, 0.0], [14.93273432406205, 0.0], [14.974605578505315, 0.0], [14.99647683294858, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541, 6.063299316185541], "velocities": null}}, "time": 1740481184.3636148} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2480357555406792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595136232421402, "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": 1740481184.3636148} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.3836148} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603741479615895, "gear": 1, "accelerator_pedal_position": 0.2480357555406792, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.3836148} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4036148} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612237170259696, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4036148} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4236147} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624958665282861, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4236147} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 9.128423912970664, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597600688519082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571993973402216, "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": 1740481184.4436147} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24795760812532924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629193292735466, "gear": 1, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4436147} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.4636147, "x": 13.234164838336826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.4636147} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.234164838336826, 0.0], [9.39658885582962, 0.0], [9.49658885582962, 0.0], [9.59658885582962, 0.0], [9.69658885582962, 0.0], [9.79658885582962, 0.0], [9.89658885582962, 0.0], [9.99658885582962, 0.0], [10.09658885582962, 0.0], [10.19658885582962, 0.0], [10.29658885582962, 0.0], [10.39658885582962, 0.0], [10.49658885582962, 0.0], [10.59658885582962, 0.0], [10.69658885582962, 0.0], [10.79658885582962, 0.0], [10.89658885582962, 0.0], [10.996588855829621, 0.0], [11.096588855829621, 0.0], [11.19658885582962, 0.0], [11.29658885582962, 0.0], [11.39658885582962, 0.0], [11.496588855829621, 0.0], [11.596588855829621, 0.0], [11.69658885582962, 0.0], [11.796588855829622, 0.0], [11.896588855829622, 0.0], [11.996588855829621, 0.0], [12.096588855829621, 0.0], [12.19658885582962, 0.0], [12.296588855829622, 0.0], [12.396588855829622, 0.0], [12.496588855829621, 0.0], [12.596588855829623, 0.0], [12.696588855829622, 0.0], [12.796588855829622, 0.0], [12.896588855829622, 0.0], [12.996588855829621, 0.0], [13.096588855829623, 0.0], [13.196588855829622, 0.0], [13.296588855829622, 0.0], [13.396588855829622, 0.0], [13.496588855829621, 0.0], [13.596588855829621, 0.0], [13.69658885582962, 0.0], [13.79658885582962, 0.0], [13.89658885582962, 0.0], [13.99658885582962, 0.0], [14.09658885582962, 0.0], [14.196588855829619, 0.0], [14.296588855829619, 0.0], [14.396588855829618, 0.0], [14.496588855829618, 0.0], [14.596588855829618, 0.0], [14.696588855829617, 0.0], [14.794418334342105, 0.0], [14.87510056317618, 0.0], [14.935782792010258, 0.0], [14.976465020844334, 0.0], [14.99714724967841, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541], "velocities": null}}, "time": 1740481184.4636147} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24531571546332662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640228402937997, "gear": 1, "accelerator_pedal_position": 0.24531571546332662, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4636147} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.4836147} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96428012708645, "gear": 1, "accelerator_pedal_position": 0.24531571546332662, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.4836147} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5036147} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964819201227989, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5036147} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5236146} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653575285396664, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5236146} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5436146} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658951099402568, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5436146} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 9.234164838336826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.96376537513474, "accelerator_pedal_position": 0.24795760812532924, "brake_pedal_position": 0.0, "acceleration": 0.042258345043484635, "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": 1740481184.5636146} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.234164838336826, 0.0], [9.39658885582962, 0.0], [9.49658885582962, 0.0], [9.59658885582962, 0.0], [9.69658885582962, 0.0], [9.79658885582962, 0.0], [9.89658885582962, 0.0], [9.99658885582962, 0.0], [10.09658885582962, 0.0], [10.19658885582962, 0.0], [10.29658885582962, 0.0], [10.39658885582962, 0.0], [10.49658885582962, 0.0], [10.59658885582962, 0.0], [10.69658885582962, 0.0], [10.79658885582962, 0.0], [10.89658885582962, 0.0], [10.996588855829621, 0.0], [11.096588855829621, 0.0], [11.19658885582962, 0.0], [11.29658885582962, 0.0], [11.39658885582962, 0.0], [11.496588855829621, 0.0], [11.596588855829621, 0.0], [11.69658885582962, 0.0], [11.796588855829622, 0.0], [11.896588855829622, 0.0], [11.996588855829621, 0.0], [12.096588855829621, 0.0], [12.19658885582962, 0.0], [12.296588855829622, 0.0], [12.396588855829622, 0.0], [12.496588855829621, 0.0], [12.596588855829623, 0.0], [12.696588855829622, 0.0], [12.796588855829622, 0.0], [12.896588855829622, 0.0], [12.996588855829621, 0.0], [13.096588855829623, 0.0], [13.196588855829622, 0.0], [13.296588855829622, 0.0], [13.396588855829622, 0.0], [13.496588855829621, 0.0], [13.596588855829621, 0.0], [13.69658885582962, 0.0], [13.79658885582962, 0.0], [13.89658885582962, 0.0], [13.99658885582962, 0.0], [14.09658885582962, 0.0], [14.196588855829619, 0.0], [14.296588855829619, 0.0], [14.396588855829618, 0.0], [14.496588855829618, 0.0], [14.596588855829618, 0.0], [14.696588855829617, 0.0], [14.794418334342105, 0.0], [14.87510056317618, 0.0], [14.935782792010258, 0.0], [14.976465020844334, 0.0], [14.99714724967841, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541, 5.963299316185541], "velocities": null}}, "time": 1740481184.5636146} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551606658958772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664319463477441, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5636146} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.5736146, "x": 13.340324842116338, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.5836146} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.389323, "x": 15.0, "y": 9.212400000000045, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.5836146} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23750437759140702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669680386793197, "gear": 1, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.5836146} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6036146} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665022739317247, "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": 1740481184.6036146} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6236145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660151135462551, "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": 1740481184.6236145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6436145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2373279863254839, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965528628352518, "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": 1740481184.6436145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 9.340324842116338, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667000854657273, "accelerator_pedal_position": 0.24551606658958772, "brake_pedal_position": 0.0, "acceleration": 0.02679532135924234, "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": 1740481184.6636145} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.340324842116338, 0.0], [9.502884902096557, 0.0], [9.602884902096557, 0.0], [9.702884902096557, 0.0], [9.802884902096556, 0.0], [9.902884902096558, 0.0], [10.002884902096557, 0.0], [10.102884902096557, 0.0], [10.202884902096557, 0.0], [10.302884902096556, 0.0], [10.402884902096556, 0.0], [10.502884902096557, 0.0], [10.602884902096557, 0.0], [10.702884902096557, 0.0], [10.802884902096558, 0.0], [10.902884902096558, 0.0], [11.002884902096557, 0.0], [11.102884902096557, 0.0], [11.202884902096557, 0.0], [11.302884902096558, 0.0], [11.402884902096558, 0.0], [11.502884902096557, 0.0], [11.602884902096559, 0.0], [11.702884902096558, 0.0], [11.802884902096558, 0.0], [11.902884902096558, 0.0], [12.002884902096557, 0.0], [12.102884902096559, 0.0], [12.202884902096558, 0.0], [12.302884902096558, 0.0], [12.40288490209656, 0.0], [12.50288490209656, 0.0], [12.602884902096559, 0.0], [12.702884902096558, 0.0], [12.802884902096558, 0.0], [12.90288490209656, 0.0], [13.00288490209656, 0.0], [13.102884902096559, 0.0], [13.20288490209656, 0.0], [13.30288490209656, 0.0], [13.40288490209656, 0.0], [13.50288490209656, 0.0], [13.602884902096559, 0.0], [13.702884902096558, 0.0], [13.802884902096558, 0.0], [13.902884902096558, 0.0], [14.002884902096557, 0.0], [14.102884902096557, 0.0], [14.202884902096557, 0.0], [14.302884902096556, 0.0], [14.402884902096556, 0.0], [14.502884902096556, 0.0], [14.602884902096555, 0.0], [14.702884902096555, 0.0], [14.800088089226794, 0.0], [14.879511108807481, 0.0], [14.93893412838817, 0.0], [14.97835714796886, 0.0], [14.99778016754955, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542, 5.863299316185541], "velocities": null}}, "time": 1740481184.6636145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23660366612858955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650428173200805, "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": 1740481184.6636145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.6836145, "x": 13.446580471732716, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.6836145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436652840073644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644671707658239, "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": 1740481184.6836145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7036145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648623433028697, "gear": 1, "accelerator_pedal_position": 0.24436652840073644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7036145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7236145} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652366761478108, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7236145} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7436144} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442041344495089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656104903257958, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7436144} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7636144} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.446580471732716, 0.0], [9.609038066616005, 0.0], [9.709038066616005, 0.0], [9.809038066616004, 0.0], [9.909038066616004, 0.0], [10.009038066616004, 0.0], [10.109038066616005, 0.0], [10.209038066616005, 0.0], [10.309038066616004, 0.0], [10.409038066616004, 0.0], [10.509038066616004, 0.0], [10.609038066616005, 0.0], [10.709038066616005, 0.0], [10.809038066616004, 0.0], [10.909038066616004, 0.0], [11.009038066616005, 0.0], [11.109038066616005, 0.0], [11.209038066616005, 0.0], [11.309038066616004, 0.0], [11.409038066616006, 0.0], [11.509038066616005, 0.0], [11.609038066616005, 0.0], [11.709038066616005, 0.0], [11.809038066616004, 0.0], [11.909038066616006, 0.0], [12.009038066616005, 0.0], [12.109038066616005, 0.0], [12.209038066616007, 0.0], [12.309038066616006, 0.0], [12.409038066616006, 0.0], [12.509038066616005, 0.0], [12.609038066616005, 0.0], [12.709038066616007, 0.0], [12.809038066616006, 0.0], [12.909038066616006, 0.0], [13.009038066616007, 0.0], [13.109038066616007, 0.0], [13.209038066616007, 0.0], [13.309038066616006, 0.0], [13.409038066616006, 0.0], [13.509038066616007, 0.0], [13.609038066616007, 0.0], [13.709038066616007, 0.0], [13.809038066616006, 0.0], [13.909038066616006, 0.0], [14.009038066616005, 0.0], [14.109038066616005, 0.0], [14.209038066616005, 0.0], [14.309038066616004, 0.0], [14.409038066616004, 0.0], [14.509038066616004, 0.0], [14.609038066616003, 0.0], [14.709038066616003, 0.0], [14.805552573306247, 0.0], [14.883744959983046, 0.0], [14.941937346659845, 0.0], [14.980129733336646, 0.0], [14.998322120013444, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542, 5.763299316185542], "velocities": null}}, "time": 1740481184.7636144} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686053759900488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965983786499602, "gear": 1, "accelerator_pedal_position": 0.2442041344495089, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.7636144} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 9.446580471732716, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644671707658239, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575253277731415, "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": 1740481184.7836144} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686053759900488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965438933880903, "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": 1740481184.7836144} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.7936144, "x": 13.55276293091197, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8036144} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449448676771709, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96489483629154, "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": 1740481184.8036144} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8236144} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449957491813005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653616836866404, "gear": 1, "accelerator_pedal_position": 0.2449448676771709, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.8236144} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8436143} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.7192879, "x": 15.0, "y": 9.04740000000002, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481184.8436143} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449957491813005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658342421935795, "gear": 1, "accelerator_pedal_position": 0.2449957491813005, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.8436143} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8636143} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.55276293091197, 0.0], [9.71525334545449, 0.0], [9.81525334545449, 0.0], [9.91525334545449, 0.0], [10.01525334545449, 0.0], [10.115253345454489, 0.0], [10.21525334545449, 0.0], [10.31525334545449, 0.0], [10.41525334545449, 0.0], [10.51525334545449, 0.0], [10.61525334545449, 0.0], [10.71525334545449, 0.0], [10.81525334545449, 0.0], [10.91525334545449, 0.0], [11.01525334545449, 0.0], [11.11525334545449, 0.0], [11.21525334545449, 0.0], [11.31525334545449, 0.0], [11.415253345454492, 0.0], [11.515253345454491, 0.0], [11.61525334545449, 0.0], [11.71525334545449, 0.0], [11.81525334545449, 0.0], [11.915253345454492, 0.0], [12.015253345454491, 0.0], [12.11525334545449, 0.0], [12.21525334545449, 0.0], [12.31525334545449, 0.0], [12.415253345454492, 0.0], [12.515253345454491, 0.0], [12.61525334545449, 0.0], [12.715253345454492, 0.0], [12.815253345454492, 0.0], [12.915253345454492, 0.0], [13.015253345454491, 0.0], [13.11525334545449, 0.0], [13.215253345454492, 0.0], [13.315253345454492, 0.0], [13.415253345454492, 0.0], [13.515253345454493, 0.0], [13.615253345454493, 0.0], [13.715253345454492, 0.0], [13.815253345454492, 0.0], [13.915253345454492, 0.0], [14.015253345454491, 0.0], [14.11525334545449, 0.0], [14.21525334545449, 0.0], [14.31525334545449, 0.0], [14.41525334545449, 0.0], [14.51525334545449, 0.0], [14.615253345454489, 0.0], [14.715253345454489, 0.0], [14.810995346361485, 0.0], [14.887944677270587, 0.0], [14.94489400817969, 0.0], [14.981843339088792, 0.0], [14.998792669997894, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542, 5.663299316185542], "velocities": null}}, "time": 1740481184.8636143} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678075496413373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660284151817142, "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": 1740481184.8636143} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 9.55276293091197, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965166790780395, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757380887927306, "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": 1740481184.8836143} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678075496413373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657508770694879, "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": 1740481184.8836143} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481184.9036143, "x": 13.658979062751342, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9036143} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469945435498003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651963778461716, "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": 1740481184.9036143} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9236143} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447016061436341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656321413954142, "gear": 1, "accelerator_pedal_position": 0.24469945435498003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.9236143} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9436142} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2447016061436341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660675699748852, "gear": 1, "accelerator_pedal_position": 0.2447016061436341, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481184.9436142} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9636142} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.658979062751342, 0.0], [9.821470850860203, 0.0], [9.921470850860203, 0.0], [10.021470850860203, 0.0], [10.121470850860204, 0.0], [10.221470850860204, 0.0], [10.321470850860203, 0.0], [10.421470850860203, 0.0], [10.521470850860203, 0.0], [10.621470850860202, 0.0], [10.721470850860204, 0.0], [10.821470850860203, 0.0], [10.921470850860203, 0.0], [11.021470850860203, 0.0], [11.121470850860204, 0.0], [11.221470850860204, 0.0], [11.321470850860203, 0.0], [11.421470850860203, 0.0], [11.521470850860204, 0.0], [11.621470850860204, 0.0], [11.721470850860204, 0.0], [11.821470850860205, 0.0], [11.921470850860205, 0.0], [12.021470850860204, 0.0], [12.121470850860204, 0.0], [12.221470850860204, 0.0], [12.321470850860205, 0.0], [12.421470850860205, 0.0], [12.521470850860204, 0.0], [12.621470850860206, 0.0], [12.721470850860205, 0.0], [12.821470850860205, 0.0], [12.921470850860205, 0.0], [13.021470850860204, 0.0], [13.121470850860206, 0.0], [13.221470850860205, 0.0], [13.321470850860205, 0.0], [13.421470850860207, 0.0], [13.521470850860206, 0.0], [13.621470850860206, 0.0], [13.721470850860205, 0.0], [13.821470850860205, 0.0], [13.921470850860205, 0.0], [14.021470850860204, 0.0], [14.121470850860204, 0.0], [14.221470850860204, 0.0], [14.321470850860203, 0.0], [14.421470850860203, 0.0], [14.521470850860203, 0.0], [14.621470850860202, 0.0], [14.721470850860202, 0.0], [14.81636276833752, 0.0], [14.89206859816548, 0.0], [14.94777442799344, 0.0], [14.983480257821398, 0.0], [14.99918608764936, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543, 5.563299316185542], "velocities": null}}, "time": 1740481184.9636142} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662243166351, "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": 1740481184.9636142} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481184.9836142} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659464309617939, "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": 1740481184.9836142} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 9.658979062751342, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651963778461716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575758593703823, "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": 1740481185.0036142} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367773668482736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653912373714963, "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": 1740481185.0036142} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.0136142, "x": 13.765220848065695, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0236142} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470868187601422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648368131305218, "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": 1740481185.0236142} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0436141} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470268560197111, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652742279222929, "gear": 1, "accelerator_pedal_position": 0.24470868187601422, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.0436141} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.0636141} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.765220848065695, 0.0], [9.927708805625318, 0.0], [10.027708805625318, 0.0], [10.127708805625318, 0.0], [10.22770880562532, 0.0], [10.327708805625319, 0.0], [10.427708805625318, 0.0], [10.527708805625318, 0.0], [10.627708805625318, 0.0], [10.727708805625317, 0.0], [10.827708805625319, 0.0], [10.927708805625318, 0.0], [11.027708805625318, 0.0], [11.127708805625318, 0.0], [11.22770880562532, 0.0], [11.327708805625319, 0.0], [11.427708805625318, 0.0], [11.52770880562532, 0.0], [11.62770880562532, 0.0], [11.72770880562532, 0.0], [11.827708805625319, 0.0], [11.927708805625318, 0.0], [12.02770880562532, 0.0], [12.12770880562532, 0.0], [12.22770880562532, 0.0], [12.327708805625319, 0.0], [12.427708805625318, 0.0], [12.52770880562532, 0.0], [12.62770880562532, 0.0], [12.72770880562532, 0.0], [12.82770880562532, 0.0], [12.92770880562532, 0.0], [13.02770880562532, 0.0], [13.12770880562532, 0.0], [13.22770880562532, 0.0], [13.32770880562532, 0.0], [13.42770880562532, 0.0], [13.52770880562532, 0.0], [13.627708805625321, 0.0], [13.727708805625321, 0.0], [13.82770880562532, 0.0], [13.927708805625322, 0.0], [14.02770880562532, 0.0], [14.127708805625321, 0.0], [14.22770880562532, 0.0], [14.32770880562532, 0.0], [14.427708805625318, 0.0], [14.52770880562532, 0.0], [14.627708805625318, 0.0], [14.72770880562532, 0.0], [14.821670147153604, 0.0], [14.89612838602854, 0.0], [14.950586624903476, 0.0], [14.985044863778413, 0.0], [14.99950310265335, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543, 5.463299316185543], "velocities": null}}, "time": 1740481185.0636141} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659280904344342, "gear": 1, "accelerator_pedal_position": 0.24470268560197111, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.0636141} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.083614} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481185.9393387, "x": 15.0, "y": 8.937400000000002, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.083614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965651000024263, "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": 1740481185.083614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 9.765220848065695, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651139291567084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757014542035844, "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": 1740481185.103614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678680548216083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650973952576756, "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": 1740481185.103614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.123614, "x": 13.871404394617036, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.123614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486897234500515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647735614460378, "gear": 1, "accelerator_pedal_position": 0.24486897234500515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.123614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.143614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482756346310786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650024066343911, "gear": 1, "accelerator_pedal_position": 0.24486897234500515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.143614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.163614} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.871404394617036, 0.0], [10.033865651870814, 0.0], [10.133865651870813, 0.0], [10.233865651870815, 0.0], [10.333865651870815, 0.0], [10.433865651870814, 0.0], [10.533865651870814, 0.0], [10.633865651870813, 0.0], [10.733865651870815, 0.0], [10.833865651870815, 0.0], [10.933865651870814, 0.0], [11.033865651870814, 0.0], [11.133865651870813, 0.0], [11.233865651870815, 0.0], [11.333865651870815, 0.0], [11.433865651870814, 0.0], [11.533865651870814, 0.0], [11.633865651870815, 0.0], [11.733865651870815, 0.0], [11.833865651870815, 0.0], [11.933865651870814, 0.0], [12.033865651870816, 0.0], [12.133865651870815, 0.0], [12.233865651870815, 0.0], [12.333865651870816, 0.0], [12.433865651870816, 0.0], [12.533865651870816, 0.0], [12.633865651870815, 0.0], [12.733865651870815, 0.0], [12.833865651870816, 0.0], [12.933865651870816, 0.0], [13.033865651870816, 0.0], [13.133865651870817, 0.0], [13.233865651870817, 0.0], [13.333865651870816, 0.0], [13.433865651870816, 0.0], [13.533865651870816, 0.0], [13.633865651870817, 0.0], [13.733865651870817, 0.0], [13.833865651870816, 0.0], [13.933865651870816, 0.0], [14.033865651870816, 0.0], [14.133865651870815, 0.0], [14.233865651870815, 0.0], [14.333865651870815, 0.0], [14.433865651870814, 0.0], [14.533865651870814, 0.0], [14.633865651870813, 0.0], [14.733865651870813, 0.0], [14.826832204307097, 0.0], [14.900059073932933, 0.0], [14.953285943558772, 0.0], [14.986512813184609, 0.0], [14.999739682810446, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435, 5.363299316185543], "velocities": null}}, "time": 1740481185.163614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651817435930506, "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": 1740481185.163614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.183614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649092291467711, "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": 1740481185.183614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.203614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643647666734677, "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": 1740481185.203614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 9.871404394617036, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645445575736162, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753068991412964, "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": 1740481185.223614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368517440853366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638210584550599, "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": 1740481185.223614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.233614, "x": 13.977524494593599, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.243614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24529459128401765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632781033284568, "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": 1740481185.243614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.263614} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[9.977524494593599, 0.0], [10.139938050838804, 0.0], [10.239938050838804, 0.0], [10.339938050838803, 0.0], [10.439938050838805, 0.0], [10.539938050838805, 0.0], [10.639938050838804, 0.0], [10.739938050838804, 0.0], [10.839938050838803, 0.0], [10.939938050838805, 0.0], [11.039938050838805, 0.0], [11.139938050838804, 0.0], [11.239938050838804, 0.0], [11.339938050838803, 0.0], [11.439938050838805, 0.0], [11.539938050838805, 0.0], [11.639938050838804, 0.0], [11.739938050838804, 0.0], [11.839938050838805, 0.0], [11.939938050838805, 0.0], [12.039938050838805, 0.0], [12.139938050838804, 0.0], [12.239938050838806, 0.0], [12.339938050838805, 0.0], [12.439938050838805, 0.0], [12.539938050838806, 0.0], [12.639938050838806, 0.0], [12.739938050838806, 0.0], [12.839938050838805, 0.0], [12.939938050838805, 0.0], [13.039938050838806, 0.0], [13.139938050838806, 0.0], [13.239938050838806, 0.0], [13.339938050838807, 0.0], [13.439938050838807, 0.0], [13.539938050838806, 0.0], [13.639938050838806, 0.0], [13.739938050838806, 0.0], [13.839938050838807, 0.0], [13.939938050838807, 0.0], [14.039938050838806, 0.0], [14.139938050838806, 0.0], [14.239938050838806, 0.0], [14.339938050838805, 0.0], [14.439938050838805, 0.0], [14.539938050838805, 0.0], [14.639938050838804, 0.0], [14.739938050838804, 0.0], [14.83184919785012, 0.0], [14.90386158768236, 0.0], [14.9558739775146, 0.0], [14.987886367346839, 0.0], [14.999898757179079, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544, 5.2632993161855435], "velocities": null}}, "time": 1740481185.263614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635263694353584, "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": 1740481185.263614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.283614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632620315786913, "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": 1740481185.283614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.303614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627339050282862, "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": 1740481185.303614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 9.977524494593599, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635494868278938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25746175047705766, "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": 1740481185.323614} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696421815216476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622065097571474, "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": 1740481185.323614} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.3436139, "x": 14.083457424204878, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3436139} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.1588736, "x": 15.0, "y": 8.827399999999985, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.3436139} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607797456257674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616798446414772, "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": 1740481185.3436139} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3636138} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.083457424204878, 0.0], [10.245777784185956, 0.0], [10.345777784185955, 0.0], [10.445777784185957, 0.0], [10.545777784185956, 0.0], [10.645777784185956, 0.0], [10.745777784185956, 0.0], [10.845777784185955, 0.0], [10.945777784185957, 0.0], [11.045777784185956, 0.0], [11.145777784185956, 0.0], [11.245777784185956, 0.0], [11.345777784185955, 0.0], [11.445777784185957, 0.0], [11.545777784185956, 0.0], [11.645777784185956, 0.0], [11.745777784185957, 0.0], [11.845777784185957, 0.0], [11.945777784185957, 0.0], [12.045777784185956, 0.0], [12.145777784185956, 0.0], [12.245777784185957, 0.0], [12.345777784185957, 0.0], [12.445777784185957, 0.0], [12.545777784185958, 0.0], [12.645777784185958, 0.0], [12.745777784185957, 0.0], [12.845777784185957, 0.0], [12.945777784185957, 0.0], [13.045777784185958, 0.0], [13.145777784185958, 0.0], [13.245777784185957, 0.0], [13.345777784185959, 0.0], [13.445777784185958, 0.0], [13.545777784185958, 0.0], [13.645777784185958, 0.0], [13.745777784185957, 0.0], [13.845777784185959, 0.0], [13.945777784185958, 0.0], [14.045777784185958, 0.0], [14.14577778418596, 0.0], [14.245777784185957, 0.0], [14.345777784185959, 0.0], [14.445777784185957, 0.0], [14.545777784185958, 0.0], [14.645777784185956, 0.0], [14.745777784185957, 0.0], [14.836604400242384, 0.0], [14.907448843405193, 0.0], [14.958293286568, 0.0], [14.98913772973081, 0.0], [14.99998217289362, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445, 5.063299316185544, 5.163299316185544], "velocities": null}}, "time": 1740481185.3636138} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622927337469835, "gear": 1, "accelerator_pedal_position": 0.24607797456257674, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.3636138} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.3836138} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617919189507705, "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": 1740481185.3836138} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4036138} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612917974262055, "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": 1740481185.4036138} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4236138} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607923681135871, "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": 1740481185.4236138} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 10.083457424204878, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616798446414772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733227346797044, "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": 1740481185.4436138} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23717204758477234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9602936299550964, "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": 1740481185.4436138} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.4536138, "x": 14.189210400288738, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.4636137} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.189210400288738, 0.0], [10.351445422871805, 0.0], [10.451445422871805, 0.0], [10.551445422871804, 0.0], [10.651445422871804, 0.0], [10.751445422871804, 0.0], [10.851445422871805, 0.0], [10.951445422871805, 0.0], [11.051445422871804, 0.0], [11.151445422871804, 0.0], [11.251445422871804, 0.0], [11.351445422871805, 0.0], [11.451445422871805, 0.0], [11.551445422871804, 0.0], [11.651445422871804, 0.0], [11.751445422871804, 0.0], [11.851445422871805, 0.0], [11.951445422871805, 0.0], [12.051445422871804, 0.0], [12.151445422871806, 0.0], [12.251445422871805, 0.0], [12.351445422871805, 0.0], [12.451445422871805, 0.0], [12.551445422871804, 0.0], [12.651445422871806, 0.0], [12.751445422871805, 0.0], [12.851445422871805, 0.0], [12.951445422871807, 0.0], [13.051445422871806, 0.0], [13.151445422871806, 0.0], [13.251445422871805, 0.0], [13.351445422871805, 0.0], [13.451445422871807, 0.0], [13.551445422871806, 0.0], [13.651445422871806, 0.0], [13.751445422871807, 0.0], [13.851445422871807, 0.0], [13.951445422871807, 0.0], [14.051445422871806, 0.0], [14.151445422871806, 0.0], [14.251445422871807, 0.0], [14.351445422871807, 0.0], [14.451445422871807, 0.0], [14.551445422871806, 0.0], [14.651445422871806, 0.0], [14.751443333624527, 0.0], [14.841154249050167, 0.0], [14.910865164475805, 0.0], [14.960576079901443, 0.0], [14.990286995327082, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545, 4.9632993161855445], "velocities": null}}, "time": 1740481185.4636137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478589181720773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9595468163219901, "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": 1740481185.4636137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.4836137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599661522903126, "gear": 1, "accelerator_pedal_position": 0.2478589181720773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.4836137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5036137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607938415649502, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5036137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5236137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620332284122753, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5236137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 10.189210400288738, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600445197285938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721908078503875, "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": 1740481185.5436137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777799138870837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624457854666065, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5436137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.5636137, "x": 14.2949173179372, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.5636137} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.2949173179372, 0.0], [10.457317240948036, 0.0], [10.557317240948036, 0.0], [10.657317240948036, 0.0], [10.757317240948035, 0.0], [10.857317240948035, 0.0], [10.957317240948036, 0.0], [11.057317240948036, 0.0], [11.157317240948036, 0.0], [11.257317240948035, 0.0], [11.357317240948035, 0.0], [11.457317240948036, 0.0], [11.557317240948036, 0.0], [11.657317240948036, 0.0], [11.757317240948037, 0.0], [11.857317240948037, 0.0], [11.957317240948036, 0.0], [12.057317240948036, 0.0], [12.157317240948036, 0.0], [12.257317240948037, 0.0], [12.357317240948037, 0.0], [12.457317240948036, 0.0], [12.557317240948038, 0.0], [12.657317240948037, 0.0], [12.757317240948037, 0.0], [12.857317240948037, 0.0], [12.957317240948036, 0.0], [13.057317240948038, 0.0], [13.157317240948037, 0.0], [13.257317240948037, 0.0], [13.357317240948039, 0.0], [13.457317240948038, 0.0], [13.557317240948038, 0.0], [13.657317240948037, 0.0], [13.757317240948037, 0.0], [13.857317240948039, 0.0], [13.957317240948038, 0.0], [14.057317240948038, 0.0], [14.15731724094804, 0.0], [14.257317240948039, 0.0], [14.357317240948039, 0.0], [14.457317240948038, 0.0], [14.557317240948038, 0.0], [14.657317240948037, 0.0], [14.757263698932945, 0.0], [14.845800250743338, 0.0], [14.91433680255373, 0.0], [14.962873354364124, 0.0], [14.991409906174516, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545], "velocities": null}}, "time": 1740481185.5636137} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24564664555055848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9636817432391954, "gear": 1, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5636137} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.5836136} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.379688, "x": 15.0, "y": 8.717399999999968, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.5836136} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639599494642604, "gear": 1, "accelerator_pedal_position": 0.24564664555055848, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.5836136} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6036136} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964535919772671, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6036136} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6236136} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651110922028504, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6236136} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6436136} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656854677277973, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6436136} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 10.2949173179372, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9632700427162787, "accelerator_pedal_position": 0.24777799138870837, "brake_pedal_position": 0.0, "acceleration": 0.04117005229166715, "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": 1740481185.6636136} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.2949173179372, 0.0], [10.457317240948036, 0.0], [10.557317240948036, 0.0], [10.657317240948036, 0.0], [10.757317240948035, 0.0], [10.857317240948035, 0.0], [10.957317240948036, 0.0], [11.057317240948036, 0.0], [11.157317240948036, 0.0], [11.257317240948035, 0.0], [11.357317240948035, 0.0], [11.457317240948036, 0.0], [11.557317240948036, 0.0], [11.657317240948036, 0.0], [11.757317240948037, 0.0], [11.857317240948037, 0.0], [11.957317240948036, 0.0], [12.057317240948036, 0.0], [12.157317240948036, 0.0], [12.257317240948037, 0.0], [12.357317240948037, 0.0], [12.457317240948036, 0.0], [12.557317240948038, 0.0], [12.657317240948037, 0.0], [12.757317240948037, 0.0], [12.857317240948037, 0.0], [12.957317240948036, 0.0], [13.057317240948038, 0.0], [13.157317240948037, 0.0], [13.257317240948037, 0.0], [13.357317240948039, 0.0], [13.457317240948038, 0.0], [13.557317240948038, 0.0], [13.657317240948037, 0.0], [13.757317240948037, 0.0], [13.857317240948039, 0.0], [13.957317240948038, 0.0], [14.057317240948038, 0.0], [14.15731724094804, 0.0], [14.257317240948039, 0.0], [14.357317240948039, 0.0], [14.457317240948038, 0.0], [14.557317240948038, 0.0], [14.657317240948037, 0.0], [14.757263698932945, 0.0], [14.845800250743338, 0.0], [14.91433680255373, 0.0], [14.962873354364124, 0.0], [14.991409906174516, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545, 4.863299316185545], "velocities": null}}, "time": 1740481185.6636136} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458077888476316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665455389443763, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6636136} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.6736135, "x": 14.40104677432711, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.6836135} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23751505135370596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668318319499958, "gear": 1, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.6836135} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7036135} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663675897743825, "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": 1740481185.7036135} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7236135} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656420155504944, "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": 1740481185.7236135} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7436135} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23735271376890008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654004927030558, "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": 1740481185.7436135} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 10.40104677432711, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9665455389443763, "accelerator_pedal_position": 0.2458077888476316, "brake_pedal_position": 0.0, "acceleration": 0.028629300561945847, "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": 1740481185.7636135} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.40104677432711, 0.0], [10.563599956536308, 0.0], [10.663599956536308, 0.0], [10.763599956536307, 0.0], [10.863599956536307, 0.0], [10.963599956536306, 0.0], [11.063599956536308, 0.0], [11.163599956536308, 0.0], [11.263599956536307, 0.0], [11.363599956536307, 0.0], [11.463599956536306, 0.0], [11.563599956536308, 0.0], [11.663599956536308, 0.0], [11.763599956536307, 0.0], [11.863599956536307, 0.0], [11.963599956536306, 0.0], [12.063599956536308, 0.0], [12.163599956536308, 0.0], [12.263599956536307, 0.0], [12.363599956536309, 0.0], [12.463599956536308, 0.0], [12.563599956536308, 0.0], [12.663599956536308, 0.0], [12.763599956536307, 0.0], [12.863599956536309, 0.0], [12.963599956536308, 0.0], [13.063599956536308, 0.0], [13.16359995653631, 0.0], [13.263599956536309, 0.0], [13.363599956536309, 0.0], [13.463599956536308, 0.0], [13.563599956536308, 0.0], [13.66359995653631, 0.0], [13.763599956536309, 0.0], [13.863599956536309, 0.0], [13.96359995653631, 0.0], [14.06359995653631, 0.0], [14.16359995653631, 0.0], [14.263599956536309, 0.0], [14.363599956536309, 0.0], [14.46359995653631, 0.0], [14.56359995653631, 0.0], [14.66359995653631, 0.0], [14.76341499771852, 0.0], [14.850695006411257, 0.0], [14.917975015103995, 0.0], [14.965255023796733, 0.0], [14.99253503248947, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546, 4.763299316185545], "velocities": null}}, "time": 1740481185.7636135} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23662165476017788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646312368651588, "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": 1740481185.7636135} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.7836134, "x": 14.507287821250857, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.7836134} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24444443481646072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643447233269238, "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": 1740481185.7836134} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8036134} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964749800421164, "gear": 1, "accelerator_pedal_position": 0.24444443481646072, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8036134} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8236134} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651343158286897, "gear": 1, "accelerator_pedal_position": 0.2442843753461832, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8236134} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8436134} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.7099507, "x": 15.0, "y": 8.552399999999942, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481185.8436134} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442843753461832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655182984766596, "gear": 1, "accelerator_pedal_position": 0.2442843753461832, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.8436134} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8636134} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.507287821250857, 0.0], [10.669739604933314, 0.0], [10.769739604933314, 0.0], [10.869739604933313, 0.0], [10.969739604933313, 0.0], [11.069739604933314, 0.0], [11.169739604933314, 0.0], [11.269739604933314, 0.0], [11.369739604933313, 0.0], [11.469739604933313, 0.0], [11.569739604933314, 0.0], [11.669739604933314, 0.0], [11.769739604933314, 0.0], [11.869739604933313, 0.0], [11.969739604933313, 0.0], [12.069739604933314, 0.0], [12.169739604933314, 0.0], [12.269739604933314, 0.0], [12.369739604933315, 0.0], [12.469739604933315, 0.0], [12.569739604933314, 0.0], [12.669739604933314, 0.0], [12.769739604933314, 0.0], [12.869739604933315, 0.0], [12.969739604933315, 0.0], [13.069739604933314, 0.0], [13.169739604933316, 0.0], [13.269739604933315, 0.0], [13.369739604933315, 0.0], [13.469739604933315, 0.0], [13.569739604933314, 0.0], [13.669739604933316, 0.0], [13.769739604933315, 0.0], [13.869739604933315, 0.0], [13.969739604933316, 0.0], [14.069739604933316, 0.0], [14.169739604933316, 0.0], [14.269739604933315, 0.0], [14.369739604933315, 0.0], [14.469739604933316, 0.0], [14.569739604933316, 0.0], [14.669739604933316, 0.0], [14.769349952930392, 0.0], [14.85540203194373, 0.0], [14.921454110957065, 0.0], [14.967506189970402, 0.0], [14.99355826898374, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546, 4.663299316185546], "velocities": null}}, "time": 1740481185.8636134} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687443539849587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656301537632771, "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": 1740481185.8636134} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 10.507287821250857, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9643447233269238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25751684362043104, "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": 1740481185.8836133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23687443539849587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653587467394158, "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": 1740481185.8836133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481185.8936133, "x": 14.613459458334486, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9036133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450056531733539, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648164968823169, "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": 1740481185.9036133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9236133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24505967537036713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652910483715643, "gear": 1, "accelerator_pedal_position": 0.2450056531733539, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.9236133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9436133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24505967537036713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657716927620865, "gear": 1, "accelerator_pedal_position": 0.24505967537036713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481185.9436133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9636133} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.613459458334486, 0.0], [10.7759461873779, 0.0], [10.875946187377899, 0.0], [10.975946187377899, 0.0], [11.075946187377898, 0.0], [11.1759461873779, 0.0], [11.2759461873779, 0.0], [11.375946187377899, 0.0], [11.475946187377899, 0.0], [11.575946187377898, 0.0], [11.675946187377898, 0.0], [11.7759461873779, 0.0], [11.875946187377899, 0.0], [11.975946187377899, 0.0], [12.075946187377898, 0.0], [12.1759461873779, 0.0], [12.2759461873779, 0.0], [12.375946187377899, 0.0], [12.475946187377899, 0.0], [12.5759461873779, 0.0], [12.6759461873779, 0.0], [12.7759461873779, 0.0], [12.875946187377899, 0.0], [12.9759461873779, 0.0], [13.0759461873779, 0.0], [13.1759461873779, 0.0], [13.275946187377901, 0.0], [13.3759461873779, 0.0], [13.4759461873779, 0.0], [13.5759461873779, 0.0], [13.6759461873779, 0.0], [13.775946187377901, 0.0], [13.8759461873779, 0.0], [13.9759461873779, 0.0], [14.075946187377902, 0.0], [14.175946187377901, 0.0], [14.275946187377901, 0.0], [14.3759461873779, 0.0], [14.4759461873779, 0.0], [14.575946187377902, 0.0], [14.675946187377901, 0.0], [14.775272982738452, 0.0], [14.860083745262871, 0.0], [14.924894507787291, 0.0], [14.96970527031171, 0.0], [14.994516032836131, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546, 4.563299316185546], "velocities": null}}, "time": 1740481185.9636133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678982599969858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659745451453964, "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": 1740481185.9636133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 10.613459458334486, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9650875278274614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575683157550543, "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": 1740481185.9836133} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678982599969858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656976113156179, "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": 1740481185.9836133} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.0036132, "x": 14.719668543701626, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0036132} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24473830452889292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651443193920323, "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": 1740481186.0036132} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0236132} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24474243482843702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965805383894825, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0236132} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0436132} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24474243482843702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660256053756988, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0436132} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0636132} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.719668543701626, 0.0], [10.882157914240075, 0.0], [10.982157914240075, 0.0], [11.082157914240074, 0.0], [11.182157914240076, 0.0], [11.282157914240075, 0.0], [11.382157914240075, 0.0], [11.482157914240075, 0.0], [11.582157914240074, 0.0], [11.682157914240076, 0.0], [11.782157914240075, 0.0], [11.882157914240075, 0.0], [11.982157914240075, 0.0], [12.082157914240074, 0.0], [12.182157914240076, 0.0], [12.282157914240075, 0.0], [12.382157914240075, 0.0], [12.482157914240076, 0.0], [12.582157914240076, 0.0], [12.682157914240076, 0.0], [12.782157914240075, 0.0], [12.882157914240075, 0.0], [12.982157914240076, 0.0], [13.082157914240076, 0.0], [13.182157914240076, 0.0], [13.282157914240077, 0.0], [13.382157914240077, 0.0], [13.482157914240076, 0.0], [13.582157914240076, 0.0], [13.682157914240076, 0.0], [13.782157914240077, 0.0], [13.882157914240077, 0.0], [13.982157914240076, 0.0], [14.082157914240078, 0.0], [14.182157914240078, 0.0], [14.282157914240077, 0.0], [14.382157914240077, 0.0], [14.482157914240076, 0.0], [14.582157914240078, 0.0], [14.682157914240078, 0.0], [14.781123782791806, 0.0], [14.86469219994379, 0.0], [14.928260617095773, 0.0], [14.971829034247758, 0.0], [14.995397451399743, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547, 4.463299316185546], "velocities": null}}, "time": 1740481186.0636132} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966685354279933, "gear": 1, "accelerator_pedal_position": 0.24474243482843702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.0636132} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.0836132} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481186.9288304, "x": 15.0, "y": 8.442399999999925, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.0836132} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664075215125854, "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": 1740481186.0836132} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 10.719668543701626, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651443193920323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575722515421487, "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": 1740481186.1036131} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678332747536493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965852433701034, "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": 1740481186.1036131} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.1136131, "x": 14.825925658849366, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.123613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.244618869032256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652981151945497, "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": 1740481186.123613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.143613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465020425973907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657236680957294, "gear": 1, "accelerator_pedal_position": 0.244618869032256, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.143613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.163613} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.825925658849366, 0.0], [10.98843492947157, 0.0], [11.08843492947157, 0.0], [11.188434929471569, 0.0], [11.288434929471569, 0.0], [11.388434929471568, 0.0], [11.48843492947157, 0.0], [11.58843492947157, 0.0], [11.688434929471569, 0.0], [11.788434929471569, 0.0], [11.888434929471568, 0.0], [11.98843492947157, 0.0], [12.08843492947157, 0.0], [12.188434929471569, 0.0], [12.288434929471569, 0.0], [12.38843492947157, 0.0], [12.48843492947157, 0.0], [12.58843492947157, 0.0], [12.688434929471569, 0.0], [12.78843492947157, 0.0], [12.88843492947157, 0.0], [12.98843492947157, 0.0], [13.088434929471571, 0.0], [13.18843492947157, 0.0], [13.28843492947157, 0.0], [13.38843492947157, 0.0], [13.48843492947157, 0.0], [13.588434929471571, 0.0], [13.68843492947157, 0.0], [13.78843492947157, 0.0], [13.888434929471572, 0.0], [13.988434929471572, 0.0], [14.088434929471571, 0.0], [14.18843492947157, 0.0], [14.28843492947157, 0.0], [14.388434929471572, 0.0], [14.488434929471572, 0.0], [14.588434929471571, 0.0], [14.688434929471573, 0.0], [14.786957685668087, 0.0], [14.869270699773772, 0.0], [14.931583713879458, 0.0], [14.973896727985144, 0.0], [14.99620974209083, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547, 4.363299316185547], "velocities": null}}, "time": 1740481186.163613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661525468258256, "gear": 1, "accelerator_pedal_position": 0.24465020425973907, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.163613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.183613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655916346181515, "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": 1740481186.183613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 10.825925658849366, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9655751783590252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576021131685819, "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": 1740481186.203613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367338880610615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965031499729521, "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": 1740481186.203613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.223613, "x": 14.932133228619435, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.223613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24473142903873404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644721409572589, "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": 1740481186.223613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.243613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465120806028273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649129033853086, "gear": 1, "accelerator_pedal_position": 0.24473142903873404, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.243613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.263613} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[10.932133228619435, 0.0], [11.094591058959539, 0.0], [11.19459105895954, 0.0], [11.29459105895954, 0.0], [11.39459105895954, 0.0], [11.49459105895954, 0.0], [11.594591058959539, 0.0], [11.694591058959539, 0.0], [11.79459105895954, 0.0], [11.89459105895954, 0.0], [11.99459105895954, 0.0], [12.094591058959539, 0.0], [12.194591058959539, 0.0], [12.29459105895954, 0.0], [12.39459105895954, 0.0], [12.49459105895954, 0.0], [12.59459105895954, 0.0], [12.69459105895954, 0.0], [12.79459105895954, 0.0], [12.89459105895954, 0.0], [12.99459105895954, 0.0], [13.09459105895954, 0.0], [13.19459105895954, 0.0], [13.29459105895954, 0.0], [13.394591058959541, 0.0], [13.494591058959541, 0.0], [13.59459105895954, 0.0], [13.69459105895954, 0.0], [13.79459105895954, 0.0], [13.894591058959541, 0.0], [13.994591058959541, 0.0], [14.09459105895954, 0.0], [14.194591058959542, 0.0], [14.294591058959542, 0.0], [14.394591058959541, 0.0], [14.494591058959541, 0.0], [14.59459105895954, 0.0], [14.694591058959542, 0.0], [14.79260269642041, 0.0], [14.8736844846285, 0.0], [14.934766272836592, 0.0], [14.975848061044683, 0.0], [14.996929849252776, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547, 4.263299316185547], "velocities": null}}, "time": 1740481186.263613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653430310154697, "gear": 1, "accelerator_pedal_position": 0.24465120806028273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.263613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.283613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647989957692692, "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": 1740481186.283613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.303613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642557142805238, "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": 1740481186.303613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 10.932133228619435, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644721409572589, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752567215468974, "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": 1740481186.323613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368599730679965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963713185386886, "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": 1740481186.323613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.333613, "x": 15.03824222008845, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.343613} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.1501093, "x": 15.0, "y": 8.332399999999907, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.343613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24534451162615734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631714079281093, "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": 1740481186.343613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.363613} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.03824222008845, 0.0], [11.200650554583278, 0.0], [11.300650554583278, 0.0], [11.400650554583278, 0.0], [11.500650554583277, 0.0], [11.600650554583279, 0.0], [11.700650554583278, 0.0], [11.800650554583278, 0.0], [11.900650554583278, 0.0], [12.000650554583277, 0.0], [12.100650554583279, 0.0], [12.200650554583278, 0.0], [12.300650554583278, 0.0], [12.400650554583278, 0.0], [12.500650554583277, 0.0], [12.600650554583279, 0.0], [12.700650554583278, 0.0], [12.800650554583278, 0.0], [12.90065055458328, 0.0], [13.00065055458328, 0.0], [13.100650554583279, 0.0], [13.20065055458328, 0.0], [13.300650554583278, 0.0], [13.40065055458328, 0.0], [13.50065055458328, 0.0], [13.600650554583279, 0.0], [13.70065055458328, 0.0], [13.80065055458328, 0.0], [13.90065055458328, 0.0], [14.000650554583281, 0.0], [14.100650554583279, 0.0], [14.20065055458328, 0.0], [14.30065055458328, 0.0], [14.40065055458328, 0.0], [14.500650554583281, 0.0], [14.60065055458328, 0.0], [14.70065055458328, 0.0], [14.798085075903685, 0.0], [14.87795496498703, 0.0], [14.937824854070374, 0.0], [14.977694743153718, 0.0], [14.997564632237061, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548, 4.163299316185547], "velocities": null}}, "time": 1740481186.363613} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9636905807737509, "gear": 1, "accelerator_pedal_position": 0.24534451162615734, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.363613} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.3836129} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963163366371323, "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": 1740481186.3836129} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.4036129} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962636882075597, "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": 1740481186.4036129} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 11.03824222008845, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9634422028005735, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574543189214009, "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": 1740481186.4236128} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697626734694174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618485221284343, "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": 1740481186.4236128} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.4436128, "x": 15.144164180106086, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4436128} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613803542659557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615860993186018, "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": 1740481186.4436128} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4636128} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.144164180106086, 0.0], [11.306479744447925, 0.0], [11.406479744447925, 0.0], [11.506479744447924, 0.0], [11.606479744447924, 0.0], [11.706479744447925, 0.0], [11.806479744447925, 0.0], [11.906479744447925, 0.0], [12.006479744447924, 0.0], [12.106479744447924, 0.0], [12.206479744447925, 0.0], [12.306479744447925, 0.0], [12.406479744447925, 0.0], [12.506479744447924, 0.0], [12.606479744447924, 0.0], [12.706479744447925, 0.0], [12.806479744447925, 0.0], [12.906479744447925, 0.0], [13.006479744447926, 0.0], [13.106479744447926, 0.0], [13.206479744447925, 0.0], [13.306479744447927, 0.0], [13.406479744447926, 0.0], [13.506479744447926, 0.0], [13.606479744447926, 0.0], [13.706479744447925, 0.0], [13.806479744447927, 0.0], [13.906479744447926, 0.0], [14.006479744447926, 0.0], [14.106479744447928, 0.0], [14.206479744447927, 0.0], [14.306479744447927, 0.0], [14.406479744447926, 0.0], [14.506479744447926, 0.0], [14.606479744447928, 0.0], [14.706479744447927, 0.0], [14.803289782915025, 0.0], [14.881993834025439, 0.0], [14.940697885135853, 0.0], [14.979401936246267, 0.0], [14.998105987356682, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476, 4.063299316185548], "velocities": null}}, "time": 1740481186.4636128} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622066231986267, "gear": 1, "accelerator_pedal_position": 0.24613803542659557, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.4636128} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.4836128} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617072147285541, "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": 1740481186.4836128} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5036128} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612084975663907, "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": 1740481186.5036128} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5236127} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607104706557378, "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": 1740481186.5236127} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 11.144164180106086, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9615860993186018, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25732578322995775, "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": 1740481186.5436127} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23718234808878236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960213132942072, "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": 1740481186.5436127} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.5536127, "x": 15.24990782233614, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.5636127} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.24990782233614, 0.0], [11.412138589542941, 0.0], [11.512138589542943, 0.0], [11.612138589542942, 0.0], [11.712138589542942, 0.0], [11.812138589542942, 0.0], [11.912138589542941, 0.0], [12.012138589542943, 0.0], [12.112138589542942, 0.0], [12.212138589542942, 0.0], [12.312138589542942, 0.0], [12.412138589542941, 0.0], [12.512138589542943, 0.0], [12.612138589542942, 0.0], [12.712138589542942, 0.0], [12.812138589542942, 0.0], [12.912138589542943, 0.0], [13.012138589542943, 0.0], [13.112138589542942, 0.0], [13.212138589542942, 0.0], [13.312138589542943, 0.0], [13.412138589542943, 0.0], [13.512138589542943, 0.0], [13.612138589542942, 0.0], [13.712138589542942, 0.0], [13.812138589542943, 0.0], [13.912138589542943, 0.0], [14.012138589542943, 0.0], [14.112138589542944, 0.0], [14.212138589542944, 0.0], [14.312138589542943, 0.0], [14.412138589542943, 0.0], [14.512138589542943, 0.0], [14.612138589542944, 0.0], [14.712138589542944, 0.0], [14.808277385232557, 0.0], [14.885849667323969, 0.0], [14.94342194941538, 0.0], [14.980994231506791, 0.0], [14.998566513598202, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476, 3.9632993161855476], "velocities": null}}, "time": 1740481186.5636127} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24790843660405454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959716483372741, "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": 1740481186.5636127} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.5836127} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.4792216, "x": 15.0, "y": 8.167399999999882, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.5836127} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605608180843718, "gear": 1, "accelerator_pedal_position": 0.24790843660405454, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.5836127} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6036127} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613939688644598, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6036127} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6236126} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622259665679913, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6236126} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 11.24990782233614, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9599647222050824, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25721355878903696, "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": 1740481186.6436126} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24782828359435752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963056812514026, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6436126} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.6636126, "x": 15.355667407889465, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.6636126} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.355667407889465, 0.0], [11.518097267873063, 0.0], [11.618097267873063, 0.0], [11.718097267873063, 0.0], [11.818097267873062, 0.0], [11.918097267873062, 0.0], [12.018097267873063, 0.0], [12.118097267873063, 0.0], [12.218097267873063, 0.0], [12.318097267873062, 0.0], [12.418097267873062, 0.0], [12.518097267873063, 0.0], [12.618097267873063, 0.0], [12.718097267873063, 0.0], [12.818097267873062, 0.0], [12.918097267873064, 0.0], [13.018097267873063, 0.0], [13.118097267873063, 0.0], [13.218097267873063, 0.0], [13.318097267873064, 0.0], [13.418097267873064, 0.0], [13.518097267873063, 0.0], [13.618097267873063, 0.0], [13.718097267873063, 0.0], [13.818097267873064, 0.0], [13.918097267873064, 0.0], [14.018097267873063, 0.0], [14.118097267873065, 0.0], [14.218097267873064, 0.0], [14.318097267873064, 0.0], [14.418097267873064, 0.0], [14.518097267873063, 0.0], [14.618097267873065, 0.0], [14.718097267873064, 0.0], [14.81346002998129, 0.0], [14.889840576406677, 0.0], [14.946221122832062, 0.0], [14.98260166925745, 0.0], [14.998982215682837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476], "velocities": null}}, "time": 1740481186.6636126} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452486126288212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638865080209473, "gear": 1, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6636126} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.6836126} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643927072426246, "gear": 1, "accelerator_pedal_position": 0.2452486126288212, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.6836126} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7036126} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649227658342332, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7036126} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7236125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654520900636444, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7236125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7436125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659806808362352, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7436125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 11.355667407889465, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9638865080209473, "accelerator_pedal_position": 0.24782828359435752, "brake_pedal_position": 0.0, "acceleration": 0.04144167506023888, "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": 1740481186.7636125} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.355667407889465, 0.0], [11.518097267873063, 0.0], [11.618097267873063, 0.0], [11.718097267873063, 0.0], [11.818097267873062, 0.0], [11.918097267873062, 0.0], [12.018097267873063, 0.0], [12.118097267873063, 0.0], [12.218097267873063, 0.0], [12.318097267873062, 0.0], [12.418097267873062, 0.0], [12.518097267873063, 0.0], [12.618097267873063, 0.0], [12.718097267873063, 0.0], [12.818097267873062, 0.0], [12.918097267873064, 0.0], [13.018097267873063, 0.0], [13.118097267873063, 0.0], [13.218097267873063, 0.0], [13.318097267873064, 0.0], [13.418097267873064, 0.0], [13.518097267873063, 0.0], [13.618097267873063, 0.0], [13.718097267873063, 0.0], [13.818097267873064, 0.0], [13.918097267873064, 0.0], [14.018097267873063, 0.0], [14.118097267873065, 0.0], [14.218097267873064, 0.0], [14.318097267873064, 0.0], [14.418097267873064, 0.0], [14.518097267873063, 0.0], [14.618097267873065, 0.0], [14.718097267873064, 0.0], [14.81346002998129, 0.0], [14.889840576406677, 0.0], [14.946221122832062, 0.0], [14.98260166925745, 0.0], [14.998982215682837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475, 3.8632993161855476], "velocities": null}}, "time": 1740481186.7636125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245445165291126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667721937421538, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7636125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.7736125, "x": 15.46183830301949, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.7836125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23749380367220946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670356656285188, "gear": 1, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.7836125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8036125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665684858498065, "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": 1740481186.8036125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8236125} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660797920233782, "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": 1740481186.8236125} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8436124} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.6989007, "x": 15.0, "y": 8.057399999999864, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481186.8436124} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731644900125567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655917755267014, "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": 1740481186.8436124} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 11.46183830301949, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9667721937421538, "accelerator_pedal_position": 0.245445165291126, "brake_pedal_position": 0.0, "acceleration": 0.026347188636499597, "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": 1740481186.8636124} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.46183830301949, 0.0], [11.624401561132563, 0.0], [11.724401561132563, 0.0], [11.824401561132563, 0.0], [11.924401561132564, 0.0], [12.024401561132564, 0.0], [12.124401561132563, 0.0], [12.224401561132563, 0.0], [12.324401561132563, 0.0], [12.424401561132562, 0.0], [12.524401561132564, 0.0], [12.624401561132563, 0.0], [12.724401561132563, 0.0], [12.824401561132564, 0.0], [12.924401561132564, 0.0], [13.024401561132564, 0.0], [13.124401561132563, 0.0], [13.224401561132563, 0.0], [13.324401561132564, 0.0], [13.424401561132564, 0.0], [13.524401561132564, 0.0], [13.624401561132563, 0.0], [13.724401561132563, 0.0], [13.824401561132564, 0.0], [13.924401561132564, 0.0], [14.024401561132564, 0.0], [14.124401561132565, 0.0], [14.224401561132565, 0.0], [14.324401561132564, 0.0], [14.424401561132564, 0.0], [14.524401561132564, 0.0], [14.624401561132565, 0.0], [14.724401561132565, 0.0], [14.818865968833602, 0.0], [14.89398565660709, 0.0], [14.949105344380577, 0.0], [14.984225032154063, 0.0], [14.99934471992755, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474, 3.7632993161855475], "velocities": null}}, "time": 1740481186.8636124} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23659526232180972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651044353257656, "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": 1740481186.8636124} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.8836124, "x": 15.56810108363452, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.8836124} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24432949505026547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645276532884008, "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": 1740481186.8836124} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9036124} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649181144705492, "gear": 1, "accelerator_pedal_position": 0.24432949505026547, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9036124} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9236124} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652876368268928, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9236124} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9436123} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24416625558886068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656566471738772, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9436123} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9636123} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.56810108363452, 0.0], [11.730561541565914, 0.0], [11.830561541565913, 0.0], [11.930561541565913, 0.0], [12.030561541565913, 0.0], [12.130561541565914, 0.0], [12.230561541565914, 0.0], [12.330561541565913, 0.0], [12.430561541565913, 0.0], [12.530561541565913, 0.0], [12.630561541565914, 0.0], [12.730561541565914, 0.0], [12.830561541565913, 0.0], [12.930561541565913, 0.0], [13.030561541565914, 0.0], [13.130561541565914, 0.0], [13.230561541565914, 0.0], [13.330561541565913, 0.0], [13.430561541565915, 0.0], [13.530561541565914, 0.0], [13.630561541565914, 0.0], [13.730561541565914, 0.0], [13.830561541565913, 0.0], [13.930561541565915, 0.0], [14.030561541565914, 0.0], [14.130561541565914, 0.0], [14.230561541565915, 0.0], [14.330561541565915, 0.0], [14.430561541565915, 0.0], [14.530561541565914, 0.0], [14.630561541565914, 0.0], [14.730561541565915, 0.0], [14.824071379586439, 0.0], [14.897959071273256, 0.0], [14.951846762960074, 0.0], [14.98573445464689, 0.0], [14.999622146333706, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473, 3.6632993161855474], "velocities": null}}, "time": 1740481186.9636123} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685366559817847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660251461664932, "gear": 1, "accelerator_pedal_position": 0.24416625558886068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481186.9636123} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 11.56810108363452, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645276532884008, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25752951860400036, "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": 1740481186.9836123} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685366559817847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654793775264102, "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": 1740481186.9836123} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481186.9936123, "x": 15.674288941638826, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0036123} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24491471372310722, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649343651939127, "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": 1740481187.0036123} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0236123} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24496410457794013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965397389882291, "gear": 1, "accelerator_pedal_position": 0.24491471372310722, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0236123} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0436122} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24496410457794013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658659447059241, "gear": 1, "accelerator_pedal_position": 0.24496410457794013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0436122} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0636122} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.674288941638826, 0.0], [11.836781212241668, 0.0], [11.936781212241668, 0.0], [12.036781212241667, 0.0], [12.136781212241667, 0.0], [12.236781212241667, 0.0], [12.336781212241668, 0.0], [12.436781212241668, 0.0], [12.536781212241667, 0.0], [12.636781212241667, 0.0], [12.736781212241667, 0.0], [12.836781212241668, 0.0], [12.936781212241668, 0.0], [13.036781212241667, 0.0], [13.136781212241669, 0.0], [13.236781212241668, 0.0], [13.336781212241668, 0.0], [13.436781212241668, 0.0], [13.536781212241667, 0.0], [13.636781212241669, 0.0], [13.736781212241668, 0.0], [13.836781212241668, 0.0], [13.93678121224167, 0.0], [14.036781212241669, 0.0], [14.136781212241669, 0.0], [14.236781212241668, 0.0], [14.336781212241668, 0.0], [14.43678121224167, 0.0], [14.536781212241669, 0.0], [14.636781212241669, 0.0], [14.73678121224167, 0.0], [14.829250233443535, 0.0], [14.901893990995202, 0.0], [14.95453774854687, 0.0], [14.987181506098533, 0.0], [14.9998252636502, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547, 3.5632993161855473], "velocities": null}}, "time": 1740481187.0636122} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677617574613335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966333850197357, "gear": 1, "accelerator_pedal_position": 0.24496410457794013, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.0636122} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 11.674288941638826, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652067768946903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757658006636885, "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": 1740481187.0836122} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481187.9188466, "x": 15.0, "y": 7.947399999999857, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.0836122} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677617574613335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657779708388441, "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": 1740481187.0836122} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.1036122, "x": 15.780508642807344, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1036122} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467983184068887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652228618659144, "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": 1740481187.1036122} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1236122} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468100165789353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656561367533736, "gear": 1, "accelerator_pedal_position": 0.24467983184068887, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1236122} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1436121} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468100165789353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660889574115187, "gear": 1, "accelerator_pedal_position": 0.24468100165789353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1436121} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.1636121} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.780508642807344, 0.0], [11.943001659435025, 0.0], [12.043001659435024, 0.0], [12.143001659435026, 0.0], [12.243001659435025, 0.0], [12.343001659435025, 0.0], [12.443001659435025, 0.0], [12.543001659435024, 0.0], [12.643001659435026, 0.0], [12.743001659435025, 0.0], [12.843001659435025, 0.0], [12.943001659435025, 0.0], [13.043001659435024, 0.0], [13.143001659435026, 0.0], [13.243001659435025, 0.0], [13.343001659435025, 0.0], [13.443001659435025, 0.0], [13.543001659435026, 0.0], [13.643001659435026, 0.0], [13.743001659435025, 0.0], [13.843001659435025, 0.0], [13.943001659435026, 0.0], [14.043001659435026, 0.0], [14.143001659435026, 0.0], [14.243001659435027, 0.0], [14.343001659435027, 0.0], [14.443001659435026, 0.0], [14.543001659435026, 0.0], [14.643001659435026, 0.0], [14.743001659435027, 0.0], [14.834352350777358, 0.0], [14.905752018890352, 0.0], [14.957151687003346, 0.0], [14.988551355116343, 0.0], [14.999951023229336, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547, 3.463299316185547], "velocities": null}}, "time": 1740481187.1636121} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665211782184214, "gear": 1, "accelerator_pedal_position": 0.24468100165789353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.1636121} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.183612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659648089661793, "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": 1740481187.183612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 11.780508642807344, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652228618659144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257577694823982, "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": 1740481187.203612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677433310281326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654092108200362, "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": 1740481187.203612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.213612, "x": 15.886752745847467, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.223612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469563882249779, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650723384249884, "gear": 1, "accelerator_pedal_position": 0.24469563882249779, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.223612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.243612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468900890149894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652901432203427, "gear": 1, "accelerator_pedal_position": 0.24469563882249779, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.243612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.263612} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.886752745847467, 0.0], [12.04924152982815, 0.0], [12.14924152982815, 0.0], [12.249241529828149, 0.0], [12.34924152982815, 0.0], [12.44924152982815, 0.0], [12.54924152982815, 0.0], [12.64924152982815, 0.0], [12.749241529828149, 0.0], [12.849241529828149, 0.0], [12.94924152982815, 0.0], [13.04924152982815, 0.0], [13.14924152982815, 0.0], [13.24924152982815, 0.0], [13.34924152982815, 0.0], [13.44924152982815, 0.0], [13.54924152982815, 0.0], [13.64924152982815, 0.0], [13.74924152982815, 0.0], [13.84924152982815, 0.0], [13.94924152982815, 0.0], [14.049241529828151, 0.0], [14.14924152982815, 0.0], [14.24924152982815, 0.0], [14.34924152982815, 0.0], [14.44924152982815, 0.0], [14.549241529828151, 0.0], [14.649241529828151, 0.0], [14.74924152982815, 0.0], [14.83939264858552, 0.0], [14.909544342619888, 0.0], [14.95969603665426, 0.0], [14.989847730688629, 0.0], [14.999999424722999, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547, 3.263299316185547, 3.363299316185547], "velocities": null}}, "time": 1740481187.263612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659414100584356, "gear": 1, "accelerator_pedal_position": 0.24468900890149894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.263612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.283612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656641833091985, "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": 1740481187.283612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 11.886752745847467, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651317005391183, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757137702081123, "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": 1740481187.303612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367847717849387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651103061501154, "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": 1740481187.303612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.323612, "x": 15.992937917075146, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.323612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24486003588173463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964785633039723, "gear": 1, "accelerator_pedal_position": 0.24486003588173463, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.323612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.343612} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.140291, "x": 15.0, "y": 7.837399999999859, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.343612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24481825372659688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650139113340396, "gear": 1, "accelerator_pedal_position": 0.24486003588173463, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.343612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.363612} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[11.992937917075146, 0.0], [12.155399771711885, 0.0], [12.255399771711884, 0.0], [12.355399771711884, 0.0], [12.455399771711885, 0.0], [12.555399771711885, 0.0], [12.655399771711885, 0.0], [12.755399771711884, 0.0], [12.855399771711884, 0.0], [12.955399771711885, 0.0], [13.055399771711885, 0.0], [13.155399771711885, 0.0], [13.255399771711884, 0.0], [13.355399771711884, 0.0], [13.455399771711885, 0.0], [13.555399771711885, 0.0], [13.655399771711885, 0.0], [13.755399771711884, 0.0], [13.855399771711886, 0.0], [13.955399771711885, 0.0], [14.055399771711885, 0.0], [14.155399771711885, 0.0], [14.255399771711886, 0.0], [14.355399771711886, 0.0], [14.455399771711885, 0.0], [14.555399771711887, 0.0], [14.655399771711886, 0.0], [14.755370614177345, 0.0], [14.844290659834968, 0.0], [14.913210705492592, 0.0], [14.962130751150214, 0.0], [14.991050796807837, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547, 3.163299316185547], "velocities": null}}, "time": 1740481187.363612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651919720751457, "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": 1740481187.363612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.383612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649193607334292, "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": 1740481187.383612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.403612} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643747046723075, "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": 1740481187.403612} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 11.992937917075146, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645571964538646, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575315656750026, "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": 1740481187.4236119} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23685030717787092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638308031364365, "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": 1740481187.4236119} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.4336119, "x": 16.099059190794723, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4436119} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24528799727359077, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963287654962264, "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": 1740481187.4436119} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4636118} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.099059190794723, 0.0], [12.261473215883292, 0.0], [12.361473215883294, 0.0], [12.461473215883293, 0.0], [12.561473215883293, 0.0], [12.661473215883293, 0.0], [12.761473215883292, 0.0], [12.861473215883292, 0.0], [12.961473215883293, 0.0], [13.061473215883293, 0.0], [13.161473215883293, 0.0], [13.261473215883292, 0.0], [13.361473215883294, 0.0], [13.461473215883293, 0.0], [13.561473215883293, 0.0], [13.661473215883293, 0.0], [13.761473215883294, 0.0], [13.861473215883294, 0.0], [13.961473215883293, 0.0], [14.061473215883293, 0.0], [14.161473215883294, 0.0], [14.261473215883294, 0.0], [14.361473215883294, 0.0], [14.461473215883293, 0.0], [14.561473215883293, 0.0], [14.661473215883294, 0.0], [14.76134158120059, 0.0], [14.84904693802393, 0.0], [14.91675229484727, 0.0], [14.964457651670614, 0.0], [14.992163008493954, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468, 3.063299316185547], "velocities": null}}, "time": 1740481187.4636118} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637996049742588, "gear": 1, "accelerator_pedal_position": 0.24528799727359077, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.4636118} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.4836118} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632705984552138, "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": 1740481187.4836118} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.5036118} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627423245474319, "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": 1740481187.5036118} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 12.099059190794723, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9635591349517778, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574624188130791, "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": 1740481187.5236118} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23696313382314788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622147821247431, "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": 1740481187.5236118} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.5436118, "x": 16.204993080250453, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5436118} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607265090001587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616879700629998, "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": 1740481187.5436118} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5636117} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.204993080250453, 0.0], [12.367313855344069, 0.0], [12.46731385534407, 0.0], [12.56731385534407, 0.0], [12.66731385534407, 0.0], [12.767313855344069, 0.0], [12.867313855344069, 0.0], [12.96731385534407, 0.0], [13.06731385534407, 0.0], [13.16731385534407, 0.0], [13.267313855344069, 0.0], [13.367313855344069, 0.0], [13.46731385534407, 0.0], [13.56731385534407, 0.0], [13.66731385534407, 0.0], [13.76731385534407, 0.0], [13.86731385534407, 0.0], [13.96731385534407, 0.0], [14.06731385534407, 0.0], [14.16731385534407, 0.0], [14.26731385534407, 0.0], [14.36731385534407, 0.0], [14.46731385534407, 0.0], [14.567313855344072, 0.0], [14.66731385534407, 0.0], [14.767014085757195, 0.0], [14.853551314688382, 0.0], [14.920088543619567, 0.0], [14.966625772550753, 0.0], [14.993163001481939, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467, 2.9632993161855468], "velocities": null}}, "time": 1740481187.5636117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623001826934078, "gear": 1, "accelerator_pedal_position": 0.24607265090001587, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.5636117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.5836117} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.4695618, "x": 15.0, "y": 7.672399999999863, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.5836117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617992459558798, "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": 1740481187.5836117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6036117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961299002660275, "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": 1740481187.6036117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6236117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607994517466054, "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": 1740481187.6236117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 12.204993080250453, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9616879700629998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25733283602078894, "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": 1740481187.6436117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371711542428904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603005921567661, "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": 1740481187.6436117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.6536117, "x": 16.31074686394302, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.6636117} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.31074686394302, 0.0], [12.4729822541673, 0.0], [12.5729822541673, 0.0], [12.672982254167302, 0.0], [12.772982254167301, 0.0], [12.872982254167301, 0.0], [12.9729822541673, 0.0], [13.0729822541673, 0.0], [13.172982254167302, 0.0], [13.272982254167301, 0.0], [13.372982254167301, 0.0], [13.4729822541673, 0.0], [13.5729822541673, 0.0], [13.672982254167302, 0.0], [13.772982254167301, 0.0], [13.872982254167301, 0.0], [13.972982254167302, 0.0], [14.072982254167302, 0.0], [14.172982254167302, 0.0], [14.272982254167301, 0.0], [14.372982254167301, 0.0], [14.472982254167302, 0.0], [14.572982254167302, 0.0], [14.672982254167302, 0.0], [14.772454070160691, 0.0], [14.85785761932723, 0.0], [14.92326116849377, 0.0], [14.96866471766031, 0.0], [14.99406826682685, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466, 2.8632993161855467], "velocities": null}}, "time": 1740481187.6636117} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478546398709996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598024228345304, "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": 1740481187.6636117} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.6836116} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9606399163833363, "gear": 1, "accelerator_pedal_position": 0.2478546398709996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.6836116} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7036116} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614661302707981, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7036116} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7236116} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622912006579234, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7236116} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 12.31074686394302, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9600514212781387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572195583788887, "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": 1740481187.7436116} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24777364522060807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631151288551426, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7436116} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.7636116, "x": 16.41651435876285, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.7636116} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.41651435876285, 0.0], [12.57894669235506, 0.0], [12.67894669235506, 0.0], [12.77894669235506, 0.0], [12.87894669235506, 0.0], [12.97894669235506, 0.0], [13.07894669235506, 0.0], [13.17894669235506, 0.0], [13.27894669235506, 0.0], [13.37894669235506, 0.0], [13.47894669235506, 0.0], [13.57894669235506, 0.0], [13.67894669235506, 0.0], [13.77894669235506, 0.0], [13.87894669235506, 0.0], [13.97894669235506, 0.0], [14.07894669235506, 0.0], [14.17894669235506, 0.0], [14.27894669235506, 0.0], [14.378946692355061, 0.0], [14.478946692355061, 0.0], [14.57894669235506, 0.0], [14.67894669235506, 0.0], [14.778108781356762, 0.0], [14.86231944288575, 0.0], [14.926530104414738, 0.0], [14.970740765943725, 0.0], [14.994951427472714, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466], "velocities": null}}, "time": 1740481187.7636116} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452201839899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639379161722026, "gear": 1, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7636116} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.7836115} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644404918377959, "gear": 1, "accelerator_pedal_position": 0.2452201839899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.7836115} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8036115} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649667307838844, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8036115} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8236115} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654922406502007, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8236115} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8436115} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.6890776, "x": 15.0, "y": 7.562399999999865, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481187.8436115} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660170223364252, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8436115} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 12.41651435876285, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9639379161722026, "accelerator_pedal_position": 0.24777364522060807, "brake_pedal_position": 0.0, "acceleration": 0.041096623757846173, "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": 1740481187.8636115} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.41651435876285, 0.0], [12.57894669235506, 0.0], [12.67894669235506, 0.0], [12.77894669235506, 0.0], [12.87894669235506, 0.0], [12.97894669235506, 0.0], [13.07894669235506, 0.0], [13.17894669235506, 0.0], [13.27894669235506, 0.0], [13.37894669235506, 0.0], [13.47894669235506, 0.0], [13.57894669235506, 0.0], [13.67894669235506, 0.0], [13.77894669235506, 0.0], [13.87894669235506, 0.0], [13.97894669235506, 0.0], [14.07894669235506, 0.0], [14.17894669235506, 0.0], [14.27894669235506, 0.0], [14.378946692355061, 0.0], [14.478946692355061, 0.0], [14.57894669235506, 0.0], [14.67894669235506, 0.0], [14.778108781356762, 0.0], [14.86231944288575, 0.0], [14.926530104414738, 0.0], [14.970740765943725, 0.0], [14.994951427472714, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465, 2.7632993161855466], "velocities": null}}, "time": 1740481187.8636115} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541512730280174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665410767414505, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8636115} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.8736115, "x": 16.522689877880403, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.8836114} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374893105560462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670644047633816, "gear": 1, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481187.8836114} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9036114} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9665966236990129, "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": 1740481187.9036114} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9236114} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661072783279755, "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": 1740481187.9236114} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9436114} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731154696092793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656186111951386, "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": 1740481187.9436114} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 12.522689877880403, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9668028314942021, "accelerator_pedal_position": 0.24541512730280174, "brake_pedal_position": 0.0, "acceleration": 0.026157326917948642, "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": 1740481187.9636114} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.522689877880403, 0.0], [12.685254492734746, 0.0], [12.785254492734747, 0.0], [12.885254492734747, 0.0], [12.985254492734747, 0.0], [13.085254492734746, 0.0], [13.185254492734746, 0.0], [13.285254492734746, 0.0], [13.385254492734747, 0.0], [13.485254492734747, 0.0], [13.585254492734746, 0.0], [13.685254492734746, 0.0], [13.785254492734747, 0.0], [13.885254492734747, 0.0], [13.985254492734747, 0.0], [14.085254492734746, 0.0], [14.185254492734746, 0.0], [14.285254492734747, 0.0], [14.385254492734747, 0.0], [14.485254492734747, 0.0], [14.585254492734748, 0.0], [14.685254492734748, 0.0], [14.784011613476764, 0.0], [14.866960714929814, 0.0], [14.929909816382864, 0.0], [14.972858917835914, 0.0], [14.995808019288965, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464, 2.6632993161855465], "velocities": null}}, "time": 1740481187.9636114} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23659168961101223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651306212649714, "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": 1740481187.9636114} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481187.9836113, "x": 16.62895569738603, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481187.9836113} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24431377744373622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645533565126366, "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": 1740481187.9836113} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0036113} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964941818066081, "gear": 1, "accelerator_pedal_position": 0.24431377744373622, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0036113} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0236113} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965309298716548, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0236113} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0436113} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441501791072392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656762701833823, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0436113} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0636113} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.62895569738603, 0.0], [12.791417370548562, 0.0], [12.891417370548561, 0.0], [12.991417370548561, 0.0], [13.09141737054856, 0.0], [13.19141737054856, 0.0], [13.291417370548562, 0.0], [13.391417370548561, 0.0], [13.491417370548561, 0.0], [13.59141737054856, 0.0], [13.69141737054856, 0.0], [13.791417370548562, 0.0], [13.891417370548561, 0.0], [13.991417370548561, 0.0], [14.09141737054856, 0.0], [14.191417370548562, 0.0], [14.291417370548562, 0.0], [14.391417370548561, 0.0], [14.491417370548561, 0.0], [14.591417370548562, 0.0], [14.691417370548562, 0.0], [14.789701971965405, 0.0], [14.871418497855693, 0.0], [14.93313502374598, 0.0], [14.974851549636268, 0.0], [14.996568075526556, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463, 2.5632993161855464], "velocities": null}}, "time": 1740481188.0636113} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368507437607846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660427331182634, "gear": 1, "accelerator_pedal_position": 0.2441501791072392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.0636113} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 12.62895569738603, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9645533565126366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575312996012298, "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": 1740481188.0836112} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481188.908753, "x": 15.0, "y": 7.452399999999868, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.0836112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368507437607846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654965750017084, "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": 1740481188.0836112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.0936112, "x": 16.73514585039503, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1036112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24490190989468333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649511737362377, "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": 1740481188.1036112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1236112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449506680010362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656460835301184, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1236112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1436112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449506680010362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658794300025544, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1436112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1636112} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.735145850395028, 0.0], [12.89763890958796, 0.0], [12.997638909587959, 0.0], [13.097638909587959, 0.0], [13.19763890958796, 0.0], [13.29763890958796, 0.0], [13.39763890958796, 0.0], [13.497638909587959, 0.0], [13.597638909587959, 0.0], [13.69763890958796, 0.0], [13.79763890958796, 0.0], [13.89763890958796, 0.0], [13.997638909587959, 0.0], [14.09763890958796, 0.0], [14.19763890958796, 0.0], [14.29763890958796, 0.0], [14.39763890958796, 0.0], [14.497638909587959, 0.0], [14.59763890958796, 0.0], [14.69763890958796, 0.0], [14.795369443881231, 0.0], [14.875841661963639, 0.0], [14.936313880046047, 0.0], [14.976786098128454, 0.0], [14.997258316210862, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462, 2.4632993161855463], "velocities": null}}, "time": 1740481188.1636112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367742279329181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9663456378145532, "gear": 1, "accelerator_pedal_position": 0.2449506680010362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.1636112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 12.735145850395028, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652237798356226, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575777584433828, "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": 1740481188.1836112} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367742279329181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657894987261451, "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": 1740481188.1836112} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.2036111, "x": 16.8413670697767, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.2036111} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467149201069047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652341303858534, "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": 1740481188.2036111} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.223611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467224477869787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656663475415543, "gear": 1, "accelerator_pedal_position": 0.24467149201069047, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.223611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.243611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24467224477869787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660980598187895, "gear": 1, "accelerator_pedal_position": 0.24467224477869787, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.243611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.263611} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.841367069776702, 0.0], [13.003860608835561, 0.0], [13.103860608835562, 0.0], [13.203860608835562, 0.0], [13.303860608835562, 0.0], [13.403860608835561, 0.0], [13.503860608835561, 0.0], [13.60386060883556, 0.0], [13.703860608835562, 0.0], [13.803860608835562, 0.0], [13.903860608835561, 0.0], [14.003860608835561, 0.0], [14.103860608835562, 0.0], [14.203860608835562, 0.0], [14.303860608835562, 0.0], [14.403860608835561, 0.0], [14.503860608835563, 0.0], [14.603860608835562, 0.0], [14.703860608835562, 0.0], [14.800959643651424, 0.0], [14.880187521884313, 0.0], [14.9394154001172, 0.0], [14.978643278350088, 0.0], [14.997871156582974, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546, 2.3632993161855462], "velocities": null}}, "time": 1740481188.263611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662508064539874, "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": 1740481188.263611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.283611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659726321146349, "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": 1740481188.283611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 12.841367069776702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9652341303858534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757847578391, "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": 1740481188.303611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677304201554894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654168617967938, "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": 1740481188.303611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.313611, "x": 16.9476121592411, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.323611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24469009089076577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648618616331899, "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": 1740481188.323611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.343611} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.2399144, "x": 15.0, "y": 7.287399999999871, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.343611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24468319162122681, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652969186522636, "gear": 1, "accelerator_pedal_position": 0.24469009089076577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.343611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.363611} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[12.9476121592411, 0.0], [13.110101294887663, 0.0], [13.210101294887663, 0.0], [13.310101294887662, 0.0], [13.410101294887662, 0.0], [13.510101294887663, 0.0], [13.610101294887663, 0.0], [13.710101294887663, 0.0], [13.810101294887662, 0.0], [13.910101294887662, 0.0], [14.010101294887662, 0.0], [14.110101294887663, 0.0], [14.210101294887663, 0.0], [14.310101294887662, 0.0], [14.410101294887662, 0.0], [14.510101294887663, 0.0], [14.610101294887663, 0.0], [14.710101294887663, 0.0], [14.80648912924049, 0.0], [14.884468870262957, 0.0], [14.942448611285425, 0.0], [14.980428352307891, 0.0], [14.998408093330358, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546, 2.263299316185546], "velocities": null}}, "time": 1740481188.363611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657305107487073, "gear": 1, "accelerator_pedal_position": 0.24468319162122681, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.363611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.383611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965176433484815, "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": 1740481188.383611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 12.9476121592411, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.965139265520163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757190129449614, "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": 1740481188.403611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678390594875834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646231239756808, "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": 1740481188.403611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.423611, "x": 17.053773371091882, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.423611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497073372865627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640705810350507, "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": 1740481188.423611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.443611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24489301114652606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645418024565058, "gear": 1, "accelerator_pedal_position": 0.24497073372865627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.443611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.463611} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.053773371091882, 0.0], [13.216212071845987, 0.0], [13.316212071845989, 0.0], [13.416212071845989, 0.0], [13.516212071845988, 0.0], [13.616212071845988, 0.0], [13.716212071845987, 0.0], [13.816212071845989, 0.0], [13.916212071845989, 0.0], [14.016212071845988, 0.0], [14.116212071845988, 0.0], [14.216212071845987, 0.0], [14.316212071845989, 0.0], [14.416212071845989, 0.0], [14.516212071845988, 0.0], [14.616212071845988, 0.0], [14.71621207184599, 0.0], [14.811828033387851, 0.0], [14.888585619018652, 0.0], [14.945343204649454, 0.0], [14.982100790280256, 0.0], [14.998858375911059, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546, 2.163299316185546], "velocities": null}}, "time": 1740481188.463611} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650026591432509, "gear": 1, "accelerator_pedal_position": 0.24489301114652606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.463611} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.4836109} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644647818353774, "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": 1740481188.4836109} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.5036108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639276496809859, "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": 1740481188.5036108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 13.053773371091882, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640705810350507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25749784990392516, "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": 1740481188.5236108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690547956567468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633912615324063, "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": 1740481188.5236108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.5336108, "x": 17.15984403541566, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5436108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555820172111825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628556162440379, "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": 1740481188.5436108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5636108} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.15984403541566, 0.0], [13.322236759866072, 0.0], [13.422236759866074, 0.0], [13.522236759866074, 0.0], [13.622236759866073, 0.0], [13.722236759866073, 0.0], [13.822236759866072, 0.0], [13.922236759866074, 0.0], [14.022236759866074, 0.0], [14.122236759866073, 0.0], [14.222236759866073, 0.0], [14.322236759866072, 0.0], [14.422236759866074, 0.0], [14.522236759866074, 0.0], [14.622236759866073, 0.0], [14.722236759866073, 0.0], [14.817018610390125, 0.0], [14.89257125841691, 0.0], [14.948123906443696, 0.0], [14.983676554470481, 0.0], [14.999229202497267, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459, 2.063299316185546], "velocities": null}}, "time": 1740481188.5636108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9634019284023724, "gear": 1, "accelerator_pedal_position": 0.24555820172111825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.5636108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.5836108} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.459951, "x": 15.0, "y": 7.177399999999873, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.5836108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628795775059512, "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": 1740481188.5836108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.6036108} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623579499215548, "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": 1740481188.6036108} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 13.15984403541566, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631233461022151, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743223310318203, "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": 1740481188.6236107} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701198976120635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618370445387947, "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": 1740481188.6236107} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.6436107, "x": 17.265734214764212, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6436107} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24631515703669135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961316860249272, "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": 1740481188.6436107} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6636107} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.265734214764212, 0.0], [13.428035940749108, 0.0], [13.528035940749108, 0.0], [13.628035940749108, 0.0], [13.728035940749107, 0.0], [13.828035940749107, 0.0], [13.928035940749108, 0.0], [14.028035940749108, 0.0], [14.128035940749108, 0.0], [14.228035940749107, 0.0], [14.328035940749107, 0.0], [14.428035940749108, 0.0], [14.528035940749108, 0.0], [14.628035940749108, 0.0], [14.728035940749107, 0.0], [14.82194633270051, 0.0], [14.896339144550687, 0.0], [14.950731956400867, 0.0], [14.985124768251044, 0.0], [14.999517580101223, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458, 1.9632993161855459], "velocities": null}}, "time": 1740481188.6636107} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619598893372927, "gear": 1, "accelerator_pedal_position": 0.24631515703669135, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.6636107} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.6836107} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614645110802483, "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": 1740481188.6836107} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7036107} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609698185040184, "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": 1740481188.7036107} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7236106} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604758105616591, "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": 1740481188.7236106} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 13.265734214764212, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.961316860249272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573071440704588, "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": 1740481188.7436106} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23721186757452045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599824862080818, "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": 1740481188.7436106} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.7536106, "x": 17.371451103240858, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.7636106} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.371451103240858, 0.0], [13.533669630593296, 0.0], [13.633669630593298, 0.0], [13.733669630593297, 0.0], [13.833669630593297, 0.0], [13.933669630593297, 0.0], [14.033669630593296, 0.0], [14.133669630593296, 0.0], [14.233669630593297, 0.0], [14.333669630593297, 0.0], [14.433669630593297, 0.0], [14.533669630593296, 0.0], [14.633669630593298, 0.0], [14.733669630593297, 0.0], [14.826669023509679, 0.0], [14.899935097391019, 0.0], [14.95320117127236, 0.0], [14.986467245153701, 0.0], [14.999733319035041, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457, 1.8632993161855458], "velocities": null}}, "time": 1740481188.7636106} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2480507117873506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594898444000495, "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": 1740481188.7636106} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.7836106} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96035227089933, "gear": 1, "accelerator_pedal_position": 0.2480507117873506, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.7836106} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8036106} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612037684846342, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8036106} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8236105} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962054087667793, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8236105} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 13.371451103240858, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9597360800510026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571977374360668, "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": 1740481188.8436105} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.6799552, "x": 15.0, "y": 7.067399999999876, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481188.8436105} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247972799370777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629032297905002, "gear": 1, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8436105} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.8636105, "x": 17.477189842202876, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.8636105} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.477189842202876, 0.0], [13.639613174536834, 0.0], [13.739613174536833, 0.0], [13.839613174536833, 0.0], [13.939613174536833, 0.0], [14.039613174536834, 0.0], [14.139613174536834, 0.0], [14.239613174536833, 0.0], [14.339613174536833, 0.0], [14.439613174536833, 0.0], [14.539613174536834, 0.0], [14.639613174536834, 0.0], [14.739613174536833, 0.0], [14.831582653486265, 0.0], [14.903660018578897, 0.0], [14.955737383671531, 0.0], [14.987814748764164, 0.0], [14.999892113856799, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457], "velocities": null}}, "time": 1740481188.8636105} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24532358073361102, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640091627547306, "gear": 1, "accelerator_pedal_position": 0.24532358073361102, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8636105} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.8836105} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642669506026164, "gear": 1, "accelerator_pedal_position": 0.24532358073361102, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.8836105} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9036105} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648070814465315, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9036105} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9236104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653464639993098, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9236104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9436104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658850991812923, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9436104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 13.477189842202876, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9637511961937933, "accelerator_pedal_position": 0.247972799370777, "brake_pedal_position": 0.0, "acceleration": 0.04235427257601676, "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": 1740481188.9636104} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.477189842202876, 0.0], [13.639613174536834, 0.0], [13.739613174536833, 0.0], [13.839613174536833, 0.0], [13.939613174536833, 0.0], [14.039613174536834, 0.0], [14.139613174536834, 0.0], [14.239613174536833, 0.0], [14.339613174536833, 0.0], [14.439613174536833, 0.0], [14.539613174536834, 0.0], [14.639613174536834, 0.0], [14.739613174536833, 0.0], [14.831582653486265, 0.0], [14.903660018578897, 0.0], [14.955737383671531, 0.0], [14.987814748764164, 0.0], [14.999892113856799, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456, 1.7632993161855457], "velocities": null}}, "time": 1740481188.9636104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552437706248945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664229879120283, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9636104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481188.9736104, "x": 17.583348571499474, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481188.9836104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23750561408644177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669601311102749, "gear": 1, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481188.9836104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0036104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96649453183291, "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": 1740481189.0036104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0236104} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660075507764788, "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": 1740481189.0236104} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0436103} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23732933557674885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655212446617538, "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": 1740481189.0436103} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 13.583348571499474, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9666916526453214, "accelerator_pedal_position": 0.24552437706248945, "brake_pedal_position": 0.0, "acceleration": 0.026847846495351435, "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": 1740481189.0636103} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.583348571499474, 0.0], [13.74590825701602, 0.0], [13.84590825701602, 0.0], [13.94590825701602, 0.0], [14.04590825701602, 0.0], [14.14590825701602, 0.0], [14.24590825701602, 0.0], [14.345908257016019, 0.0], [14.44590825701602, 0.0], [14.54590825701602, 0.0], [14.64590825701602, 0.0], [14.74590825701602, 0.0], [14.83670986325217, 0.0], [14.907528211848964, 0.0], [14.958346560445761, 0.0], [14.989164909042557, 0.0], [14.999983257639354, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454, 1.5632993161855455, 1.6632993161855456], "velocities": null}}, "time": 1740481189.0636103} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366046484818828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650356124587205, "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": 1740481189.0636103} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.0836103, "x": 17.689603364946514, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.0836103} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481189.9006577, "x": 15.0, "y": 6.957399999999878, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.0836103} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24437086306334707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644600986382565, "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": 1740481189.0836103} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1036103} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648558226177377, "gear": 1, "accelerator_pedal_position": 0.24437086306334707, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1036103} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1236103} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9652307185078329, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1236103} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1436102} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420856807169306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656050949517435, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1436102} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1636102} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.689603364946514, 0.0], [13.852060624739524, 0.0], [13.952060624739524, 0.0], [14.052060624739525, 0.0], [14.152060624739525, 0.0], [14.252060624739524, 0.0], [14.352060624739524, 0.0], [14.452060624739524, 0.0], [14.552060624739523, 0.0], [14.652060624739525, 0.0], [14.752056378565207, 0.0], [14.841644253617302, 0.0], [14.911232128669397, 0.0], [14.960820003721492, 0.0], [14.990407878773588, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453, 1.4632993161855454], "velocities": null}}, "time": 1740481189.1636102} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686134081933502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9659789526131571, "gear": 1, "accelerator_pedal_position": 0.24420856807169306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.1636102} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 13.689603364946514, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9644600986382565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257524837750566, "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": 1740481189.1836102} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686134081933502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654342070612809, "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": 1740481189.1836102} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.1936102, "x": 17.795785192993907, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2036102} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24494839583537673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648902163893379, "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": 1740481189.2036102} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2236102} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499945179678645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9653575110523781, "gear": 1, "accelerator_pedal_position": 0.24494839583537673, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.2236102} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2436101} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499945179678645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658305380079198, "gear": 1, "accelerator_pedal_position": 0.24499945179678645, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.2436101} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.2636101} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.795785192993907, 0.0], [13.958275390471856, 0.0], [14.058275390471858, 0.0], [14.158275390471857, 0.0], [14.258275390471857, 0.0], [14.358275390471857, 0.0], [14.458275390471856, 0.0], [14.558275390471858, 0.0], [14.658275390471857, 0.0], [14.758206908384395, 0.0], [14.846551830290023, 0.0], [14.914896752195652, 0.0], [14.963241674101281, 0.0], [14.99158659600691, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453, 1.3632993161855453], "velocities": null}}, "time": 1740481189.2636101} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966025214480847, "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": 1740481189.2636101} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 13.795785192993907, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651621174381423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575734850012839, "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": 1740481189.28361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657477120283501, "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": 1740481189.28361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23678129001991657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9654704019342519, "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": 1740481189.29361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.30361, "x": 17.902000907770052, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.32361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470174859704583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9648581108304626, "gear": 1, "accelerator_pedal_position": 0.24470174859704583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.32361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.34361} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.2305155, "x": 15.0, "y": 6.792399999999882, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.34361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24470401526187557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650764459449592, "gear": 1, "accelerator_pedal_position": 0.24470174859704583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.34361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.36361} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[13.902000907770052, 0.0], [14.06449255230544, 0.0], [14.16449255230544, 0.0], [14.26449255230544, 0.0], [14.36449255230544, 0.0], [14.46449255230544, 0.0], [14.56449255230544, 0.0], [14.66449255230544, 0.0], [14.764282518233115, 0.0], [14.851384007772026, 0.0], [14.918485497310938, 0.0], [14.96558698684985, 0.0], [14.992688476388762, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452, 1.2632993161855453], "velocities": null}}, "time": 1740481189.36361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655129455897855, "gear": 1, "accelerator_pedal_position": 0.24470401526187557, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.36361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.38361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649583969809143, "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": 1740481189.38361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 13.902000907770052, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9651932840498285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25757564495824037, "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": 1740481189.40361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367777211829886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9644046167316135, "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": 1740481189.40361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.41361, "x": 18.008148623171483, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.42361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24493917225439704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9638516036546492, "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": 1740481189.42361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.44361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448616980220303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643191845753359, "gear": 1, "accelerator_pedal_position": 0.24493917225439704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.44361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.46361} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.008148623171483, 0.0], [14.170590073121703, 0.0], [14.270590073121703, 0.0], [14.370590073121702, 0.0], [14.470590073121702, 0.0], [14.570590073121702, 0.0], [14.670590073121703, 0.0], [14.770166122010545, 0.0], [14.856048107386204, 0.0], [14.921930092761864, 0.0], [14.967812078137523, 0.0], [14.993694063513184, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545, 1.1632993161855452], "velocities": null}}, "time": 1740481189.46361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645071557955804, "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": 1740481189.46361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.48361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642380613050148, "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": 1740481189.48361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 14.008148623171483, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9641280143707072, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575018289994794, "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": 1740481189.49361} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23689898388304367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639691532631656, "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": 1740481189.49361} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.5236099, "x": 18.11420417619556, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5236099} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552878012820667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631635463940356, "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": 1740481189.5236099} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5436099} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454586369357368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637057557118827, "gear": 1, "accelerator_pedal_position": 0.24552878012820667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.5436099} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5636098} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.11420417619556, 0.0], [14.276598876171596, 0.0], [14.376598876171595, 0.0], [14.476598876171597, 0.0], [14.576598876171596, 0.0], [14.676598876171596, 0.0], [14.775891375958004, 0.0], [14.860571600723684, 0.0], [14.925251825489365, 0.0], [14.969932050255046, 0.0], [14.994612275020728, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451, 1.063299316185545], "velocities": null}}, "time": 1740481189.5636098} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642422084177084, "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": 1740481189.5636098} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.5836098} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.449891, "x": 15.0, "y": 6.682399999999884, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.5836098} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642422084177084, "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": 1740481189.5836098} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.6036098} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637181318766436, "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": 1740481189.6036098} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 14.11420417619556, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9631635463940356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574350174907251, "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": 1740481189.6136098} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23700749332641435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631947812129009, "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": 1740481189.6136098} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.6336098, "x": 18.2202202839661, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6436098} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24592445237169827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626721553115765, "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": 1740481189.6436098} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6636097} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.2202202839661, 0.0], [14.38260364382763, 0.0], [14.48260364382763, 0.0], [14.58260364382763, 0.0], [14.68260364382763, 0.0], [14.781540646236792, 0.0], [14.865019917471265, 0.0], [14.92849918870574, 0.0], [14.971978459940214, 0.0], [14.995457731174687, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451, 0.9632993161855451], "velocities": null}}, "time": 1740481189.6636097} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632644869821402, "gear": 1, "accelerator_pedal_position": 0.24592445237169827, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.6636097} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.6836097} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627449779403253, "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": 1740481189.6836097} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.7036097} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622261882472513, "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": 1740481189.7036097} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 14.2202202839661, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9629333777365398, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25741907578641804, "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": 1740481189.7236097} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23703320931394956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9617081167992372, "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": 1740481189.7236097} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.7436097, "x": 18.326094526719686, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7436097} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24641326600952393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611907624945776, "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": 1740481189.7436097} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7636096} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.326094526719686, 0.0], [14.48838973829473, 0.0], [14.58838973829473, 0.0], [14.68838973829473, 0.0], [14.786915966288392, 0.0], [14.869238018629446, 0.0], [14.9315600709705, 0.0], [14.973882123311554, 0.0], [14.996204175652608, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451, 0.8632993161855451], "velocities": null}}, "time": 1740481189.7636096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619265558472894, "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": 1740481189.7636096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.7836096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619265558472894, "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": 1740481189.7836096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8036096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614329472413322, "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": 1740481189.8036096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8236096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960940021860401, "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": 1740481189.8236096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 14.326094526719686, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9611907624945776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257298414943778, "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": 1740481189.8436096} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.670971, "x": 15.0, "y": 6.572399999999886, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481189.8436096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.237225660423226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604477786616578, "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": 1740481189.8436096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.8536096, "x": 18.431844890680622, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.8636096} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.431844890680622, 0.0], [14.594088281689993, 0.0], [14.694088281689993, 0.0], [14.792144505107617, 0.0], [14.873326848769619, 0.0], [14.93450919243162, 0.0], [14.97569153609362, 0.0], [14.996873879755622, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452, 0.7632993161855451], "velocities": null}}, "time": 1740481189.8636096} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477278518955033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599562166041115, "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": 1740481189.8636096} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.8836095} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607776543577623, "gear": 1, "accelerator_pedal_position": 0.2477278518955033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.8836095} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9036095} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615918528716176, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9036095} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9236095} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9624049244728141, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9236095} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 14.431844890680622, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9602019125552249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572299727565084, "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": 1740481189.9436095} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24767901438862655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963216870456742, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9436095} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481189.9636095, "x": 18.537626224608736, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481189.9636095} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.537626224608736, 0.0], [14.700062869504714, 0.0], [14.797556578601668, 0.0], [14.877544004700725, 0.0], [14.937531430799783, 0.0], [14.97751885689884, 0.0], [14.997506282997897, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452], "velocities": null}}, "time": 1740481189.9636095} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9640276921180959, "gear": 1, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481189.9636095} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481189.9836094} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9588795778234872, "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": 1740481189.9836094} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0036094} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.953738586397578, "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": 1740481190.0036094} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0236094} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9486046974169852, "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": 1740481190.0236094} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0436094} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9434778905303582, "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": 1740481190.0436094} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 14.537626224608736, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9640276921180959, "accelerator_pedal_position": 0.24767901438862655, "brake_pedal_position": 0.0, "acceleration": 0.040498961411305656, "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": 1740481190.0636094} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.537626224608736, 0.0], [14.700062869504714, 0.0], [14.797556578601668, 0.0], [14.877544004700725, 0.0], [14.937531430799783, 0.0], [14.97751885689884, 0.0], [14.997506282997897, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452, 0.6632993161855452], "velocities": null}}, "time": 1740481190.0636094} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9383581454580531, "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": 1740481190.0636094} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.0736094, "x": 18.642255982888702, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.0836093} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481190.8895564, "x": 15.0, "y": 6.462399999999889, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.0836093} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5942282964313452, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9332454419918059, "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": 1740481190.0836093} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1036093} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9132454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5942282964313452, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1036093} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1236093} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8932454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1236093} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1436093} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5944682577252809, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8732454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1436093} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 14.642255982888702, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.9358009147844093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2555472792603338, "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": 1740481190.1636093} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.642255982888702, 0.0], [14.800018972925963, 0.0], [14.879457449450117, 0.0], [14.93889592597427, 0.0], [14.978334402498422, 0.0], [14.997772879022575, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452, 0.5632993161855452], "velocities": null}}, "time": 1740481190.1636093} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23684738398932476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8532454419918059, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5944682577252809, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.1636093} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.1836092, "x": 18.740536571595726, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.1836092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.585385923823698, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8528526457461664, "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": 1740481190.1836092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2036092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8328526457461664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.585385923823698, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2036092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2236092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8128526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2236092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2436092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5877424109868785, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7928526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2436092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2636092} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.740536571595726, 0.0], [14.876350259737517, 0.0], [14.936677989762732, 0.0], [14.977005719787945, 0.0], [14.997333449813159, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523, 0.4632993161855452], "velocities": null}}, "time": 1740481190.2636092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22861327109376184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7728526457461663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5877424109868785, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.2636092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 14.740536571595726, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.8528526457461664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2499162086408707, "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": 1740481190.2836092} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22861327109376184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7715374222956273, "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": 1740481190.2836092} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.2936091, "x": 18.829130632123295, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.3036091} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6063709215110569, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7702239195760366, "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": 1740481190.3036091} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.323609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6086996791216414, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7502239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6063709215110569, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.323609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.343609} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.2199366, "x": 15.0, "y": 6.297399999999892, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.343609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6086996791216414, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7302239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6086996791216414, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.343609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.363609} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.829130632123295, 0.0], [14.937106716406817, 0.0], [14.977263783144489, 0.0], [14.997420849882161, 0.0]], "times": [0, 0.16329931618554522, 0.26329931618554525, 0.36329931618554523], "velocities": null}}, "time": 1740481190.363609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7102239195760366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6086996791216414, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.363609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 14.829130632123295, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7708804560284394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24448658957628813, "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": 1740481190.383609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.705414355947849, "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": 1740481190.383609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.403609, "x": 18.909817557149807, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.403609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7006109593131602, "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": 1740481190.403609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.423609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6806109593131602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.423609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.443609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6606109593131602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.443609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.463609} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.909817557149807, 0.0], [14.96729843016162, 0.0], [15.0, 0.0]], "times": [0, 0.1, 0.2], "velocities": null}}, "time": 1740481190.463609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.628255886815303, "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": 1740481190.463609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.483609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.628255886815303, "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": 1740481190.483609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 14.909817557149807, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.7006109593131602, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2399391051287551, "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": 1740481190.503609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6235501618143473, "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": 1740481190.503609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.513609, "x": 18.981843517264423, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.523609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5106700600388568, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6188503166178511, "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": 1740481190.523609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.543609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5058864879293254, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6107429796470758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5106700600388568, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.543609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.563609} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[14.981843517264423, 0.0], [15.0, 0.0]], "times": [0.0, 0.01815648273557713], "velocities": null}}, "time": 1740481190.563609} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.604176001507251, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5058864879293254, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.563609} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.5836089} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.4398854, "x": 15.0, "y": 6.1873999999998945, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.5836089} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6110726869649955, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.5836089} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 14.981843517264423, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6211995052530103, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2349188635159164, "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": 1740481190.6036088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260807915951836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.61796079741184, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6036088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.6236088, "x": 19.049341527320987, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6236088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917607609645343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6248403245370329, "gear": 1, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6236088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6436088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29202554807407477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6316053784694852, "gear": 1, "accelerator_pedal_position": 0.2917607609645343, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6436088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6636088} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.6636088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6383950534515388, "gear": 1, "accelerator_pedal_position": 0.29202554807407477, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6636088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.6836088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6183950534515388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.6836088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.7036088} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5983950534515388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7036088} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 15.049341527320987, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.6248403245370329, "accelerator_pedal_position": 0.29260807915951836, "brake_pedal_position": 0.0, "acceleration": 0.3436542242084626, "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": 1740481190.7236087} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5783950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7236087} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.7336087, "x": 19.117125889986575, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7436087} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5583950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7436087} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7636087} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.7636087} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5383950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7636087} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.7836087} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5183950534515387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.7836087} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.8036087} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49839505345153867, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8036087} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 15.117125889986575, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.5683950534515387, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0316504820404595, "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": 1740481190.8236086} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47839505345153865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8236086} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.8436086, "x": 19.174149345866248, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8436086} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.6606176, "x": 15.0, "y": 6.077399999999897, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481190.8436086} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45839505345153864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8436086} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8636086} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.8636086} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4283950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8636086} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.8836086} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4183950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.8836086} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9036086} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3983950534515386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9036086} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9236085} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37839505345153857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9236085} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 15.174149345866248, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.45839505345153864, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.025021012922866, "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": 1740481190.9436085} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35839505345153855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9436085} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481190.9536085, "x": 19.219072801745913, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481190.9636085} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481190.9636085} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33839505345153853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9636085} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481190.9836085} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3183950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481190.9836085} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0036085} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2983950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0036085} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0236084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2783950534515385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0236084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 15.219072801745913, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.34839505345153854, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0186335438052727, "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": 1740481191.0436084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25839505345153846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0436084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.0636084, "x": 19.25189625762558, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.0636084} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.0636084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23839505345153844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0636084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.0836084} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481191.8799243, "x": 15.0, "y": 5.967399999999899, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.0836084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21839505345153842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.0836084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1036084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1983950534515384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1036084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1236084} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1783950534515384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1236084} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1436083} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1436083} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 15.251896257625582, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.23839505345153844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0124880746876794, "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": 1740481191.1636083} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.1636083} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12839505345153834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1636083} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.1736083, "x": 19.272619713505254, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.1836083} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11839505345153835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.1836083} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2036083} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09839505345153836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2036083} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2236083} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2236083} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2436082} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2436082} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 15.272619713505254, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.12839505345153834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0065846055700858, "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": 1740481191.2636082} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.2636082} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03839505345153837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2636082} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.2836082, "x": 19.281243169384922, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.2836082} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6105246878604861, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.018395053451538364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.2836082} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3036082} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6105246878604861, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3036082} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3236082} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3236082} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3436081} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.2097847, "x": 15.0, "y": 5.802399999999903, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.3436081} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3436081} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.3636081} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.3636081} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.3636081} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 15.281243169384922, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.018395053451538364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "acceleration": -2.0009231364524926, "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": 1740481191.383608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.6125, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.383608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.393608, "x": 19.281511070453956, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.393608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1740481191.393608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.423608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.423608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.443608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.443608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.463608} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.463608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.463608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 15.281511070453956, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.6125, "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": 1740481191.483608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.483608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.503608, "x": 19.281511070453956, "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": 1740481191.503608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.503608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.523608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.523608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.543608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.543608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.563608} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.563608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.563608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.583608} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.4298215, "x": 15.0, "y": 5.692399999999905, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.583608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.583608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 15.281511070453956, "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": 1740481191.603608} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.603608} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.613608, "x": 19.281511070453956, "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": 1740481191.6236079} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6236079} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6436079} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6436079} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6636078} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.6636078} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6636078} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.6836078} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.6836078} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 15.281511070453956, "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": 1740481191.7036078} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7036078} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.7236078, "x": 19.281511070453956, "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": 1740481191.7236078} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7236078} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7436078} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7436078} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7636077} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.7636077} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7636077} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.7836077} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.7836077} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.8036077} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8036077} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 15.281511070453956, "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": 1740481191.8236077} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8236077} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.8336077, "x": 19.281511070453956, "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": 1740481191.8436077} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.650066, "x": 15.0, "y": 5.582399999999907, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481191.8436077} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8436077} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.8636076} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.8636076} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8636076} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.8836076} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.8836076} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.9036076} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9036076} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 15.281511070453956, "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": 1740481191.9236076} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9236076} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481191.9436076, "x": 19.281511070453956, "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": 1740481191.9436076} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9436076} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481191.9636075} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481191.9636075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9636075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481191.9836075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481191.9836075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0036075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0036075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0236075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0236075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 15.281511070453956, "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": 1740481192.0436075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0436075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.0536075, "x": 19.281511070453956, "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": 1740481192.0636075} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.0636075} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0636075} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.0836074} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481192.9799073, "x": 15.0, "y": 5.417399999999911, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481192.0836074} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.0836074} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1036074} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1036074} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1236074} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1236074} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 15.281511070453956, "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": 1740481192.1436074} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1436074} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.1636074, "x": 19.281511070453956, "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": 1740481192.1636074} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.1636074} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1636074} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.1836073} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.1836073} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2036073} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2036073} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2236073} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2236073} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2436073} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2436073} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 15.281511070453956, "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": 1740481192.2636073} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.2636073} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2636073} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.2736073, "x": 19.281511070453956, "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": 1740481192.2836072} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.2836072} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3036072} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3036072} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3236072} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3236072} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3436072} -{"agents": {"ped1": {"type": "AgentState", "data": {"pose": {"frame": 3, "t": 1740481193.2001073, "x": 15.0, "y": 5.307399999999913, "z": null, "yaw": 0, "pitch": null, "roll": null}, "dimensions": [0.5, 0.5, 1.6], "outline": null, "type": 3, "activity": 1, "velocity": [0.0, -0.5000000000000001, 0], "yaw_rate": 0.0}}}, "time": 1740481192.3436072} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3436072} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 15.281511070453956, "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": 1740481192.3636072} -{"trajectory": {"type": "Trajectory", "data": {"frame": 0, "points": [[15.0, 0.0]], "times": [0.0], "velocities": null}}, "time": 1740481192.3636072} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3636072} -{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1740481192.3836071, "x": 19.281511070453956, "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": 1740481192.3836071} -{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 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": 1740481192.3836071} diff --git a/tuning logs/2025-02-25_02-59-27/meta.yaml b/tuning logs/2025-02-25_02-59-27/meta.yaml deleted file mode 100644 index 985dc782e..000000000 --- a/tuning logs/2025-02-25_02-59-27/meta.yaml +++ /dev/null @@ -1,19 +0,0 @@ -events: -- description: Ctrl+C pressed, switching to recovery mode - time: 1740481193.2877665 - vehicle_time: 1740481192.3836071 -- description: Mission execution ended - time: 1740481193.2983646 - vehicle_time: 1740481192.3836071 -exit_reason: normal exit -git_branch: infra_a_auto_plot -git_commit_id: bb666ba8618d89aba11f7662d2aa8c2b78955b47 -pipelines: -- name: drive - time: 1740481168.1473489 - vehicle_time: 1740481167.323631 -- name: recovery - time: 1740481193.291234 - vehicle_time: 1740481192.3836071 -start_time: 1740481167.9695773 -start_time_human_readable: '2025-02-25 02:59:27' diff --git a/tuning logs/2025-02-25_02-59-27/plots/accel.png b/tuning logs/2025-02-25_02-59-27/plots/accel.png deleted file mode 100644 index 1bfa24a3542d8b8ce480451056b552acba1d910b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 229317 zcmeFa_dnNt8$PZyl_W%j(jbZuqEJ>#Mpl_+M3IrbD=Ax|VTbGxl1;-dGeVh>y?5sK zc-4KmuIq>I=kxgkE|153SMImB*ZcWApXYg;$8ns`+g(oP3^^G+83_pq`MI+amqcn%IlRZf!opODi|gQdq~bnoL0068EU;?)bKOsU1w(9izjOG)QS>YG{^2KadV$9-m|lw&hqO19W2f6 z`*iXo-ATQr&TQQ;R1-(JX*1b_GN~wu%`A5lDCIY=TmMphT@lBvyUJUl2e(%FRkpF_ z(q4{EnX-Mna^I;vvn@mUTSLsE@&z(ivAuZwe|+7cmKhjX^N(-fuXmg&Nl5?oty3&( zum0;BBxfZ^w*LD&?wjuX`+fFMt~vVem+WUDAy)eDuR9X!-u?YA;%|@KNa+6kogM!@ z%=$#dt<1*=@Vc+uK-v#?L~MUuG% z4lXW}+3CE3f`Z)Ab;Qry*+%vM+%(s?2#>uZmA`bUF2eBLoi(-f_4Td$&~Z;)R)~@A zAFDQHtx!@`{nkox;`h^7Z28kjpQ4!V4R&{Z(}If%E6j zf6F_6;XsN{97PtK2Z?O!kJ;QB)#++m85V=D>~H21MvN!G~KE`NML@*kgI-{wCYg5C4z z3(rbshQIsvd*LI{+@SyKjYyXL|M&YI1`3+@aEFh#*^d^F7OrUCzd`b1p`pHBB0|n! zG9e*hV1#?ko}Q}E?<0oF+{xTJB^Cx@j3=xtejPq?G`6laz2eg+-=CcuiFd!# zb^d=J)}_9op*T{~)8|(R>BenEE!pOtM=4hyVCCFjFU$MY6I|QU($W*;FDoLLkeK*g z*zoJCE5-C%{(AA9eg7jx>>l|@@3lvH9y^NEVs@`V}=TExS$fr+^bhc*43}Br2E|9|NG?{H>?R(jfCV> zW3Zt4^;|=fb z*(PU>%F4>rYabsprRiNTYR%zuS{TkWxOvl~q@<*;AyFm7ZXmukMXQjG-{`WUqGFNW zGmV`t8!1LcQf1FtT3Ql6Ik&tps#6^%oNCfu(3ER!GW0!@Ya62wwVs}yyt496mks0| z5#kR^vU|fAqNKb%){t(nnC+u(t_nRt;XM33+gyLBy-<{%fuXA=LY#QezAv$|A+|k% z+zxYNblln!Ub_W(WQ58W#LO)Q1_plQjuv=+`}VD=z|nrFHCF&X7?qtZh@FU(4Hw}y z?RXa#7w1N~PpT;TnI=7+p;eeabgIi&v?S(Yu=e2Br16gwqPv%KZg;%9`>}fR#c7vq zqSeo|oNNQ0&W|2^*REw~Xy~xAG%K&B#-NsI>>chje~9=U*a%fMH40}F%PPTM2}wyw zb%*g{;t@xf7>JGTJH06No7d}Dm#I_gGdI`e`(4AjTWe+MQ+K()&bK!=YU}DIv}S3@ zT%RLHoLm@6FXibmQ(~jmZb(oXAITjpi4Aw6PgF_qiHV7k2{$jL6!~W8KdnAHUKn6alCCaCUZ}frFicLx=c@8+9+~gzYS7 zWfo?qe?HSHK|JgHtay@YH$7lrY&=rGOstT%KpP#7m$jmb%E~ZlL~E{fX2ZjnfMXM3i4$ru_7b%QvN9 zo}J&QX?x+~#D&=ELx&EzcYb_WN-of{J+swHO*-T__x$Xrvvj)IA|D@LF}9Hb8O!OF zdNz;MP*ZLE66uDmZiC6WoX8M{PbWK(!a>= z*yZVi+x0^&l@XK@*k!L>ya$c5IyaczJb`V}`8Dx#yz0bgkp~Tj(30x+T?1{2ut|ZtN#PRzO+&+|h={#N>9k2nNkpt3AAa-Y$Gt6_ZiXrO{KVyjHU(} z68qBMynQQ0?5=7CJMt;jU}K7}u>FjLxVSiRUStG+1`yeRIFn_5`*enyQsp%?81=&) zt!nlA$ucrBh{AZez`@pG`B!hM^=O;SFf)(tSrqbO4eM4K>o(h1fxzFTDM#^K1aD!| zZ?e0?q!;VsiA)+($(L_8?Gbvyy5!Mb@#XeX2gfgeekZ5|nhjaCCQzCFJ< zsL95g^}~xrSAJE`b^FU|R|fIbB8kNF3Prwpb$BFyw#{bj{l>0@#ANpQUzC(UAnpR~ z4(S)FM!bk{3quy%mQp>Joqgj=%ySV(yS$~D@3l=$mjifZh5BF82^gzO2lF2}DE(Y6 zfcJ#qTyqskW0n{EbAkXxjBhKNod&ighV=Bhqh4sCC;e-;)z()y*sU zLff2K5)%_WpK011(sW*$Zpyc}uC2Vzf zwTzoehc)xES}pNCn`gzk94g5;2-k~#6nl2PyGtr5nEvwRe&d|}7@LW5)-IG&&Wga{ zD>)W7aN;wwuOm^UTJ+cPH=;zajt?ZJl$>F9q$VdPXDnFq32|iUD>Kw7S}EwPM`Zhc zlod(U}PlFY-q?>Gq=l*CiU)m%0~u69y{zMUZoakMzRQii+8F!6WFh zw#Nes1`pwb{1OsW3_FL&x6ItT!*Y+sv1<0?r@V58pF@XwKOYsDwfw~@lHU03<5B&i zuhKt`0R}~gxsnM9&)8Ol2)c}onJ&%`rkuTav7tXzSy|bjy+F9cmzir}=?2;Q_3Pa{ zJU-l8zr}Q_Pd+MXu&>Vz`R(eDBKNV$N#1Wc602X%er~H@W!g6~RLe_C&#aXj3YQ5L z$~W~!UMd%1x<@#4w6oPp5eFC06E6wlkFY#um zQ!~jwa79gxBZt|<#NH zs;a8)b0BZ@;-W+GtZte4V#j;Zegv~`cSpyISxw7d^NhlFit~L@zWcejxEcza*PNyI zmKta;EVP&&P|^_|cHVW&;8B9TZEZML;o_y(g35k-UOql0dLCW3AESMD1+=wj`>IX_=FgQ|9fn zj*bpm5fLFF)dYoDpSFd=#wQHADJfBJ1$!1klRL9P) zXIxswZ>sMA7C*&_XN`}GJDZZPo@XOZfAs2|m$e37b+Uj{(F_8{eGB#UO7il4)J#mt zbG^4v({I$r$xGQgQm%dp>#S#4{Yty+yg0rQVEkY(gOEkvmX&1t*%2|;{YS2(NyN6* z%PA_}M*`oOk~cy2^zaq!H~v);>RG01x=MY|sHz6B464nyU9S%FR?WD14b_~Do&D0w zDqaEOmQ%h=!ZpA|p)$@K{cnw1J@AUo#FPRtW#y-l8Hkbb@lxg}`6#L5&dYg`8B-ZI z8`$xnq@pW}ytmEGX;NlULIHBX{TYK*L9rYNe!$#cHYA>opyx zm0n#=6&s%|xPO1$F~hH05mn-vnqiR{TT`uuRr3HI5W=TUpT1lB)!WBMDpbhwwZpI5 zQAtf~`y>rf{*N5?h zHtKm59vcntWR{HYt@`MJO2z=w(hjm-&j-E;#tz?xAyNX2moJY@tWiU7$wKM{$CqZjc zTSuoh%S>nYanpBfgO+_YYo2hZJgtm z&iL#`)hBw4M}1{vBnw)o>X+3I1?PZ_kJ^k~RoYn8SBT73lVPZ`xHwsTa1ar? z23Zkr$#aFmS>^I&HxbAAtLXa@>Vribh0vTvpFd)L)N(-azN>5CP#yP1 zZAbwebww#D>j6f37!tDEWw8H(E=jgwV=|jca)|sul2##8Ww1c$^kAcRTA0Y&Ti+j8 z4Sx$PCcg(f>5D?p(Nh^5W9+J_y>Z*_Q-Hp%56sEUMp^_dhQDPr1s@VdAQ89>4Gr~h z^y}B#uU)&=lx-dxX}K(ez?uR$5^kL1_)qk*T zA#zT{>4%RVZEu!Nzh2ofI?5GHC1`f}hW*UYX;ahJ39PmW#gAvLdOq*MN9@FhiZNc_ z-`~G!+qSn^{&#qJd21uYHx9Msf3HtEmDs>?`0(d$0dnB&W9SC1)-io9#xWl6j|~sX z@qQ-bjg-aEW7E1a|@65Z;ptFNC>a{Rn8iIwbX|(;p;J1L=XL! zn2WrY3}w~TXI7S%QY{CST^h;A$)8jr_=1MI8&MlNQ5@5vm94)dEua&z!Ot{~>8H+Qx{~d?~uE+@Dp;hAIWyWHHo4iL9>_ z{p{YowNpU$0L@ByU(>_6cXF!7*&Ly4cU}<&#Jf7czX}K9?x%BGlCFlc#LKOI*VMJN zwB8ssUoyzYl1hi2%x?NT-c@QgP=BaCMN7-zq7FdsCL!yQSB;xZz`q!PR0+2-u* zteB`wZftC9di%E6wQGBC-@g4QD98gjGep#x33Sr?yQCY5RBDi+y54G17V(d^Yabii zCTxa~a59*zzWR8owWOr-nZ_D6wzd({fjp)b780jVui@e4HCvju3^{JL)_M6CYh+ZE z>qAkdlQwsd6{$9F-fU`Z-Kej2{QwRdO2Y?$0ZY3OPtPsiG7KLg7^86R;*^uo|vIwhU!*kk=;N626ZpptL%B|DMT0VtSl6+P*ptT z)Sw5Qa0WeSXLt9yj{X}J$Z=Vwo%gh3&jX1^IxWo`v}AGL{QAlrJjr?*4(0m~A8u4v zR|ilaNmBNFNWuIAk9Ag7wiH`t)?G%qTgYM)EvI@-d>eMZ_SF?$Y^sLeQca;ZlQ4a4 zZLN?nIE)QAGUBLYHF5I$<`xz{R#uV&(AZ4%Q5v`9xu@$_vv6{5Q+sPfWZ?Ua0OkBb zmIL>r&iFP)*z$Xg1X zwPJG~@87$B|2jO09luz!G$Va%uc!wr0(mzPjiw*k_+0KEp_(<}_kstgQGi zDJZPuY%pre+XZm5Q&T`xl-Y4%rWiY2^ZJ^2=z?7gm?ML4Zw`S`Q8eP@;n@Mo>S>$h z)PdXcDOe!Hk&$T<0Oy|l`z3m-O>mgS9&Tf-K|LUFgr=sZsimc>iwh|cO<`d^=n(cG zx22}0Hl^$PntJ2#>^*jj8hO)2Dymjr&F)i01yQo^%j_k9AKs4m(102r-@jiY8+P*j z$A=VVI6%d+w+?)I5*X+X8fVMWD~0$=2NY8@8Gn9y_7J~}hlhsDEPj;omnYS*%gsSMn*>b2ztPQDNTx#OU*aC%ltq}dCK^H zX+VdY3b+!=q+@9433ltpbfeZ8kVzebgP!M~u)i-a-^|a?k3ubV`!)~Y=l!`k8?5P- z*lK*rYAM8ktFiLw)nhuPzGD?2P+kcE-*kaQcLk?K(xwu9_61;PtIFASXRU1S@~Pg= z&b@C&^_`7w-9oNC+CSF$(XR2Ltn4$Eefy$O-7jFBRuaqxzaAM$q6-WRtOLAb&*Soz z+6Rz!0SD;W%Z8hl3Da}qIyXjIvM;%k(cB+I;jZiuUe-Wa)ioUXo>?8oci`OP4dnDM zzYN9#?$v>~c-hjT9y&lxLvxOS-{=u?D64uRK5QL!!27L=U$0GVq~zn@b@I*~k{fM# zwwJWEBZtB$m`<`?e17!wZEI`V<#}>Op{Z<3uu7bcXmIPWThT;C3iAX`ya5FE*x%oO ztT74*NovXNq=KB>9<}c{j(wJrfj{ggSC&UtES$7f(Dqx{jXF+ry8}>j+S=I-C?*2& zNVOUg4Z}rIQPCSHQ^ihSO|7h+iiwLyC#hxbTo7uwnL+dw(KxUd^eO^sZ;UcKjNO%= zHReR;6#d114M{u_Ze6NQ>3u^awL=FFO5LoF^OLc3aBz6Jk%EctO(9yiW+Ak0bs$8^ z6QUB)0mZ9l-%iVSoa=nJp;5@}$9)+soik_7+yDbo_iM7(G8t=ovHijdN(fG@J$iUl1<1dF^8?F{^yIrOv&sPgk*;;SL6Uu$G z@+s=skzaC7pFW*th=ZaGZePJbzgh(w%XgzrB35e-hanL_f-h>u@9EQnj==Aip0F!< z&1@NenkR7X@k=IQyG^4Ud-j|{^^AMZhjxAsIn&9@S;mTr0q^<3xr-ll;%IQ?sZdZ* z+`yY{XgqxQa6rM*j9Pg~iB#Okcay?f_d`VvOzh6h%`F@orRO(dD=seXS31GLalyu| zW0dqA(ar(|b1Cx-`)(mKjM^bN*Ma=uyx#VKFI(t zd)}-dH!vu&^71N7%*^a`DgYp3L%+a~S2)>QeF0frjE|9#F&Zq3i{bglO(dpfjdmwa zoal!ZQfoi92)a_L`C)b!iRrk+hC4Wg%O482Y})kbM^~3+a&SPvenjLJ=R%O@YLEAy zJ1;Hm&{^XYe<}JU0(sD3G8`G;2A=pa=sY`Y(ZraM1L zJ$nZlZt4mr97qUW+t;pLyES=mWW)z0oIuQCzmU&5YopF=XykJRVCllzP*wo+?(D4! z6)$vJ+L~;5>z4Oss)Kt_ioq+S{gU+D*$KsCLnF--Kfm#om1S^u1R_VYeKFKfQBldt z&E3+=p%{0EXv(ceTHb@ksR1XOKTt6~Gb4r05eyUs2gk1!;jF9g*S?I6<*3^tJRQEW zxKU70P^=jxq63^(+?Dj0wrL~-N*Wqh@MfDtuY>-{vK|d<{M*sx{i;dj6`djhJft4r~_Es}Mrz<#=**pTThEiRf4HE~-Ee!Vzq zhtxF(TIMyxmg9ngn}rXuvy&mg)aAwm2Q%1B_3aJz^zy3DeIOz+uzuaT7sjnQ8ya?r zI-N9b$=VxiZfg3j;t5A80J`F<%e60pNaWJ5Uj+S2V1y@?J>A_MU@m#HV&Z5u2A7tW z%)n$hOjZgAX{4`I(S^J8|1<>=-n%?oEwZo`07?q^%ThBP8i1R-`{~AH4cCb+w4C>q z6N@1Hp7!OvE#TD5bAz^Uo^5bw$P40S$8cu5@*7q) zHMOk_{9A!l?mc|?ux;@2L|fgLFWgAZ5krvUj_OzKZfa`k(-^e{<>!k)QRcT^S$6y! zF4`WK(ZHi!v?*fmN38c=etzYY&YT}_ZhYCm&CUHfBjZV>OxVfhxD3mPT7%c93J%i^ zDpJm&`DKumOu?r~KR>z#Fg>B3(20nix48wxf$Qy;;pk=dqNcEYM?*v~3;=n@&JTl} zrPFd=%8;7@$|Tx%`GJ8%9A31^M{SPpASv`80ZSF<S zyro>++%^#(`1RYjU+o#O$OLq|7(S3#%}5FHSb=cXfiqM_#WGkq~+#7c~jUtJ9ax3Er?E3O5FVH?gKc z!OF_&gE&{UPPu(BpW)M*7xR6!QQRme`GaMFN3X5Tu^#0N4nASc3C@jXP<%7w(T@Oc zdgl0O?*YlF860laMy|hJ6>=!}dxjzHw%x~HoTa!8>D+LPZye8 z$`32>XdR3cuo|14Ed|0Ow@YyhlNDW}hJ>}fg7Zq+I`lSDNn8mCFOX$?19ui7VArAr zX>I|IQDWGk6x28UsjZC(aW96J$Xm4#$YTy%plcek;zvYljCE2+$5nK3t^>w#`HCr4kQm4D7VgoHcK>! zM|I1#H@6@n{DOlMtr_K6!d(e*j7P7cPeTXE7bpHv<;74T8c9T=G5YOoqrLI{ZBkAD%?r;sUH6}}Yoy#OwEG(rcY^k-)%2=-Jo^@P^`z~@%O)>x zZ*r%_@iUj9Xtc=&^61@{sa6BG_#>b06Q27n%0hWh0W@J78=JTqzb3gxpd!B~Pol*H zWV3T}$S6v$?9kWO_hJ^++|FZ z%?1jl!@;??f06-7MOiZnQZS293;8twY0te8HNRGF&%w_A0qwb-IT4LuPvXVS$dZGF z0X9CuZ;nR$Wps3Wz27wyTU}m4Hh6vQqheoA;WT&-MWchPtQ)}vuv@M}Q9GTn#=x8x zd}#CD0F7L$`1;CEdrzETfbJV?R0S~5x6VX-y8p|WzM@97ZA76PcM2Ov3IuwfPJ$0* zPxEKLeP^f({oL!Ga%ph}fGW-TAQo00dn; zJv~he(6@dVEzLHxoki+@=lp%AeNBe|RF!Lqytn*9A?$nBCm9jc&t@nemmtjQhMZP@T5qfwKC-~ajZxNozK zU|r-B6b~ugq!jjj^5jWmxZtf@w+OMPa}hg!)zC2UvgrHw@6!T{iX>bH-SRg2fOw-} zS3H{aloJPZ-vaMbRngJEi-casKZ}IxcE-0fjBQ6`yy^M2)6ua7e}8?A6kXod#k?0NC~e>CuLu15%yCpFUOAmdWSb3^L&UZJZaM521@H?FEjm1r+r{ zLQ|(gZ^eNL%0N7$s6xZsR3cLx{C82(=ogcWE zkJZ((we(nk9Tn(ewZV9K%ArK8ffkq~Z_poL%fLr^4APVVhp&Swpo@oa5~q>- zwsw%C{PFAt5@6r7K(Mg!HRXj6UDd6QPXiOMTSkfc^=6?g1IsE#1Unj$i4SOc+NbewgIaS3q2-I zDe-9=A42wlCoNY+kMwll0GPmMm2u;N1lF?o`9y^}MO-n2zy#y;d^hX2SKz-kF)=ZD z%={P}=P5K(}&%Y9UFd6boUXr|Z^svQ(v~Hdx1_(Y z8e$v?ux6TIt-rga8T!14C68@^l7sa?9X1ElhyV0*M+N_{=;A)%r2=!3L*-QC@x zUZ}+HTXNg#7&sufA#9uKCqWd?NMVCx^bl1JsYdN*Q%VRhirG(bD##zyR|opOv~2XL zr=n`(YHFR`3z&C{I9%?OxdW-_kY?8|zhHxxF);}>?mRno?9k-}>7GDw#tJ=WU(q#j zEfbd5!Gi}6k_pS^WI3;hpl#4Ie-O6JaXTqRKI*}k+>2Cq^}z-@Cn`br=Vx!Qv{O7t zP)-VxOGZ~x!N2w$;G|N5qF*IUk^LIt-NJI+8(7bCKbt-Ecgwc*Ukw}yi}+hGur`B9 znO@52U{d?QG8v74D@ENqrm8`5+-WgOPNwoSi%x2HK4DhiS4dVDw6U{GsHvPJwCkoq zE;hDzXhswVq^t=!fi$>8XtO%=?P_ik^#X@0wM;h~lgR;?Bn<=BfqhR43<#j65lVG{ zPPwxJHUE64%yJT#12Mr`VLGu&|9OcvQYaiR#8^wfe%(Q%Th=2zZf6c!ROr{&nnpFm zfIJK|%^|6>Ycw-%(jYf_R31Nm{3@J*8yYBoN$XV@=A#3F2H{c3=9skc4uCkjrc2y$ zq?!Z=F8oWGEwQ;L290X39LDE}4kXq;Tc zJ$XaVFgBwhg*%cDbiq{-?LpL6C6@!E7rO(ZfZ3H?Wi+L`pY_64nIy(KPieb^e)e5^ zyOyhQSoQ9(E);OKoPyNom>9y=2!jAWqykqkt9$qCA!%!CgQoM)-=E6J$mm6_fyF#8 zKuhzt+0k~DYY(4}q8Ss*hSTjLv1;ho;$Xxz8iA1FF&o*#cdC2cP+s0i8X@ii;-GDd zSQ}%TzvdLuupSZ2@Hf=uK9Gu{oDTs{cQeW<^w|-$gTc0ldwH0PTm~+G&`-ejKw4)1 zCVnor&HrcomGpzJl9Fgrx_WvJ1|%ZydxpiUOYQPVIsI(l>KSXsdTW%=+ZJ1bo8 z->1vB!b-}++t%CyM0S6Jyu^V62g=0a_718nCqz38S(ckZmJOaDr=1mk7XN-&v`!I|8 zfUG5?r?T>LZUebwbRL2puNKm>t%iestLosbkoorQgYfWh?LjJcHiZ~3c1wa~zCAKBLS{V?a8`7_&EfP^4113V ziBXlP!ryt!_KcT1Ea&}yV3$dz=z6m^Yw&-6{?t-gF{5;B%{Z6TOTgXJcGL4%iZ~B`+KvX zJ$fXkq!Ym*(ELF$`oVYd*-!~e0&(?;OJNjn{uTeRv{}VS{d)Q=8poty1<`p; z9Z9FQHFr>=0*97T@JHHG;AC~c>PqQq{?nqMc<)wo+Ik=?|H|pncC9(ZJsJ>I6xlL$ z%XdW8`|sZj{?V^eDOtUlZMt5!+@7@PLGXpO<|33&s#Bkn(Xiu;CIi+GFfI~g#vGi! z_uCp9v_F6Ou63Q|V|vVPY1(+4e{UETitS8IP34S+pLv%JRzjK39d(UNvDDcb>KXDj z7Zjq4ECVN;C#Vg2=Hd^w-UTmwI^*z9RSGuye1S|u;rtNdQ+9$lplnpVU`uhVH~i3Q zhf$XIPr)E=9nqx8$yl6KVFmyZ1D~U7j+Dq-vFD7H)!Uj=L9wy1?=$MJm)j#~KSFf6 z*!n>J`6QPigU~x&&HyJL4Rv*D4J}$iPagQ1-{pVtg-?KoTuedHP z_^Jm2S^!n^!-B1h9xqpR{1SR{MD43?b#_onCg8^V=H~1sX?b}{7*)0=P*G92z)H~^ zQg$kB_l4}Qq!pT@mHn!+TwKw{AEGJD2a2~ponSKfcbNZ^Ka$`4BqYQO?tli-~7QMETSVvIXo5C61Po)_eQwgwH_ zCJWeT1WekFS#rF54HmxH>(Ijn2}ASC(YhUj!{HgQFdQM6+hcJ)WnCbg9sq36DQMap}k^ba~v&@JDfubnPTkQf3>|yPgjWW@1@F59utoF{cI94t?&sS zhNKkJI1e%K9qN=<-NQ{z%pTki4TULpF}IVh#su^Moq-Lj9jV({QI?Ny=)E@}xa9Mm zA-P6^X(p`psoBWBEFvOIM^xX`op4%m{PSyzW4; z|1Vq;`HcLZUETQ?`S!CchYp?N?*(^!NFgS!hLWIGBU&CGxUiL;#LB{gy5dQZ|J}p3 zCXjIv1<~(%n-_&`#z>$O3Q@dON>Zf(sVfQft_JMb-2D89FJHdA(1b~+XwB6pZXq`8 z0;l5k*IuIsW$AiiuMQC%$LPt$#Kex?`u0ZK9CT|5q3Ve+3i9w=;{TGaFAF}S|ILW! zn5wJ<7jMDexU=@t1JZY^Nl4;A4W9A-Z8(>9(w~?6l4CgtE4k>q=H@FYrJmc$LH_q; z6dW=$c?bVnZK}>0*W6Tfmg-5gMT7-7u7+Hg7;A6`|3s!YJUmRfbLWH1b|!Q5s%-*E9q8})qhg<_dxiW14c*kXk!v}@`5eWD&>*s4XB1JsA$2x;@zXQI14`3?3WpheM1_{;#>Y7x+DC+2BC>-z1-H z`}AoG`c$DLwcSoJERoN4Ik)Zo{|lJs5F%MlocLaUi%w!{T~{y2k<(D@bF@h@-B?%NM(+H@FRp(<1uP0-ryp>l`gc zhQN%(C4Sl+JJxb=bS>R{P?o{eF&*Z1nCk!ZIY6i&x48^MEW+TPohTOJ0>AmM3BCMA zfdgn(U{lrO?X3=1iJ>B_;$3r5Y( z$Dp=O&dfZm3=y_hc9l8&tjyd2jznEuUBvp526$pX-vhxIw>pT%OR3K-HY)yHch5Fp zEJD#EYhC<~HPPcmV@e=tSl$bdcPrcBzL-ZkCj4kMX&&DAuavX>!ttfqz_PNlU<3N6o51dTx<1mD z?+LFPabV#sMYZI>WAa#E#P(5x-~>J2Be7F!tvHxEnCw27p zvJ%Di@XToAt1B+Q*&Z1gnZCx9aG51UR~s0%9r&Og@Hp~30U~@4e?EU{xb^B5m0kK5 z^tn&uH#o2K%weY5x&Itbe>jfsmf;&@nU4U{1@!&PtakB&qTRaB8UX(_%0{OkjnY zfq^5yu<3QghtNmd?hg4dgLuI@8(&lDO!y$;VlJf!AQA~1W(!IkG_J7^g<6QjA$khZNloTEq7(e;@lqITXr`6nnn}uNx3|=a?LfD(5x^jjV3vi1=ChrxJ3p+4(p>g+ zGdX!ftngkaztnbG8mZc@+7O-sJ<6(2pg%%*T#8^=O&~0K|D?j=)}4h^B`xh`l#Hi^ zciM%Fv7F(g&1<8W7cWkYzP}G9sp2|(_Ng}G+WB99=S7Isy1ZAeT)7PSiLCYVLBC!) z5|{~y!)cAqFKw6KmqKsC&X5rPCaKoos*a8V!S~{@B-H!O!)?kH3_MAIO>ke9^HVo= zi#n zC1Kcyjks;lmX~cb0*1LLkXN62(8aBc8m$%kLiP?4Vg|yq;QiLsa+|;VUnh9&VXXpn z1GWSh-o*+xB|ZQL`SI&lWqww>wDHNWwA@h0yL);Dls+l~{y>qUs&JfbwH71wpE3cj z`~djh$QV&@+;RR586zc0#H_fZj6@^hcX$*Unsh#?&>UP~CD_LJ8uuG$DJ5s>pLBF|TreefhCdcAeCX|GAHNh+=^hwh56-rojQQbs(qV2p{2t1ARg(c6 zDl+{0cy?dDWNU991w&(6HgI18&#T)ITxi2g=dA%Q=`f@6W9iYjy8~za%?u2Y<^0G; ziP+o-`>lKy!wa~L(?&mGENMk3)due8ENEe=zF!QE5lX~+;R?KrGUu&P)9W>Wbjo?m zEG&FWy`n4N$>;lHVQBUH(7H;sQyzNwPbhhv6TqF8OEaJ{f1-k8)7Gtu5&O&{Nz3QM z)-IwQCHsjI>&~lR)%Pb9FqT;$Hv${fdqT|_Dd9nXNJem;*_aURg61k0u@7$f$CX7T zCG2gbm>HW&p*qrV2^4knXMhC7z9I{WhiePxerze06<>z^<+osug5X&*#vd4t6c?dj z5EU6oUD&pasgEp+{>Mhi4!Vbu*+43 zXTu%19?)8{f8S2&=h0@Z}BbbBNo>THC;(v&r4ur2=t zoRkNG)zYt%gV46nEX3-^sbwY`fg7hly5*F2p+H2(u(KgDwF-dwc(IjW1yia4rW?iBzgDZf6fB%J_Qc}=)764(u|}DeHI3I9#`sJzpjl+hqHpg24b9p z4c4{$V5zzw<_k4)uLmraih7SW=YAS7^929#qsNaUO;xyJ01c4hlw|bzV$glP!0}DX zhJ_O&3Zx*p6(bU9J$-$Nj3WKbAT?3}FaHDf4b4jqio!nzkZT*na0eDX*h;ODM7tFss_Y zy=wFo{%@TUFK#;ut~zuUuq?x2BBOjE9!>^m}(n?z}2+Wx9gt_a9}D< z2N}5~KL)fgWXEptG8fL9Ek7k>g_gCDdc>h&-cQ5ANPvh@+9iYmrFYnQ50G>DjSw9( zZhVoN%P_+Tz%i4y-Ixfd%?%Sl8KDG`fE0EWHzZ_XfG%O0{3rZ(gyo4X7_bW%tdn6I z-4{ZQ2S$!STXfvC06PKjh^fTi zpxanlA3HaOI#sm{+l^GBBWiSK<2`IXdQLCpU}<7h?E`7Nyu7@W@c1u;2Xp`qg3kz|+BMKHU31(mdfv7xc?amotKTq|XzYF}nN9Eba_Yp~IQ~i$sjQ{wEP)Sg7 zNC*d$X)Cka89zYw;zdc^7ei1bxS>KeCCK?%a4_+pL~(_9oHi zpL_s&h<=JKpc;Vn0rA-uM9>lDOatruTpLjP~2xTO7d)IL^Af#Q0KcP6qe4 zx+|wn-H{O>J1Zjt0#KMR>U#gH&xvqVA%1KK5;XwNstC&Azba{SD zLzWoeB3x5h3?H{Louo7G`RqqbK@!uAX{@Qj)xzg8{1l zDVQtaT!!^TWvB~k?>$KTdx4sOwMvk`yoJ2x3xSf+8eYz|I$}37L@>7zrRw>1G{_G{ zz(7PZ5s5ND4C{dWab*fe>V@jq0Z|RwszgaP#8MH)M4W#yfO zJ?iswZsLL=Nz{NEbPIScwV8D)9sRGZpey4M9)cDjo~YE9nRc08ja^n&){BmNt?1H} zznl{cF)%h!wb>0G*}98o9Uc=yWOmnb4M*@zh?F6F(J>rq0195IJ>Z2(3;hF;qVn?dJ9~OIu(GnE-(-Pz z3#k}=!Zz3rHlKSuH6X7A&`JoH$bPu7hmK(5n4cjIu@ppxCJ77UR0S`gn5_OQW$$~0 zFdD!gDAPoreEvKc#@PbCc{ERqkDmsWkNolC%Q7slEA$69hHcwmXK()zR4NpT<-w^Q zU{m=2*5L{8!|%}08i>+zTpyr7Y>=Q$tl6z}(1y+E?>4Na*&)F82Ckv&#=T4G!*3(W?cF@zzq2y>+tJ%FGf@d*711K;)isp$J)8zmuuzmiye?4)FK znqFsL-zMB@fbC9&0LUyUG!O>f~hCL2}3<%&I1iP-m% z95^=IVZzd?7Po3Cq?FR)Q4by3OpwU4FQ_lHeaCe$#PT37tE5Em zb@V^#Kq)f=)3MK5f7bx6slk%Ifa^2s_D>H@!|tCy376DPNA0vaY<{YCF&S|MfNGL* zY$=f{U~1aXU~OqBDJ{JfUU%IZq4_j8yK!?Dac_cuy?_83c6f?daR4#EnEXY@)5F7S zJ}kM`U^^3&CX4Z5v3WDhQsT$&xwsG$5TVTBkN`0@8#T=fKW^wor6(xkZqORRkco}* z;f*?mhi?@nPr+UH+O$&)#?-5*5q2s5K|vM%4(@S9hqMY#!f@$={_h7^j2c6492NCK zCq^jz0>y|eNTE7j*@}b#?}e^8Y~FPX)YQM|V{}Cq9n&=C(3Yim^25TZn353=#n3I)t6^IEn zI$|JWC0Qj!^PuSXmksA-BI{F{HIS1z)wU?Bo>S!_|Fh`Md=_Z zyiVis)w;5YoSd(}%lj6R5Mgct^(x&;M(LM8Knu{kgoC=To%!z|`W$Mz*naG9l5PG1 zZdfBm5z-Fy2Z-Rt5nNfI%Kz-yvxfi_^y((?vF$t|eY4!2$aI8*0zGtKrQG(hDT#bS zbqBeRN%-BweHaALK$(d#?q$}DIUS7~>N)^%Rfa7`hKI#=*5Xp4KmQ*A-Z0m~C>4K6 zwhGCS`}$`(h0JUG;K036*Iq!ROlVBT37Z*d^#s)!uZdO!j8qeBcp~$C`x+ib!JtQ^ zB8-19gR4yV$|(as_Vlv)&w+uPPh*29VC%w|uo!kqy0tZpN#-)de0uO66F;OQ6(@yaqNY85kA;+ypb_X515osgL!-bV1O6qGg zfW$pEPlC{^mHz3iV$KWy_Ccf&*BHo7S8GS2IE~}7ByBK>2c1)Hp*4XOo%ZF+m+v4E zzs%oW`zZqW0$86VMkbUD5}^MyoCswZDic=@5hfY=ua1aY{~ZyS)491LqH)(>WU_%GXfxGXG*!k}{Rr`~u&ss!86bo5mU!8T<`Z)a(tN zz6HJHqqr#HO|dRY``B7d?;X1WHtu5DU`u!PPN(hjjn^LpnvXEYZ@|=v;E=F>^_X4K z&)Z4O_RfXj!uni-PQMCf;Ta|_rqaQERpURooU==FcKg!vu_tHu1pU4?3+a6P9Vtao zsmM$!Q{V~1wpFs|FDHicfR@ymqX{41CE&m{V~Chxei{#lwGe5dLM3d-b@RVZ?y`Y%+Lpwwl7w; z7lF6!g2&iXbY)U>)Q@&INuEyGqrKyq&I_5u#cEj#Bf0jk_Kl&&{HWka@iK8<_?`+> zY%`Qv`UCx!51i3cWsARWR&2kf^!q}}J>vBA^gn_OlMnT^0E}|~y!luFGUMFW%mNx1 zWLm?%*VhO1wZw+m-E`<;Xm>j?n#UW4`vrf$Cvn?ZPfw2y{cNb|$0sV9yWmXHBd%2x zE{MOk{Nzk*|K=GpM3&CaG>#OoNG|B8igW zi%?Xk+ZTHTx)4@Az;T2JKpRU&+>t0z!YpKAARR6uoSgN;BMWe$>m&2BDNy2m9xE-= zibJtQE)*hkzc0$f4XNX3ze|DtFVGtzubMR|sT4men2LVRtt0iUS0<3>K*8cqE^FJW z|Bt=5jH+_$8bCL4#A5&^NZXWvAl-_9($bAecQ+fhqNp^2AdNIAAYBqFp&;FjAYIZ8 zcRqWg?|aU7f877~ea1LvAUrYGT(fIk4bzmDr>dTWQB0bybNSYD`CVd?l9C@GQgdHP z=^Vr~{DD)&(P%U>i!35CG69;yc=`AgveNox1UG+fY;{#oV?Vn2GZ@)Bh^^eRv$G4~ z9}l5d7y*wCG~uX_KQwAyQDrLAf+;6pAlyWzi*0N+c~C>x+#7Jr0K*a`sh9KGWPFgB zb}*CA>kX&5`jd`iLr5SkrpcliVxVN`Nme+!vAo;Jnb^D8=|2^fm21HBr-2f0G>j&z z1)o$GvcB1R-(G#4Sbq848m9KuAfqRdL5-RYJ^E=CQC@btQ?Yx-2-XK;x)fLfAM3J0 zcTCZ8Bj2b$-~5Zi$4QVGt0O5wyT*`ezZ$d%F;HX_XylnWWXe78*j)L zmbrRB0oZ*tH8SY0^F}5!f)>yPS&WbqH%y8g{kYud1O9#u^rO_F`NBh*upEZ$D`*>J z=BF5x=9|HIGuT&T@>>f``+<`E1wl!0zWo(s1vp@E33gth+b>TVUl`sezB?h+XizbPpx0oTYQ4=gcw+bFU;WT{{#kM`R(`9WDjEr^8C1e#r= z0Q>r6Lk=!3WMrx?yl25H0cv(m!|1|=JuXXNZdSdof#+`;NJXL7dXSll8%81h#G`KlqpQ7B>J_9CJp2W94)+sMlZV_e!5jzl--AL{P6)!t7*fk}}Mgsbm_68QzNwu9GYFd3de5eAUB4LKVFn@;IBELXg z5cz0Ah5hNz|Jd&Q`?R0`{pJsH;D`TV3#qLj+3~Ota^^A9HfpkQtj^ z-v5P>ukjGWt%m3~@%AP(Xd?ra^;7@G#3%g7(Mn!7g2@lY#&4e_8bd7JQKV#7L&q%beHl=Fu88kP0F zGpJg!bi6o95GHZYp;7N5gp!@Ro0>opg0aUeA{x>MP7#bKUi=VCOu>1bxpX#%P4O?( z3P-sm3MKH#kqG-f6v}uRjgPt;xj+$u44vg3*;@u}9`cqPRrgj0aQ)BAUHX4==|33x zpA`BJF8(Kz{~H(o!^Z!x@f!pGzm^hMeT|B9G&Y%eQJcB^N-__t#f|gam99oxPkIL$SPj2*I=!>dc|X)ax#_lK8^!5nVksiD(CTO>TE5O};tb^Sobm(hiRF9Q$F(h=-!}bFF7=irsdG^ZgbBnzH;mJqM0d22^`#H7xd) z3@k>6b=8tG^V}@A>ClU02Kxe|ty{a->EyCm;N)JtrkaoTV0SpBDqy}bypdrm`!Y+D zgGY>rs@qd(jfldLqjpaAx=*^Ft3s?PU~1#rtCEeucN8Nu`@``?KcnuaH66uK)-QL5 zMts!DA(o7uQ%x#ewaEevErUTm#%E;x>uFfv~bt(MlZ?PN`y776Pq*{6?%Uhhp+*@U6kV=VSy{1rGoiuiT z?ej)tit?SAPmS#}MgrYrg#raDZ@yG47y$)k@n`cdZ9XMPtbLzh>FeSCHrZ@h2mq92 z8c;9TL@c>ui?>(T-fYtN94FeRHc?T~*s1;^`A9{f$xADDHZ$d&EC0^6f1{?Lg{zrb zo_%5k(Se0yMF(~q#@EGEQeqI)CkUafaGs5tf;k=UCO{u1-~(qgR+xEKt7qz3!*?boE+( zUhV8vd;N@u(rDf5nuVqBIdFJE)zToJKGB<3devfUFTT62e{imNS$W|_N|>c&e$1FX z;goOb)oAN`O&at9$E#KI%{?fu+x|@kj}IHgsFgDnaOP1jb1$pRz0hPHAl+XjP*V-? z-sm_^abViIyh7bT2@~uN^ebhTVty^~?d^`O(kq{VWz;CvWZW~>Y|Skw--%Uo6=&w0 zGo}aQ7cTKUo0+{kHO6K$FZ@cOXZ;TKc6G?Qu zC04FSsFBZHRZ2kjj@ysXGoy*0UJEE8wzm~!&j-fh=J^7zPVViHGiNBWxTe33)oDQ< z*3Lnpc5r-6wc;IpFW+FP1&903qpa{BR4oJ)NQxL$jwAh|gvN7&sn&9AAe?Notx9{n+{UwcX4f!=ot)hug{GtQKjIq1}Xa@tsx&VI1!ztQMd zaf;NRCP@DE0m5`Hp-xyuLCdBNKN9hSHbx}k2Z{5-`ej)N2o@n{421T z2+Y%b*_BjGCMOf-s5hp@o#$UVk;%XST;{JSxVN;Zzt~o>apweOGs`E0W-y~_uV!e~ z)O_eu-tQ0%R_wWSwJ{z)2E3{vV!E>~9$ICq6LX68#B8kIpH0*Y<7=h`Nsr7G#~ysp zXHm)oX|q#MfCz~{?}WXZ5EHWr(^7^ejh7Iv;(_U2G#+b)9wd-XpXc16IE9=n0o~9J zNOThUBSdg)Apn?kgu!c6JdL8awg2z1&SqZJx}e%-)u6K-$@`vD#1-XfKdqH5Eq$*> zmh3MhXZOU(-D7rE6RMXX{V5{k9cJoK6X33<(aKHXSXhN#?z*OU4u{9)uqo7u6$vDi z2SqaCN=nF)4A@B2_S(6j%>^fjuZ=)`f?pPT&J<3$vXjz9qGib06+$~dh(|L^=e^-X z0FJHIWs9TS%1IW6k{qb0*5NglwcDcZ2Ej4{tc^l*iOfwsgU#eVob&WKzHYOo#sMH7 zKNdalAI>Q8+GxlXr&{Jl;5qe;K$$7_b%B@D>a!HleQ$5(CbbU+;_L+uXSHiR_DWYD z81Ae_ovS9be-YL>>kH~=^GywIA*d}uyayMSr)Opo;NYl%50_JOQ-0-9z7~I;JYy~ICD4x)z_~dd{bz+B_;kryy>_KCoS}YG$3Xf~SnIPG)xi(=fGjsjLH<{tU z3>ZePZ(@rau)~VpT5+063PVO>r#0ZCwbI^p+wq}N*e!U!yo!Gm`z&+&{mul>fSoSS ztK-Xe~bp4u#E*M^X5cN0593L{p_WfHUC8qK&zsy*Z>(QKqu_d18LUhmZ!> zu~w_$2mHBirl8!ssr)idowB|?hT+~{2_E@!My#s(j96&#=a~Dmw90o23O5=;Pa%?4 z($(;&3N_3}c?O>o&I%lUB*LODC@D=};rXO9(OWa5ZsIcamcBXVtkk&3l(cCA4k}^i zzY(aANIeo}Eu8Q>&w2^Su4H2+MTiP=a(+-bjfiRpMOQ<_`|HL2!<1{l&+~4(lN!J<-sx5XIaCr#`$u_yxvZo+Re~CG0kSGxjBvu+&1) z(dg4NGB0j6a$gqQ?rEwitk|7{vQUwJI1_B3aXUD6=gNG={$8R5K5h**x({Wi2swth zEY15@SL!Z%c@T4~XUr}3YVU>&jY966fKl*k3hXh0JMEGHGr?#U`OF`i&iP!VK%Kwhnq_MfYmKLN+4bCx?0%&^ z7%FyTSW__m<|k2ln%_93!g~^hO z>$41i)K~&_7GPYQ+WCt6{<=rSWVR3-qEidCE+zaa5E4g@1&Xir8r7Pj!n6e|KW~3; zX|o-+Y3fsMu=c7%wIY}PnTbo<6Ll1+klCw9ott~-4*`H>zV<$PuR8&Sw%!?+U+tNp zOK`{&?ji^&1yd9`s!4DuD4+_)G7jz;A3ni!37oqxID zzFu0(PfE!mF|eUDs}E+YZx(+se*s5c`F1YYtD|EP(Tim&Tva-|jX#Ti=o*SaA*c)9 zu$`B5)yEFL_?s%~&ln5m0)`@anSXfKvE*AYidq!-zW6$oh!`$+$5%_7!K0_#;U;@|E2@~6eP6{5;# zv886q<3}r0Z$;R<9zNa<_3r708_ZjbTkiZnAXT8%?VvNb@o?*kSc_S4<#aFjiaj%+PMN zmyv*;z;arW#^}O$ray&{gTcvhOm@i4v1n->JVm^l z!&$z!QnvvE@yPetJj~yxnob7Ue|VHaXP1`NeKpPP=eE?5VK+erXw1 zR}*wPYy60r8H}i~7Cj1e_c`i@Fb$jq^PV|i$gWKq(u?8UZb;IS#eLDIR`JX)Q)5Sz zcHTqT_X918&BYCK(X58|v`ivfa>zr_`g4s57H*7pI2We75k3vHh0_*kdjxpjH6cD; zGv8`HQDwmO-m|eA&krwl*(z79YY&_hQj;g$U%4&qHom7*6-MoHnVg7H%6{)r>AdpU zje_FaO|FIhZbO@99_2ZL?!S6#ESfa(tYvqM9h^I%Y2(^9oEH>7;4n;nV{yf^F#ezR;}2MZC>T1 zeid~pOt2Y$tGE#2T*OJenmesA_}WJ;tE)z*!JTo9y^v;cW4U8>(RF{x$H+{Y<*%r4 zqRP$0uHCxz9+K00=-M)tOus1RN_ZMBIg&$_DD-zIODmbxdoFlfEu_`M!B(-q~IH{^*{YKH7wWu)gf^;$6r=e%G+~#Tz~`sB&7O zIO{fVT1eo&bRNDH&2ABV1H*RD#ymBOCE{J0rEf({ZhYS|=e)(s{oUKrCiZ8y8R=H^ zZL7;e=2c=%7xv8@XD$7@I_H=-cD(S9=q?Y2o@G3cH2z|!^Kk*;T$b8lwOLSN&^|tI zF^inlm0$dpg}xZy%A2pIm7F(B(y(7Q8|`5_YtB>Pf7RG>(9}%eeAfE`GTD#WS7Y3C zCCyB^1LvRa)8}t9T*QmgV|wZJ61E95s;%Q}+4CjKl3_#Jy~s*;*33*Y$$x|oMOx6U zIO+VnvxQW!&-tC>S+uk?TH)A%zkwPclbb(;y4wi_M%;cI5CazJi_wbS17>7FW=1M|q=3r1^6?j2*qAiIlX#PxmpQy_yZPdr2F1w!=5X4# zF8Ns#jkl80qK+sThk-0jQ+Xkc?6OHy^6mdiHfq);ll_HE6WR_cwAmos4)yLdMN+`wH~yN_UG20|S3;UnNI1J~)YFgeS|kK1+Pr(rOUb^qiJx zSgWz~{wB7^bt!h1*SNSdaj-wH5I`h$NR~T@2{nTn#|S1us=gj$4kx3GLJNwl`5t7l z?^L*p?fP^D0>qij z?;~+t4Jk?ib{R_c3(D+qoY_XyCPx^M!r-%j)#it7r`& z9VHq+QM*+wkjX8!c6Q^BoV7$0yEv*ky*l6UJE&^1yWas=Rt9V(iZgDn?Y_?8xbe-9 z)-wPrk$tWfcgoGGno~t*JIhMi{ak9Ph`)5rm;AIR!3vAZVBxekG0MYg_CtIY{hjOz z&)c@CqDL^7d+b|pe;$x!=_4OL#XbAIzU<`kMFF9qj}yY*(Wb6Dc2k`j+d><1 zzJk_r_eKx!Ar5g7z(;>kcKs-FMC3FFn0cA?qlYS+%j6^PCXzprGX8aaoH;m^eyZ_0 zi=rjV^v-lfwf#~mA`so&dQS0`?krl$yr|e(akd_b!xMGXcuDtuRN@{L=FILn!^L|D z_qx2h(&cqb&HvlP@?yXDob~=rp{_Yv*N!sBiY-n@G>XqawVxgRNOPHDlz65!0!nH2 zAN!~FIbM*VVdWM(L3Td6*iF%rNf4#!{FFIwpy$Ioo^;Onm#;O}Yd?I#A9>RDy!NVL zfcFm(1`jRWAYGD@c15F zMt`BUUxO>r$B8J2m<*;4XxL;7Z3@kl^6!nLZ*43D*j0(#^tcJbfsdZYQV{AD1ZeeV&aC()E>H${opW}L3sFuPR6LF)z-a5jft4k z8Ak#>D!1!ri1s@|IJaoMI$~oztc#{VjC-r<@nXeZeMpf>ov~;D#i{4dq5|Bttw*m7 z;1w}OIuusv2$sJeUhd&rL_64t?T)GW*{ z0}6tIzG)6SE^$YWLrIn=-3${n!G{eqaS-e963Djc+dFT4TVINdi{E{FCmT@|)EQ~p z*12IHrQ+kS6GR3ire$2V@Oad79|F$Zu*rKC^XVIPO2G$&enOez5Z0OPpRWtclJY@&-NoaiTj4>{&2y z6>Km!Gv+^&ec!+Kia>g4J^x)AQ+D>?!doy7L(87o{{;dA8tGj8Z}Vn`0o&DYX zhqs#egto^%*}KhrI@0!d)ngLfP#AEc&)}83M3X?F{ayC1w}!EVjzoAhIXw#$?ne%z zYJNHrITh#UpGhd|f*B2AM3m@X?{&7@3uVk_1Zc_jr0LPyKc2Te#t&F6H%QP(9^wgH z-&GSDNE#{{wQMb4e%@j2qI-E}C}tvtY7Ncp^7C$Q_j${|HW+m_O?X!-8IS05mFT++ zr!6)%%cu`cw$koR7`74bR+>!7zqwceH6#kl+XSc^92J%ys3M~&P`wXP=O2j4L`@Pu z)wF974eo+7`C_p%}BoWzvU zM2cNO^(FBxg)JX(mDa8pt;Br4n=DQZ&+1n~RhZgDOGEq8X(xtWyT(wjc^ui>3R-1f zp^SpLtyFxSG`?_HcZk=XPOt(+%8{;|@D~#&ADAGRb$BwwW2DrTk(|9nQX617sIgg^ zQo9|+`aV`uw$^`jp9>@2C9l4)v@J|5P!Tk^l&&vfTq)Kw#ssxcv0tKqFeFv(0q#70|R;EgR99KrY z34xi!IxG_rU>;ImYP=-FiK1M5B)%m3+(SXa*jzWLd~Np9 zfTL5;;I^k$iCYsJdgQSR(Z2t~@J2U}1)-03_lrVX6>3SRI!Kf4s$=xGe$c2UYkkQH z4Q3F)O1&HDROe4?@!2PLot3Du-``#SVk+oh(mfPDU791s*B0!uwL#?eHH3X02h0O@ z0t}u(;>=cTRz*n(uQQF~lDM{NqQ1n`l0f}Rua7*hN96v?ONP0>9L!QIImVkDa@Sp^oj!cBz(E&x9={TG zGY3W|+d-p^bVWHFA&&*oc_Nz2nNY6ug@!e4ABw+aJH{t^YcE!vxmDqe#d6Wuf^yr` zSkIRy0cAyZE0+DHXpRLjnslFrx5ni)Y>_lYz2LdxGW0`qEBLu`>yOp2uEOd|`;{Jv2%?rb4(O>cv=mnhllPrqw`s7Jv^+dO}$tbYWEa;?`6J! zpN!sSCf`LjRnL>kri64#hFLdqQtYAc6;^lE=4^jH-d2v@-7nN_%8{fmTNz8v$d zqeIJhsQkE?GYiIua~rLTd;-Rn3yY#EDL13>wJox_gKDNVppdr5l~FvF_qBXP`GioF zA&t(xSoF@Uj_Z$hIJx2RoIs$3zCH(G4?a`|ew{8}=(V@$-p=&zySzJK*|;p!p_Aw8 z*jvcb_~l4A@xR2F;Zi9o&n#wN=~Uc(4f8H7omls{j2gUQV)tL3Q=T+C!#`tfq1HYL zY6r_ln$~A~f{}>%H=$T3C;|@jr{Y`l78-)qRf(yUM$-1tcmY>=b=QY0&_uXcJykN} z{%B=gfRwgk@s5N}MT#9+?&3IC1&`MHTGx8{`0%K>!d9yevC9yQ8cDKSnJf-j)5>z` zc-Ly*RfY~(KlH*NcZh3;=orfP+XCe;8&bDTVF_CQfF*6q-o!$iE`{~v5YF&|=x`sF zV(z5N&vSL4qMlT5x6igVK}UKjJSAtyu_>m^&?Qmf{h^qk!t&LODO&f*oL2oCBJM*d zRPs1f7=rv8dcb$$IsWkdlR&1>b~>09JGam7KQ~G8MHP`k?T5byFwq{%Km4&hkfY?dptC6Eppmu?j<6XZ)_fvw#YK3U`qS8m58G+l%Xy{V9@kDw7nXA z9yK_9vmpJ{3my!wlJqHjTRh41-bHVYx87w{&^yy{*1Eg%#$-_rC(2TH zNP=tR$7X9`tmOWp!qDAy0qg4mwzGN?^huHqv0?5%^GQ<*%N}}cg_~+eDk~S{oNyHYqn9+aOz;eY=M?FgOQt4J~V z5_t@0{J|^=lvjp*(s6E|G#hhWB5VJv5AG?|zr1f@h;PNU)HD@Pu@aEAk!#8CaAja| zOuUuKWBYE&*w(wY*I{#H>mo>GMU6bS!mhylGn4tgv@stAW;sIIlM6-s{=k14*31Zj zWXR&jdHbxH-7Tc7A1hF1boRHtnWAbO3*vroFYtZqiwVYDRbsNl|7FF;!@oE79Plt+ zfu^Stur{d`JOj%}?XsyNYLi^B+o)b$sR|mMdU?6FtuV&@VcvSyr)EyMHG<){_?4$3 z!w+!(z6Y_LklvVuu8QU81u5+>%CU=HTpu4Uk;ggcT5?i}Xi#8AI}~%H{22RsP#@cb zl4<>;?(R={P)QYPdNee;-+))iMYC>`aP4n?TG0_)mvh#gEMQ_3=W#n!RP}3vcEO#!%*sZ$ zRtSmuq}F$9`GkTp>TM(#?mt)gWsqy+%ZUT?&-o^H30n3_3thxiyde-#Fa9RD4^_BR zFtKg{-Jr~Ii1oSobBms@=UCZEKP0A){iG|*#Ve}nQDauv+OGAV-IzcK-@ZkMyi0MY z=`B-QW79zrxcecZiGCtUKNwa5FN1Tr_La!9<_H4$W>$_ge%}e87lhcjKem%kuRm}fLSouX9BN-jtb}FS4AuPF- zuo{j$;t&B8f06%VkGJ>BWpQu3L5(P>4{s}>@9>e_(on1guVLBmqLXw+e z)eY6E2$Rq=Mg5%w!?%S}UWm-Vv%=R)j_5P7l}d}m-ZR8UHW#iBZ3t_8=NsB=9L)0g zaa`x_3}ll%=3%Z&D`~|>^sCA-#abCkn?nXrs z!CM|MQeWWAd^^;b#)+Dt81IqELh|u&ar0q;T`Q~*Kr~WYR#rwvQWGQq;ShW94e=MZi%dg{pmLJYR4VEUj4txI{fU zJ2R1rNKVv&P_RX8aj(J6M#p5v%%VqaS+TtK4CtSiX~^c5EsDoN^I(MORF}?rNmmjy zWI5zDc^3P;xom2TZ-w2}L`w1ksWi>u)=lK?1@Y(`nV;}G!ZVWJGSL%b^Fr`zhX@EY zlBsKHNmuO6R19uM1fXYir=X`;XrhT14vg8_9opX=>~fnFp^<<=g%dk!!aNG1eU~gm zUaH(5u(1j0Q$=ZBw=x!ChnIc0I_G&`nth+Ih_*uw@4(rey#ZUxHwmdD8K3I-bq}rq zyEeMm)pr$J?~Ea~8R@;d9B5ih1j}y#Q@OZQDcpd*&Vld31ob zbhY}>%zP!DNX3F|R8e=+xBsl{E%6f#JFGdpGnIDshx%&-}0D%om$x4I?nPjaPJrKzLgczf>SMD zE5*=8%_onnr!WuO4$3)_Xdn_V3)9NFSL_`J>{YhvRLWloLWxSsdii?U6f}GC&&)tK zcMOv9wHx*0O0K1LeZLOVHU^_DO6LmlN=jU0x=>8y<-x8l$nG1A9|BnvMLEVf?%@+n zMG=okqKrGU&K+ix>o*;97k=RlKg>cjKU~}@1enJRZabqivK}kq9_-Vuf>6ORrQ$xO zLa<*Z3!Q=;Cr~LN2->0rw^{-$oHLN@uglQ(V3^>_TVjN`Ikh04J(W|>ELlIs21h8- zp?7C=WFgr6b@1#?OMpB3?qtB;|=8+iHF8G3)wKlfr% zU?45B`wt-)(HLFL?P1TmdhVYZ!{{rtu|>^86JZ`~R?Cnp5bzX~L+AmpkzyW}M$%P; z2?`zUhczQlEpF@Nii!=}P%Kweb0c|)%24)`VjOuoVcQ>y0nKfk-*fE_L{Fs=hy3RsIlx;U}_hL%pDUf0|8mueD{)6Rk%B1k}?usVsb1R7)8V)v$Eli{dXz5%N*gvKz0-*ZTJoz&3c z>F-*A`GF}?k44fpf%X1i!Od^7$@MH1ZcilMN?*j62b*wF{c^D(2VziQuqrO_hl)hvrFUhwfo0vt^dA;zrSeor@8p*-| z2aPRHp$$(vXc=9Bj#okSa^#Q{Qi9?FJ?CxEeJ?LTj|?+|nae_DQ__|aDqw85)bb4m zA+CctArZcY&vI7Px>NxkcXP!{7DP7Y5MUUOX%O(|02IPEdXJ1w6J(+qhfv?oURra* z5nh}!D2%%>h)8C^rK_~HbZ|AZH3>yOj`;!P@VKXp>S7#cCYW8t8furU5Fvocm}K!Y zH6ms$Y|BfXO0zp>y@h+z1AazWBWif;5*Qts|l{BnfUl#K|X~)g1ngTU8E7-ulV##MS;8~alb3G- zBFtcrm=B?q{obmQYxKEfS!*h`k{UVOAQorX3A@0dhR)|wnh9;AHYcY=={`};%LK)av ztBFj6FOa39<5x?@A50dqJAUADRJie_=zviU);4wMT4M5drn)F<-4kHJGL z&AfCh>kn-?@)J$shYo6#e}Cw^nP|OdPb*ta_*Hr=&f@|)`@y$Aiv0&k_ zfZe9LW@XaZC!PQoPy~lLisS*364|;gAo#v$XLHCqLjIiffyAwJ0`5iq)%Kcs`1-X0 z6y^0(B=4i9$4;zwo-Oco&_+%TaV)(k*dJia$DRgpac!)sKwz zpfp4O`RX^FOZQs{7_f`DfY8hYg2u_wA2wrSL~ETZawQS}LaZ7m=fm#9rTq`a6j^A+ z=uMFf>331xjIuzI@PNp+R}o^SyXH7}-n_!XqwXXA?D$jBcPTb%6d1+`6pU@|!8b?>ppLghLYrW&{Ke!JovrwPd!vc;ud^%(@ zTBnsLU;p_W4)O$hxxq`hEsByt>70^KS%STMYmiFq8ySS>9X>Iu3Y%*d^VF#?g*GC) z(@d-S?%lo3-Bfj6d3$T*i*WtkFLgnN-c^T|W9gcEHLrOOg&p#RKMJ#yd5+lhNxjZX zNKf!MU|%c|os=@&OtqrG=mJe_ngh20r}xXR#}yT?Lhb@#W4I3ZC^`G7V%}qoiw)Kd z=A(6Ny^j(4y4}J{XBpIEl%7PR6lp~4h7c4y5dp3U>hEMmtxBTfTykXZqk5Ux9MgW5 zXXY8zB3{u8(V4i9vxJq`FeyK-VIMgVCvmCFsu!-S@^sWU-dBEA$c~NttsGtdP)ZO! z!(^KF1z`%f5)fWHDV6uQJ5BWX)1$_r_a&Kc_BtaVJ!;{3aUrWsPtJ+F_Z{|ToYFv@ zJ!d|whT!s6o%*3L94^Hd01kIWj)25>KK~K`owuK~aL(7HC%gam1BPj?a+(%lX`x`G zT~jSZJWIIJ4RDkIw0Y=Z%XC^aVI}-lSYd_88|2^jvnM{`nEm%Q^1+A;QsdYs-X8$cH zjhQZ-Ge^CFox=ZslOt-JT?0O}r8G*CBI%relqoqr!1*aJG{D=TxW3aJbp}EE=^{I< zrVvz@9P63Y2>mx+4#~F=Sm-J#R1}+|h#WK#S@0l_=+M_el%}M3I`f~GBi$)PG}`g6s){l`v9kyI)qP8ignZqAgh53N0N7aT2h(2MOh+u=%r{~@vW}D zl*AK*zk+bP)Z6fj&MDf3*)*}k98eh}5d7+{J14*v&!3WgeZw|*~g z&4?579yBk)fLzi#=^)DT6ui+>ptZX5`y6>uXfcrUdX${fbf2zwv#;g?Q%;VTpc^XvHfM{@_ z0MTgZ`LAWRFWo8m7uj4gzCm?v?o~pELMia(>sifHBM4b-8B>RZ4g{npP$^OE-o%1~ z!bxu7lGej#Kb#1~qJ|{=UY*OKFe1d2{lHU}gvDkaV6$BaNBlU=k8n7(6tJP~am{0k z26`6&s)Wk=fat>cGS9!4$fbSM$>m>L zA86!<|P>_H{Jcs2_ED1FwK?L- zgfJFr`~o8Ei_NbAL`4U>8D}uiAtb3Gk?LpiACkwBBSQlEA2R-~N(tr=um>W_HYrr5 z?`kqfpM-bEiGNU52_^}rO6%`p4UB}}AeR_o{$S!ik9~^oP$=&IG^joj`lFE%{&Ld$ z`SaHhuT-1I-iZ251nQK`z9inh%Cd7gwjrj$_0reTAG zl1#h9EVN*m&iXO7g|d=k?LJ|eXwM~*a6$wc-+wa+QLI?$PZAFT1$Cg^PLNPo$3{@H z!PBI@#Vk$adWRv`} zT&xbiz|=_M@FSB)^Oll^-Zij3GqO_3AiO=9Iz5OvHHhn0+wQW+rFaH<_{3;BltwrJ`-VDom1r{+}*#) z6GSY|c;E43w7fo)3%5;zTa?pYC68+!1BUD z^EKyFvs#`oaF_|FUTPuebsX)r^3gFDHYwKQPfd^hHte#oej*}nNzLM0y}A}p)XDwF z$Z(MygEWf4F)fu6L>a*Kh8Sx&{1y3Z;8aT{kGcSd#tGE~dC6h6-b%zUIq3t2Ko2?@ z5xDkLkb+IH4q8$l|CigC7gN(mhtIdg^bWA)D5t$g@F4kD zE0fi)#e}IC4>!Sq{h!$@P0ZyNcE6gk+_T*OB-!?CA|sRu0SYb#oazEs^RV3~wjj2M zQL@wV?+s8z5a|JWHUbF>QFM6`YHjiI%e7r?6&1^-Qy%@>-HhdHo?&zMAbDcH6{a%J zB6na@v}1!rs63|LN^{^?&MP9}6yL8i{Wgq21cE_DHJ3WQGlrIpwcp@M3Moe$G40Om zZ+WyD?(Kb}$~@TSX{>J(NP_=FE6>MYS+?5i#46B{Ciy7@9WGN;A)$Q+>4{VveD(Sg z71mu`t+u8!f68foVZFyo)T%MDpPWp{rl~%=al>QHU~YpP8|7R1>{7C7x%bxY0Pd49 zIN|jDh=bPqcO|Z zB4s0?@Rv%;yzU{N8iHY7x4p-P5@FceQK%mW!ockT>GgBqlB5$teqD_$!TZ3S<=4!l z1`i2$H^%GWZl?#Nv+)g%{zk&yi1mu2@)kaDdNvdPZG*f5Y<-dsLa6TpVWs_F%;t;8 zK5k7?hJ^L$rzcP#))ZWM2U39GuTij|mE{g_YsU|N!w4b_QIN>sOpQn?xSEmZH)2N< z=iRq2_j*c)=#UKLFWJC2nTZz<-pXE&lP%1DzbwQnvOB!Ydi}PV_(AL*N6~JrnoNJ< z_Pr3>#@S6Rw}UuO2hehvIgjU`Az@>{I;P!GgYwR+E8)n8;M)3)k72g%zpV27syHZK z<-flgMmAf7uQ%4bWH>g;3v2qFeB6@r%1|ljw~a_8(y5L zxU?_zeIEe?9U5_@dTcFGSqkpKUZ0ds=N>^BiTG?*>VJ6Ir`pkOe)nlkC}HJ6BnPYx zn{BCakNP%K+!Gl014TT4mTB~=9cRp~i**u*!ekIYnkARxiuz*|ug;~awRz((|L6XN zv*yE`${h9-IUR)&l?Q%>stNU3z)TKa5x?Vsb+`h-V${jIAJn?3S`L?vBW4Zoy{6); zqW>a+Lhy~m8`LJeaDpA9{Rb#>MhQghUb(F%+0XXd8Nu34(a91q;#{Wc2jPt7CZGtE zXb*~CN2Fj2!TxUw!_!*}XD}9Th`<>~urB0Q@T10~!-y%2VuSmN|4F(M2pK8+%qTr4#WYUXz4h_ZOmEq-Xl5&=c&EyoHdb~ zf3OfYcrMtg5chVF*x&vB~?+y^R^aYUCFr~=4`1A96&B(JyOe3I)NVcy`t zQ2%SmII(_P8<7Y6T)4=7<+vTuH0#eF_EIA64vZQsXT_x&UCaVs$6VOU=KeRL2ek+( zP9i46`~yp>fmCPPQXCw=p+0}|L?IrxssKmi1i^4CHq#trjPRfVgkm@h{|_pC5mXwj zwqJMbs|)XvQT_V$#7pEGku6+wEQL*ZAMlH~3;#)<6;qVxJ!P5-~Ll(kJW?| zr2pYo^#n^q;|_b1%ilaV_ahJo&Tra*1=l+rW=tXDILw?7tps0t1PXDOO@+M5Lf&xHZ*F9ipe{{cE^?b3U1kVbfwRsgs%_+zd!p3k?QaqD?OJ#r4XR4gmKa>#>)^rk zDD9Gt(_K)fv!Qq3i~wcK$RUkdcltF&+FG$aTH59_LxHmojy0<>u#`5i2RJBp#0yX& zwQF$2BeuOT;$iDI*4(@z!jtlG%rOSdy1QmbO{azIw;TpEQgI|&WxPEwJ!BgveE%q> zN(EB0Icra$CsQZ7r}=^pR}QUCS@Pd6LC7!;V?L%v$KB_`3hV8gD)bs?kkX|IH(itOXhF^C1gpSu1!Y&)(vTp%D*f?ym+{Www|P-Y6WGE-tOYX^ zvn=C5+T*vT{-}`m7^m&LZ2TYBXWB*}4{&@^*OHDH^&B5(P`5mfEbsvJC+~T}TEec| za>l^k+4|~7>;r}|YX`v!P$bB8gY-ZRQ5)U0Dfcqd2-h8!A4WudFP6>!pNHq<{#ddWA#)f^a}q;X*)hr9jJ+8Z7lyF8u=;mC(Oy*l z$hwDw2wRBl2~A#E_zFq;sk#C9yoiK&jok-Qw~T6W zOTj%A#D3n%+wNPCNjN?QCYlcJHS)6%MrhJ-gTLfhu`c`ut~i{CIK=d2fHkOKo`6B0 zgn$s$#A-Fg4=@PZURo_tf8A$TM|IYKH@feDj$IG~D=zh}hJ4sHPVxNnAG#dBnwp-P zGDD;^p9o*v$4&e2@%n$E_R%nXD~EWxK9TwmY8Lx;*F5|>(=uA6GsMlvldy$<%$X}c zMJ1N|zmFiV6o&gQeO+L0$c9`05H-#)0iwR!b=`_Hvl?@b!M4Akl?S^6QTnMCDv@50 z>v*V;e(4W=9$0$IGC^JzhZ}1+t_bopeMnkH_%7pR`;19PTui&3Qs9?=LH?RK4x=9z zq7o->@G$gd8GbkL6A0X8FMgxU)jcKSt!xDN|5zpjF_#GMA*e(Ec<=j2{UfrWarQyf z4qfRFfpNP-((g{V<2D&*EzvQ^f0Y!r)$}aL_^Ca8;y&IYj)>HeOlSD#BEZ{` z4Klcb|C;T1gC&Yt3;FzqQDnC`e%`XZX$F}qd@|ez4)|Cdw9GMQrqb4P-|GY44)S<0 zU5-YKuLp+LBWHhAv!&8<)Fvy6{*KH3e(D6jXo((PLpEV|0o#`k`abJOR5edVD2`dA z;P6es-T$Lmwc-@@5JYto3~xUB^NmS@5D3Q!Akj1gR8Y>5I1Y*;^|fnwED`?f;^sGi ziSG#F)J2?0>*`3q2rGXGE4TP>^9&OYxMjY|F3w@rSGO|~+K9xz^X>}8}&o8&(b?Jb0g&n?)(QDZAqEhNtT2l5L~l{c${7 zl4FFfbOV&7@~eNMxxdMK;jGbKVFOL&Qv!31@Q2-O?L7_`bwO<5&Imvhh{IENVP}yN zDeO-ElN@t23&Oa4^6}o>C+sa?(;`c{!`lZ>R5msf(pfeG&~+C)f5#-T=DV=kV>az2 zgHiH4bNw8KI%_O^0$Y-&emX{w*t#)jiT+DSX-yqE_9AcWA-xS}`YpUVGB2jE$BkI5 z-CPMn;@^Kt91hHOd)x<1+#!X7Fwb%^b_1&(fCjmM${$jhHT)B!t&fJ&ZeHQh z!9NW$T!Xh4-j0>wz~2`BNXq!gB<>6U5y;+l4S-Sg6X$25b-Qi;&#g>Y%tkAy{ zT%|%HVI|07&s%-U2ImWADQV#wM*e=u$O?%6DgHndTw{}?&%Hq>!~-0cn2Q+SvnS>- zOCI_2Y?7vroH@~c#fYhh4-{p%dx`&r7{IO?D#w*ZKG- zs@I(HN%+Yn>+jYb84Xcnpw~TpV_f=Cdtv+&_02#Gz3-Vv?U-8>94{{r65f6zdMD{3 zT|@JV+uGp5bARV3muOqdwcZ)+^{rib_qz)nu3Du{>J3x-#hK8GN`U%$S7$qV$#|tM zIq=dILKJDYS$LB@g1YbCc*AR}0>RT~e{*g-Vh{yFmj|EUO|p-3GqE1FTV>`~!)D0g z_BT|{!rStXl0(ctNyYv_v;ZPX@|eRu^-0yyiM1BIJ`~BsaRU^t@cz$NwyWTrMzcD6 zfydzzhG;ShMMjpdB`hfx&hDZwFUI<+AS0yPZ0ZR-ff)=U$YUA1WqVcZ|6%L91F>$u z|KCzP4S7NXg)$1+dxTQ5%WRk#A$z23Ev2$|W?7-KGAoq5g)&1{8Ie&o-*dh1ThH@+ ze!u&Vr_bkhzpwW-&Uu~JIoEZaqpmkd;)*|moyWaeRoCvHq4hDtg_#E4J~U$O(K4jW z@b~$1++r8vlTFmM`bl4e7vX3R7!!ve^znS&*IKdxepYK8_N=Z}88P(xAjt%4c6JRH zU(JHY+t8UD_?*XsE^^D=Q=#?WKHCcGDfDPR;Y<|5olKdHnuzX*`Gg`W*|gpEL`PBv zA2scmWqI4pcIRypU7h0Sp&eHFlM}#~AcDcR+dQ74?91T*P%!v-yCRL{Z|!hS)uns4 z%S!b^U4GcfThwL7`)T0M^Zt?v9tu0XcQzyyn+!V>bjtfO@fpvfe)^%E*T!-H|Gd|O z$X{nF%0D4v^-(`$q)*({7{?b{;T(OOL)YVA1=>pap8QtbL)NrWRuJ)kiRCe6Vh!P# z&35|2H)Y904A|_%T^>dYI5PNZ_vjxwvAF~!?e4uGYx4{qDkg4>4~>4K@K__pZ^|BFD5u8ulJ-MXUVw zGUSD>F&kVnP;Am15Ev7$EJI-^_-rmkK0wCU<90h?Jqvp8=!`_JR|v_!Gg`>3q~A?Q zE0a&x;P<^pkZdNMP03ERlDZ*$FZ8fQkK(N#;dBS!?+IQGE-iZT$<`P*PssTHEO|&A zKodV;S>nUnNmiiO9qPmd5lrx47t^>Eq?!7-m+0sG(d%hJx;(x2s-r@woYtgvE`kJj zLV68BzKZ*;*L^n~QGy=T6xQ(7ECB?1G$s41vk0BvcXR9w?s<6)lYCJRJD_;|!DdD< z!V{cHuKd5y~p8#fadJI}=vJWlgxj&b4jm0A!-!i#j(qEOkU zX>tn@3Pcn1M!nvc#whU;O;Z$(%Dz$s;v+fiT1ZU=&xijbR-mSOT7w#+58aRH-G97E z*$9K@cI}-Etv}lg!$^V&&FpDK(L`*%8ALICo}z5T6p;46!t(K(cB&N_s{lJJzU;eg zO&i^dNcK*!P?}%3R;6jg_K9_qaX-i12I@ox5w!U8byxo`y018yH#v6#nHLXM{c9J- z0qAgOps6)HJFwoE!OI-{~!6>eWTC{Yw{%x$Udr8~Dh?e(C1M64;># z&LdRR1x_hXS3))xV<>`zlER@xaFRo`%@52@Ok9Ez?}PdETNfEUY_8Xtw#l-Y(lEcg zmGky$z3wYZXw1;LDvq}!z5Q-l1FU$pIp8+_5-d=Jv`j_~Pb@W=Q$GmB-2!xMidcQh zzj6oYy*5`nXkW3%9!hXmXKpNKR&PHV!&|OM;(3|<<*i3#TDz!^GCEp3Za@<(cz!on z0H+g3$Q#0M_1Vzw4|zz`TLCib{TMF=x|2NEX&m79O=_WNro(Hk!@f;LDwDNwJLPhW;>y14!siFLwqP0wB z+|lZ=R0kARymn4DHH;MFdYu~jI5Q)?;!xS0EdpuW|F&8(sb4%-e$3q7|CXr<&R;_% zjxW@%nNYe>3jN>3FoUJALbwBwqItONLs;vCphBB2cQk`wjLL<&m_{TF-(M*4yc6_?Vzi5Jww(Xd!rE*^>A~tlH+0>X+v4NKSGF{y zhJJ1HCG*Z*n(U%czZ>euiIiooC<`Xdn-+kcQ^<&e7qo?Rj?gSJ|1Appb?r{ZKuI5z zk4a>99SYUljIpnxwf}l=zwqoj#;PMIZyQZ-+DaRR+dfQJ|BWekhY&QuE79uhtmS(y zO6f%07}ci10XdZUhHf^`REd;i&%AUUni2I}xZx$jU9vbR*G&3THhErLrBxt8De(fE z>Abq{yYM324rs1yQgAJI=Qw~S*T1#kdnn3r0_pm56MVd>&q?y3;wu%!*C$Y2Z8$jW zkJ8lX!lC;akYOHG(XV%1`i&(Ss^JN0xIY>zw}j;>T3pW|iDVpKAq(4-*d!7zrN@b` z3 z#19L<66w&C&`a;nP&+k_%zmuy(p2{e<$PLkwO)P70_K6~mSlp~*dC2rPc{FGIW4qa z%c)*;3%!o#e(<5fQA6k)`XrQu+UeSit_b02CgJG2ZI#vqJxF?ilB0=EznvR=H|=4o z-dN=JWkSEhd3#yFvE&Ym;Fp;@yC$V}Mun<94pn-}0X*&(GVyE7y8(@aFAd6$6|+R> z5@TQvLgr|0@ceL4{^0qEQKUyGf8eE`Kc^{wzzvU?u4Yf+xVe~b?FlmcoD0%LHn4wKg(3x@Tkpu4&o2 zPZ~2mg1Xx(^XsT!Pk`6zP&TCho1TpO#(+Q?>nhq)Y zl9p|X)dSM*Fgm`lNQLYFI8{hWf5TNU+sag_UuoUO=nha73HiaFcbn!K%%lWR7rKq5 zW_-_8!14IGyG^87oQe56BZC#lyeay^*+l~jM=Ad4e5LD(RwieEK{c%Eh|<-Ov^Z*}XE9ga zzc;*1GC(#SdDka*476-Omkf8=x&U>!xJ=R?x*ylO@gMscnAZ%|)$%e+=aYH-pz@*W zuNWx2bs@&N+aj;J;llnh7DWrlf5uxYRySO3DH{FiwbIi+_QtzJ-k+`hQIfcvC&Fa- zT!%>NrIo?`r59J0l?;|!<(ee=SM(vlsb9?g?*;0YWA~}>VlnkGNq#Te!g5X~H&B#W zUqBBwJaJD$oZz3x6`ENcsN(5`QX}S7zx{cS$7;Bj$Mxf*YX+qw;W~r2$QjIsdu6;3 zh7+s=Vt?!%r+gbXX%^5$#YVOas(8hY!+%2Cc*7m~Zq`30$Pe1d9JDJV@rzl33UrUr z{ky#C7kY2ydOQfV~K9~$cW;x?5<5FhSL$_(K@B1;>sW3)}hZY7k(1pJc)WC4&(o zij&|qtn@?CFLKA@ByrQp%`Mr>Z}Rl8vRA!eVDmB=UB5r|i`#%Ac&|Lx;7-T2`PJOt zs3ab!7d4bk52$AJlJqIR0>ugi!=b$5Ij`lmA#c*%50HLZM{GCcOzN=sxK+=w$bB9N zj$A8vG2Q?2Vloun>vYFwlp~giDuRq=&1b+Rot5Ro_YbyyU;5^@0ryr@Kh8COxDV-r z3uo&%@f^({%*}4AfGCI11jfL9WxB(vh3D3Tw0OhhgQ%lOQXnOyQ*2J(G;qB*}yXBaac6Q0FyiPsw@*~~8 z+4Y@ixh80eQQ^PUNV65bL|Th{{hV>d|GVYI;@-L zLc!y?bsS}(%*&hx%YvXl@NzjMy)~|UxEE=ynE@nQ66#xUI~U?4b42$aagxAfD4*V5QUW%$Dan7SNx&f1 z!?E9Ep>ixWo&hc_d3|(dZ&AR}_&o?jmz8Txvi~WFzldCrv&<=ah2%Smwx0BISP4m_ z@Sn&Bt-FMO6HS8JHpCEnj&@+8H~pG=Ej-YH9-cN8Yai%Als5zciNU$^`* z0qISn6%K(#%=GXm5qHdkim5l(=i(X99=fi15SDgkXX($K*>JV2O5g3rUJ!gURLPG4 z)DX|>d%Z(%CM?sPwPg8IX4T7rzTyE#yu2M0+pa*@q{yUeo!mE8`p+#}wF%St8A0Lb zm$C8gq5SKjbWLX}n8p^Yx{8H_ZLBuV8BToWII=HKPmV9&=F(!v^|{{O8OI; z%muH#*@|7(*1mt@{No=z6Y+&5JvO;Z6P6`&AY!U5AENxm z5!EQ~Yc_~X)k*S0G$5K*sAe9dhMsE_sYU}@Oa=A?tinra6tAWU;!AH9d;N2}6nW^2 zwV95w1IjJ^qTD0pbH?d$3&q6sQ%O6?v$`6ccs;EBc~ z8nH7u5$}$Z-5Fa8^MYEZ)ukINrPa}W^C>O?UkdGwSNkAIQ+pEyE2rs2J0N_&ye67e z*$qhfzY>Ci$SDwu79{EA_;>in#G<6}jiaNZK$>yMoN}?k4eckrp>M$lTsic& zYuzpZYbgCBT!Iy$%h;xQG@{!0#&C%@Uz8o1SQcSrFbDF%lB6=iWSf}NMR#<8Ottu5Yo>+1*}sHh98-{-zM_@&_NweZ?`%}1>z`t#95tt2RDWQC#OG_y=U1PXHm z`>%ch2cS7=H)+|60Yh z7PBYFR}CJOxSy$Lk+IOxesPf@HD&E z0BWr(t)dIPk2!AJERTIFzTWnX!z0ioruO%cJ-cP3K#&7#DBt?}kX(^&Cy0Dm15kA> z))Zyx(^1Mn|6!!B0mwd=NM(==5bS{il(KACx%)KZRq-{sPcmoswoYoQvn*z)pfW+P^}s`P{*Wn&b2kN&y1uGjofsf>86QC{ zN>U0Xkuy(>LJ5aBHK7(2a9O#Y3`jKS(lGo(>?kD<912?pK{t`NzF zz%kl4#P(6d6598i4Y4%n&$reYk}ZQoY3HG?#k=1JNXw+Bw(;CN`C|g&5Y<*YZuxU0 ze?kmHm)irkl1WNW%k($9FPWf6=KAIg1My@9;(M1azjOWdwt5w!92XLWjt{TxS2v44 z=-9xQmuU;t8fG%-oi4FAs@{3eLR#kHzNjm_C*p|3dO=xVgEBWBun8X~c?ofOqM*5<1WYrpgwZQ!R!S^lzryv0n|>*Z5$0S61!^zx zgkXrE>pDcUauKFXBtl7vX14}NH+1#*T%lJelsL8 zP#OXm6jVoDm0&(9{)7V%u@)bVG~OiB8xV8=X@R29U%oHBF$V)Y$B+wUZfP~Qe9=_Q z)wmX-cUtOB0dlB0p5Du;u;wIgbD-TCt!ou{fX{}wu}q++?xbZXOaK8Yxuz2$BKr}b zUJKyER@+ea0hfSFupGNMZrN}occeX>uPV}&a^t>E!~9iTo_62V4hlq?Q0K#wZ7^X# z@umMvHAI^pu_}dwyN0;+tJ3vlxh4-NZCo|l7)|u-AYNuY+^hGy(bm(k&-i!0*9KuQ znHpNjwj>OuvtLmJjQzq%h|&gsj8(62TG$ZtB;99zv{EaZ196vhACAal0PRmZ|p-+W*wqU!X?OgG|KFA zNePtl#zSa$0m7H;E2CPK(Rkitex@7wvZ>1flE^=7a&}oN-9i<8BOc(Nyyf zecDGA&9&)Y1#N@9BydT5@y!(?b--2N2Y5aH)T*LSe@CK(2pT88t@JIFba%wV=liZVi_Db5GJ@GFS{&x;vm| zR=A{L>gHL18Ai*1F0YNXAs65?2)Y5C($bHR`L@L*sxib%1#r{_<&zXDN9m$n>#|)3 zu38z4%Z@5~9Mii{XbfM$2kjFwxuLvVMxWBP-ne@}TzTd!WT(&&>tI~}%2@UJr4GoT zM*MR7%}*KnLSc?!gHP`>JiPFBaPOS3@H@!T^hoh2MLS2bbk@W9D^0pmuIvVPbdz++ zlh;K~4WSci^Y>{IJhY7Xqg*B1go0y%uE7WGgUb94KYoeI)^je}GN5R2@X-*YLYSu( zZ$1j)oWkK?rE38$^*Vi2ZV=~#ZwsK(#q;#^-(KHhZ}e46mjb;ggrpR4=lyp6LgmBL zQsd|#++_R19z~x-N@n~7(zX}B2-QyY6~@e3zYB4XW(01h_r|XWdo$Fs433M?drMTF zAS?y$pU3_TFL=wUovE+q)&M0H#tVOUTOM`YuzXd-rVsP~nIYHp*SHILkYg6axkT3& zhlU;tG?_d7z1VG;>1XUO#)g#FCBS2)r=J1YECT1s)Yz-#kf_J)r|$#XFQ#`C(;CBl z>JV*}9>#tsfjjP(Brf}Jc#q8j9{{mb4Yvje_77F^c-p&9ImRowPNP&n_Ty=(RYL)Y zfI$wIzKg|97OidtW35U&e(eWw(YSqWxNIVF%bW!HwU8zyrI z7S0S0M1v4K`yGjjsNnfq^q1-`Q~`J zqp!aJmbf}OLZ1#?z!mDHzgp;%UyEx6^@&8(n-wIR7Qa3x_tN|!z4G{xN#PVE;Dpx`(j^FXQF z_aMCA=hPIxu@oOb>G55*ZTYX4h&7=_S&65pMIwiGVC*}u+^>Wr=KxTT0R#mqCdnDr76VIB+L=QS^M0(dgC;4i{28VcB3X zPY>H)mfT5yn^LOFZ4DzzaB=Ydoh%jEvSq;8?+c>t@IjkgE$pbnDAH`-s&KUOM#)^P zO8^Qi4MH-Z$VK;z3z`1tuc+|2Z$I+|)FGIGO0bhD>wS=d<{YXwZ$Ddm^xWFJTdP{x zj)4MaxMky!g`D@PPcKyMvhu+Lg;jpZN-vd~5+^a6Fo{iIrhpwPrcdLaGKL_er#=*I zN+~uRcoA6f3;lP+ALl|xAx7m7n*(&~_qK<&PQK2q<$h_;9YL!=e>8`aMZ@w;0RkS9`^ z1ZDd%f`nD;y@scdNT{)jG>!1zj7FOw{aCN^A#1vT?pJ8WBKLk&Ul~^WG8jjIA{>O9 zxjB86%E$>ss`l$SsUZh0yIE>QdE|tdb-;<=4>VN8Si`yX#6#vF zByb$uIFU+`(xt{llw#~6cwov+J6SnQ7hk8h(tmSUnuK`_e7*DVby=nTkM*>m3oZ0T zlEeP@GL*4`I<8Ip!FM%|j(^JZypGh%{^ObbmE^FAQV5~q;Qk@NxB!v2Unypubi8GQ z$lGU`uw2Ay7F#1qXdqKq079u(#pCIV-5n+S5L=N1snQUu&M~bY91c0>kK({Huo)!@ z3G>Cm7VedBBC_(}q|wlyfSJRF$*r|;<_>%{d=4ad0HLjH`PVi#&6TCu5qlIBhrkj& zs`aC5U%59M*<%!P1=s!&(iE0@WszL zm`GlGvn6=$ITdNz?w}Z=Jwh7|_PZq}vqUGe%DcIlm7qAA!DK3UQK92djsX5L?0JC>I^vt90se|s zl1TSR4(q2XU+1t+o2dFcwAU?oZdc%)*LTy(zJ0u|sOOw-(WC3W@>C_;W#y+?Nr~0W zGf|UI4?B$u&ZvYD_Fb@-=oA19`qS1sF;RkNueHX!8YZhlW7dH7S{NC)JETb8eVGlp z(ICRudmz5#Ysq4(HD%QgN~@TKh3S3AMGIoB8G4IT{b?k$KqLLA>2{AdLq9MNG< zd-m|85ima;brk#88m|iT88_Epi$Dh!d3QQ^e`b{qXsWQw@QjSL?tFb>eX&iXdT)Vb zU})-(1O7uk(~?v?8$UnUPwm|8FD?4(TQob;4ES8;hix_tt5etd_=RLZ8CL7shKVml zgzyG@E8`_k(j5_VR!D5^Qy9FIo;5Rb1HR0VCSpDb2BhOxMT-tEA?EN(`q~Ve&T{0eEb~MX?DlkTFR}W5!LrQlEn1JAnI&c)L>e82%0e0XJ68f zs7)-Kc@ywjkGQ>|jNf%qe!R0wL``eYor-CGN7~?acr@*T6YY(%fLs!^L%A%wqoss{ z?+X8hP8_+2jU@yS@lPb4!6WKe@<}_m2lTqBNY{r2t=Jg-g(qo=Dg?0%(B*%nuhf|M zB<=RTMvAl65rk(k4Ls8kb@Dv9wiZ$ZF-U!AO8&Fv48D7Ln9SV3p;&W}dd$^^J0gqd zd8MG4!ZftBB<_1_4D+*yBVE|C#2;+pvb}+gwTyuuqLjgL~WP@FO5-jqHrqeE}HW{f) zL)pdR_TqN;G>+LIr!`>_juEwJ!mA9?l|!I4q zT;`61&~_eu@sOj)kvpO}4jm%<@?FQMJoz3oJleu&{8fDd((xS&B#1@=6RucliaM=L z6lE5rM+qe`r! zY90l$3~|1%W16CE;qlC&R-tY1yEVQhwvqA7dGgkgOc?X8opihD;sA&;i|!lW77Q>pqpTGIUOQE`H|c z=%G0Vuh}c-d^Z+0#Q5W~n{#M2VdzWfkbB^xQ_I2W97chiq9Sxc8cOM>O15^%PsJb4 z`l?=f7}}q|Pcm?j<^XSyiA|(JC$e{|${YRrrynkOjJ?{%xbaD%l(BhZB4f}?+U$Ca zXM5Y=BI$x3>l>bHS*I|p<`Ib@<_*S*vCz>{?lO2$@p>Vnp6BE@jc zfiDR8b1;=m22dk9XtC_cJxT!F0R5HN#qW9jzIWo@O0JJKBn}mlF2p)qhiOSYNwjF7 zqMEhz-ql^oedthRdPPtl6+O37Q6{wJy<|#l|LfwlVoiOz%H9?~H1kES&82-acik+e zmfok_T)Lm>-`wxC;q-6|=G}nM(=Z)kCT(&MZ$MjV!+xBNp&!$O9--R{hF4o5D5F9C zBOAxVS=clfs+yMK4_lxMVD9tmYMfc~>q(jQgzgCtRxORoBCt~|qCU`sK`WHm1x`!= z3~)eG-~E)2ywcC0qE2fcs_pNE(_BdU%bM-_nRSeYJ{P6E>o1SKQPIEFQ;_l-HONU6 z18JZ#aPX}$G}!8el4E*$#m=V{KJ~f;hCk|;t5CFDPiE*NyMUH&*nIBy*YXi3{;BW2 zCod&ZO0~d%I1r(}VY{{(t8G(_sXRZ5a=5Z437b3LvP3hyY#gIdb>`vh?DG-=7SDz% zdBLMj$UtE!*N}bb4^cW7&eq7T^mezRRe=+3WO1Xt>|V4b{%nWakbMPjL>aOb=Arq3 zG|NQ8TFaav-#;wQJ=!*xD5$%P=K`GfJqYoQLFUmNj}sp}_^027$njLhv!}2r`if>i zL|q`l^SIcYQ?l^+a8b;v3(3;FFH?f`7-bSCZ{U$ppQ$tORgGWCaUgDw36f9kpj`_r z?F#h_dd~S*aoW(6Eifb0aH* zYsH~41|PReAT-8goS!^s8n%b2xJ8&pse^yc<{{W$pe1f+yEcg;`aPsTd*<{f@ukToQncTRm{lss|G;H-M3A~H2ID7?GHiztNIp4( z<*>)4NI;ow!n)xO2FOm_RwoQei06o4GwBZ%1_6S`ZY1Kv30(o}awsLPMApf4P+FB$(lmf8Jlgl->3!&HILG;)M)A z)QDYwTsNf3hT3Jlg;3uh~WE87%&Ay$<*7DsTk$Y zR`kl_+s|ElAkJBKnz-oeWe|cCneVd3ro#VaSbV`tc*3*yz}Y=}9A$4X!z+hzPPeJ~ zRQA9Cm-5owZ}jwLMTuP157{*bxG{MjvHcciBk#{zzRd5^#Mr*@iZ}@1!usUeQ`(6} z5-h=vFjdMlmy#(R{OOnHg|Py&;Lo+~WR2WE1rS(&4@lwX-p38WCKr1e$gd4wISe0O z2J%EpuoEEa$a@;n)mXbo=G`Mu`#TgmzxESe1Uw$_q5WoBndrj@k@R)wP&<>zGjJ90 zzGErrNXkQER45c|+P;6HYYc&BWcm+aHgF^4G=Xo4(TUK+)egf=>{x<=2A|Oml3MN3 z{2MNGxv^Qq#h6&yP2pGMz1IUlAWs-@@B|z&viWX<3`?*1Q<6W@%zoHRON*MqL3k## z+M3K;M?7w0Q=d~yUyY}i#3h%PB017ID_$3=Wj}X^1}X= z@47s_w~pXPxF;9!QCRvdblQ9UZ_?L1LIxbX{zs0C-bLO(V646DSQL;*?^dF#bj4)v zo;%yw#LiMEWAvC!GfQI#tFW%Hy&h5~7b;TNVNi}tr;3+9+dx532>Rv;APYoYWT&{T zCDg@aM$Ood!N|vA+wG7gchWgbVsO6;Q@%^k-$Z-%M!+*(W3;r9>FMc4yfwz8Kl6*g zJcrziGTG?_%z(Mk2Oe#qcRkP(L8s)(pcggj!>|iAS7gBK4u7o%&UfX+Krt>1g(V;IF*)fn&$Y7(;dRguEunzLZJKM%CwW zy)Uvzzc0r^{%4YtjynM5RuPo9>G=NXiNcekN>+uhtq`UgI>YYV{>Zae@bL6-P3dO< zI3mE-wf&XBVZ?iKNS8X^3lhJ*j7qwZ0~Aet3eB&fC%!r)8bWFh&rJP+*c1engvI66 z0zT{Kyr=Q*TU>F4&Ks4RQb*$hmh}6UT~ zQIxeYg!V!vD=l0A742LFQ1*tc z2L=8{I=AB2PO2d7&;;6;)ga@Frmsb3FquSL|7BfOmDGjQzV({d1-QH>Dbxd*b6$^| zUHl080lpMN6>>kfNd@?4;Y7^=Z6y+cB*6{DR!Q0f z9zeRyLb`2KDJh!1c>n)1YQ>r&M^Zc2)Gs&dyf9(x#yQ`$sJ0SxL~wDV>&^6{=#==z z&~%sHuWLFvy>EJB6McL#?D3KI|Q_b)rN{jQAs;d?B1 z1$%rC9i2K8&Z=WG-Z*~QI=Y|n;a!@&mU04pU0od^XBj%XzjS5Z$m9IsCKW$T{*&9t zdpP$A&yu~YxIABh+zxm>e0r$3@0nTEA!old5ubH`{#|bO9926^&KL<|M?+$#Nu>Ab zs^hUEOlFyhOkS$osLbTovOI-79e_3QGe9kf(CX%0gKjMf+8v!7F^)I4@KTg1m}Zc4 z-WTxx(*2GQUcC9Ym`v-XIBc?xBhc!jXcrP34AT!WEC&h0%J$)HN`Bz^bt^6kQx3YI z-eocRYp85*{9AMw4t_xsNXiob$-Oqfg(i{^@$ueY^vmK4kI)VD=hNmGsI2$Uq%!90 zsy;3gN;Y7UBLsce7NLy(0wU@0H?%N9W_T4_QGZNkh`z%l@6*x2KV=M?@25?@Qls4! z)3&ir!iF6Ud)KPKxKDR^7{59RH5!`cmC7PMybzvW#^)248`R2oWMi`K0~lG{e<0J04cL@F7jW287%%qotgDik7mBd6mk6 z&W9%JBgv%GtznttQ@O1F@vRYHyEm<2oxW!!XC6QU?ttAO=x>h_~O){~uogI{u$WoAW!US=#y#eA2g;H9O>JHSgKS~S_Nx|}`G zdLh#qZ-STo;en8V?PUk3%wGJBe-k&TO+kSGW^+uGKQ;cgs5xII$DBH5S0@4EQipL3 zUigo!eL7utf92!XGap5H1R#-}9cX^#k1Pz{&k-`(`JjQ*|>jpivH2e2~I)lgYFeyhDrVzD!F z=9nsn8%5bVXW@LCCE7CrqtIls)vlF~( zHd!9U`Ok{(Az%>WsM-Mdi$!W$*Y|mGUexk@BzA-rLI* zt|q#+2K);Dr!#!k6{If!6pWd+DX1TBnm`;A!+4(hAiyM|8FZz@LVm|h!!33!axfx3 zlAC{16AXYnBR(hkIYnWI)n$&KltLhgc}Em#$;z_**R%lRYkGBuY+yL2tzn}2wo(%x z`Y9GDRYMZooOM7EnWtTU@bFY3G75&2MEP=>v*f2mD;u>tH&h4Y=eDuviCZf~&= zW^#Ec3HpX5zL48Aj+R6y&8n>Zia=FH95+@N@Q!lrk1-)3>VRJE&L!ll7cKuF$Nk!a zAxX?3AO0p%j-Ll2q|%Y&jg?Jr;@`F)A22V95=ZG-nP&=(t8brB)}cMU!GnHFy zG&WhG z%ky7-FnCCMpHB3L5GGNu8xXAd^Xt8g`*g&`x)8+y8K4Io?&>yd@(QA<*lLJ>_qOVP zR)aP@Y-i{5*8+!*2U$(-l5jpABjFi?HT(nR-uo|7M!FwRIH?{JyM(v#lLlD?TfC>c#BN9EpQ%%>@VBWLN0hKU1rH z5WHSFd#U(Jxvt)ul;d6X_}H-B&pLURCWnJPdqa1t3x17gC#bcTe3lynyntwY^an!R z9mT1=V|Tcee=LlX?whK~HjIxg2EL>te1r141my+)v$QA@Sv@M7(rzPeFXkLZ4HKb|bs!!cKhnOcboW9D#F6 zU(u*}Z^`7~NVPE>h+eqkhw^=K?*h#{QHO)dl+@m-qhCq=pz9hr5qLkbg9Dl++g2u3 zFgfw=3q5HCtL|@}yeY3Gm=4V17K(ZQgYPOOVuB={a-U)}DBph`*S_z6cPy)IYuqc( zg%4vUJcJfS%Xsz}aO6@e1Q{o13V5h_tjCc;R2j{o-R_?=$in`y7fK~!njHJH)C42s zl{eJPCwEQAYb?ADxHFb3LLz$N5f^2Z5<6c;4>z(x? zj>3C7id(B@Pc3xdkFu9;4U%1pzQv+~^{IauEK?iU3bP$!Ag5?Pxr6hd-%&RLb{RhD zpIOS!MeYUA!)1}?$$C!Go0e^{8NL3JxzUG(q*hyCW+W|MLIArGt(2N}vXfLzq zT;yttxq8n;^2#_Z8|LN{d$mu7?gmyp7&DAN!}MupOlk=rNsi7;{ea-##*S#01H*bp zE9@T3WU(V6P9)BhKb3Y{ydBhAvy~S+%4TSh6_b|W1~va-Xfu?I*YQXf-Ph7anIJC(mjVw?LM2g z(oU;Xz~0o@a_`YY>;9u`)vxzjK2s*7bz>U&h|GgAn!^ij47r3~%q@5yp zxYBE6*{w*oU+1#5AwG9lpX?sv*)D~MRu_$8&EP{j#`|p~&xz57*p6Qej<*n7Fx^~r zk=X96+JK3=D@f0p6L9~HbX8qnQ1iH1YNoUJT7XXaWv>3KLv>W!EHG!#cCIURI9&kt ze7Sr$H-snIo+V8EHi>KmcWj!p=P(BsC#@INPoJeT%U`4op8lG9bo`LSDdL(=5KdaT zovPJG;~$Q`>-hX)QA*$t7Z5bJm1pZd(kghz7cgbI#08T|?YfF+$Nt*ily~RVKj0A;dXOGVv&9^j=@q(D=QroZ4aIgOvg%2YmSN zeExmXjOgf2DM2=IXyuPo`ik7A^ZKEJjB2;kS1-mu#zB6 z#q692W4V^@5V~X{o9kdDOr8#rc@#K{N_NQYtG~n*BVaB0*TwK%Ad9O`}V+vnM>0|&Yg^T#loTn${`ym6=K z+|P4wmpYCd=iGKF_#NB#FGri7i%=CfMc0QnX{ug5Petwh<@83T5DsEsZql(-P_ow z93KHPSm;_Q1RX{XgP5ILsEw$a37+1@Wi=Xkg>S)hb2$YRn$a&dC#2Nsv}n$Yy78?8 zcm1jjEw5*c^jPU$;$QuC-Wy=z!&XB}V&q0-vJWO$08Ju zDxJ0Y`Tit20jC{?4 zizSUIv#opv^?#}NecPu49w(SL-YZ-2R@=`aKz_*5CKjrA_~g!WHgYZC%|3P~n0FDd zP5)sU-gnR4t_h+R?tOywGWuFp&p0bpH`VVN|8Pd2%KgNFfsQK+oss#$Rh8lYD4?*i z)UwxFJ;+5$?DjI^_X8XuP;miF$UT2#8APuFSxxQ6R#$zU>nkr_IL<>`@ST$;;cYY5 zZ#FD-dhR4H@<{8bCGeud*O$4dDZFkkf#g5*JbkHt6*80wBn7ZLKqi3a&^-_H%E=z{gt8I zui1xWV`wv|LM7`T6Mp5ogWLz$V)7eF9`ZcFEbkJp1ME`OKpCa>g5{=M4W3Qr)``*- zzpu_-@nd@#>7U^X!w&twTwp3Y|0kGLk=@iJ?*N1==h)p;gk8vZ}N$o8l`#D}?mZ*0^pKx~)lS@RE49iH}Lu~z@XXKm@U{z35 zep+(PQY$0xj$-%g9Fq_Ar?mI`vgdX*L<8!xj7D#w{yxyZ=Bz!6$#W@AX)NXzTkKk9 zXPAkhyfV|Nr2j<9!E>fM?SK6Jj*Bm11XBN=wRvTeU3kR8*k$Z)1TxXYDgPsQX3MO@ zN>?ln@+|3>oidfZTH{K4TCiz?upA-~kAmshBp6qR?^0w`I-Biu8QQMV%#bHcB1*&S zG%|aMT0d@25=#r0GoX<*-2yd{`^bB=^RmUq-mJwDscx&GM3F5ELxDRX;>CO2#yalo zzalZju4m+27L5>9s&PwrrE$nZO{w~=`Nv&*P0W;Uy0p}F{#D2wtMm_;@?oODF2UfN zsi(0Vh+GyhHA9ggDFR1~-qc1SpJVMm*fnSAVpnyE;VzdJS9nJ*sCjF>?7oLphJNpW zab_}W{aYAk#`;LDhLtAwMAE&m5{)uVC5a@e(wJPuw@C$AE-1!7F@f`VPRLTSS6fafAB1vMXUYHcoo@B!@4x;4$KQrhA zO!4;tr+bOr9_i(+GgpVNny;-sQ^=&=q2Bv#-$SmKn~d6Uc``|9>@B+<$M(xNpYi`t z#!`sH;KEX}6v7eF4kE2u6(G6EGC}Qqw8Uy9Te$M*n-8L|E~`0wPW$^Qw(_;GQu~Vu zkVUy6DR*jk4C29!i+n>$LOy;reS-c;>JP(?bu?`q@D={P^Xw46N^NM`T`^Iuns&qW z*!VL=xJkz}!k8qHVp)BCjJEB`7g_rbUNSUu+47U+@HC)6y=B+yocR|WVmfztCz0dj z!MBNoX3K0NN_r5IQ2M6Has6VgL#hBtr=ZFS*DSRg)9IhyFRKb&r%=8b9lUz{W$cCL z1qS)@nU_VXXFc$}hCtQc@eS4>c(-@|X3%r{5x?#0l6$G|L3Hk#Ql1|ip3N1(?wb>p zLDx#`<6Q!c3lu+K6zp!L_{{)eaEjmdvY?x%V!@vro$_#f@ytT8z~TpO3-sSQ?b^p* z^rPSV`<+T=BX{7D#j--8w3T-qg`tCcR3er`#%Y+{ZSyQ}!9*uswO~O<{BvE7dn0?D z)Wok-C+mQje+yFiX2u-;vzB-k*`k4m)__C6ibdJt?NL3Tc`gYr$p$W-GI%>(78>nk zFb>XiUGt7HH(PN?{-LHN=#*9@aa>`?wk?-0g=d;3FNL$w;zn-ZsEHYLgBSuT<72kW zdas@wc~?CY5y*hPn&P9}^9FlDLK@9~(XFR@5sFSuq(Nqv1VnU3{ZI zPCWM7bZ+kJD>r_;_!LhmlqOAg!6fD_kBGo?%2J~ush_hWby**i@JW#2aO9Logu+d5 zc&+*p@psmOqO3~2A9{3wOq@+PGn5kwFj->V`S30*qOQ$UQ+fKj_9C< z4@pxsI7Rwo|Mq2ly>>A=dC276mSU%|26jD>)1+CJRw^*&RAxn@9b<1ky2n7#cuSVo zw&U8uCO&URp8w~e%9BYlLYx+xdtoSL@h=)z~TusVcZV+#>s7@?FGP@Ve)Z>m(6_3kF+|(*Nem2#8?Qi6V2wAf>#`~McN8>-S zsrjz=YhJl7P^}q>_4Y{w{uw}FRP;w(G-0JX2@$=Y=j;cbQym9($m6jqPOSTySi+Z! z`q$EGcxaM@Ss{LWI*YHbZ^crjMyMm2mD{`I!r6g~c?ph{8g`x7Ov zWgL{WGDcSVU+1*9{*on`K6gw064=Hh7rqOyOM&*-fI>AO(aWXgp|vRG(z}*LHp-8pa_c~qckG&)g1V~Qd6!G;>_g8_w56U~_srB6wXd4BzR=9xVwS0sY^fbll*Nyk z3H<#iqlEcIiM+B))Zs?1CT;Cwk&~t**Z_Ts#rQ>~0Pz)LeiaSJM~;F5B96Vyc~8Bc zp5NhKMZz`|(Jc!7V4_`h90ix1>0Xo+JHG(i;+*E=U9JQIZ@FMCezC5ufy5Rq~dh4*Lx-V>aKv7Ahq(P+=L_kVfq`SMj zyITb5kVd*YrMp2ux*Mct=x*LUKJV}P-s|I^VYq-fd+!zZeXn)SI+$|zs+Lb{w5sMg z4c@>g!;lK@#)fW3(2(QH=sLaKW4n=X+-t_Xy9_d0tj)7>vH$iOyBTlz-JhvKb|kj} zO4PIdYD16bE-J>}3f^1!q2D8kq@K%;5;n{3NA#DHe%WgD&(hif9FWrU>^QXobl zvG-}I^yYk`FoUVsN99Y-m1?4VOv%WnvU#1hktkJHHMUk6*d{KeZg=@#2luplhjc!0 z1%hkHvA9O&PJD5QYfaNe{)lQ?iDfyIuKj4P4;QNrhKadW%U*J|mYf-hQ%mm_smM)C zR7G1#H5kRou99$R`iAXXV-qmOnJ00>3xEr>f6e&2AYmwZnD__n364ng93>ky1pEK5 zC6W&_hBhG~)ael7Sa0hggMAM`76BlZ(RWx^?<*LK=0Yn$o;m;Bgq!tr> zHCpIhSc#EI1xQSGJ#>iA@cm!@`8_%o#bs#BF#8V<5BW=<7X*>!Oz5y!OU3#J9HHDx zS6}QXxTleFPvp}tmn&Jfde~wqv2q9b6$~%hw>h00h%9?n$%Pni(9HWdwzF5be7V>! z7~h+h-qz8aKAiSN(C@IPuRQ)(omu?3jMqDL$z|1p)$}YKnrqd(RfFfy(Coc1AZ(?? zAg3wZ3gx&yGcc?y)!-55_1+qYImj~I^wLSpy*CyQ^E!;DLGLQI6d_{BCZbnMmu|7k z*~HtbtNJoCIf^$La4=J1**j;kc%L{~d6q*oW#Veu(n;ItaE8`(TJL@ilfEH(zw9Jr z<lB8e9b%%mjl#eltvthXYE64`WK;<@w=&!wdcJ!0T?{HUD}6 z1W@xPzZFMD_)PA!MpYFwO&nVyBJd;dC#Gv5jO)ypY)M||iBmy3C4ozBshgd4_7+W& zg{e1KIthI~XwVDdxjf$3J$?>%tmq^0-|?BdM*r~%rIXE|T-ux{8|I9%1#g)Fv15mg z;3xz7-l$e$tFe}Gl5moPUTFmw6Ol{AS@4oi0*})cDYxn@*XA#mj^uLDsurf=>!ETW zhi>Dkn>)R^Qm38@VmFcc$iWn#uH?JM1*=!N%u z#Wk;tb1568tZpB*syuo zYDgWwXz*?kq;Fg$>hIS%eeKLS(o5CKm?7hY(U!uJjaj`#7Q0H0!e-o0yv`r?=hy&r z!Ho@Dblaj&1J8h)$WYX6@VfeAn_>a8Uso9>ww(06fs(Ml%stp4AFN687B<@<9pUt< z=YPZq+ag#AC*zjoF4yN0 zP#+Cx$;HdxPwArvRNT?;TbT-aDT&~H_*MJJh(SjrInOCMrJ>J(z9zJXogBgWHYZcm znTPl8Z)#$k*4=oS)`%}zvl>E?^|8(58m{DZpS&>j&tfLl`#uzZN83UB>+R)Yk@|OE zz$boH1`tm}s3Aa{$CxGfaD1XKw-jNoY!5$mA2)=0f+W0v4NG2C_nh6*iPTJOMtdGa zQ!P4>Lx9S2+7dQUrRQ{ic!t5|!0xq-Yl%EaXMbB>zWo!b#O;(+8?se%>t>0V7JznPSG`T}Yuf9IRs4GnoH&T|$ zy*hJbrsf8ZOj`AEWHo(LW8CSW^kuW_(&~O+#p5Jd-;YvB!b!F3x@l6B#e#5S##w#g z5MZ6xog3wu$9Wo{SshMXRBilO+kNGS*YOl8343b%f9gf~e~l#choU{~zj}tsXAsR= zE?@0_S~7A?Y{wlip8a5lGTOC?!g&_Ab1wn@#_B4fH~f=RG5?vS+qzDc)hFvx{obzA z+tY%q>kD3W@9?L8$7=K~=bVZqL9C8!IrBfm`B#`6H-OW5*>h^hiRy0{qW{^}yK!pl zuK^3qMM|K`dA3l&x>p91`NWYx`O+ZZG+43nEXaI7m}RA5wZ@YA)H*_;koS6;gys39 z^Nx&X{Qjb5UW9hz7kCo;h{ms}yOr0VR7LGT$1PgQC@KFG%HddEDt<GP?l`fliG>#{^sWSOV566-i*H`9bGgBpWv z=d)&>RMna3PBE9IicGe-^01Ogm$6hH>u-YNE#EN0z;4eA&W{D~DxD75KM@hAuRrV! z#;x1*JSRs)i|K$of8adcFE>z2fQ2Tvvh{@Xd-RT$1p#2;AGWtc@_$v#kLoYA+&u;t zf23eo37j|ndeA;kAtpLwxXG>hQ4yRAjN$o8L=9L~#ViFWm_3`D>0;~@#{NpV<4m7S zdI4KpO(0!RE`wihBU?(|bPDhAaRm@up6``S4`CZSWLKzH9y3*2X=N7_BXxjRfxRbaxMJ{(9hl1>K zj*p6l`4%p;<2w^G`9T@_Qg5O=uJf;G8Q&ycW+(87mcUJ`+Ff=>Ay7hX>rKqLexGA#HJLEliVf2Y zUp}Z5RtG|t=o?+=5T4YIdjzSh@q;#7JMt5>=DS~l*QZ6w1+O^y$5u`bs_=TQ?$G7g zX5E*T#!0Skxo>*8r(3+dGOWDTT<6NuMWRjy7l8y2K-AzlyRDV4On<}W%v2cnVk{Bm;#vbB7OKCW2t(E*FcwCxN zJ*PFE8^BWoZcijI1HBn7HG92tKx5%^l&`%%!sDD6K6(F{ zM(-T?HO5tvqMl!*6cfsB?9=CXF6ekd9?)xXdo*(Y)JQGFlmo+nnJ|3ohisfVXA;#An%mMu{L0u z+4nMp`gCdD$;^IohALiH%LMK0TFn*}dT-myw)O_8<}2fQ>V>X59nJWq(@IOXl`LiR$z(*9 zh?AQs2Y?FBv>!1@Hh?4l|5)XlAzAdcm*&4XZn7G7;w<&06w(I&s@AJ<(GJh0guTd= z9mI7)p&oCZ`M7zAv3pqSKjZ~R0Nh@6u5~i6$W6APxRlq|uxa#G`UY8wSEBJ=H$k?o zR`_FMfb4)MaM0{l@WG=(1!0QVba$#ozoan#Kn|4f%(q@baf^&1%!W!#_a^&lczXAl zu%x%o_oz>2VF`$E@;%c{eM14n6YE(sh*T%yrOCpCBkuxDXMzj=w^=0B>wU?s9c!gw zC1B(aE--tuy`WI{#d{NtW!E~ni@kz0yB?fys?)Ajs_8`JyuTTD=%Buv*U0N)sOCi$ z3P^+W!`Zs*UeTV6q<9&e#Q;aY-jW<}So)@ShS7CevAqAY{OY2tcV`;!fIB^{>FkSg zVj~&PNV>CTy}`l&N+mx^jw=6y0$SJKYjMG7j48*R)1N$a^n=q#s3E7pv6Z;b@KJ=< zu4hu*do1rscDz}qw{MZU6Sb4q`Z>I-_qzNJ$WXO!y_(Df`wk5RBnC?WcHawl9^nqB zTiVSJKh9J3C%l`kJd~Fs4i@Fvb~b2@wqTpUkfJD=G}ZZO0P{ZbW8ZA1OJz9oS>Bzn zXIYaz38j=+JU(S)ar}OkX5I36@dGoK*ci2UtMoyW-cdqX0HS~Y07_M1@n`m*%#mu5 zA_;B>mh>j(jBOP?SB;@G4?m9T%9=gyj zC5=y=SH8WGUrUW1946E_p%gbV+v9p*Jtr%MO^gdCPR?P=9(;q zT1pli+VaB*=3>oVSHhRYra$RCcTh#QEnIONH2k@Xs6H;KOL0N$e~G`1IUy7@={BZu z^(F-(TUSKWX3sxfiKKF;HQOg0;k|<*dG1`ZxNVxi{03XeNvyViIXp-!SHDeM*E_qb zP61k_@M$+}TH;0paGF%krQ9vEIfZ3RC3|I+RTGVZ(c)yi1DNnJ@X<7Y=jMc@V&y(h@!W=aoPHmQwX8DF;UJ{d$8`ckwIVPoqwlJTsfZeZ2j}GJQJzv_`lFvq>~OzFBCb$m%4$ zjB$h>W_7_;-jnPCO}Mv4>8eGJ)-C&8z+=KcPy z2iCJ57H~_;edl?;@2SSyI#S(pr=H4_t4>w#0cv=j_bf$cgi8^VGXzud4=yqhWLAV{ zX94GI+W`^Eu(j#p5lKAy5$V+8)UhKVwFy1nvzEE|$~kQ5X{>Vgl#r@{7VF}Me-qs`Q}TgJ3wpbsKHey0*yQ;0e8{&7ER95DK(^)+%PH{ z{=!7J)7?=eWzfdyIYS3CvVz~W_W$&|M)8MpJqHY@<=!LT^e-)^!5XtPe!#aK&*OeN z2}sQcySR6#B4nd3Us&jx%?`rgr#<+4fVia?T*t$4BX_ja9DX3>>1^YL`QXAAWhbIk znsMUfLk1>#d9v1;g^IPB3n4fV7~k^*f%t7IzQ^7lTGC|vicIF^ad|$yBfr17?71q8 zAX43fgy$|fUsnqY>pBa2N;|Q@oj$Btt7a+xcBHxx*j!q(d)mvvKP2|5LJaA#hDd5` zWipkhmA&=wn?E5G@rxGk20=|VnG|&!g>)O*Pc*VtyHp~E2Z#KFkj*Z6^i6SjC z8B;#sWnN9h&OHq=4p;Z$BIRbbwg0XTNHfSX6D@O6;EJSboAxqSz4Nfaj({_pnBq(i zZ^_rAHwwE_B~W9k{d^K)uVMWym|B9{y-E=v)(N5@S{;!S<8`5^0v$a z;&mb5lM_=!qd!}IAL_G$1BB<|4O(%y+F8om8kV9vS#_SjFVPCxssP$j15Hk-MxjGG zfF$s`HHp<)@UWU;e+NAhZZ_J@K$!fp>^^>VJ-ewdZw0*@#hwi3${p8D9BaMxDkHt> z5{i8(VclS2KKylmR*aR5Zs*lV*XDJ$>+fyS?-eacNI5u_%cCG-$d_{G~!9pTGnKc=DiF+C3f|eppbwI1%N(tOimS@x8%EN-!{|e-~&ZBulfY# z4C-jFVfmI#Qod0-Wt8kJY7nTc-$X+p4u6*AQ(yOLI!j*)iwe& zmceP)={!l^d&|({P;tpjdB?4jJV&rU7arSU!mJ9WP!w}}#gNn@Q~AZ8UMV{v`Sc&_ zM5T-v(vN?6q|~OXShreKl;o}f{04%g7COltVIU&=oFv?w$x#->>%m zPjrB5K0nm8DjJ9%9FtDt*o1oeA^Ml9@R-l_em&XcD%@FuB<~jBi?j^2%RHYM(_P+Lo1)a3MpLjD4&bEl-oGckp93(RTWK^Kw6wkDBu`g$Rc+9btpMb9a;FAq$6Qf^g-Xn~f}Hl)Co@1ifJXG-qTs{rm}nDkCwPMrY|Kc;wUp;&_#(&b z6x;rt@smez4B&Z!4g>9xJYHL=l~TSif*67Jnv?n_)L4}abJ zel7*Vt0tfx=vZ7Y3}`keO@W#UFd`9e@1rktiLpgMENi*g5?gF^zeWBH9AW#8D1Ha< zVx?C)+tkuZu-<59WK#2;Nlx#2{^rO6HhjRL##j9dB)>Vy!vos9e3AE3)xtSrYN5rH z@%|Fq&iXab(wp-*tAKXba(Ae!*Bwd8Y|57TONs{sN(pz8(XgAMM=dn?S#CSP1t`G6WzboLLC0G4w5 z1_{w0WD$USXW&q~vBM2kGOX&x1vUx4n*H-fVsPbfjFxu4COB?}!#z7yB)wQ|J=SYt z^6}W4ODPBN7=iEXuL088F>qhbAJzdow2^ZKuTfby*|eZ&aRt}{2e{ZPl{eIn2mJ*D z4B5M(=~I8`MgYS(>p{hP%Y-um$^;Ep-vh&)LOm^fadkB{DmArRbi;wSZIE1|?Y6*$U z_I1>3xLOtSygP$gkaaRk-Wm12^SqJ9MG>Z6T4@3zw>Qs3_JjMmACN;G-3I;Z=j@@O z`^)NOKqfMSq71~u#1o8xU@ z1|F%Y;C!(nI_)0*v?_=33^j_i*kGHd6(d+;Drd1ud+U{jK{ zN!}T|DNR1zMZ7X?%PRpdLC^Toha;tUrFG9`mphJTSU+W-))QhUATd$TyG>58q=%+w zjD34w@>4zkSNyJw*5U+wMhU2=VjsM{y$=(29Nq_y7L>9)HaB{k&em$-<8`u7V0uTC ze0XH8v@Ktz#&UZh(4ip69}iCyIqsjC?3k*vDU|W(5*f_`4my&5Ao^#}FS&pAo?&s- zhl=>W_PkasQcy}L0W}gRL0|#>@ia+ye9XG(-oh8n3XiEOly?oCvegdH-?A}ft6u$F zBZaw`m+@S}G_miC-_iaVi&(PD;IZqqs+K&eznf>NgbOFN)@j!QkUZcoSxFS_%~@p4>Q3LWhRC!*C!d*1$G1^w14qZZI z)*RE_5b1>elKYvQ=SH=8ug4;@BuM@=ytK@wUiJ@59PoQp!lli?e;-rUu2sULPtCCA zvJr`pJg&?ED3;A4A#3@7i`(?%&kt9@S+_f+le5afeXFJ<3+rZw3@b3+W3@FYw*Vf} z>I(&X)!bOf+4xU_?H&4}erDwoZyEZ>#N$q&^Lh#8&GlO6riN!oVond!j>+K7p0ZyM&tK6(><$G zu(b|uzjt3RI2N74_NdQ(xA#$JYFAjqd7Z|gIy@}7dETscO3|xEDf}Q2b7RV&xLfsA zh6^bH4_1k}0E$;tHwbF3CKzoRfh>%uS)Q-*lYA({;4wO&-&09mHI^=B`O%c3z2n@>ZfpF$mb!{wu`x*Xd( z^gzN-w!=PeEYrwb=J7V05E}G~CO|V;p4MV9>s$mm4BR?2b<#VJgZ3B>=(gzJP631N zBr-xmGi?vmxZ4gg6Hi)4Q~kswoHtMXKvE5EG)!#hfF8HGC*gVAIhvpC7sXMz6NG~> z2K#luwc1}nc7NGpYDw`ZSv*QQHJZLB%KVWW!|+~)|X|*B=nj1 zzY3ZR=6cJSxDkzwjsJ=@NUH}m*dQ`50vWBR=>f+mB6V|iiAWYC5l{oel}_k?_9TXY z@YcFLl(@uGlw21mc&)P_RYN%x7Zlw#MCr(>d(6g&N7uu(A(h%^3bwpwq3`Y zGLQk>mV0vC#=BAB`d;MnernZ~a+KAg+rn5YFP3;+&04u4D1MSyL9DiSr-Ab2?9zMQ z2f%2_Vwj{nsBn?7!_Jgqakn|ytVX&+jNx_`a6WB*u!E6e0#l@jlX?4Mfq@W~kplq9ew!W&b zUc5^yGMye!j#X<28wZIKHts!BroQZYl-~i`G#s-F)Q1&n3yojp!rKhr)57oh>17s4 zvw%(Vf?(@NB2O#E4a7?4`-2nXX00CK`k?>y0=(7P_5>gWdpfQN#2|Q4C6$-){z4s; z`pFt|HQ>NY+pE=C;z+B5__j9Hs%*U39qMrOm!M(863_HpJn<6VrP0Srpk4Tjh%U#K zA{Gmg^;_qkSHthKnLIIn<`zibS`BAo^F?=u8S%EV0jVtODbd*m(G;4o+~A__-Qkg$ zCC}K$WTwGC0~0{QyY)Wb=j1Bm$)4+?5 zXCF>J`IF4fWSqKHe?W9}PFBPTlMY3FxJuGfy;d9_3u*)peY2le7NoeKwcdSpwW1BV z%*}sdRZH~kReI^9k9KqAy!op$8QaEH`;R^0AMlp0R}+SB?$1Am6|Y_TV7%cnm7b08 zsV3W{>Gd@~8Gfc!Vrsjhqln70tj@CT>2B=)ZfTas260TYm+)}B)$3rKhYfdHuP=m1 zXE!!~EbZItOFT#mT_F!HL_=-aA0V~kPo&-)(Nc8cD+i*zNgTHGMDw0z?&*cydBJ6$ zrE|9Pc;;wf)~z~qR*lJ47F;SJl=^E3rxaW*7keo)i_$-ul<1Nfr41&{J)~S{1$70Z zhZQTGNzGqWALxj`B!3z({{2AQjFF8qH!tyElicOFvw1s)ecLr1tei(Xpi@vp34+m_ zCjkFqHoynZjujBVdHlsNwDN+ZII=qm2n;zkbhJJKP@A@Tf0Ck@l*qT^7XM2qT$sDS!De z=ka)Jqv!8Qb8oYf)r@x&!Sh>pww5{Vu!YA-7Py(=6W6VCJ~+Kn@44QWSa*)$u_YIl za=fUgX1yRg==;#>BEi)%tG#F~=-&}c2sc9WMN2d4eE7u0 z{QYS%(WuhZ#~J6w1(z!rKM!5-?zY_(&U>%18uGKc?VPYnmn(~zusI*H&+t9&6g#~A zMV9KOoN|0;>$U&vDkU4T@`|7+v#rn?*3rm0@a^Med^WAQN$+R_Yqn70(Vmal`-j#P zPsA{&8VT0{io(=Lc+dFymu2`*ZF7NU&fpj{Y+K zHVbTneWm_kfON=VFa7f;4V>#fwJd028-yRo(%}mb_^1P6z{JFqeeo>z_0WBsuI9(r z$m-9h*TN1WuFq6fspyWec72y3{Bghf3RMY4h*U~Vg|@Z7SD}G;SGS^ov#ZVjj%*hD z6;sye*20XYl#BK%G`OCBXYe56@6iK}3wqO@U4yL3s2@14wDZ|LyS2_m+)Eqh@6vmm zjhdGc5taxmowq0+2?y@(Ifd4aZD8s5lZ_r2_arn{Y#tn7su~A)EcL}z)$n!AhlT5F zR@Fxd&!6`Ft+fs*WaME-L)r+t>>EfLff|ku?a&J|7?j5sW>!2J_Ehrg{qP6XK{*h7 zz5QKR|AR3-JNy{^BHKYMJ&wVD0HTBV)t@zBSdmjywI4d4p@dwwceZy&bw<8XXzsXD zw)~RmlC7(5fqSyyK$}i_%mgJlF;2>XU9)a$FNIG&HsLm_umF3IM6>Q8E|yyj+9BZ1 zUWgRYqWx8P`M~wID~2Ir4~g%yT^(jUGV6Pi_^&RFqx$Oc17UZ)Nw(>QNTV;g<;W#P zp26n5#xvAzHy1tpblxod7y)Mi%cQaRPzpB5KXhR-#JBrA>uh`5?r*9hXY-Q>|3q&~ zo^KCoG3e3Z{N`|DIn7!RqeOJQqrZ1^-QnNJqyVS73MAm$2W z#aD6A5N=Lvb( z6`~u<{KH`8{?abdfv|X4d84)^nyX7eh-xDrWQ?p^6dV$3WU!4f;~PCK{YDZJ$j|?; z6b0RJYhz|L~ zFQ@9s*}^VEvTgMPjiM(YvC}o0x$0#8)Xb;~TmL1S`r+ouguP<&dkkd$Po59}%1rCKADiLA3XL zf4?fk2u2hQOP$$U|4viDiuwd))_jf>6ZmoFKBZ}C!u_h+&n=Wt();c{cRt2D8A|GGoH>!N@D zwbE0k_~Qn2!KX!PGV{a4TuAXU5(ev06&ynOI7_eo?TKHd7Tl8fUODtwHq&=C*l1*G zhewf^3nnkF#Cw{mAgH|bbyc)ZNkYg{+N*7OE2s>ig)}Z&S)d)R-yZPJMvw@@5Fih? z`wTn=)iYlc60pK2*`$R-6%Q^vm06sxJ=1Vps!KZA#OuacZVM-|!6rmHTa~h+y)8iA zfvl8Xsg@Hm-^0+ZaA_d{tVMi}_+IF+nH^0~>K}Ico*WI8j2|uSF&z#*Iw@aUJvr>5 z&-=S1>K2N!wpAP@pn8g*WDsw-?A{-+<)Too5`!1eXn=x6XKoU2*t$-X#20e&(qOHg zw)Zu6|AKL&Vi}*EALbF(rYYy6AAWIO4!unhs+(Sr^g92(kB@ey>Ir@oyXIRure~B4 z9NbVY-`&KSmJ?NbEz`G}$G*m)h1k!8!YxXKV@MC~c9F|yRT#9KL&3W$wC7~jq!YGA z5ut<=Ytng2wyzV2vz0UuzTy`lOiM|3r?q|{t+RcGYyh!Qw5Kk7M4Y_iP=7RZE*BbH zxq6Ydi)y0n&y*w^!YJzG;WGWccvdU;VYl?NsVC7NH}uRBHwiK1fWdr0&7wzOt8LO7 z#re`J=f7t;TKen@eYT1EXXtKgbb31IMt$xe{%~#@{;h?5qQVSSkVE{cilD;yzWLh$ ziy1Cej{n8{)F0dr!C3l}Yq7B54i@hl(i@tmZ1fZAL`9rWViRLW6n}1UO06k|Nxm?E1&p_UXE8P3^cqJHL3; zw>B)ZnnqGh)H-HVq-^m_{8pu7llgMQ4tE?(bX=*37vL4C4UAnAb~mP8*iWU&vs}!O z{XP|MY`c2-nCqnPo{z*>N$E5l;7%n-T(1sIDWq-jr1Eg1g$Bf=BWW*JdpVrKbTsu`xWY~S-MJ!b*8I+wrp3Uf$3!3X z-v?GekEX4~Rl=nBil5Lu=4+E4mTLdLhF!j4LxM7plrD=b67o^s&g|10I__8@FjI^G zs&@0_nY_)f)VLVF7mwGeW_~2;z{aJ*gJUS@i}*qS-feQ9NAu8-2|5Tdw=Hi#l6}cN zmh~R^Pj9{p?XftK?RaYqQbQxfx54!8zl=u-kp$npEjdC-go$jbO3{yWg$#t$e_&e+ zx>XTqAC&c=!T^G5Tqn;`LN8JK{s$lR{^;c0jP`8k?Jpr>Yv^Y?Kjiu&Rs(^g*Uu2| z4|lwpe%lk-HKb%*%u}DH{yWjp5#9gb7KFKmb7bT36Xp0fmzTeK_B(8SQ6W?23JD+I zd^uiomoMUn5kC%TZz-fodE(t*gjITblIz9P8;~iDLNj_<_(*%d%zu2tUkpN(C%95r z8D$I5f@p}!q7~cHvSPTmHQ)}e*omBtk+}Npr=cPXjP$5Z^23N>I;tM>OEW&!!Dfhy zVY-7xhnAyK2|*$5F;qRz7P#kvYB37RE0w--cJ1>a`m~e4k9Z;}Nu1!3S$V4+ni`AN z^^SnX(J_^S)AL~g;dU{x_w=+7+JMQGn_sxt%5`sp_XNJC3zc*X=jN;$kB^OP>|S~7 zkz_w~x6nL+(Ei?;E)gtiZ`#HGGZ4O0Ygs2s#BBe9nL(R38n`J)vb0h(zx(Wq4bza%1VHoN8lY#l!%rj_e6#hhvlyrzMeV?dfOt0p7-|>trDn5SV4EKLo zYmHuf6)*hoj+tx*F7L_5x6`f889}YCzW!<*eTI;7yFg?JtNr(o%u{D8ZpE!|1|}Op z(JqbJNF#0x#oGQEqGRf!2+=P-sVi3C6aof&VXWVL{DSq5&K8avm1Mg-rjHl=bFGxO z(LdTQ{4ds-H}(qd+uwz51vS;Jw|o5X38-+;tImvXqPuMyjp!(U9n<&Q(46QOHm7at3;gRU?urGhDr5|29WC-A|(bMVlj1#*tg5 zH`OK%#4T<*q+X2rkL~_idd*U!hl_o|5>AQv)sFK*@7o|gr1(9ntdAeDxdN8#*3_=M zItrJzuK>cUWc$a#e_pXDoaUsHU{TmUqM%E-r+H4 z_|(Ofdu^q);rir!_-fJJ}FEs_lkqW}6D%I0BG!XMEa}Ck1$5=ui zZ3JaiVi_EQM6vqW5e<)6Y_xN*T&!^Y(t0z*|9IliItS#+ph2AMonrqb@Q<6qlyH}5 z#q=otg{jY?<0gc|N?eRt{qQLXL6!04JIxc35+g`Cv4DXz%NVu5t|p{?0%8+r!w``oDDD^|&?&&}6TsPC6DZ&Z3wV+y zd3uxmu=D#{4TUDnr@|K;=+X5*3>-bwyZr`&7cTyy`9W1x_QkD+nv#Sg!f}e~!Hs*n z^0!wy4w-`oH;PeVPt9!}pqh11`lJdkZQO7+$BvCBVrFU;M#2O`?)yZy8%g{#9{EZW zUY-Rn7v|}WLSNkBqj>2deyy()W`A6_3hVtPMrqTY6M;X^2S3c_qnC{3e?Eqt3=Rdy z0er?;Eq0qw9*6rCmtVr}3sb-eZnu#E(uz!XaCC;ah7H@Jp_mS{k-$WKV;0$s7bmU@ zpqf8jBByfJl2#;AsnwGzlkTVY%ZQy8QrQ6K?U>&={=*27%j=Yvq{;O*4#Zw3`=p3zxyK$t_PS1gdQeZp+`6+3cHhzdFkBYImDyHTFm8%A~(;)wTy z-JN*rD~Oq-xEYAejpN;1g+K)zz;am0S!Wx`D1c+HYhXmO-x)|W_>+@rKKgq zPlq#jCM1@^Nl-VJu5c0>?p!*#BW#e(f)IZClG8|k=Z6!rX|k{&0_Uh3?w8Z8;%sx`NB!F^^Fbqj6(Q4 zRR%}s#OqyC8&eaLHZZ-~H-hK-nYPyzB@_m0u89Z?Y+I`R6 z$XC&WZ>{*AKKdHlnUBe~)`!y8vdZ-lzPz)|O-;Se+srgv?%kj89nEILBVQPGg$z)w z4AnZhpd+S6z4U3-;zS284M>(`q92%ny6W6|L*jI>w8sLZ@nk7#@NL+`RoX*)mFYNx z>#;$xTD4iA8!@q%xVSBt$VmR~9WoeWNnc?!n26x(jgVeiieWxg+>Xw+@HIP|VgZa^ zeM?72@{JT*mZ8Bx?+s6jd(ArXcSCu(!{Ib(zT%PtflS$=9&{#QosCKCjOpLCUx%~D zSDNRIR~k&0iu@>q@sBpcjP*~-w$_pn3Z;NB)46pq)b72X93*S2-K<@^M5k5BgYf;8~$LLXB!rd%r_ z%6r4!v0c45oSU1e)BOd0ie;^fQsKk9?s}N}iD^h-VoQvPIt+}IXt4d%?|r72zsO*> zj7OIP)zLpNE%z%WORx?@2*?k6!i@RLWY=2p4A;61v0qpnH@(s>dTI0UEpq0f>kU^q zL*ue-X>^B#8i0&0>%29Pf!yCo9`q^+4rW|lvZNpIlU})!sX1jwfQqkpVBmU@kfS#O_bN)Fun$(AQ)M4%m zVlYXUv8oEKbk5M+oED5Q4Vu<+M+b9n+m1H|GUOOrACGrkd^uf_oO;P099p)px`)S9>L4jW*nt-d8OU+E;-Vx~gt#4& zYVQe2cnwf_fEJ;o!A!{ZN20fM>~NelM2J?A)3;-s1qsHHEwE!>8HUZsPX+#kPB9_+OQo)jB0H^9y72b8l@PKYDTPX+ z@C#KTRnw)+xMo^52cXnGNg)JOQXuin#Kbv0y{T`Fy@sgzw|G@&@pyV>1<8#x7rpf^ z6-f`p9MHfe>?kqby>~;u-}+TichMAisi%z#ohP=bUr30>4FfxsFQvXhXgRqiJuT7Y zQ}}ZCgJsu!Kh>uO%@>am2pC_6N|ozMWRfIehrFL&;2?4DPl6)^enmQ)#>J6B#oytT zZ^kk^>F?_uf2SIk2bW)ZmFoK+dh+?|V>j0Ypni_&cx!h`E!V{&1y9HVyivcxZPkP* zcp8l{fWWQiZ2BmCvKj#r%7Jc&ZGoSL;~yh}4OuxB75zj{{gN|$QeRqit>CETzQ=f< z+nU0QgA$1|f<;GKl{}Gih&TX^?cp*(B!skkl6#HnJFevRE(cS)*_VW)iJ1i1A|YMD z;X2XLBcnR5_ac%gY```U`Cixnfn3;J{l?PS&V!0>%+D&G==+9bz8UoJI?qlJW9f2OWdhTF73Q4M^mlj1~S6C>{doVaygeA)3U~toXo1fB1xh{R!J^b~MJC z)GpK7;ejsP=&15Fl}9N3grhS{_APoA{_q`-R4D^(&}^y8&rPfe$ziN!%j>M<2_%^Asa-V`OeSDdBBw)BPbh!Z_X{#+KMrO^J7nkcF~)S&lH_od7Che{Dbm9;v&aOxUijyCUBeGH z;Kkz2v>bzo0(+Mi6;mDO=_h`WdxtKUN8GFb;pm~R0?apZ#VqDiD-EzxA_s`MwYKLO zE|qj@DBNY^HSB`4FG$b`iHIsJW

-J5+XKX=>W;d9fI91_PxewxzF&L(m|BC9VeM z=dfuqVS8S_dZi+atz@Q#<=&rXgc8G{9jAZZ%Jy;^D->sYVNh0!wN0FgNJvJYnefWJ zkrWAH*4_DZ5KH-(@3T}BI{Q%#!bO2%5eSjQ*zz4uEoe81h1E_I(y&9W*jv(;+ZFyi z6Jlh26elT4P@eMY89sq|_wN~>B1ZEGnowzs&dc?3p80=rnBR|N3rzB0+^_smGf1u) z6zKqmeXSR1qn42ShxU9alLOUROeTRWgD5YArqMlRHKu3fga#Ns+6?QERofeP;+J9J zMCF!lRY*IdFEzMc+qTtYVejFmY~K*KB}b0()TV58o}e(tiv4@XO%DWGRn^giSQZ;N zdO|(UKc?HNV}Yd^E&|F_gG=@)Pxyn{b@~5AovuFoL>c@`ojJ2K$MP-u5S0& zK)Kz9nCdy%+sVnv1Rl?ZWnXXUi`4)!y`E5l{DJ}iae&MF=#3P5qP)Ry#C$^)pl^u= zQ9`Lu?bs9AE9i#eEQFfbMi*#6{t~g-|BnOmQ=oiMV~OW~>mx}25u!36txoxZs0xw6 zM(|y++tC(l@|F^2*Apx=Ae;z#`OE7B-brAvRW?-01@hFQ?JJ>;1|?l-64_~F;6sSF zG2kKz<~w}jra%!}EzdK>1=p>VU&fE^8yD-=!Z{D;%**=Rk~79;W&*#X;$@bX%be@u z;^64Ce?u~{u!y-+0W09Qyw6`L6Cke@sa)Es0SmyW!0scgMsbSd>%_tTOAER20I3Ii{YM`wT5KR1mcEDpM4isLj4+f*XUoN<;h4I|!r15xi++X(c z>fN00Vc4sQ|+njWD zb?eTi)Q{SqlC6Lrm{?m2tE&@*lX3@NEPIo&EqgHSI^BG|nXS-&>UDpTc9R7I*TA$`g9=)h7A?mBZo*dZ=1;DEAxh3eo)jc8S&gS5CU`!EX4E|5Ga_h^7g# zkm7^ht%7O~`e(87pFa`Wg4i_Y)$3MccyRrlB3jt*lhm_ zEQS2>L(Ayd3DB96KYRYXH(NB?W-G;6Z#-A>63j&Z5gGY^xOxk)s=BQWbRzIo_wsy)?>lT*Yt1>w z9OE7Dc*k5b4qk+Q*cy5+EO3?MgV*l|E^$?RJ56~ETTn|97q}nTef;>*VByE7^69si zK79Om-lqYT*6Tk%|AJk&@+w!|@twzyA0yW!bRLIy+|Ra9=YFuKs@e=FJA9FwsQ|4WGx) zo>9`dZ%O7`z80dLbXlSmfj_%&=@PX~63n^tj4wrj>#n(J=_FnxJ^b3o=;)wTULbV} zI-eBG%qAB(mKY;6cUsUri|}Am*ysi5TVsD{6Avtih|A;546t zJ%pL|A>w}d<7)o8o;&*CpNT4sfm)viY$6fwp&|9KF&xQyZR;9eInD~Hom#LQyK2~s zdSfLeCDU*4=!k2qq1ta?(r31{g;Rmq7~U@2eOMJ_+6~@oPMRx=qs-yC(HXzQUu>&nc@~`OD z<>Pm1tY6S%F$j1Vg51OZ0`LorzM6%GPzk9LwL3uweA(eeAYF)H@~Rjyu>kh`QhV}*h^(s8*W_xT=mg>3h{taO|+5C#5nY6 z3L##n$Lu0b3j!}%G?NYIJ)VY>mN2sPQWA*9DY;Jvew>fIyTgp*#Ct=Q1pc)>ehV3S z=F-L>qN{`~IEWy7nM_m=7#L;PU$h z#r7EabS$3?NcS8D1_ucakwE%5Ma^&Vmfp>0DRbp0DUv^=*>-@rB2(Dr6}8Bc!?_P5 zuUKz;ncTn37J-;wCjTTODUP_0dWe!O-#p6*k5F&unbQJB!pTfiE`VFsb^O9@aa*5+ zkID7ttKO)2lSw>QZto4?Gu3=6x-9$o>~qWy!MCuff|*{F-KL-3$#Gqd2q|%jOV;w|`L3 zcKO7Njlu5fprQ1kZDdHZm*vC@n( z+;c;AdFJXrXGjo*!fhnR8Ev^jYP<5T8EY)z6L~0D1EcVe(D@oFu`i+GKm7?#D@JFm ze)wPL4I?>^#ao>EVwvC|NFl9pgt=CD%j?&l{eB*29j2}NpAPwFtegCgPVjwqfTzo zSKMyLKHM|ix_0)T&7y0X_lPa^L!sx1tE#H1^SBlFHJe}ehB3P_!@5qiJFeZ5mlqZm zFsnKF$FA~%|J-32LI(7hw`jO*OJ(%WAQ^;e5@PuQ>a?-qWsDrNKB89|gWKf{?)4h* zafmASog=Q14)G&j`uF7H7tAibmS!6*&dygOo3-)FnWCy0 z#~t&`$LpiT2HeK1P%hT($qaia*OtJLWoUKOpPkPF3xPDybKOOqeO zf3<&%(tQ3pl~zOk@n2A~=nve&;$=x3+qN^}c`$oVu|Y;2W%E+SZ~4T@QTU;_alv>| zy2fG*4Pt1%e4(*dl%5_zRH?SoFM4q?SN+U*^!wPlW{GL|Fdz2r?H+Rri$b%0)_lvn z%GFzS^iIhhR^#O)4h{~U;+$Yr+(pzU(WXo>kFwx=;Igh?TlR|W`md?Ttl|?m56~1L ziuJlnFAfW3=DCDQ@%v}Lnk?(v&X|6Y`Ft{x*2B2@pV=e8BQ<3Ae}oHg=B&o_s#v83 zIh|%q2q;l)trRXtCB^wVStY!m(ibCylCh?K?k{hIPCP3=Wgi!?IG=7J#R%j{yfd}& z%ZD>jf|MBO515@+S+YmhP=FSKA}^LZQ=&WPj!q0+6T`GY8mYGlC;jc4ABa&YcpMJ@w0sJ-ocFZ^d<<^j5&H*HHiIusrA$mg8Ni(DK4 z2a(4ZYUA{|)nb+7;p>0nK7Us7$=*9$_I1hqN%tkHyZgS~yAr8eZ+q;+L^+>nMbJiQ zyq#dk_9*iQIBtVpqDH1a{6(yUled3+T(|hy_}U(eTvWT=IDDV3*`M4lKPm1Oi(Du_ z{R@E4`P$v*^Dnis8aSCTo&J4NnB?}*XBPM!_$+LMD&~=S9{BRiNECfQp81B z|5B>0oyr>Et>!Z(dkwCYnv2*U2n1hyQB)7sj@|%?5@<>dbv<#~hTnRF58{mudr&s$)d52>)O>4NfFlC{L!ZR zc=tL@ra7f*(s?W&SL>%?&D>0<`)qT`R8l=PAQ+g+7run(e8u^qrkz!mk`J5h*XThW zF!SBTN3N2_tQT0-?pAR=x>oTz;o#N9h6HUYkxwXgaVKV~(aNnKt)xlx6oFH|Df|D5 z+y3tfk)Us?rmAYNIa#AO7VoxEQABf8z1_84S(BWM`t<1&c=X5xjL$A&4HKNhYmRnP z`L&1HZR<&1r-Ja;{-&BBlWGqsODSM{O@8BvLWuV>t`n2_eDaX{>cKeO?nU%!KJl*x zvTAh&6W>4vE2D?7q!&;t$q$FT0dWx!W%-9Zwc@$3U+O1LkGU68O{_Gd{2tnZga!*5e#b-kGtHT5Ms`{PbQKH~ z&kC{edXEfUjjxK88?k<;x2zvN%0ZwyO|F&XgE;HCV2N(bQk_-ITMPXIEV2+<&y``D zwEj%)+r0Q;x-o1ORL`vi(R|fA{Q;R~E6wk*?_oBc5(EOU9~=(=S(w#nbAG9Hfy#mz}_y1+}rw^2^x~TMZGodc9?sE|Qfke{r7?|3}=`uQ#iS z2T7HDSA!lUqI+g(nn!j(^T6ge#G-t$zO=v3=B)9RCN7V@TLf$km_UTHFW7xVTRW*A zqWhIVKz%s0=)Ggo{`OMRll!37Nj#gaPd>V<^HnC!_U!GecyS@Zx7?WUbCC)@V@oe* z(|@mw*p^`FQ>di?f_X`>enV(Oo1soNqjhx5c-nf3+-UcEpX9!oz#UUHfI;u^D3%Of zDPK!GZ9ftknXG&XGEV<6!{}gr)Unk+(|Gz1_GpP8Z}|+bcXV_-Qc#Fm7%?+5^A8J? zdHB$`jZgdgtA@U>axVo>4G4Bdf5q@T_->?_BsKw32!K8>g#S4}mp_dnItS5DuJiov ziTuoGVRQ8KV!5H+ov7fDHkpG@m>YHHrf9PzWunVFa_sF5(N&$T(`;Uo^C~Y16SQzX z;fv9-iH-(;S75sp_py{gp4dC5>oL|e-PTFeRVyjIx3nf9{#%{r-tZn>kI#;>hx{_* zRIhg=R9kN<6omaEVvg$SSLrlA5QJ#?hC#W+Z)nk|bLP-<%v|-HRbpi5ZMKZ*nf<-# zH7s)b(BM)4IW(Zs&Ep<|c7| zBVuSxUFuO9g=07Eo2R7*{=;nwpd_-6n!o>z^n(Ha^l!zWYR<_+fFFp0j*R{)VR<_< z3&oGBOufK=od7S3sNtV zg`Avq4P~mf`+sNnk@~4CN=^ zOFuyVW-%rb$_0Wo^xu1t20htm{UGV*KyM}<77#$ZXPre7b9k=Bkhx4qsTTLi$%kRt1 ze;RdYvaMP!>CE%qIY=`q+|B17a_jc*4$M|_-!Z>wjFX|Kn z#NRe_F!u$uwK8=XOX%k8OW~S-!l#7dMPPA5=Jr{|pqXk+B8l$`rIN|9$6N!|IC{}> zz)iN+7DUMGKZB5pDyTNMMvidkBCQatVk*lC_>$0>{;S%hat8(6#TPPj;rsYcpKeUO z8xum9Zv0TI=*&$t0EAfKLoZRlzS6B)JTNAUE`^6Mg|T=sk$+r*anya(RnI)WLXqI5 z)cN#ae}TD8*e%m<2CI5jm(T1~poV(X*~SP$W&pb65GK$AGKrgEcT#^juSW3r7cFm1 z$BJTRY!ceUeqW{yT5N@OchzgI5MTc zjfd{@F6H-Ueju}G8Icm6{eufS07+=%YIA#+_(GZwDL}uBjCiU(wXrLVw|ud2!y}A+ z&-2+LX3Bf|e-s~Y$9`#>GvX_NAmIj`*RgHb7+2*oV>Qq%MYLy)m$;ho=-sDnkAR-o zYG(>-cXZF9A;e=Rzf@T%LR7yoQiu(hHF^OvR%VS5q#{Qz zfZIx{TUuO9O-^P&iKa?u*LjM@#>E{SPneg^#@lyYlnC>GM9AfCivlxKO0MEDJuAII z4Klx-BTrpU{vTAMNX%_@#Itho5T?;%)#5c`M?}p4i4d3Btxqur5h<-A>7fNEMmA!i z0|1$%R-{qa>6TG!Zm@4Uon?iyij)iBK>?%(q?SwKT#bhwYB%!C)}0t{bs5(;4{)=` zMZ7I5i<*T_s4%sVD^0;MpDBHXmrQ0mPXI{8AmNA3rehTv{I0vYGY!td6M@Nb-f#=v9romySh_b!i3#`#(!Q&U z3db}3CnKslK}@A5iZ?Q(W4T3{NbRMiVdPN;PS4WX_Fq851He4YLGaz`x}0;q3n2ne z2j5x|MRue25?jjp`%`t6pfW%8 zVBkgNvkYmgw**KFSm!gQx%i*5H2HaXi_%E8_S(5$Xb|PnR64ddGiz zv|`?Bv0y}3w7EaH)+r6I*59Unyrrf@w)gQ~gLw}F&rkoHjC8}_psCooGCtC~AO$ts z634w@F6Q@?pf-HBT2go$IJCF07;1i1@tm3Gv6xbSwg;5WF(j{=Lpctf$R*)Ckb*0O)YyqHiBiFRCP!Ee;tJE8U zm2}dh5hu`)BXBLbI!kd-D^1;J-1#=^m-j{+?WPyrLhBhGET9N3(X$;Y@RvWxn<;NV z<7&RO*xNem8x1r4tu`TA_pClgzKJu=*uUtV12pbrAS-y2Hz54hVqt*P8IthSZ{oFL zAgpC;4X3s($)mL@JCahyzTL{=I}@+OlaaUWqsD0$z=mw{%u7B>)S(6a6bt#anCg!}AkUD>XO++7QgGiZY9 zE@Gb0$r=vD`;#`e+9t*9Z{K{MOoT8OQ@hMqjg&}OvOQh9(?G-DXjC)=2^T;&0BQB> zj&7Gfs%D*+iggGSECVd>Y-%aSN0%$ev~}lp>s!C5c>^oQpOovumGMY>0Z7XS5;1v~ zc+KFp51;_fs@uJvF}B{?>Qf3K3h9mjA8OChI_5@tH9qo+Pw)>2ifoy{z74 z)FcCibu*k5_+Lc&4Q(1U6P$qL1bN!V`c1x7vTX_79KW_RJXoCcr;WZ&WZB;B6YA=j zV}PP1*HOO{G+mxGk0v6WbX|{wu9c_If9uSz|7QIP+N93lhpa^C?duVN+c%kUhLeEu z{g?dfzV3bKe0H)gYUPEQ@vFhTKs3}uBp%F`g|Z9m44qHieyX z-EZn?-@XwDB`8GA3DXc>3z06b{*p3QVb9hYLe18R_M!ChRRbSY%#~Q7$`3SF_v0ssKj1w6MeD(9txXUs_Ut8Vfy%5AI2!0)J}L6b==8WntevlP zV43pJ!el?od)+q7>(*)^$YScTFUcHyrAJBtZ9IgjbVl??=bvD!VgzXsy2O1c>?owm zifxDLOrtBUUQm#=v@Dg<)=^ZM@h7m<=PR}6*<>unkiMIX&v8L#_cF`;@f)Sdp3p-+ zyog5m0?K=m^d%2#SL`Ya=1j3G<2jjqsX_RtD(`(LOEa~sZ(+j!ohHvm;oE)X@{0j8 z(!GQ7Hw8)^9gQ^1uwUVFL^OuP4@dRdCy~t@a1r{u%A@;(JYuh?Jw|QG9FUbiNk>gf zh|n`;IoC-l+nhlEm9KiBA|w9IhYu%jFT8yDvcvT_IQVk@7!eIIKLf8SuIq%diptAN zr#P;+j#=5*=Gw!V=*DOSYz#C(d`i;01+A7;QzG0%(E1tFpbvmex-Q%$^d-n#mF?DhJz)+q8S}BHI{j}yUbq6> zDILYdOjS`zZxzNT*c?b|m~3kyW#@Y9%Ap7jcRhks`0=E9*0H!_lvg)iOYQ-)GTwg3G2aTkNV zUiamT)DXNj>}lP+=Y#@X)7ZhKq2W;IQ&a#A;Ew5~zBEw{dQFecyCVC)v5vQ^Nd5gK zu~9!MDc5-<_#jCJFIp@kZ6x*4E8F(R6G(d=ehyFna7r5fH-O_#!%cIlJP`jIwBX@j zT)pmT(RQhLC52N4OtE)7RH)|gu3-W_0Q)4yLF63xmEN-WVo)~1{vH6NYbjCfpStR5k>$y5>>5YAI;&cm zrs!?B&)xX1Qn4RM%^F*_5>Y;aVA4yk(etQs zH&1e_r09zY()X_FGQ)C-K%w!UIm3{+Ze4sfUHO0=nK=0Rw@y8vu-~6_BLctQl9A*Y z`2IaED$&OSNBj%*X3b_`Ab$19-k39JmZ4bN8b%-15=3G2yXa+mM+fB&`o_+{(2(nd zRq^lS;kB3RKE0;zS_~!Sz9LH1DCk6Ge7a@U z>)lXSBYM_?t3SMe3gL~AFW>Oua|O!M(et_gj`e`*t)}bs zca|dsSo{;OuguQQ7J&K=c}8de@EcnfBTK%0;eL`AN}-hGX!FbIo?B5!=RzZt=Fw2I ze!jEZE3lSZyfqudm71Q;%8-8rC!?}bD1Xe7Z|uX4QS#j7fo_Ql?}rrv^8Xc2NC>PA zw^M8bW8X(Y3pjMi$@dxUf4n#2w6=Fpfi&hf1nm1G^$O%`AWnEwJDv$$w{yqoXU^5fHOC1vGvD35dYZre*l^ww&=isE}KSWRQ!Et}v$ zZ6Q1xt@M2bVS%7=SNuwuSood6;bFH4v5#2wU@&xLct#8s+|`bcFQGhFzD6TTwcla( z%RMQcXOp9&fgnEY^mNA;1Ls0_*0p~gR{sEdliz*GE-+3?+;0BHP=5Z0EPkmsy(25F zg~k+A!V@-gZMo>FDB+pqsM?sOgVPmizi zHP;#OIjW~X8^lWT;)haNIhIXZVsHie9FY$W#0EZ?^;#ypILgCUqEtwF#Q zJ`Uki%4cEuY7Z~PO4VW%xoH)y)za%g>acU(-@o(SC9*v)>E?$SuGauxW(qGWv`D?) zbVTsCmCR6WCcyuZNR-aga*w0EnIE_FrPS5Q^_*vL?(*|Dtve>+7l~4uy4`8td%>`= zGUiscKB4!sF0y*PZr?~@%JZ)^Vl#sp`XMDHcdJ3hxV-vzMuXk=D%9#7s-$`ErV(M& znk0MT-bc*ke>Y(y+kE(qatDDoWkG6~6F5Y0IO_$(bniZOy_f$n<$vGr9%nMkhnL@H z&oK8FrA0Pl>UC&?z;{5FYj4B|6np&Bb`@P0{)lEdkxiavAMIJC^_mjX(}zJ512Zct zJGt}2qZg8Nc|EP* zoqKU|0^?0NZS@4887|34~7S^YBU|p>ccd?xgMnVScgg&)v3qY2PeUsVS6S?!`{byNe}q89*WtB{Hj^*xG2#ZfiK(98gh%x0+K&Sd@_9)6bV)xBaT9 zgVje_h7=-cq2u~!;27Rqu|;b)0X(g>?9#-O>-|4Hx0RniZK{I-z}I^A4dng70}`n6 zi{mh<=&xKJHxpe~vjVSAh4>Vac&*e|oSh!EK{%#wqjP)ps&r7@N8g>O#gJzY#Ihq6 z`8Bh*^$#Auc5-S9rsSPHT+0umwyx&UgGMO-W#P-!=%cEoL^s1Q(LH}I_nAw!uy`$* zN@=Tq6WhB#Tz`;lMW2hZDP^#fI&&Cmf*-8Xp{%}lTaK687Ov%0EqW%xUvsMG>rJdJ zwHWrEg_UM~x~;MIyR=G^z15$DY4s@ys>j@Y>RS2z=W3}Z{FFtq!Bm5qbz}7szqEFY zFFOX;q@^)Qhm5{{+I{gd-ISm~!i%Y!ewQgp)1;qqUol{CpF*MjE*{~2h$hLYWHfw| zI((U0j8Qt|)?SrzS9vy(W0of>PS!06mqQ>vBR&sfYGo%?RklUiC~7eOWld zHM<&gGDUTx7fof>FjuEZaeABePijffUTj(!F*(mra%_pQ&N+5jkfp3*~4I=$-M^qlfIEF+O4XA{~xn%u8-J_F@@O}hHFmpK1yR-3)x zp4 z#q$GVm-#&h$HZ;?m zk8p4Rwi6xwC5_zB4WVOf&MI@1DfWgFvYB4xeoVDD(x9ikU%az8nisRzQ|*lLZ9&h= zbs7$i*0G!KhjRF}Sy@ksggWo57aqMk#cszg-Ee_FW)Q@hX6@xYKhBFes@<>Qs{Q*Z zzuC5pcG!Bj+qkfUHLkf$Y_AYA(k4a@9Z@>&OTtqD$WTFWS0PCpGsNfmdUvn|_cm&L z%H=Spm<}8a?e^lYoN^Ctu`1)^aX5K?&yR=$s9Z4m~tD zz~%t9#F0BQQz7dGO@y}S7K%2IT@x?G+baaqiH_cSYH9d0hDWVTW6dV+>sPsG^@&OS zgxwwpC|*mZ&Hwde850DGJ^p!Krh4w{t!?}l&h~betG}XGZqr|z&pvIuhb$<6(_;jqkR#IrIWt_@?D?TW`DHKgL||+SO3INcWZw+ zEi6?0c!tOpbZRZv{b-aoi*SEMX+b5f zPi{Vl>T{nJr>}~ITzj#;S?mVT%r1XsAzDALvW7&QAB9S;VWBnT4wFy&ygeF-iKeE@ zaiT;?kfv84)&u9h6V~ez6!ncO8rNRi7unYO)n@jg3`X$;;^D=QoeP*AKe4Njcvz3S zZ~sD{?$^~#vJC#(nrWK*$=e-llH|eHCAbuSjmJ=`MvjpU1ji0_M@SeQroy#5els9A za+q^-v)htkX~a0r(k>rDFT>{-S2kI*%#FtdYGwQT zwM9Ksg5Sris>Xq_LOo(M!!tk=QvIS;tc@5eJUhwMotxH$V=j-Qy$%-a1QjX_jeqJF z-72#`Cn0>p6bm^Vx#zF418T!OzM{Qtkt+nO&v*Vxwoj_9*i96w-4A8s<93X0OVb?4 ztcU>D*77o1mwaL(WNhNy4szRUtZDI+6-C?S6u(8sQ{+F@%J|LwOY15R-SnTC4t2vT z%uV%WGjceTpD?X#aJD6p=eDn7#=>Yx#)5y_kd*v-Zy9j|^(Pi9nWKCPfj0%=%8^be zPs@W<%}R62S3Dvf#jMCQGKhBc;j$eIbBkpR-35e@J(lEoxT4d22CJzGR`0Rfr>}d7 zf;0GG5cz`RDKwQZ1iU)!P|*@Y9lx`Ekk3a|BeO@7N*~>!}%NNArjLUV^NJQ zVQe(USu-0@OJ4ETt$Uu*3j7_`!aEWxu;-n+`c<|jNTJ7qth)8ZM4~A`y)nS zI^9V_FbCAoNtsuvmGci^%Ot4AM4{Mv{m8%c8bReN}e~aj(G}Yla)_cFGPM$;@7wWGM!rbH`VZ_ zH?Y=+*|+bJcVVNvcaW=>LWfyPPs)SaR{Dj853MAJKJ%Ki0u)iQJ%XRkd2G7rb1ro? z`oZ4L9?MWnN*t^3+K!t-CfX9Ny8Gd^)%ewWAul|;XuXf{QEV)CiT=-t(B52pCRByX z*K=2MPN_7ptsGv>_k|60`EG8?1HabVqYZ6`BA`e`qVCR-^)*fYV*tcKzd*P`Ej#-P0lrs$ca>GtvgqrPC5_xM0o_?_S zPZ!Z4N6Yfnqw1DV6g-`83F}cGi1tgqRXzs##?&z{5!O?FiPYgim0<4+!^5KZqO!5KP}udqit2TI z7CwXf$XbS(E4itXt~wzGwflEEvwbVX5w1Yn}(phu|qDMr5gb7^R3sK8>3QT7He zwBP^iK8j2_{<69U4JdpKaSEliSIH`jmv)1v?U6@J z>3b8QaI@Ia9~FlrIj)+!{q~+mV^evR9#bCsA?x4AIQ#7vXTC%#WLKUbhyx_?H;cDx zFtb6n{ZIG@Rbj3qYM2R7acQiIIYX~oru0q>*tIIsS3UPn&7SKx?iW`$p*C*3?7N2C!3%jLa;~6osV2=b64V`zK56JtB3&b_OR@acdO9AvgKGN+ z0~unUIx7A;ZZ+Vw2~VO!1ILE*bg3zHUn?0e9WC#&qv2%q>*0{r z6Qdf)iA*`q)k`!9FML!nJjS5O%Ictv1>Fs>^mF`Lj{b>x^}%8s{B(iCIzUB1kR{T7 z;hXBM7HEZd=8&`rpas3tuQ=?U2c?rcwQ$Uh#>7%?aaW*nmg+VV0{4Crg@3#Yrcx0CH5$?g2;A z3f&wuV2rXJp@TUZZSeneN{=>|d(-CNkrh3_>3dhRgz(40q7oguDAmY~Na$l35M07a zcHGE7%={adE_fxHTeA5>6}=)$>QBbbp?X%qoYHL;Kby1;X^D3qe zhCf%*uaHyO4IfQd6Ib*G(+J+_0xyz%Bm(V3=oLjTp-Pp@*Fe(Ul9iE2MI?S~GkC%Y z&1lyI?Ox2z0Wi26b-$6ko;9LF&P2nh`n$VBP3MRN#1`GV|1Z1ZM8!Y2?l53E4Y5%f zj4HMfK@8echw6hKQC#|Tesr#;<93}K0ihn-zxdmp`_Ym^Z+&Lv6bM>rn%)!0z5XM; zweNMdUkIuajR}+0fh?YvKR#-HfA!lttm^ejpTI`>+^mWC(X+vm$?e4b<|VQH3M_gG z#AQS{q4;EHe~&Y4+(1PiHlQjp zW61R}&1_;y4oQFjTV=!#dj(d$M9zkJ9UBdLBmryu4+*!?*vr>73`Z&m-9%hQ^F98z z%2`*3b?l#9rWGn#_2i#)HjU6>S$Fme_VS=wl z3d$E_EmBo)ea!|-Gw5NCcjlLUqNn#v>%i%+YsVLC8(arug~8v%-A^H=y||<$L~U6* zLbdQ4YozfPIFiaxR|*MFI**-R=RbvQhF$T3NLry;YOV$ka`!vT?g&h)VcCS^TG{Po zgYv&WZXf+2)Vgui5V}AdGX16ZeCUrE;9v{2d*j-i(MHG=gUf@6EIRvu{_yE5_)9pP zr5)%^7liaf=+3r3zl-r+cRAIp>7q|Iy~K0Mo>Ek8*191_kf6)Fj>^>bEDrRy+te)p1$)gbva_ zW+dm*8{a&IQyyN@xXg#!0@dFJc>2x-vb~{+30m+@HJ*Amod3L;ln$k#ESvIl`vc$5 zAX?g~I)ef$4Px-C+m?s}gK*jgbu$(EG^KdJNNC`qTMw3!rZ#KkqSylv!odn!NCuXK zp(AIGH|aorbr{(m>4uHA{vsM#={5IW;7wm{UCFH_l*qBqhtE*S5ut|HBTA(Du&$v{ zni)=OxUqdcL}J(QXlx{CZ0fOW2h}uMQXdAT>TvEKne?VUv|TS9ZiRMcI%JlQkC(*r z$J}mQ#a}yu z305Qlnqs&u>&Ns{DKa{mx&YfIYvAY{&pW*To8%V5qBqI!*HAiZYxeHKA-l2wr1s8x zYuDGE9o4n@iS4A6!+a0pxw*YJJ31=fxChNv&hB9AVNfD!fnct+S%#yw4vo$K(k`&T zs7^FY>Q;=Pz46BNIadMXxsZ*^sT(2#YXI4HkbSo(|F#iK(0mqg2kS&@v ziN1B6<3TooYG3aktZ6E|I;ubav+jmD8u_6}T&_ijSWB6hEa5gx`CogAH|@W?8w*~8 zYx3-Lziqhgba#1UgKl77b&bovB$}ga{Eii%ehfOyiw1OP-SaW|^fUkSg5KtBc+QZfnv<0ZuWp8| z(Nc>!SepPMFH94U^<=fk6#l>;xKoIr{bI9I?RLTlqzcNkMvxeW{0nBl@wKsuA9MuY zekBhyq(4IY(77(B2mtG1G*a+9AdCl`ivSWW5nd1Yofz)t_X$4%__#}_GBE$Lp=fZI zGbQ>UgYA!J(cwzj!{1J2W zFyK$!+^F!qwQj*TS!W_M?cfCw#f#qUPoa#C+j^-jc$}9?Li0fVkl40Tn*7Vjx<$6- z$Dei18G`MhWThlk9mgzr5CjIysp0AI0YVHR47DLsAQO4qKY%0)A!N47i2V(B z2Hru?v=mu2g28oHpdx}T@+w$8F-`QX;7Dj;`zeZ?V&>40!Zbs&Vs!9#frJFP)HPAp z*MA`1@j#+80*`70CCse1O)%V$^wDdN^{JMJg|r@3=!8Z`=Vd!l)?7VWMa7p`@}YWy z#*j=#!tDkNG&1Sn8AKvUOf1UgO6BR{+ML_e(Il?qM2O`vYO?ic=g(dhdM~63s}4T1 z9Z-^KVTsluHHo*CHr~YkThy;0+@c`7uDW?AwyWTI(=13LgPFoaiYC9p9WGbS|GpGC z@WT3cc9*lgrO~(L#E1J+{{BT4xZdPT*QMcCP`6~MP#bgxsPYenQN?sx?A;JkeI6rh zwf1-R+MTal-_G3h8zvLQxyXYGx4VSf)U_?i=2}C7AQUk{&65IpL8Wqas~k@(_&jyH zt?Gf#hT7*WxJyHJopSCjK%MSW%y6fA2Dwp>C$&E8uN|W21{bVbF-i~8RN0$vcTVOy z$=2))p71k1F{ML|#2o!+dLC6yuSy7`_&d+#x(xkhPXc)Sg#|VKg0pft6**TY?dc6w zf-}S|*$zE3X@NwH5+cF6Lp+?;(F_f(lqwktA&3PJ<>^+5{n5^%wt>}vF>pn(KO?2k zcekyzz6uX!K+HmjT2jHaoGt6-2=3hQj6gFhX(? z*2!7*%A?0AA+cd5HX32^y(N4s}lw0{uz+s-tHtRg_rvta1U5=LS@)ZUzu zCcNF=dvjIHM*vWHhO}X+btBnh4?F(FqkPM1ZtBZYPELYdbqgIBwDnnaL-&-<7;Uk> z4k`RE0u!Sz_-ZKz^ZiG|j9~t^NA5opACtA7UA}ZqVtrf@xz6Z=KGYV>H(SD7F2#TN zuEI$iZX1L!Kq`?W=wUy3xAzWhA=DIbq<|9=wgTQ(SbMB#&%v=7VMumb1+=eTo1W9L zgCx|1Xy7D*m+rGylKde-&Yh%#n@CJ7qkbBcFYepB`FdHD4jMnmvD&;b#CKlj)(UuJ z>>0iP_zQp}+EjViHX+4nE}VITIZSsl1BCSc20@-s7s3^tjf1uamVAXj)gH z_d@7+PzH0K!g*U2!-7LAl;=(ly1nSyXq|L`!eZSOM8-%Z+2@}Y@FK$1tRow9=6TX4 zA13%kHMp1Qz3N295XxG{muw~OoEs1U$&$eBJgoI|Pr!dmTs~UBIJVvcjQoF=k5D`daXdP7H=&$TW zdn8H^JZY45vL9e}K+@vuQr*vV_Q%F?d(&?PFfp(}9VHn}{rY8BfGbw7feC4~HK+)Cq^E0mz)Kb>E zhgG^k*s_)<@TZ{35M0;iA$SB7x8{Ff?49Bzj*jCP>j`($x+7+f~_A%}2@qvkJ_B>jsy)FZtd-?iW8%;anOAuRB*(cVdaaqLcUD zn{{WW0)Y69IwJnizc>#UYuA>3qL7jr9bNnRfM=@c*%{V!Al4+-ts%^zgNQrU|3R4a zO_a{unga^=9|;oIJQpTjds^p)Yby-XYkj(CZ6~}5xM>c$l0&;aHtg51>qNV!c+Vdr zJS-Fvt^o@C`3*5OZxQBARJ zAxGsoB<2)OLP~U(4AvJxY_GQV9U8_&_s4mqgRh0JRRpydx^KEo1py58(muPSqknzc z-ycDnr$?Lg`PF|P=iNgL>_yfGZVx3sxhMBsL^28o7Z03J3YCl=EO`LQ;44{|>`K=| zM}AE(Cl^PQ)i*_a6w37q%8C>YVNgyYN=0%=`VuOnOo$mOt1Ug<{B*w_feP}mcW;8b z@d$ z)fO^(m$lZi*mHmF-)_xD@2*uC1IJuTj}Q+}W&3cntKbEZIyvMB>%g6P-aD=t5|rOd z-EF}ub)7Op5T#1sdih?3;yiMap+mqelHmJb44niG51Ws0nxof731apThpfpeh3=xEdcSqudpD=WK z@g^Pie7F5WcLle^I_2r3>TGw#XAUUxSiI!HieY3zVTcD&8{~1pAA52BYnxz$lS|zi zc{+mapNA5a06h&ARC%ME1N(XJ(TaqBRF2;}0&i;YfZrn1$h#3rP-s;bgqp@vd=7lRR@6V zVh-Pc>VqjVr1Lna5L$hsbh2Nr#jC|CiBvsW8#m;R}O=&TVKgX2Vn`4{vwf0AY zg-}&MqT6o#OB+=qO0aD-n!qLXPb5qgYOh6}LwQfW1}lctXyMSnQW3h0;a#1-dk}6C zIflqEh~vAz|BnRkXii-!Bt3_MNE)XDGElf!T$VSUEQ^PNQJ=!x?7Nyt61G3Pp#tt@ zWvzTh(qHh;qz6W@${Q`fDZuRfhsc4QYkx1nh1FOk)4^(B_6NcOqiiBapd!PMIjU5s zLU^}?TcbUbZkx2ACD4FUE-SJs8o8PzGBmbQ$T3O(T@|hX?D~U`l9%L0vC7~7wBnMb zzqOJTwPm9ST#eTMy5Ywii`rVS9u_s=m#?WJwH3%=wa=zRg|WIn^Rhv1s1p|9>H}vMu5ZN;f7Mr$i^F}9g$QL5jp8KhC&JeF zgNomRH_E#HPf99FVL@wya{ll>+B|{sm%aI52_&-L^3otEb3?YDTW)!{vtkSBIicab zPwU|1Z2`SPwKH<=YqXx$RF=Rj7f~zue~bX?IRaq#NFMI+&lgF60~wx3cy-2(T~E-9 zHPTOkDiPQhf~NyWD74ux*n`?)Aduy7F|r)r&+tX>yj|%1JxB{_vg0-WJC1Hgi#%2X z=_j?5BmW_e$C+InQIjKZbjA=j7Pv+vyMQ1VjF_I`#&`wUgL)8`g#h0%XAAt^a0MWC zl=lnB6;=Nd*8fhZiXygdA*`qR$BO?Kk66)q<8@pV$LO|L(*L&1DW8s+F#Oa0Lvp&+ z6-rM%I)S^K-fw=xk{dyB9h7aDx(uu#91E|5PJO=dACJZ?%XGocm>kD#+jdi?9EJvg zpGYk(=7pn__6R(|+oQNg@GtgLNb@|p<$@AuBCP+q)0X|!?f`%K!{}S`1`rcj_mL*-r5! zT8pa6qj4*9G8C#0!USU^n_^!1dUj48Rr6!q4GwD;IVgLG7J`sLl>qA>yinF1#k0^5UsJ)*%u!_mir1qD_g z&uhxoX}0}t{9hzd2idiwO`ST`?yaSq5;_*;w3K_go3v0`>;X{20-`2zd;nqh6mYGJ zUp=%u_72E%ZeB8vgL>ChtiyBW1zZ7B@Ynm=ns&jMsBp6Wi_2C|4>Jzj_UPQ<|MeV& zruz%+=LT1%?Mkk6Ffedgk2U22gggYu*D>PV@Ov7upJ(?4wk%#={tKW|Cr5d?oe*8~ zDQC`ijt&pfZ*Als5stlEXWo+%<8jGC2}eGg!XE%S4E1h*y|nnxdr3-zVm;1L zhhaq7WkUZV>;FOV7pl^*n72sb{A01;W2 ziF*k8*|+n&XF6A&zto|pf0L#{OVu;4qqf{ssL?H4IMlJ?H`GTrbK;@Y}^*Mus( zzRR3+gzzSK0SJ0pJ3=`JRfbAFfK~*RJ4&=NPAF@-*lhInZ>pCsBbTrfp1S^+KAx_2 zL|o0%Eb13zt?Td9PrTS(_O_oG(WQLtth-PrI3s34NARL<{q>57(8u}_&A6shKkL>n zYm*JcCAU>1q&c72TJY5$^mwo^=A}HbS)*G7ZFyp z!%ebZR-Se%#M5WYM0)9IY{ORh5l*-2q@?u}wdP}*TdR|~;|uE-rZKguOO!!UWCJbY zq=Ysd7d*gYmgH7$ZhcNP;CP9Br{ZCH9ZHYBKvBu*)72S86@?-xxJ|4}4b0wZ%QY)| z>%M@Mk;#zVSu=qg9A4q4LZiUgcpM-Y?ZeR0<$>zOeK|C_qpvEcn12b=n?wP+PWt^B zG*+-O_U#>_8oBhVuR*U~J;Gr7h35STeoU{$Bf1x;~hCg~Z;UR7PIYrDKqa$#d zkz=BNpsWF>ik@Qlm&3$18XV=?PuhBTFm+M%_Fz*XLK~EqKAwf6uw$`%F+1D8B7Hgz zU|kJdcHV1NQS2irqJ#5qbccFzLspKNPn;vh{`@P3z3@G1#UqFv^uA?)O0EBXbd`=^ zc)6VQ3Ko(%15a#RwtNF!f?1-KD7WCsi`y`udgpdh#J#_Jb`h#o-+b*>@l{MZbhF`7 z)PBsQb`yar(N|+blgD|_?!~a@I|Fd@ti{2HRmyLkMElY}#moBObTv0K%%7ZpK?kgy zPTev%{t#%gyxgr*4d!#N=-0^9cXz zSvt=TNaZoZy;#os-%)PDcpfCY zZoKnTgFS*+vjJC4FKjB1_}2BreX@sGmES+q@DQ3AKPNug5$#U{uD&3J@XEkj5jWSP zLUCZ;utSs=i6NXN`lH+G!1v*rAf|756f;mej)xaeA~@>xg|AS=z13>wZ(=|JQ%ke6>re zziv1e&N_4$GbI60Pq&jcEq61ZZYTV`Bu+k&LJMp*AgQdc=yi5=GJJXvDl~yS_IU>Vq)j=0pK4xcY3vI_pg4NUfvo! zm0AIIl4j#!bm|Fq!<<%A?&{%`boY&)6HKj#v4)Q%<`=|?2o-VNkZxmGuudzg!Wf7U zm$FSlIn)O+5tLHyXIxv!kz-2P?nls-MVDbhYaW_ugtgmYUyjb4F_XM8-r90_kWKO9 zcWq|OpNJ0yT7+!5!|0`h0=Vg2z8>=%C+&JHG9I@kz53P9;W92Y$FV)nVUvb0yRCpb zc}BBheYdH7dzALgQKa~KpOUbs$C?KJS>MBSgaz&Y@U*8;Q>Hn+-chMlAI5X+d&%kT zmCB)#tv@9bYB&a~&2)ah#GCr_fuD`9Uhy<%U^`+8whg?kH9i~R#yBCx z@f$?Ng@%R(xUm}tuU-ZruOvZb{J_F8H?R~$-6~4Kjm)0FC4ygrQC9@yA;(lWt4|mH zCL@96y5rS8JGW&!p!&D6Y|zeyXr6+i&i^D0G3+6<4Yd<_H3s9Wrw>rxDKy&0HSXn zx6O99DcJmHwI7vCu1x2i1FoWaqda;<8u_0oahJ|H)MlQ0$ac2xc6#flL)hcrw)mI` z3$MM)Dc`!{gGh6jXdu)ZEj2eMl!u;@vwx)7qJshhq8M^M`u5!M4gQNy0UjJ^AjN#_ z&e4B}0n@<$nW8lGL8Y{t;a>x^bqvGPnsqoH_ljU>B7 zIO8)QzRH8Cazuqx#qTBI#+j0++~^0SorHIBXfa+cy#8&`ox*H5_3b12k8dz@aTNM; z{Vylo{oy`q8KX$9iSzuk?usNH^}9?r_xHwTxvn>-vr?fs*ajws3+V3_H5U`gWZl-9 zlYaF>Xo=5C&vU*X_4D8|n9Nzjvb&|v3UxavKY=OBkSBY{2C$i)X#)Co%A~_zK0S(> z`*sDMYu~|gUs^+P4fvfWpwZ}F`s|G0A6Hk9f~~li5Fwv%8@=K%>2EKs(S#WRkOZi+ z|7;h0qay>qcV3J+?E|=4QRD1PehJk+_mvvu;=`I-^C5rk<7>?7q6F6b@bTU$)0B9M z(qm7njz^IZx)`=7&>I)6<<=s_u*LI`U?PwQ038^>sEuL9Apj{;v{4L&)iXk9(JQU0 z37iR`^{!X;T3eYXu4+ku9oFM?ZE3o8#SP*~+8B~gQYdJ!{S2N5J45oIf%40)@0MT* z`2ihNxVYg|Mk!tfT!OomHR!Zq_kKE9ullwrvWLLC9IbRHaprncm|^?OLTixSU|^MSSa@{crNss%i3&+*pKe} z0c=9XclKI6P+7D|LsKDoHFi8()42JLrbOr$gz^3#9_N&;B8?uKjb+ekh>ouh%Yahe2P+fpJB$@Src*2-b?0*HSRwiIv8RfuV@}X z2RxjmenWyqw?eNGEK@U=YLFUa59WIBO zOWWaV_d{(l+pm}?$MF{Q-9vz^;1=J(WN1Q#SWta;L>(fOKdz7#PR{__Q0^oYq){hI zehZrCO{_m{u!dra`w9NPn(3hUDJcKkA$b>pJW*=_Ysz=#fz^whAs>DC@2oBC1(SzS zQ5m$n&(g0^5J5*oE)*#TgYMl)R1SrM!A8kI#5?*!p2mddFKfX}{8f#xCUb@~Dr~I& zdjvW{j@FBp1m|LfclchJMm-pwh{lHi&IDL!nk(O^CKNBgk)l#uq0;ZT8n)y2VN}UB z*c)YH!hsc2JQX}%_Z5z~3geb%lHGYhukI}+aJ3fJnq~yA-YA8KUq(GY>DqDVl0LOJ z1$~xequG@Qwh$AnKb4fG?-X6F>Kp_3psN$a6m09dJ@kKy3Nj+xVD zj`eigcR3&-h2)yyx5C!z--)HLPwy>PEYZzi&+2ne0=fwn_m(%^6<%m~I0ZF-WvETu zOgTv8_KRH8lh!o%{T)Somc?IwBo&Qpj-fP z0We3S6tkUZ;OXx0O!(!5G(;H28Rf@uE<99@3$E?S-Ef;S0H+DvQst72kw*c%{qLC> zU|~>{4kx~yYo>bu5B&fJZ}s2c(U|;DfhR8p`br(N{|v%=@T?AGRNhaNu2Ce2T4U^o zUyJ|qsoy2qiQX#xH1Lzx*)$dpGcAtW?{x@hDZg$q>HzAR8?A+$}6u z<-ohEM1%vuY_@1|V$T{r{(GXs3_E5u`o?+&+-~{KspWeEJ!Wq*;II1?l z@zeXw*u2;~E~p>gb}f_-1`JXR>+mmUN58ImDgemSVg;w`CPkBJ6i)!4BnRc)7b^kc#Wou5$oJP!3|y{#dUt#b`f7Gzr2 zMfdfv$eNCDR^&l?fBS3tI@K>EpQ;X{-vB|pt`z=&)s^!eRq=teK)-Xv?RyfhvoB}= zRLP|1X=ARPE->^9i8tC=-)!}EfT;jz5OMY#+%Fm2@81y)HvupjTnCS%Z*JZUOVP~{ z(v~vJx|^w0F=T5fh$%byJh}zX`UQX1|FefV8Qcy0=UgEG*^5JcvE!JrVCYHR9*kd+ zY=HGfRoZbdDf^+Gfnl^PCy)Vm9D}^Fr9A4PsvQi+EE_$5CumOD3M-e*0%OiLA-}f<~-?b=)y|ku0I3J+IoS7iSd)!(qk+7RQQy8aHZ!V){C|ClSZQ0HxdItPSKkI5dsWWYKIGal$*ov*Ov z2i6q$ADW_0_VD7t`PbsP*)eaOnb6z~$W%CrEoxmwejDS}`!{(XqQ7-%gc({pRI~-e zlUr-t77*%qeW5N~7oaDV$aMVdmsVJ>1MGq*%5Zq}RNNnI|7z7ayYAP6(S{oLUjEqy z#w2!^1Ui|)ezAW(0?lv(C&O=4N`aTGHV#h;<_o7C?UB8>4GQd08f0KZ zId+5VBb*{7{JZ7RAGP#8Yz#7cggDBDRImg&X2o%==L7?>==V?j=yhQGg@;gR_&<0r z>{3j%&iv0atNl#6Z|B(x9%9iUVk!juwksZ1A&;I2r784N(V{rOE;V=aj6pMrReGvt zrKSo^V^Ka=z7y#kFZb({mt1d7E@jtizpyw*8~@#up?tSPW{kp!)no5{MA5HzkV~V1;53 zmb6^@Y0$()#6rjbOg|MtcP0ej$Hh;(SV!1)8KPTgOF)a2upL8Uz7Y2J+aUj{xSJ=6 zHVwA>>m9CMP+tU{`ws0tY+CaTLpT_s|MKNA+Vdf5Y@R)5WL^eZ1cs7U2$~=M+-LoMcFW~lY$)8SHhtm7w_Nr?aSr~sSbxf=U7d8mA&uS6eGF53 zEX;v5DG`^<unY-tLYQzxi6=VG6 z5=UV5P3GWN=Y07;h{LXTeU2(8 z@-?V)t65gptLA35FdV%p_=M#Om)2dZNvxQo30+ro)#?Cpr*YPaXHDGD;}{|B>Z^Y% zCgelp4#6l#cr~QG?YqKEO6dDu{s`RJSAq}10ip-v)I4Ay4X$Ci#E4jd-m9m5iIMn)z?TZl#}J*pVLdfH-EYQqxghmh z3EP+b>)DfQ-PV)!&q@;&m?1btdoCcxX2c(GKUkF#d-E8vPh3b#PIS)mCxR|6PLe+0 zij9S3(L%xU#@H5a!i8t#)F+6U3W3LJojV0_M1w<#vbv2T>x0Z#f!uES+JPAqXQOHt z#UaNN41W0cG9t7f$AL^X{y@nnvpJRRHmRM}Y zaKIWxtW;#%lt&Om5?KK)3p?=yhTUew9~qWYhnf7768pIm8kEDvB-MHBKCBWVK4&$mqp^MW+VUHlfRX zqSl53MWx_s?ROCmR^7IfA;AUujk$nX)js{GhFyvL`=BQu;b-l9M)`xwJ@ejN;qN)do0nJ(sJoY z+*yZyIkK3H3{Lt!RsIgHJ!*=I$DqXMth5eRRs|;ub=lH80AJZMi4raaQu)%c&3&?s|sopze54;91AeHKW zDS<7FfFfd?Ltfo1D-wAR&wD$oE@BbeTvhV&{m-tG!mtXjdlC6k^L+en()s3X3rv8p z)l3w4oH?k*4OpUqB*y=1A0-Bm{fjF-wg3(dXEpZPcBj^xgi2ok*@MW4B@_eu`zTP{ z8=q3I^QM;?Q}t&r{Wx{4z_)HsGxi8}Cl|)cCfB4l-{!&0 z4A3RKy1KeN?ah8@)Sj6weL|xBGgh*bikgy#hi9s93shxBvqa#M1moeu#s2#6+KYF& z@4>`xI5w?Xk@@0TBJcj2TFEn3x*vBbE*2V)!}U;~Kkr zKhP^B*w5<1j|j$bmiyE$@VKf72Xra&sz(RYRmye=3vYZ)%`fcFa5AHMF;i@luw1=# zF0jrH*5rj8RJFvgfI5Ge9!&w5`8N|tVChUzGj?X5rW0UyVCQNb-DF^ow63C}&lDBt z_|*?2=CJT!k$rq=au;>)>_8x>-TS1t|}D~|K8d#VprR!%AU50Qul2=L*7+#ok9 zTmMuH$;b8?Rr#NVs{q)EL_Q{$ih)K=i>fUzl+VoocoTD{ z+ymGZ$e~9I!*l`2aROzSv1maP*a35*`rV8)LuN~p#j9Am{ zijn_0$j`_Ze_H$dhYFxo)#UCl;zGo123|T08#2SjKj|fX zdL@*UkfhiC_u%))21v=|YOiTO)!fQ5XTuao`&ZDAG;y=np~2jXDMM1k$jc#Nl6T1l z2zpZJVPk315*A!Gum22i&P?92(Crlp{dAug@!n zUU;z^H*Va_QYYmHTqt6h9M0LKo@cFgOpi6Sg0y67#DDwPePTjefRi42B&)}L2=nWRkDf|g z5<`4Os^fx(t2fk$$4Aao&roB-7ef1SRrNnOuC814pdD0)qx#gKg4qV171vbD1_qkdNw>bSK*&O@O63-F1Mc}%{QEwla(D69&~ zwI9(Fxra#gamA3COY&Uc*9p8cmgGBJtd04HbLEcWmysQ0i$fGD}NIXS;2}u@PRagY?x*A!8eL z8JT#+l4fvB%yb-ClOM%+aKMs7Q5qy4pt)^*T@^EPB@)FxT32sW{JZ-znlKL#Z)?!Z zZCw?bNi%yJN~Su6n1oP=BbZz*hyZ5pvVGR8e+5PKVuunozy1=pZT`ik8%|knaFc}T zT4C3-b@x?#_QE5a-B#VrKrCv(u-t-MJ9??mm*c!v*^mhUA#GO}m+oz$zb*GT0c(?p zlQ+rVFx_Gt+@$z=dTaK@5ONyOO_y6~qXv5cruufzZyyvKiyngu`uU-UX`&OvLZZ$$ zjwD#EK4B%<>spJQVWd-!K(WW?RDVDG4ZV#+6_GdIi z(QmmVh4FY5zK=eiB&CkUeF1p6Vi%R#AtV%)qFEvg+l02FR!*>>sPO4c!^4b7?#n~P zu#!?e>)=D;z~g8|Hdx%9WQDurZ%d8(n0|{@wwT;QH-> zPBH9dh~|=HehadCm}ue%*Gu-{yDFiiB}98ouoNR+%(&t@4obq;f;;pR(Q>JgCX)L> z8Cf((Hg?AbhGDx2q*AkAB+)6DGSx=eS%M!4fa6U2ztaMr%G&aMtJ!03rzq9q)^G4eY9gph8TBNAZT;Ayiv~WZs7Da{T|&{fu`We)5)CrP{)~xS zZ&{e1hq-o=0d9m|Z><~{4e1Nb8^0m$_68A4k)=-kC}_;18-z|cFKCBMzpJUKIf2){ zYe3+ksIsV$ExDtiM5g8}7C|0G4d;cAAeRI}t-20j?BMW{R%LHqe(@v(y0SvlZ66>u z2PYDE;?x#XgAL{o)8R1S((t@aBS*0YH|m>ZPs@{~)UQ{^)t=c7Z}R5ChU@aqq7$#m zCpKToBPDQ)jRMpLbxp2TD3H}&GOwL3g(UN(2!s)Hp^eTLkXFQtla>hZLIruAKI)C-w43e;xQZKsKKhVC-565yYsSU~tTuZYLfD^OmYYdG zguSXw#GhbM+6O_LS!XddG3c`a#^HR3Hgqu=w-WKwXYM1>=L$vg5<@_(eN|_ z1KhkMBU}lU1y%rQrbewSuurN8YTHNc5;wC>uT70D)#nrei`4?U?kW+N{e-ZyJtCoi z^rCVZY{hVUmK9y}_StpAMeokxr?Z)23c=TibN7cGB@uls@DhD_MnwLYASE~AGGPWc zuv}@NplaaaI>3#gK`0BrCkz&lX58#Ab}878o>b}4z? z2%40mQANGyJ?7sJSbW>dSO$tJ1+7H(3nnr-W?fkq@ut`H$$|a_$E^~SMU0z=p(^sttc+WwGUH~98(rX*T1Te_+9MTnqqK1 zxVbSK$VXWt?^L4ZD7=OPDhS??<}#yRqe}3u^dB~x%*1odPVLcv#zKJm+&mFYpVN6| z78fNz!VXC7HO?UuKYKJp0%yuPycBA9O<~;lQ;&sS+guC!?~*K4D|17*CW8=k zG=ivxSs5ZEqk8J%pZ0WEk@~$)_>4OaK?T^!8TMiJgVq6Fgts9tg~ouvDGgn&vx=dP zDM96gM!P3h)%IwaDmj)K$DAF4f=Mh=QgJN!zL6yqHY_PI!t*0onw+Z17sUw6nu`{Y zLYBka9E59ogA@xV__!aB2KYVzS_eV5!{MZL(>2sZ%s*FlWGFt| z6bZJ5Os*okYs?N&k^Cw50Y#sWx5sLBpQir*&*m`K);PpJa-`F*&I-64r`45Zh#Il+ zo^#Z9gVWh-*>cL@@jhf^WURU-9#1~pMZU+Z*aXG{R{>Cj1Z{KeuNM;5@fBVhTNx7< zp#hq>%~ewt5!4)@@*9*^DJ z6x05m&TL4QK3$?z-Ok~@NloO<%_MknpgbbX|?BS z4y2l<-$~FK4LVpB`eKSkm144aTH8j+SAx+-@kP#Yv?Ta;mV{F1IdPuNq;tpOgTMje zAgr_Z2~PSug5$A>?twa|EdHeC;HoJxVm`>r#gm)go6U&$h+^O+xFJnYd`1nIEn~;bksP82|A&$aNp$9NWWfmN2t<+(qqXDat2=B%^B@*a;qY7OTp)N|$ki_0TrGWq%S0q6#KVG1Z3a+|`5}}CD z#KN0;y@ZXVgp$sV%yjiF(0M)tft!H9#2+F%Demm7M9w3Pg>$A#exciINxV6_u{UFq z_KTU62V>DZzaa{M&{*nv`myf!=_m80q`NHc-|^$ohdSlY;IHyr0Uylzi!Hz>RiN?p zqT=v{jJpDtbpRCL$|QF3hwBMsn$JX8Qk(eC8JMW6-)QS~+MaDP+LajB!(g*fE4~|3 zk^1L0tffjOtRq~?(k#}_YKNO~>wv9GMNklPJ2aIcd4sv485a)3u||E4NMQ%baNNXm z`~w@jHsr`SRwVN=g_%hFZ1whrGE5y}27ak!ledOnAXYNQ-0+a(S`m(%1s+eK(^X{#LAatYg>)&+|hlK=EumAw_TJbczb7tLac96#N(R?t_HSr}H zpbAMf`D;fDW$2t;}aivL;c!EYA5`U=p&1{i6)u?gVExNpHEJk>^HYPglOrfjIWFoHc_<(<5@{u%ma`sq$w{fGdDLqWU`p=`#sH@hW9YJ%%-eTVHP$ zrOt4`zbCLWtO};Ax|+uCWH%4dzcOnCF#hnmh4H&3)tn*fS!aQwSEB$E`pUTCEj7FY z`W-?+d9CiL&em8}Rfxd&5@X|^z%5H$`j>G^$tS$(3mjtvsKMbM0inE>!94V}p7AZR zfsKpLc9-tev?s>OUuSk8Se^iFj}yW;R-kSJsG*%B#KJ?M*y9IUhULKTq(h1^KD2yd z>gwt`udMejKrsR3Ltc3L8=VQ|bt_2cWCh=ktAIxjs9Q$4BW9hNZ1_p1Apn$crb%J1 z5KnYEAHKd5sA(1QO-3+V_kKEZg?i(}2f536!))$CD!|r($B*9ii3KW~jSP!nr_sq4 z{Vl+zMWeE2_*Ey{jg?9fU$EH)d7sTP1UJx|Sv;Qioch4~tZdt%c=-_j6O!sJzqkSa z4b?>X{>$$3$a$UK_069T6eu$D6=k>!$;~5kqnkU zxTXs__3-vXlB~HZE1!=NLFvsBooCqVOADOs2;e4Gy*BOTNGZd>z~1bdUajV#E99GN z_?<{_-8g+Ufy8_(=*Cvg{@bJkjeiqjN^<_w-QuWla$tDkrMqE>f;}5ump=b!YHB(; zX2P+^GKnHdg)pdL)JLjIr~U*~YeXu{D)KYYv)bEiElKWn^TusLr5~4rU4YMe(R&+2mvYQ6CMzLdlS?E2?OC zirxu8_bMd6!2^%Z-OvL2LI+Pb2X6ba25c8@3;gJQUTD%^fwy-G5(PW&(;~tM5Z_#1 z=5YOietIjQR>+EBM7{rkGS%lO&EtN>OLtPzyN_O>pgnP~(%Ump+e7?jS(i$$+d?Aq zdlu+thIb6IAo2K1mJJZNr*I;iuL!!DVkxmS4DKDN*4j~TU4@$b(0c#2D-ua$z`Nw5 z6)eY#l`dLUyRH5XpNkCNqGoAt&&l8X;H2@2#EzQ!_vz2#EoP5d@7h!=P^|U`#R0~y zT`Yr!?Biwidd}eQLa-)}-UARu&K|+{z^b@HIp?~<7kv8`jwT!ddGMD|U*rYC#T~pc zB$^&(7XRwrf#lz;-W=)+_TjT;f$JLfSA-YV^X4j&y6BbP7$dlvH<$PdCOK+^+zY|E zdStLXxCZeEC1En`dJ6^m>rIocec1MukJmg3)kwGkw1g$c0%1F zn;PoH?8Wx=h4cyv0!cNG?uz5@N?l+FX_0f5JjKg(0c>~Y529RR$dF6$Dj3uuP_FR} zcS_~8Bg|crGkT6A=g74okTC7FlQFsRBsq~4K&*%rXrc?QZ^u{tqT2O@YFKaj2)l=* z&`_hS%aYSbFcQhrq$}X?&mwcD9wG45yuIPu_%1p$}H`o&E8|l%!$A` zI`cKab%)A0r!en6RP*b49uyO#;fA7%i;H`^0b1>+S4K0r$w~K0XoTeK-`GDiG%=?4 zv=eJT-UsOZ%L*}gz4nXfR)Q9?L^!g3u>LHn5zUZo~xF zW=s6lb>0m?rfRAe=tV#|Lr_uS&}bBx8$hr2T>^rMt=Z|z26C@i(D!3SnUNB*^J?>J z`7$sFAA-R+%L93 zjJ;Ypu#G4;E2-uzQ3OdOC6Pqt`6ycSbnuabezao`2g_c_ zYlE@JS!Yjul!`{SrLS=rf8;3%27CGo{jzM;$SWKIyoPdXvwyp&x0{OfzTEI_bY{o& zl;2@TghC37f!G=pkRN|T|0bCJok?JwTI=xXc|#zW{xkr(OOaRt0#+9K0TTl&gy04( zC?qqaph!4+xr*01blAUgE#CuJA3u=uQ$uiedPrv2KM#c%e0a4cDJcoXH9EXT8BjyR zdlz0Np{E^F&phzZShy|VJb=|o;ETG3UA3??S^3}xu`_14`ClzzdiOuzRPJQ|T3gN_ z68OPOrX}RFkkoFMB?$jb9BWV4e97{BL#4#k1!e501|A_->Ggs5RyAszBt~D zx~_e$E_K9sw!*_V(V}@guwjC%IEUqa@Y5}$`1p7mb{U`>-_&!9p8iJA|F5D%149+Ka2Rb|>dPryS8121Q z+>wYBnQ6w|Sb&QKj_6c{r0IRjEHXeC2NX!$@$v+;V)>+IcO|W6LxA)5?_V4}Lwr$W zefF|Ep9X;{sX+n>h378voeX-y`a2--6Q+kg_jf@%%FDQGP|orK_s&{r+Aw%*o0jt1CJD}> zs4Ay#yrA#_DvVf(>*g!@-!LgvgNEdU5sZqE8MWCVh!yY+C6F#L66D(@f;d)jAtq$m z=VdRXLlddaPhCsN~JO3;VF5;Y5+(yZg&w9VpPHeBVrkQ5T+jDO(0@AxB$VtJfH< zK+A6~=Je*r=t|V*acvn=bAQ>+J3NdIRXV+5RJts|N!AXmj#Y`3+~^17Km1hxm< zt%py3<08VmLsBl&J^;nCI}soyh@=rmyHz|~!0uWd%I$dW+u4Hz-;$Z6%Fzcg0$rZtFxEvp4<6Ptj zzl8SFN{%)VzvSxNI!TNb-FPaCSBB1*<%jL#z6S%B8VBXN@*KnFcz$4}X`^j692Q1x zI!1EFm$bH@)b}FlBOrU$j!{UO5`iA3?ry4G!1EfyE2KaiXkL$m_dExaO#h1+Jadgy zc3$myKdqE>7HP5p&T~flGW*Y83rl(36nVPleFG7fOw zLA?EFH61?TfZ;!HM+!*HqmmSyr@j}I#W70P{BaGe;-|xc5=f))T9cfP)BIHJ0g?u+sg0QCbv(s}O5EZYKcZ;> z+36~K;p{hx87qhc%7HIBbwbGA+|PFx%-xxwO>+rL{Xna|m~6jMxJ0?r(CwK`KCQ9R z;*3gL)rz3V7v&V+cUOEn_Gezh=%+$(b*>sa9XVSmMyL;}Y{zlLqdq*7$VEZ4B>-E9 z4bHf2J0)v+t9ZC|ue&D}nO{2Ee2YrGWqb)4A76mJ3s3$*{j|6P1zp0d0+-e#MGK(r zR6uF>O~?=|s-^;+E5Q-Nj{^VN9C*;X-9jQ(nd7_mFl4!w;j)V1Pu=;$51fdw)X;l7 zDO$kEr!w;(B}ce^2unMJ$jY!|XYThjNE`Y<1s>te&a=->dxQE;*}&Il+AtIE-n%zM z#qmlHT^b-2m_JBA*Q^o|)KK^uX-fp<|Kwc+xSPYw-Dmw`^@JuM)^ojQD{K0&fBFD7 zjnaflKxH4--sv!)he*usjK)>};YTsfB76%7Qb8VqAJkyAfQi_g$Za6DX z9>JFk$Q5xKG)2n?lT%V6as}cWU+F1E+T@_g^txT!7215pE@MLa4G~D-Q5&Rl9ImqO zSV_As%P47$LQ5C5?T$hFNq{fwTffXbc|@Y^Huw|Mtb>O|Y-bG3XW#S3hJ z(BLr`tbvyZ9x#BG0%81sp4ROtPJjQ6YA$|31qC`oa( znW+UD*u#?PU4-VtrRvOq8)kQER>7pZ`wyh!Cf)H&^}WZEXgevnJ>&9JqQ81Uq!f8_ z${#0JO!jTZ%O@f^FH}rCvK6OnXkg$8OESHAT{=p*=uGAG;}YOJFjrZ?`(jEp{vB4! zQ)}NHXjay_ofECNl9Q0%O#~8iMkDhy!IGhv+-3G1PgfkPCYaXk4Z#kc3_k=}=hUsf zOzjCI@Po=ETbt`t1*~H&21QcSA$rmpYxv1O}HzboLXhei8mUfo9KmtfhhnA_=(5E>M# zk2Xg2>k(bMx7-iArCeHDno|8x6Riz=)hX+Bz#C&UOI&veEFsaDq@9Uj*-Fm+t~JX!ec_^r#@$JF_T^G)=$yf?E+a)S_T9U( z(4B=mv!BT2O0mC^l)Czla8K)}_kKPFez%Hc$zOO4*x1YSezYS_%ypB-~}=ql0eoO{8RvEdB8blE6jgky{@L7hL3v{iJu5H$NEO;3Xf zxaKDUAo-mfJ4HWKGo>7nR;n#)Y6B8o)Qv_Vuijveki`eEkO zo$!m_gDL~Pl&N$|NY<^*-f~v=nk>XIe+@Ba{qDCPI~sHkLNq`yw0i*UF`$QM-F@)X zNm^cG1FLn=hgE#~INC@mgxzFWKRXV{$H%ig(w4SCPU86DN;#<1df=62#M*%}<7ouE zvY$q~8KHXfBuGc%`-Q>IFbdC6gY~PJ!-5!9O{u9ZmVN)d(a7Ndc0XpKX!{5}ee>t& z)X2>Z$iu*GNQMl!9=_ZOTfuZqN!(LbRz~-cUbLi=(4Cx=wC~ize(2y3?Cn$Z8F>ix z%sE*3JfQUM3r-X;P8bEe5fcd}BZxKEVrUSwkR?;p@-jaYxyEN)i_g%9CMeH+jrjRVf$7p-H&pxS?!-$TahD} zs4#zjRfET0x^0S%cR773N=oTN`D@>9zG)7h$lnw+?t$I?#s^i492FmIsIlG8zWArI z4k_lZ?`n^Ie%`Wyh?1j7CF-v>Z1_s&lFVvII!5uE7889h(2qF=2G1A+|6|ue)%Szt zpSI{4sZ3I8r}H=-%!@(NIREa=u3NvHpQ%|dS^;v09KGiDTKf>RU%qP53prc@>wF0K zbWC>@n~EE*=fJ++WE8Bo>40Yt+4fU0vZxaoIS5gqdg@dLTCvoSAsfNwMdwk;1BFB& z*~|-iB$Uwbdk6JF-~#-c%l-Y22w$%DL;j#WJMb0lotH>xJTHP42kNB0ZM#uXQE~sX zo=ml`?97lpF~)THH|>;>amp*>w2QrRnx~E0f*Oa{lYA)MPf$z-PHZ*abJ2eESR$Z8 z=0Jv?jCx}2*iVlxg_{bxf8W9iD5qJ~{K(WG@bNq?pWb$FE|e_Ch6*U7#Umhgbsu#m zVRHA78TXVJE&b8;<PfNzApi zwQ-gUG=aVO$Yme}RSxisw5VaA2e4pVg&c|wr-5NRb$O#Z6mo@fnA9{#w8xv4FRgZ+ z@ABm`B>xLkcL6$ZVbN~`ghSOnV&)~*%i58WZaxd|)pi>fg6oYRWy+1WJfm+0vZ_{11K;5(` zVI!lnmeW`+0Hv17LWcz{7&-O6W%$Am>20T1LN37M$*TX8TeqzttC-3f%T{@BBsq?azkX|#2IH-X;Jg8kK)q4F3V}1&ti^j~6s<1T0S7J0+q_V)S|2f#%Yu3%d_C&~s7* z9r%6n(2pEVmzz3#Zk+bB(I4-q{@Bw**T4tahgC7r;)T{$=op+Tk(89X$IY~RdB$Fv zHL}aUbqfZ4ON}8YY~g_A>pS7vWFJxA)C3~iAl-vI0wZX*l?PUPa?{e-aUPPa>wF+m zC>;VPVUP3LVAm%35b0gxNuN#C)wifvasXU*N=i;fcFz-mdcEdGfv~kgQu}U#EQkvu zG-RJ^1i;o;-@&})%|YM>+U{<4sCm67-nwlZ5CEJD03IX*sCB$K>!CoUDqj_|bzN&D zqi-who?7<TXQV zpn;FjH~gx7R4m25phfp+S;>qDo0!RulJ8TSqZ?PXw3j)U3hQ~h;qIlY#0}-l8~Cc+ z&G|7H!a;J)mFopLGf>q-NWf(~Vqg38Bejr74Iw*+wl1Kjw}nU@{-e`^-Jm%^-Vkuw zS#=3mLmR-EU|+Eqa{+V~a?~Z)xr@(nI~c43Eddr2i3t@bd;R5tYW#k}YX)HZR#|;v z@iI#>*Nz&6PVkt(iY$)M*rGCDkmEWq8|n1Fmj)Wd{&izCCMw zH-vdL45P zT8CaH%34BYiGLWqF?l5119N z>V+(W+|wT zFQgeZHg`vdg{^>WA%kksxt3GX_v(CkCAZ?fu%J$sPMd?w&(S`-@K}J#!uIT9+gqFD zO5cG+*gC$1=*9#hl6|%tmS4bNLjnXFw1TT-UbBK&a8aXkD_-8T`>M%RZD zO3TZ%kA7#L@E<X?30Ws|4DZLVBW3f z#G>q4b~$zCzFXLsKz{-p3I$qc*<)|I5jvzJg`F6)K?MeA86H~{MkLT{Mq`h+iA$%t zfs|5E*a#EIOKvY1^Cdj4ZLX%Bpjjwx+};|Sejp;Ym7|@gP!=2M@h0E<>BY~G(daN} z@33zjtwhr$Hlxqhn4J!2UZqpmwrE z9>MZ;yRolGyi>7ld1yN#PnLM^p7R%o4yO^<(48w$AijQ$R1-27jpv{odEe{W-JY-S36MC|PmwO5XnF{(jA8uVIwVhb+ehz6-j7ZTH74d-F~4 zvCVA*$gb9|fhUr^8J(&AE^)-D&P;;Fc@eLs%p z-nVPpSABcZcu2xiL7?TtZbCM)C1f@Kxg`M;5_X`&c1jdv3d$De!_Rme&zl7iKRqaa z=@rTl_SVqs`ctqgt;4pewgQ4q&JgAI*Nt*2x;=*%Xfv0htC)FjmuD|iuV{Y$8c>+ERL@u+M9pt;vSCnM!IoFV@6&XeE3 z$!3}yh9gJ?r~(=d_~B9&y+zc&l)`82?9!!URo!>1-T`*N~SYAI1AM8B*?2S#ASGXZF33Fn_JkG3G@KHq|sPv9=ev3)8byiG*3@U;Tt;Jru??o z;2k5YPi*_GSm^qAKR~|Qp+lENOdhb+u)sQmmJa>|gs$n`Swb`{V87lt)}TNr#K>HC zoB@1>-P@{TFLxpKOdO%vh5FFbEx-uFBela4IO{A3;rPwPG>2Oc(gg^4H~}Gv(Hn!B z)A&xF+FHZ%TN_K^?G91tgk58?`pk<>=kD5LgM)5I?~HrIc1|Lz_T=!JV9T=#A>twp zxBF2@Rj|KFKFW8r0&a3jzBM*uD|KZhzITl`r(z!;}W4uKlMq4CeXJ! zH+KiSD-l+wS2zHpyz*e|nGCwCNCF7ILRA<iVCG4(42P|W{sV%p|Iby(ColrU~iJ285hCR72 zYMgVTor=)m7bU3aMu7EF78dcv#d$IIa@`E*{LmMSF{UGNG`v6Ed2noDJK3*u*|6j zW@IN;Tn<`?y3D_EamTRs^DIh)g?^EEv;<`cFXdSN{!mE!WDX4%frd5~rB%yvxk;^g zShV9<%Klx5$z8=0OH+ZKa7=`$yHOXnY})_SrO?K(J+l`iN~{L-j+Pxy{cw0efkavg z+$(aQVOWahfS{Rt$W?mnd_AY4jV@!CYS;_!TmqWJjXP}*HCvafX3|hom?uSW7fY#6 zIQ>1GX{7HE0%4}=DX?btkkxjD61Bl+5Mut!#|v^8D7Hp_bpahmB!%QXc1&qpf}5Lr zJb7h4`CP_H2Xpgdq--~8oM7pW6zK+Zh-%Uj%3*0QHE5HRSx_iz?Oy=c!{2XS*{XBR z!pwbCPO~8j^#(nj-k{A9OC!uVo|{~*N)LH*TJa4HA+!Z+NHu);cAfdk!O1NJBZ zt_Exi(4?|?iw?zL)BiSTmtdMK091i?{_iR?Z}e)~HkB=pbS;~pcJ=rRrjwxRge+H} z7;0CNZuqtP>X_ptY=4q#-<|#D%|Wtei_m^jNelwVo*`=iC@~;{SZm}LJOHEmD<-1+ zXy~0oUx)2*x0oKfY?&T)`74V?fyyND@|M^Qh2058@)X!Txg8Fev$$h{!%1v zffUm%%%JHN+8G#-ZHowXh%f8{_6tU&t4+_mnf5)W^J20V3(g~!?_#xYqv#wOc-RL| z<}+XxQhl=nGzY#$F3>(YUU0`Q54guU8*i0g90TCg^@`Oq!%)uA+=8!SvK=h>Mm(ML z@<8cQ7ZUj1_^geI8kfet^ZOwl1jWfv)Q)62oHdVm`iEEWg##zRGF_a}(4xHIb;nR~ zQE1)J1w}-}aY=oZQ#Y=@{c(RhVP1Q7-l3!9Ns|MWRHEO8Sygi94}Q8`wUZ!#BCt5u zX1Lo|p2rRF4Pv0abo8`~i%Y>{)k_HcB-?g?L82V~s4@0kX&q8=ASeU12J|hLut^M+ zD4KytfiLHd);VbA!X<+}64uy8rES zO|90(_6c!2ut<+U0fqDVr*TLimLizw1=P0}Cr_+ceHUHR1u+IGSP5hi%t*@@e(T_w z*CXK4A_+_xHYP#p$C;}MzAQo3f)J4hc~j+_n-ZkV9Tdq8%*>K2mJp;p*L(29Zm=0+ z-OvvZwpj{??d<%5g2=#toIWsxN9hy^^-s_C1}knPjLP*7;rfD~HX!L{KO3d&cQy(h zGzFRkP_Yr)czwv^9V9&(Z`;4jMa2YQb@4`x01HT;OT!ko%n5F*dgiIEp`o!jt-WF+ z4w{4(Smgy+xK@KrfAuRS%#niT)By`%(})(YY=sV>j&A5daYsdCjA^mAh#AiQ6llGV zw)Kfsc~gc$vN38|h3sE{CG)}?2r~DP)N!b&R|>uK ztXor3dXm2#)o^Tx*V=)PrD^_-hE%nD|8Qdu^3#a}Ulh|Q=4Gp(ewDoTct?4FH{w*>EjUso?*ci?gUu4gucqKwu+ zP|X!8sgb!OP>ljgf3{?nmV;nw_5+(_HY&m4>Smi0Yp1iH8!IR%ut4xGw!4C5Fbjr+ z{dmZ1{z15T zY{BmQU~n1WFK)p8Q-2$gN_1RTcymI2cP+nr{dug`{{oS1{_{dJ=NPmYZ>U~19Jf>s z^>x3z0sh5AQdB3k&Mk!ZELL?bo=eZj@cOIJw39ANmFo<-&hp2XusDT#7aOH8DjL{c zR^QdN2T6djmkBFWD30>)fw=YBz;_X8&rNIgK-(9o?F#3OT8$wt8IdRX)aFZ-6%tGL zUuqRaBpy)LNR>S>s^3TCu^2c!82hY*+~%Td)Ay3wSt(K6zZ&f}Fr z2PIpyuu#7ihJZv5h(^XA3FYr2;W4N*2aR>fZBA@#&}i3H0$pamQQeXhLCpd-2vY79 z+{y*7ll|Oz%rc(Alh|92qS06u@0=?WYBb@2CziUyud>_uR2kJbIhGci6_Z2F?$@P7 zhN64d+7c6={}|#5D+fc3mVR+`-{Wd8j!_+x#5yr{pN#`8uNe7I08_ch%bwR~ymf04 zkTsH=N1!?;4uu(VX#u>Y^yE60?HD^?A5m>>?bG?}=iC}Qkt|*u`uI`4ilpd*uEqAb z>8kSVK0~z#8kaV>0!AW87mn?3_2p2NC$?Xj05Ks?J#oi{$9RU^wguIRqP-cr5Vb(r>ig(erOnUD#%C5l)ks}@ zX4q9D{kL~1?WX^xAoh@@bL>Z}bp++YUxd)>#>Pfr2#b0UHHlPDlAzmI4yARalm)ZX zePJVS@7}#@4@VCg$XG9{bg#`C-g=*AO?In$yQ02pPo4Zxucm@gn^-RhsR$kUs(LDW zTm(s*sEgf-YR{RbPrnuaIG9d^-E;~-j{zjn?t28e+3dk|8!kh9P_S#SK6bHE!)Gct#>*vohj104|u#5w%{s~r~NJ7@A2QJ_R zP(Fhir#_#j#o*wc%BlGdU{!ci%JJyj)S0z=Yxpt!M^IYRjzCD&xtv>t|c&G8?EM$fi$B|Q>l-a#hII-iMHe4s{Ciq1xae9>z z2YWUbKRdpO*u}l2&G+kCb4h(zEIogArKP%-yQ_(vQ1y5{6%oc|0$#_U<6xf zi(;NPvt?R{yKU$%=B-#Bnft6SNe_izSFCW1C)pLq&tZ``CMeQ)|MVt@>m5|t8icTb z!zc6o)if`z4HkT{4uT_S7dS=TF$0c0GVyT+h z`p;5X7>M4>EPKcV(8rf-&!5*f!jfaB`nJZ<(9jLd0#uQ@0n$3AhXw1&&=v7fsIhsu zK#lihWr3)eSP!I5k*beP3l9Bqzz=Oj&Xy%*Tp;`jk)L)>f40B%F&A`X0$3<~dDf>Y zjmvw;q`)6{#NW>{-_ft@CFJ@9*HSj#g3!esAgd*Sp%g5ffhe&YS22QrkQ8JbSZm7x zDv5P9JUkIcv1#*WX;^=lEkM960??520%Xkf09k_vHDZIqqoSg`)8PChWI4!W8843n z%((XC&rtJhCywraZtP2#MAoHA_wTUYYg!ta8_Rp89vq)SJ7`j1lRMwXOe{v zK&cf_S@(@@w=EHp)ufox#Pf_V?~WFAivRXoxq2WQP7#-16d534xRed`&*2N#))eFA z{(dU_;6lwYz4Ovk-(ovPEc)^`E4I_UtelunJR--vddnwDtvfi@A)gzh^2je$?J)Ss zB71^x`eiCslC?bclvmHlZm6kKvlajyCWU$_D{BbB@dx->sT-wNC6v{nuJ#n;D*Q26 zE9X(sC(3%T;Pp`lV$LQl`qp%7cpPQRb9^(;&G`OSg56S-S1)q7k_uQ4Ws-+U#* z7!Y0&Z@M-iE(Ak(?~nA%gjM=*OI7+C7tY#+*^tbui@)~E+~5zqKEddk7^(A>MMdHi zuyq@pW!;8%)_Lz23SZ6(aD;jw{4k#U_f(Y&VHOHDSnN0-(H^{8#4-n7(}$Y-zHZugeaEXoQrp&w8js-u7YXZ_-C9U^_sT3 zEPHC^;4snN(g>^<;WRQD?t-qS%5ME{U2XC5-kU)F2CtJ0OoSTpZhgzuN!_o@k5RQ#=;oJ z0y2r5txn|}yJ?6Ie}<6r#gU68%xF$J1*)r0;8kKGB54L3cRss4|9D$LQG9^~ECTMI zzDEwZ1OP3djPfTeWl zC!fiJ@NkTT?y2{ii#u4n{>1GDlPn(e%~U${=OIxH*$>|)YMV(>Fi0Q&$VQ!>2r-lyQdlm|rKIXd6>3wRwSzk_Keeh=_4l{Ge2= zr@oxRa~%k;O2PFCrfPEw7Il=xr;jX5hTlUnK&Wa6z;6`Mk6l#c^YXM zR!;-?P94YU#HoE`>&1b<|HW!&#lK!tJk5I2M2+5$hHx+DBWFC~ld%N1hl2HnghX5*#iCn$c_X2_yvjX?%T`@aNSbmm1h0j-~+)I7a zL(B>u`D)M4Mbd_do>iBvVe1+HRXLTn0{r7b0EBeh5?1EE)1HpCXHVhVLv}4>ftZ{va3jniM#M1iseo-b!(rJW1xQL?_g>D<5H3>%_T# zzZ%Btp=_zIA^6GW)reQxrpxJc8>7O{F%S&9{+-~qj0g(_1w(LKq>X}Kkt3@l0~!-= zPCQ~cXcOsD>-xhqY;*CMjU}1A*0~Lf46lkdON9(tlN%H!ru9!7s_#0LPrFNY+r6j{ znHPY0VB{o%o1|_XII~fln&|1-iiVDIb|Tl-uQYviasSz`>_>(5FDQhxzFHy7wSP%Ii~R~mYOJz`Exfmix6H9PnnDFo{j=dVb=BpBkgn` zfap=FjO>D>BphQrH((596;}r$-2HE9+G`ylci&ANW!!odhax5^bc>(?7=}It@6~oH z*9rAU72QhW@s?2X{Qstm(cm*%Z*AKNzt#7`{uiB!+I(B0dLV%av$dRGU7?H{@@@Uj z$ikcj0;vT)!|4f8#~e4vA!iCyAJ@UNB7M7Yu3lw#*Cv90Lny2a*sYoO{MQ3P(2oDv zJUHm4rl;QQL2GFklaxot?-ytgIp!QV0UI%9M`$E|Pc?kw=$!v6(&_kbAR}QQM_Cxo zE(Km4NsQIDVsmfYngv^0UgTM`IKfXF3U7ucDS6@;+{3Fdi?O6x<9gIPs8JQyCHu>Vgbazys)K4t#XN_-vEJ&Opt%tFUq=`A9%JO zeaCVrK}qk;DDf+OZU28ZeGFIP6-C~`TA>%v$;cL-mY5Pi$mevVzRd_=K1i_=7r>_^ zD7jpgEYZa(=%WiXj;`9lXGZQ7hPIBM!oe>;Z6~8=1L;PkhC*2@mMzej_AxDW6>M^h zBkKR3{an*T!!mKlb+jt^tsGZPK(v}i(eOk~hxa6$bTJRtNNgjQ*%Q&vbN_e0^E|kq zm=fL|bYb1Mq?t1HHAj@2qwrn}M~RODd#v#>BiXYAqQ^fU&Uyw9I>i6K2R&P1*e~ul zp9am#9krK14~d4Wbs(qB!ut&^A@H5_kMS){wyyf+F`3lnj*g-!Sjc51JML=iq zR^8CZKuF`6j;91qi#;mye9OBN*i>#5_`6o1T zi;5VxI<|-GF4r{oIk9Z-)Xx{{hCXVFX-BTBL9q6N;EA>HUiHec?#hmVpExC!2KSWN zPQ2sOOTL;Zzm!XVAyObTfGtCe)u-&T?OKY$+zT|od$}FB-+1Y3{k!zD!yx4B1~nj0 z>`SWc>MBzEk=4n>%XHuYoTS8d8G%px`nE@~7Elj@-6PqRMXgMV^}EX zMXuk}oN8<;tCt&zy~@Y!u({MUR+x_^l%E>?sbCWf%B9rL#wo!3tpK+31v1-tpIDxQ z()lh>1NHfw|HaSvw&{%6S5W#J?AS;{#1**ZnaRPr8)g9rS z-OLWYU8lNxBgZXXjmV6sfHhS%;y;Usy*129IDQ2ErAT!)@arBE<|mPmq;sw-$V{qP zd@c`ion;7AgS`EME)cB6{${|b9*T|AwR9KpiDaROwFM@lF`~a25FaoADi~S%Kr7%i z#|h~uBJ3V)STx({Kbcb<0fgNhxV~wITZSr^$tLPh$edVI2{e@e^jFhoA37fOR|Tf~ zE$^*0hjf~M{O#_nngq8&m0aC1!?rVa<~<_LIV}xq`ve5^xASj+n>~3H$4L03 zg)BxqzE~C|B*}bOtMgd*oiRz>Ea4UIh0=HqyVGVXO5wMKOxAr{lR;EZS_U~E1j?q> z8YpLoNwWJDA&fjA3j7AS9@g>Ms`C$9F%J$%{T<6V2pf`fHy5|fIp#3CEOb2X4l24V zSlPr@_}k-##iUt?mzj%>))YHP^0p*EJSpBS%k68fczC>7xD!l@?Sp?0mtXzdDYH4+a{^-1V4#df2 zpEirv2-HCD5B|iw$q(TTD$UQlkOYGC(E#(H!a$Wt=&fntQyXYa#B_g?@n!rhT~y$` z$;;Edbk6rJDz@AaOBz1nJnDaWzWuP5ECaP0+ z!5r!^278 znB)+`gx4XYSo|&3T`R!ZAogm&w0>!75*ivtFoTy2u9z>`aa_VawLeBKebS1vUTbZO89V5|f-g^cM5^H>{CD(%n_yq$d?6nS;7&}_(*T2QuxG~`dBq3*GY@aN zqP3{dptswn9}2g@EE^p*iw#WoIuJ1dUXSo&$1=zL);ENK?ZBJ^Y`USCPglWQpKmU!*At9d~Qy)c%_H-7CRqnNG{O_yxx7?v3g082uY{feThM=p+ z@LI%fz3<1M&Z+1`t;0}Yf#j*EC(dLTuUZpTcIrs(@lm23RO};+E5?V6E$+Az$0S9) z@Cr`?@>y9gg&p4q?f^%*#uo-#fRdC$(Lr#zV5+D{f*Ux0vBlbv4xc;hwW^BjQJ>m1 z_LeebER?oDE5l^jhfDdU)iI5iS<GCQdfQGJUXOSqubb@CM6|d z4Kc6bQ9bxwXb*?@x!|J|S~UN>8!9_kT5NxqG(wAb{^(_fGxFYV)FVS-$R7WhI}0u) zm_aZ`CxcyFEZG>u^27Yu||OM6pihp(oWGkQ*6L`Wf)x zx(s8yo*@1e8dU?%j3`X6huFxt`szLQOsGJYA-iFsV2cERYQ}+KFjFxCm!|=9!}j3v zO1>GoP3Ls@+Zr2in_HXOg-jNSgfJ4SrGLVu?k87ZNxdMyU82J{4AEOJlJ7ZElB-lwJJ zBYO!}&Gq-2#eWq;ab;aMusbtvUBd&b+kU*8Y?Os$8_6SyLY$?5yVwd9cpFyqz@=>K zMu}ihrZN;Gnr;&Us*!Ie?Oo4M6?3rCm+t#a_vHF6CgNZ1sJ2^jVK{dR#e# zKwC&O(scJ);Fl`nVk0i8n+~!t2RG}Ky-rI6Q;Re1H;^N0@HZi?{169oFZY?G_kJ5B zZiC1L^zfd{ACMSJIfQ8d9fgV}#mXJwtOZLgw#2A`u^TuTn!|_c7}YQ!^j`)A!>tZy z;gdv|L47q`N`&g$J(A(kaSM)O*z2eks%*1kZG?H6?TVMHL0!A08aRZ^!1xxYJec!0 ze$}_qSW(c!(4QM}0#B@}@>Iy*D*N4hmt(dUzIo}kadcCS@>9i`(NTlWP?eqF;Zdr# z|9FY(2SOnlN%scQGW^NjUATHILwDUbPwHY(Lg+E|O@-LmzmMxp()@S4G}BH)=1w-j z!EOW2g_L_-tkCnrrzPfTZHS~u*>|<4Y};OUo-*KsR>rq-cUj%=DP?11r_A1o4c2Dn4yXPdUSKa9vpYC* z4F;XB?%}_mgo8ENp*6WX*)sr@n05r$EUX3o?wJCaT_-Y>OI$UAhsHE+N3wR_LXRPhVRsQAuP z6@Fi~;pZWxKcW7(qWhQT|4B$+P&=NXERiGhf%pYpVM&no!qDfW&k`dQQEVbThENHh7%PE-MFBnRCm3Pu@1L} z8pF|ruhe?aN5mkd-Z-I@wlZMH!hDe5;x8sbHdJvxK2&6s-`Ad=36aBKYc9$cpt}o) zR9NoUNSX7F*K4Wl%jHJKkG^54tA~v;v6Zl$u(w$o0b^1_8Y|W7g9hznW?Bq5py8`~ zhq|cj7m_mV8+yIBCTC>$>2?jal@H%M=Ve!PC#%^ZuYY7w?8ugb0YWRAI23QLC#1RB zj7UqQ$9UdZZap}j(%Xn=E(r+<6z=%}P)Ju-IGv%E=?(uU3czSs*P;z;84s6=&(l6z zM;Tjc>(RB;Uw%HUu0AAj&+XF(up0BJPtgaVoK0YXr}{8a6!By|>Y0#|h{!5|WV$40 zF(4n^pzF(Lei`tNrP!r}$Pel*;>S=>31vyKaFW3y440Gor@=b<92grJ4PNCaZV>~P zpvOFA^nI{(_p3RA4hq~c@~lYA8!wJ$^S%#706ecqyhwyof|_jXG=++yJ#;ikJ0<3O zY5M{)Xcu-gh(oUzGQ*lUIRk*v^~BQG6JE1GYiI#S%gy7acvZKUIBN5U8NQKFJ3bVi zcp&uQB6r`l0Fe%>r#U8x+-szs+K0gB2uk8=*x+7!@qq=%5QzgTTKrU0g4Lrw zONWwB03;@z&{%fCu3}U`w)nX3amnKENj*T_PlwpS zwwtSYoAS>)WZJ^EHIjB1+PT$z4&i#el?bBu5k(>CIIb1}gA+>4M`hFc>(@)enHbe> z+Job&6F#AIK7L0ZxFQot!eSeDHy{iG!JqAbRnnkw*`LWW)lqkOtZO3o#P5pp-B^k{ z>hyhM%X!2x=rF~tzvg$?&u@YD84bji>hxWCS2B8a%I_5`-Z>w#j$-s@{)n>kbgOHS zC+79**JOzl;74A7Fx>jC%Y?>RW_VOg{rR^llRH&aT}^FmOe7P3&GOG0T?5XRG7N1f z{AyntGU`MO3)YJfb~_>Q#F{(Me{J*h-kmf=(6~766Db-I;q!K?{xgs}BK#4ETdxH` ztzeLGLmGlxn|h^7V(xaCEQMz{*mb2WhgKyQ^sT4>st1s#M%XD?2+%`mV`B@^PPiQ5 z6%lyPDvB`Ieh)g;cY!tiM@Z29LkfO$jKneJs6S2@*RJVw#uSuOfjafBFCqiM^eaFQ zB@s?P7Vy2RN(dCUGGLRv0IDu*cLHyW5yXQ5Q$UXpLBK!DoIhW4v59d+Qp1*I8Tdz- z_RN2I+}#DpN99)#j1$H7s?YR~T>4=ch?8jy&mq#B{KfaNT>V`-2I8&T8`6-v-xN32 z-TWFNL=12HyWkmmprdXg`+gB1J;~K^L55`qq-6}4VVfc-ns&XHtAhp<1g83Lp)NJMca!L!yKak0FtrCPnp4+`7iZ&~RC#{!|p? zAC*pv*t6pqNI9K)nO=oF+}zXBo(QijPU?-cW^Cm>zL@8**A9^8B+YrU%hE8i5C;e^ ziUneuB}NAJ(8<+Pc{te<1V1Dz`z9`SJbIi6>q8P4dCt!j;=5L`CkvZ76t}!BJPEO1 z1rVM8)<0$;GRM0{D)%QJX|~p@fXXA~Dct?-H&$pEo@>l16kxMv;!PbM+p|==r*yxM z_%={Q)=JOHdL#J=fgJ$%=>ZiNH-LHFjQ{)BFM9-KL)G0AT*xESym(_(lrlH5B&btK7Ub}b@J*13;-dH*H^&{*VGz<4zFb-Emm|yhVUnA z2hN`Z*EZ9uRh7|Wtt{c^GjMYWiXZ10uTW|ODyXM+|2%T!Eo}6}+?CCbU4XkP|2v(T zD`@ISK1(X{PtVLOLxk95e^px?{jdJ3luvgKqs=mk%$4f-VY~~3P6HmB+Hr3yCW_ZO z1mio08I-9UOgF{zc!$3JwYwOkhQN|?bxnMq2}GO-J39k_!K(6x#>Sn<5v2=CPg{9Y z_gkDUfk24VGpZ^_y>6WDv?s9}+wUI$R2+oUuupkC5b@bRy|4*bWll=uY&D1X(jhB>uA zRttE9)Wx!|hq89xxS+e5D83Z@>LJYxY);D_7qh~5sj6J1kAca|ag*T#poKXk5S2^Henx z7CHP2)ZvW9(Y*_ci5n*Jr;V5HSA6>XiU#~r-}`ILpr15PNTUui8L~-$$fx@WxLV&}hIQKP9gLFh8I9d4!F_YtCQ}e|{cPE=K>p z<_5xNLVc`Qr+auiXt&*8G~?-i@+h*47HT)-4}-^XXr=K~#g&u!RZ+}qejbBtMxV&k zF4(ydg@pjdSxst5UGR_NJopB(4diD1t0rLL*m`2G+A5|1iwbA@pb!sB3!~tlBfv0> ztrK2M^srI=KJ}4$3w@S3qf9$L^;s@Lrv(eI_jijCXnwL`M*FYC-f-mUV$Fw|(xV}Z z&PTLnEEPsfeL8G^dhhT5`C?A=)ktE6S!blWrBaL8^6tp}gFebUkV%WRbH)`-7*)A5 zKm!{Prx3{wRmRv<dF_4?)#P4S(Vh4Vae^86RXtIgJtnm9aNR`L;e1z{) z*bHOCyB9l34`(`#6ph{%9kABN5k9#G~B%MC=0kalp z40XWd#Ls1b0zkr}{c@6zQp(6ZmNc*SOsvg4P2u_D&BYB5O5Hf+!Ap{61-FRI96YW? zzVl)C<__2sITqkHH#uo~ z?BsUe;{4;3#;bmQ=CvU}E`#(y{XMv&++#zol+e6<^BtCsM2u16abUpr14Cy5-Cqa_M6UmTn_P{#0-OX+0AP>qxcS`I9?SKZN z@s>C~=Jcj$+nt;Q^VZtBUYpx@U!C}6LQu{zTaiAOdVM&&$hFc|7+>sT*F(I&>$#vS zLcpYVC5@wVA|Pv(MRIVk;ubTs&5RG8cMCVIXLyRa&q*%lKJ{Ef@e)6We^BDT;@4cc0rG;qnklwBcV51I`!=%TYuL1Qh&zcL zJN7rG29c%#$xrm_lk(|FCVQ>f+@?}2jzHls!gT7$^G_GJ{JX~gJ#WC9a=vA2(s4)VJ;OP?X?y6(@6d84IA*-|wOtE(Oo5F; zV#ff4ci0w=BGT6YpGvI@H5)xQ@?`JDo<3|j6Nlhu|7cNP0qizXe?@dSVf|-xr}yS4 zvn;%Y3aq9zk>srjNy56HHK*|Y*WZNLd^)naYY%W=+}Lldy`YXwF~B^O!E4Qw5<5BC z|E?Vcg%RHmnrSx>=uO62y-!Y&T@wg_2NW5>bZ{`u%tg*Sp z{*y-MHfLvNjfa%|y77C>PnTdD1*~f~SlasSvs`8~ObyUY`|5Fpn!j6*OMLFvmX9Gi ze?5^U)@%H|_Vf%|}Q%36M@=707c`A1gwbI8I1wb-B{a0uiMcMj#wPCA6#VbH7G3u8=T0sa~46dfpN zcs({^ReihjtXt7l?eo6uk2bR~B8lZKC^b0ei^8~58u_ye5?l6Nk83#mBd)ng$ZZEW z+;>+UZb!eScM*(9pZLKrTVG13V>^8sSqQcvbR0QF*aWrTzF@DoSyBAT?ftZqjq_Oa zi0z1woG(gop%^Y1iH@VwM%;>i`K;o;$3?2_(u1QK63f!#B1EzD40)b}T~K%jA9>}T zk@|$Lb7|DB98PldZaREz@`eIGGu2A$&JIXEYhpd*=!8x!*o<-jtA@M-bq??r8$ZV- zv6z%HMjKCWC{AQ`Ns}dalOo<%iQjOO+siwc|G~?fcK)umD?|Q8Ojwq(cO?xaF1M-F zjYT&+I1kuXa)n?*`eqZR^OWS$ERVH*f({Q4f2z8nOKn5rLhdzGgkWkd=}LIjefIJQ zO1uuB7b5p5p=l1(7Cua7`MjpNgVD{<;pdnz*LF!lZEXmM#gJ+y$Q9R|qQ_*(jZe2! zo8U0zJ=0BBn=v0qvxBlAt+k!7?pt*vDknrOue-xz3|-1^c&IuBm|!7n4FQ7E^Lh{{ zT;O?rTY)xd;IOV<9mXHvY9Gh@Vr0=HG3Icd?-XI3%(u>x;Ry$Foa6nEA1d zNp2y6{=CBVWUE9mur+G8)2MZHL{Rtz1k>EG&E(GSPugU67r5-_u`SBk$PB23Eg*6z zht|GPdnkD9(lE`raeqH}W*{cNgOc`j$S@)?q^SK!qc+ZOExu*gK?fGGIKxx@!CG*q zDgU)PT!El0NCvF{xjl2b1VG-5*i(d{RcL-&2+#1`$84Yoq;YFHnncWA7toh!;4aLsS9+YqrKYA_j;34K~kO9pBhadl`bTZAh zuG4h!SM*eyLZa45q2#=zrmAxM6O{eTxh4G@Bh-@)zj+R4t}_P}dHrw)`oY`hc7F}_ z4vK*-)^AgLrgfXfTk2xk)dTE@+w1-CWY5;>;6+^f6(YBo9xd|6SuBMkVUo_9)FR4klwX7_|I2dE$LH5SNhDNOY7HbT<pY$50tIZ4JUI3*fNVUa3Bi^<3Vf-;<@=Z>cNr>Kkg=`19>qwo_hT zhq`14gUHjdhO*4Juoe;sf3D!FTA8c0QfpVXEaqwE^np96f!;tv zeDTr$u?p_u>r}qU1CGbNvWj%92-X1Bt=Ht(6s@s%|dP5Vur~1`o2~1?&9E@^8d*{)(a|q|W^N6}hu4l9%x- z;uc-+UkhnI-4#j{NB_I_CPZnTmEG8lDnerkQq12VFwL5FRD^00@F3-Pjcnr2(8SY4 zDk75isbqdc;<#78)Zv5PndU#vJ->X9iePex##>XW7zAPVM%jri=E#!?3@A2Dztnds zG}cv1eXZPh5}u#ZsABZXdg9xRWqOuBQ|nDFKMnil@)r%#lIw})7@M2l@InkfCPdfi z0rMp>bdW0h%vAc@x1A3Kqf0vTvcWl1y@$ONlqq6B!-ng^sLKFRbz3cva zkY&CVoX0~a$sKZtK`Dv{2F(zSnmk@j;Y&W9>J8%AnFB<37McgtUo-)h5d*b+dqJ?)4t}>~b2@%`t z3Xr%R(%+%$VNicm{0_M-V-o7WxlMh)PggJ<>Hj!JUBn@0+-WEAr9zrKr=Jv*e1ro_ z1irMI84tw?tYn^hmT`7rI_@lfsMIUg4dRccmY#I zh{_SH-;$u|jH&^btCW_2<0StMO1#1M&liGzPCq6s%TpXTO1PY!!skLK*v40LTHvb? zib;j7F}GFESz~^d<)5#$aj9d zOLOWO3qXYTlL<>=ioHlr=6Atyh!s8l7>Kfiwr7daD>)CJ8K@DRF%OGCh2H$nCiuDg zIWA3h0uRz+ZGq#jE$n49dKf>wyr@WI@;P)}ft|qw?|~-?F|j}SluU-^r3y{-2==d9 zxaGK~Un{tXOSSJOXSfKn>!2@q%kRM}9{hsACM(#AQU_O```0C}gc1&_Y<-x5peB~4 zw7p;-@Fy%=Aq`f^(!Y-pO9Xo**m0X(uQRI_gEQ7DbYs>9{IsKTugD8FZ8%C) z+5US3`pOStt&B~VtNr*`{cjn66KV{+Ul=d+=LVF;C+#p%(<+Z5_o9TXdvXzE%Do1^ zzR_nsXIBKOaHy(~Wd9SoGn~rEL+i}U%^R&{*AK-J?P&?|KQjI0Q*52}3X=~UrWgDr zM@XH>CTCKr=zwh)gvJ92{~U3}#PN<@2Ni>bQwG-;W5b)z_^QD>-tc8Z@uN;!_x1Z} z%i}*?ERD+;Ug&7d)O#$rH(WP$aScU0tr{z66zPiLJLyr39C}ucgRpA#`);n2%JgM# z`6ci--P9a@!pXSz!Njk3CUm#BwNsOb_F66Ps~ldpWHoNz;>+DP(tFqFBk{#9|W{sVE*u<7E!!12J;9mct&U*qb^7tmGZ%G;$s#|W_$R)5d~JUBab#IQ)M5# za*5#aKRf=NI@6a1wOlC_v&rG0r^vMfU#F?8XH1T?lzD+53P9`_uIeFmE6dKJ7 zMljY@7q)qs$cj1mPv<-5Y_Gk@Q!2Dl6Eg07$XWiI#CMjq5`F#A`fnfI52UOUBSdaK zgZu-ebIxo#0z(yB@b694ZX5-Za()+o6AmX2q=K%*UlB&wtUH~ako=hKF*zSYs>}uJo&V8IpSdX zkfX9?&)cgB8lffKMF~lBA(_gDq_;5nIiy-9!9J7n&Z$CE@P*Tmy)x7N-xdBMS|iI; z&)+|3BNulPPHEuxsrzrr-g;-w%_mOkmIj8ze=v=UNMsHbzx7zS=gWwSC(oW#)|o-W z;Mhb>_i>F))q*dWd7ak58^BJ2H#l!8X6x593=j*9tq*=iD17DC%Fpf|MzwKaOngziIDD9P>Q^_v zZn@U0JOiHNNHXVH<#?*Fnsyl+g&%TSGTufxJd=(vB4{Lwp^b{GP!i;1Jon=V_HK;w z)E`Yt5>~k3RtFtNFV2D^1xR!ESa7Y;p$g=Z^Tl4rT<&=VUu@Neh%wgfDSr1!Kmxrb zx3BEunjOS^wKK-1Xp*1lEYx7r&o+u-9Qd^d5G3T&qaxyV|rx7`8+%zA47PK*g>?)mrqYYL zGA^v=@wf1n<=&Q#SKyK2W?-lD0!8a_L;@qn2dQ5Pig_X^JB^wI&}&{52aO8MfF3#L zNDXoy1sTm zFc_&ZVb=686f)yBKOr#^TZSj0l-2cDPY$mLv2Y!xmU7AV!Lv%~3Qk0jdgX8f_&r^+ zgy~73y&CztAWCnNx7?y)X}Xh(`|qC$8zlSuR8qH)<$VP|K1JrL+!I`B)Cf(kBcaJ~ zEibVCXBsrF?jO9?a5634S~YH243s11AO+Wv@bCEUSDtYB`dyEPQaB0Q4%cg7L7^D8 zp{BprZ!kJy>x(0k-t_jI9q>OJH3#YdyL-yK#mS%JA!$L=rTM*rRGyvpQQ%q z=qT+1AgIa@R`?x7nm0>r3$+!T_CagE?QDptET~E#!~xhS3}B*e>OFH((0dzUXaS!k zo+N%gOvI-=-w?`0Ouaf2jK7;=Pqxy?&{UI5hI4mb5ne$QLbBmIHOQX{X)a&(!I=Rp zrXd(!si`Ch^SGDZq%rbrJ9>OUVvbvhx z4!vkSVA~Ha#Xvn-LL!d)PY2R?u+u&|Z34YGM^ftWkR#&aZm5WpJNwnDld@Ok$|Y~L zSV0y^HR6Yu&q4eU{7gx&F@I;xW1Id1?Fr>(g`+{GY;$qgF)%W#Pb?MDYxB~MvFQf6 z;*HI0iR%Yb-s3KyP=y7L$33)E+$G1aQP3s*;TiGvX*oH^;6eOz{=j~Huq<9{zum(W zQE3yjVITKK`$`G_B)Tu_qX#=dxz+rGbaUhQFeN?>$KT)EoN-AoaHcAL%y_YvWqPzY zV@bA3LIU%^u+y&fg3z3Egr7W7sINK@LoWBN`KL^c2Z7#&meXTnC z@7q6Ht;SrB3$~E!Ojw9GzVR4_M&w{lMSj$ip((V6bZ-ovlgECEL$z?c_u2U}0LAM< z0i+hnO29(riW0#$ro$hy9rY!M2rvLSl-@sVc2Ag zTLBqbAaxYoKMS4j^8XPv=#_huiC4+loSIU=^C^2m<%g30(XsZQ#`Wcd)c9q6v|3Uh zdaaG(0}hG(yD*J1L9Y99itd>N^$adRT|9Smfj)0uV8pIpcs&Y}+5Tob_gvO$%AWJ1L>H=R2y7D_&s{#7dBubu7@ z%Qb37koZaUCXY?{Q>QF(lMlN#keLS4RV3g8dg5`s@sXk}NF^Gi%lRs~`^C;9m*4KI zwZmb8%nVN_aPZ%J+>nYIJ|rbD{DID7w&9Ytm&@E^7uS|FeUg&_WQ|M>7U11`Wkh-& z>=FZHnW6kPrmHx~Ul;&HVb(S`e4MQO%Mn1wiJYx-psLK!q-k|-5riv#+9q5nV)*^g zQxVIo2jm0z#XL2U8=l$n;GlRbS2hlv3j|Fy(1ofleo zP=#G^&(ATrdlWV@7r5?}LLjv$12DrbIbZAeiMEW1(P%YF{1V%h!S>G1uU~KH71BCm zXDs)5MB@Ch_$PXjIx(7(YG5MOZ zvb@mLF@p+E2;_|mNdp`+QbZ4#GQr|lRHhQ%Ctau9Nx|_|4mgd{bk*XPgxd`iIcsv;W63K;@nleZ? zFSO&9`~B3W+n|NZjq2Szz>@#B-#8MY7^O>%kZ#TW^cwTK!BD)wf~l!n;nrI2efFR` z;Esx5nL7-8Q*5nYGLTVB$AvMFSp)N|*<~LEA@D(+mqRCfdw?3}iey)AT0ht1^P079d z`B80F{0%Bt{j}4D7fCNXC*&?)aAG5k@^=*)iq|$V(qh41zUW}QEQqSk*&uEvq@mgJ za#Jw7oD(qQdjZK#iRW%U#?-&kpnQpxm^5mM0Olra`o`6#kRXoC zVsry(jfVrPj>nUxDwD4-()gBEbD=!0NbAM4%}i|Nr@}HfgwDXgwjZ%6kr$n#kZ(hL zyadJby5XSiJhEOGBASWH!$2%OzDH$nkNXcGyo+^oLdYDl30+%yg^WHRJjm(;5Az9& zwSozxF}&0$zcV#SSd&5W646}z&nXxy;s+@p{N)vxS>!Cq<+lDAxOf|c6lT?P(k>uV zH=23G`R(Y*K_zT7P#h@$%8=WJdpkbF3O1oYdJPcv97pZ-xB-+OrW=8Gr8KHmXRm$x za1Hf+NPFQAg|XM#6q4iMe#ZJjX&gxx(TZ=~%H(@TjBbylI1)~M))R$(g&s62m)Fms z;a{A|DykCa`1lO_?ST2Jxn~?LB0yG}e%%2eVo6*%kP!D@2IamF=-Y;6T)+CXN%x*L zdhi~icDbB6&(QvVp$=+mOd3`P7wF^u^~E&iFlr_<>iTTINEvM?NYICa82e|w9^e7{ zc2lkxD2RNZnEc`B^)FixgV@kB=Gc^nei7Z69hhcd_^Is~Z_;*=K-QN>v)~#@8CN(~ z{X=dsdq@z#kCa72s@&Tv5-{4}w^JbxkOZq3G&k{iUbiB}2|)fWs9+fwF-x%Nk>m8* z-@i@(g_N4l9*dH#u~TBVn%~+t<#nn}2Y32DLkFq|V%NTv=nn%M{uj}2`Zvi_3|P&a z??ri|!TjL;la`_5jtiHaC#!_0Bmf*Q-s;iln!o7s{@y=9z^T^IvyRzZ%E);P%E@Xz zvpc~K62G6@y!QYxTB%lFr9m=&DT|3x<}o|Yg$O`7f`>j>-9Q`kzf{(z-1W zxs+ktG&8(}V&PeH5Nd;SL=wkkG-(Z+*((Xxh)*g2GgJ1E2o^?-mcX)gs`*@sKMS6^ z6t7;)XR=3v8r$1EQ_rybfL$>msOqN>5315QA$-jEUUs17IPnO>y9 zT>+9t3k`zXYr#R(oSp+3Bb0oTOI(2(e8kYWeux7H`b72fVB>VYfq&oh&)vKGQfM&p zk%Zqt3b)tB=+hs!)|?7hj>5Z#!EsE?@d9)Vs}C@aC5*lh%z%8tMW-bohdEc&_9z^& z!EvlzuohKDT%hi(=5q7&X{>oSVDX2cIW?s1XrJxN(^jz{eEDwz>HLJKtzTL2tAC?e znlCC3J1;~?H?&L3$jJDV?>wrdX{Qi`T4;w0C4sB%P8Qu6SeG@b5-2bg+3Es_0621@ zhC~WV!Eu!;^oQh&QuQF4+r?)Opnlu?JP+bTh@L{}0IU`U0W-}pr@3G5$y-=N)B6R1 z(W$W~1xn~q@InG0fM)6fQhHC><*>lNWXj~;4<|{YqZ1ThW6R%8H)>px;K2wa3|=QI zOK~rYqEDwT z_*;9sREg?!p@$)!ULbAJ89me?#{vies#r=EP2-N+C~p*AZtI%}TG13td@%vcZG|pW z(j~xPx6ncRD;jor!O(b!AdNv}=llr42q~m5H^rbqTIapciWXr4BV9b~%*A8n*L9w%pRDaxbQ)vCP-9 zKn%3|@TH^#NAI=Ys;+{|4M*su$j%yYHr2+b`#wF#`nd8~=w1Ea6MYheqg`u>FMovy zF~ltYs%uqP(0KbThZ3MI3@=V%0bU3UmntkAxp%-UA#QlF)MM8|3$;k!OX~2^P2ceF zyIJM9@6~0(^5Y~e@kFqOsaPuYrn6+4dMI?H!FQwL1|YbIP7(x()Ug46?hli+&b42Q zm&6M#;-4z;g-!-_r^H#1)JIQ*V3 zN!;wqEzlET3+GN-ZcNZ(`4m8x&~;`~rz1DhRW$B!^40%G*q_JM*nQ#S_?^fcnW8jE zg(#u{4GuC?A`~i-B8^f>G#*ce3>Aea6q1yR3?&-SV2U(TDh*1hlm^Y;YuzXB&*$^{ z{qZ}0JdeXU``q`w_g;IgYhCMFi7F5$yS|H)&aJ-cBc5IYL%Hzhr-^r0%q=jH zc#?sThT~OuWAWFJeme`Vt7``T>g(?c)5&&0(x;y}*A*fxr&W=?*p{eAL_|CX1>c(bFnO{rF^xOyff988=kx&pJIT z`!$iVN-*EIeOd_>x1fX4LpPVM6PL6DGd5w`$xpJi*&h@8^bEyYq&8}|O)qK5=p%ra zS$+;4*Eb8b>vgUJu3B9UX@o3M>8SERqgV*Q$U$yXI~4to9GDf)dbXyXC&=! zsB(|(HI>K;HGWw$FR1##>%(zwAFmbuk-Bj-`iIK<+JvzD$KyVUwx6gu$k>h8Jdyh2 zq;-d;{oLk~_~^eDQld=$%63kIU|M z!dzQAB@Bm{Jdo>SR0b28vJJexw{ybI(UGT|_y|2isc%u*&Hwgq(oQc-T|W8P^Q_O^ zbtDH%RVKZM{PYhsH8rKke%gP5DKn9PTcbC$MYd$cOiO4Ec())OIqtIW*f!vONPV)O z%I2G;;5oFVcBL!?am@Ik6hY-Xwwu7Bd+!9SMGY{0ORoGD6-wDQ`0a6nLvdHmwPj0E z`; zMXnn1cmeSF4ovlWF57*eXX?X;TYjTE_N2sbhfOG&6_pz!TnL2JCOW)KXZKzQIHCw$ z5pLbf&NY$P8o5DxXmSDMpIS4?`a$P#B$@2lbj_`M`!;+ajPuYOzAIj$==n?G6PZ)I(XU^R+B17gJOG8Hl`)m4fo27 z+iCQvG+2Jh^oe#;M{;&O%f{M5r&#GO6yx_3>!+KV6jNK%D(VYJR7$GrqJc}BY3(g0cKuLa*sh^@ zFP|faK@4j9d5>*xg5oMG2&q;ov`t&K<&r>38p&SP6S`pVTn_;*%eM5{e&SFHsuI% z+xx48)2MX%e$_)_uVQAdIBIde`Xetyx;+Ketx&F2rXPDxV%2R zzP{ed=@7?wqh@zabap&M#t997-SZsSUNz(Z3_np*C=qJynbw;OhpdVOvkRT6kj$$K z50s;MPP|BH^19B2qmRVDy=~DuTEoFZ*?hhG&cjtV6z!|tcy+A)RAa~wKa5S+az+Sz z#Oe^GpbrSZnfUE7}r}+>L(%IRI4h?Z>MatzVF+v(u~+J&AI*|sfM#x z-C1duF38y>)9ggktF%Kr->kOtpY{1!ie{!&I6-{#WYd(<3Ozwvh|lOMY6d+TwuYUd zd`Y%5x|i(Ep!!0RKW{uh4SRHFqSpawA8prYAwIh03LgwU_v!US5uryvQu6A$f_3gp zFWBZ!)C!Nk+$Qs;51|wXD0zq|7gTAb;bkCc!@=;FSZ!$Se-S zDSmGDvDD|#hPQyj>5@_h3mN0)fj>KT6mBmTdylkPq3x_+R&9UGK?UnI4tv zs6ubQUdo2SsMK8m(5fbk;sqQpiD{V1^?}j@UEYI<+CnS)6_V?3Q3C|guRq93C&8j` zEzbeE7|ZdYi5YQ>JE`_< zk{7Dk1^m7WZG6k^_$hd)F96f%aqQZR)nm)+^LzEatA?@jG)4jc$V}0bpKacT3X|~X zNa;$7-VO6|lYaZ7H()os0X<&s$h#D5)Vjrt0F>joMEL0yM7pXyW(l zkNbPeL6eOqKstPLLdW?a4Vx=r`3h!Y)adjRtq%h{7p(O!OA1G+9FhiX>JohJyo@*8 z1y3+hUGTz^kkh0+JKn(?{qk5nH_e{U0V*%-F<9IFU@vLLq$AhE=>cDO3y(t+6?ySB zU&LdDw*ww{%vXW)PKU=qSok-)k!^tNvZyMLq@IJM_(Q(uhYcL+gNk(kq<@tnQcxQ! z(OZ&jPNm>DT~#CW=y&2*Oy%k>=9>6t3NtmAOxOpbbaEMo2XG#vB3k;i!}?*(WiuM6 zr!B1s^k@D2;WzhO6M{b~%w^jXQ(FW$TFIr;m2C{Jq0yltz^=bkA57TYtS$6&HeWM@ zJj;K&H!7|c6&>ek26iF6I3jIJ#|C9bXJOeq?Rk`9WrR{C((=l}P7)=wQR_wbSp&=@ zAn+{GWv50F)Sbb>DdNF1K=`U^$4@Q;8mk(U^=-qynqkU%uoCU)&*z78c>z@`(cVHC zAQfLyR0g+J7=7W-(#jJ=JM5)6`RTFbq{2&Qj0=9hY-;s?Yf*KqZd!4F`A?Goomodm{ z9A-PIqNlQ|+D^&U6oydRkHqIJPhtIXj?EnOw{O_Uh%d3zhtT@Nd26&{?eYW}&%0mQ zq^jM=2Q#RK1C6KmI)vIkWfNxpAp4IuT(2fP18|aTD*AkoMp6~kDnqP#&>ujP>XMyw zxlX^XXe9b;%qdP3`gSz?*RA#f3pprcm|)|V9eh2WO4YT1f5E#~L|hzyMg6GLIT2+!N;%NYIW7A(vn^=j z@_B`wG`3aTET6Ac(G!})2I~d~WPhZ!)kW74qwe18!{@p-hF#oz$iU+J=>Nfcg%_Q6 zj8To%b#tElwa;@G2(z>Jk``%V0c`7E^T1Z7GVXNxb#F}+1+}6$EJC7QmPf&;sW>j= zQ+;`p*pxx9!AFk$4#F9a;^hN6Oyz$1iL1=*EU`S~(X64CdB7yV#`qfQ@1=DZa=AFG z*H@EkN*v4mTO1s+pUVy_?kQjUzWSpfO`ky#D4GG{O3IpUxdl6(S(+{|PFNf$efp-D zy`p2yM2j{2=N;I`#Bi3kEuFA6u$;%i*}3S_G@WfaznXfC>)aD|?!D@gph)BKXP;kb z|M1)2?*J48z|H3D>ZlbD&K`kF!m;cB{r1lC2>t`^Kp33qDLA0DH&q z{UpctZ-(p{`&W{KlX~M(lu)Ed=1|}7KONi_9hB9Uo(Jc4t)qx+ ztgX(tT#)B20AWeDmcnC(Ns~S~2UO%xoci#;f1C>is~2p#u@tV_9fr4sFZ=KC=3^WZ zMlYmyFzH9HsP95R6rl$^hU5Zs*zWMm+(q}G<8mR>pFU;~oW>WiMW^`Ul@qwJ?0@9| z+@hc&squ`J@?~NALA=fjz^$iOgo1X&IzG;vQY(6=uQ%@$|N5gZWWg$cyH0-vR`~@1 zMoa6s25aNPkDfza&-wj4T0gV?`V(Pf?VNa#&E|s7vtL`{_J-I>OvARWp0P91nHqyC zSvax`$4C1(JPfHJDi7Fx?|R5uLR(Qf20O1|s2YTuT=;zbYGOjY*Av7)a|Py4Jv8>& ztzF>5w`=jr7BJe$DQYy&;UVh&61BfUypePnx~?dbl(R~KT1Ub4dn-mGFd^Af5Lq4_ z`T=}&wM@rG`iCf~fZOYy7$|?VsI`D`4gkF{J-rhlSN11EC|qh!I%eLc;v*nv|Yd8;dpt_^=0|4`1+DB z?}3&x{?vblnj!l}U8^rO+@I&*P-obN+U{(K$Zu;cfquY@w4TEFh66MV^JXJv#bDiV z$@m3}$Ov;G*d;z>@02R2r!!Aofb$?zF?;4@R>*=X3K#rTm6DUK zKiuCCfMR?#Df35~#n5R1l3_onz&@z;hW{?o;2Dk2{h^4=6Xynoiy|0)z`L_qYhQ!!P*jfbyDEY-qXho8+(dB z(j|*NDU6@Y<$DuTaEkSPT(;dc((}c>f~fQFA=%+NK5td*Ee7oYOL6RTM33bS)MU^}8z+->a2 z`|VIyQ1R#^GA9dmIBSEMj+TK^D|Hb6+xMG*-RI?dAn{ zRO+!w6iMX^g~=koQya(ht+f*zl+~U@4V%h5{^TekLl{|n7=k_*^#l2bJ=2Q^>$yUF@ch-cFYtOGvU6} z4iEsiwRuhwjlfA+_8%nR)hEOEN1ggQq(ZgqZX|qO*5CEtSOs57xxH_bk}?OoAnJ(c z&%8T1@?;Sht5G@Rug>bCHwC7Gp8|B-lIG&?7eO@h2;@a$G+jZnQGFQLKuENBah{SN z9Ary<-nl01GnUV+(&HRWaIR?Yx+l&YIQK`P&&w=K>vJlumex*=WHzBB8TWqP&}iRU zKM})D_qNjJm&l$hVCABjh7FK2J9;U^ncYgB(X|J^WQ<1IRDUg#!~p0ouYRwOtpZlt zeuK@MfP%*#G35!S3*624@(0wd9?F#>%_F&hoEiWZXj0-Jx2pn`rXf4ET?$hp;!G0b z-d>`cWcxSajh;dRkoZ-5aqY4TvZx4$4w1=VMP4bdkqo)Q%MT7y#` zo6>mc5phP~V;!ak4{C2I(8YJyj#P+VBy;E}oap(xB#`9|n$JE|k(Y;X9KBn|ZU_7h ze@$Bw4q7WE%q&^`%tko;)=n~ohB5n2i5<3blA&=q@=Df#=wvLf(!1QTm{VP`&oGGo z_^EWZ0cDTb7-j{C&im5tT8kj@07!I6^eFmx)SOs6O+%Xx?7g+$yR83+bXmel>>1)K z+w9bFtO+lUioA==>IypJ*2{TV*xK9YgiF!)!yT4`8XK;(_}}xy^}vM9A}0L4H1L_M zkvjRLK3T%M&vC7xeJ9*REm~>q>a+T(L};1}d*?2e2=$NF&SveqO>VgUBX@lYv~U$f z(Kijy<$o&S*}fShmB~gI4Suk=Y8mR~%U-Oa%ixAAJIdQ*T;oC~+qX?{H|COT1jv-} zJ!KTB%5KZcM+USC_SwHC@!Nme+QpSP-HSFh{$?WMIm6)M@A2$Q> z)mPM&ldPrh+_7IHtwkt2hw0nDt#pFdZy)r(3-Ha!Kb^1Shb%PpV?`@%%WcH}VDzs) zoy<&MI-d0>r|8}8%((W6PAYmZxi?pnnvvYtlEXF_0{x2a&Octd0Vc?mD0ZfMYMKY? z0|uggDzh`>w+CymyLL6r5VuFJq193FBkCBP$a-MA1^1UP+ovkUW-~~$;$8=lJsgXS z_FwYUp6{tnwE<{tSzZuA*Twz%GYtspAGWBAW4VysuQ~{zi8XD zUM;S0F}@%7+u_c{-_%p|ZxCcVSeB6u&OSw~vl{11v*WwX)}x59a`yD(Iax&P zgUxqwZy~URl{Wy5u?nn~1!MaT$CIWUX-gy@XkqQr-cLUpVbwMv*AFK%XC*y)tmE%H z(Hd0Iu`0uNZdkHO>L&AiIBYBzKx7z@_C&T%FU7AU*+8+LIQTfb(kg6U{x^bEjH-DX zRDE`LpLyS>!M;t!y@yiw?-#pX8~`x-F9e=+ zsA<*Q5cu8@A&kX%oazbGDUT(ig8?Qaq_HaP&SW=TZ@ClhY8@Rd(I>nKaU)V25wph| z&8N}MYvh9)5_5=gZa%yGCHn&nIU2C5Z5x=RbZS$`*7=mT^zRC&Jdp8&@@*jyIxa=l4iOF4>(lnKwe&)dlry~-PkutRhzcI`M8TdDG=-LMN zU?NM=+#1$nkSTfauFjrvolo1x_Fvw}FTVVc6}6dTdH*mey9Qa_E#sr(;C>eL+pk0C zOF#S&$yLl1Un{h*nje=W1y0gTDj-6>EMncnq~1dnsRli&*I!nWpGfT}33UUvTgA?l zE)th%^^rZVxxXUz_~6XxgF2(Gt*tE?iB^RCnM9)?2I%~a?XgqFG|T@EjkG4;VE}7R zeVV-S6d3+Z9-WWEa%|WWf+O&F7n5$OeB&8{V}`SGs>@(h_h2+7no9TGmI*l&*{OmRM>U`Yh4Xoc0 zUfy;@RMycMfjL6CE4w^#De|F3rRC+~4k;bms7?#Hf9j9-(6KtJ1mHHHS|LTt4_DZ( zWmxp9Pa5*mxIX>|r!W_Df6>Xsd8lN!?gOm=rwz;%uNhD_pzIi>U-p}_wGNJE zq@<(@_po2MKGnte0B?QMDr8@6n;;jjlK+PNfJ0l7=iW^?qkA^-oCU5|egq#Qw&m_l z`Y^}Rjty*wrL$jE+9@YCf-${zo6IxW(22HNUdQc__r|5Jk>VAQaME}af-`*FN{aPX z4Gk>2Xi%6@(QRA$ie1WXpQGd-7U=PAW;zYe^$Ic>#uXG9N25nQ|F8U%;~*vw-UB-m zxd&e%roXDm9#w8Z+5NZGpIoui=fRPvdp%V8Sbu%oxt8f*Hc}`2wS=jhL5-Lh?q!oR%99_rI_E zrT`J-WfvB1;fRe|$Cqw-^jammpHgf;L|z#>z<*1+!VO!uC0CFut!)mt&nTEZ&kVMF zu-9ekS9;H)AL!VY+u8bx0-$Iird%h&UzQ!{srlihd}fa_v_t#& zCvK80S~wvrvKg8I=XVcFH{sjObNgP(o}y*~k_T$(qBs>c$%!=rz!okFG2%7E+q$ny zBQPcA^c0P5M_y;&V&g~*OZO=Q)O(#buZ+eUc|b3`^{2o4s5&QZv#!%9c{t1}(v3XZ z^=3tiFa{a;s!Bf=b@x`Y#8elUF?~N?vmU1Zveipu2p8>P-FKS{uWx3-svP`(m$8x> zjYbYRF8KJ+H~GU+WU+i{75x*}?R~ZVm57suG6y&?6=$l^MZD85sHj>?x@nfBIZ|*0TFgbYJs%V(j35Hyzo6OSf7`_Z&XZ z<~m3A-mJm}f3b*bSu3|tFQ3jvgh`^UC|J(|6+=Q)#m*P}u(^4MoONHLcW=lZ*8NX6 z3y!qb%MoMFyKC|gH9UMDW|0Pz7_*V}t)^~|gMR}CeT8>>D5}_%zIM}xrSe11fQ#};v(Vn|JZLo``i2G6pwsLvIo(!^tO#7N7?E4-E zY>V@;a2n=ND?_RY^8l^mLZmfF2c45Y3w?-fU!qSOBLqM3jmkQ^ZP5;bQV;SbtPxvO z?~DC1a_A|^2K27;TfVcXAHF$zY7aET56Ep?{xbsFUWP`$Rd4ODOcWw|8!;HQ+OIA4 z$QE-|s?nfz&Fy((fwHD?zJjai0vqmc-t*;UTvQ{DEgKxybM;svRW&t-j1lmjeJfkK zGA}LW6eQ;}zy;VbZ4qd42t-MF7>7+m=PnwB(<$OoBFWgYt|$_?67;lONx6IBZy%uXQ?Q?ux7Pip!H6El4)l#S*fDN4T(`Pm@RlU?3WxrUC?Z# zWPnF1%{gAVqhuN3H&hWw9Dd&$-z${#SkX49#Rj*+r~Nebb(&urF8gMqV@RZ_athcx z58XN%A`6E`$T16KkBAg)n~>n=m#lLG{}%$W0!8GUU^z`2X!1}$+E#M}RkGE-v;D2y z>=EJaD6FG8g^ZzST84kU!X0C@BbgQEKvxI!;SU@R4o*hl3}VkEROp8Op|ldwfT;{9 zM`6B{6crSO4Yc2NFPQpSaRj?Eu>!StW@k;%`+H;$%@C&iZq1g+Cc541o$#T+yhjbj zcJeA_7#8nAkwa6++MPPQ6TI#At7%v{9lV*+ces`CuIcf=EfL|ecj{itETcf^yFym`tcLAmH@-g$IgQ-&7B0y{~#dc>uZf zD-i6KpsVmZF9^`VmchQO-#+tB1J9f)j$vD()DfvJ(BUmEZb*bbZ_3M$@3Y;uXCq2= zYfj=J_kC>X+Xx%RZKBq-Xgx%L3ehHd${_j|vV+~O`Z0T%>vO(MV1{#V<)zVI(RE2! z{%&;FiyRKv5}giM5=LPion8d4oRaXG4tBq%v|(zj9?0x(r}9hyr|Fu*kTKxQrd~Gi z8>c~MT1d!rWvR5blwLm7Oi_X1)k1La5;IXQKUqjDf5q~~Grm{QS_3%LKRo3dXQNqg z0Q@~!9@s_Dxw4JkJvDvY90~CL0;1rEL&|l8ZGND|o8mZA(G^gCSaPos#SOj)z;0Ew zR{*D(zq?yU01+v@I8FZo6{jnMvD%x-B`m~+W~f4ATD*Aq-6kT@p94s$`s4=gER%!| zsni{K>41rGDHQC#4B;wSlg{JfPH$UFSX3)~P-j9rKUc~*m331)eyD6{n#lok zgODUvFq6tK-HzMOUM|u>@H?Kxk=Jwh;&-JiM;s-z0@aId8~Wru`=Dwcf76Aoj+v3m zut|ab9ix(Pz-(#0C4D2Jm4^2rfu0FnS5fa)VQ(Se zkoOwh9mlx{v%iYGDi@rYP>aOqui<1Y#Jv?xZI}0~*ocCdvs8gy za*K6f7=gP5qs-V};NpOsbl~>o8V^mF`TH`B!>r0#Vx1$q(5DkFJDf= zMOmQkY`l>g{Wj1kI|RPRa(A-ibmE}!5Sog%& zm!!`@?G@@OcXueZJ*2t4CynUH@5|@NFWY#}y(Fo(0#$-kE_vI3dGxOLkAyM5=54ApY~{pgySAH~WKFh0jS$1?Tjtt#nK!-bDtyKM6Q#tvSjwTelq zB&>{@A5!si%ErOiDK$-Ty%mNbe@#Tj-9YsqRZmfxOVw;2dyTU@4)2g;rktJ4+T`$s z2jmfe;LM+V3f%|j$Rl{N1f^s1H};EJE!lnNbUHbuRJKcX5A0fe${J_0gN;qxmCW2p z{{n~3%}r$_Y59q5@`!#HnehAB=8ObYcf+`$z@~6 zdK39mRnG>osBrSLgIfu9&t-f^`JJP0w=3L}k;eyXZu~zXV1yuh2y!)*8_Ksd3^!)+ zBA8{^yvSTHpgS`G@!+NLMV05q&>N=RWD@cklCSvK1Gr$fxX**;p;gC*VYyT2&igJ~ zB3#DZPQDy_y>}CS+eo))M6NnHVA-i*&k3Lf^r;ui zy7y70;+xO_zIH3&kOi*OpwlM=pH`)!FeTfT>W&QYx>Yj-1>{gWHS z2gKSbYY(AI;AUyB=8R#ah7vJqY#gtZfn6NFOyxk?^u!7;cQ~}xA(#6%Tv;@0#t39(FxB#Zd_)!6qo4fkzvtF7RrsierV137LHn+^b}+m5vgT=`2S%P`-I z;dN8Mc&6CI*tiPhS$ikt(CfgLKIi3aX?+G%Gx2R9dnHeF+IRnN9dUc!S9@Oh2YDq) zihKS29``d@NXR;5E%JT^o7ZJRMqx>eE&Ois2G$wp&A{bGSc?!yZOL1j9dp2C6`SjsSX}eXCCR+SZNBWX=Xg7wH>Upyq_ob)$>y47Ja) z)(?VCpZ%6~tPSOOCZQso*+;%<+F);5jHW68-5*mIb44iIJd~|ENsVR?eU-!N#c%25D}kVagw9^1K~Ya}Z)yMPq4AVJ3R zUve^?I+Ao;xi2b2HDr7B_4Zw|(au-eg_CkzG`l)_Zt?L07Gifa*G;$VH2xNLePTJ> zfHTGG{6q?CbfOz~>Fzh{h5>zl3-*9sR?~TTu=dDTzwXBFx^rw>MenS{b9+3`%t*LoJh;r1LHf3Szd2J z4<=moXqo1_YV3{h&v+JQY&1fp4SI1A$>T*;3|^Gu^)F3pl}8@RWcGZCS~BuY$Ep5h zxG-H@ShQZTCn6|H3R4~S{9P6BQA2mKPIB(tdjdd|@ZzqDmMK`!g*UKGW6cVpHcyRT zh+qlu}soyF-!Q9>;>dQY+h3SM6LtOTqm6cT83gdAD zs|TD>ArSm+w6p@kovfSachf5`WW%;vO$)nCZ*zk@mkec00g;#$)}a6|O!;BpJ7R)v z^E`mc9KHMOg13?$`GEhtu4W~DE$Wf_53>{h0xL75QZ?e>tRUx0O*=wW?B9h)3*vug zP>i{DOReZPxc)^oXXvY3W9esh8hqRzQHLGaIh0yu{8Zw9*g*O~Z;J$#25Q*}4jgu? z_EW7wt|KS<@f9`K1Ec@~`x9wx^yu}Q3$y2+WKS<{?AD*<(oD^o=*)@q3k|RMh!U_7 z4-uOHHJLZpIh*dE{+D{JlDOPz6yq?_>6-S@P?Bz`hC&I0c;Dxhb9tbmWV@Aw`{8pSdRiekm*Q06A|ha{Whj& zw@%E(fNK72$2cN;7%&H59FlT2N91W}T#}s#>lMrmi8!gJ*lWqVX-;bIx0cQ;k4;2U zO;I$x;fDG$a@0;19wZ_!@{-hQ$}lYh&x?{WH*J1RX}9LLMyi6UrjoY2A&)c= z`?PHxFV|48PSE)i{IxYKbQZE`&nl{jb9^;=j+WNN5svduI13|bh7xNpEiF4F!xZXEdU7q>d_9AF8A#EMo23)fue?6#C5t4wn(Fkn#)Pg=ci7qRrDgC?ML3@!$BdM zSFU^{Y^H!hz-0E6hze6bAn|1~4nP)cT+#P>#W}jOj~ZQN;>cNUJ({o7lnfwc8c7r* z@a*aq|HhwM_+Q$cd~Yh%SqdJ+$fxYeG|OEw3j%pMdP(F>a6gn>AEIbAK+@{42l~5^ zXv|uzZs|(j8!IcDi+l5m)8>yK4sHhZ`?&@|j(!t%YoDKS_c4EZdiQj4|6o90Ob9AS zn1A`T3-Usj$)Vd@hw704icU}#i(cGu*6DYa&tZZE{>H0;p`O z0teCGw&1j~k~OTcbJ?ChuZiL8)8t7BURk>@L@bvFxlN|BXX1viz&AXa+-JXPDa_wI#yYR^d!hW3f!lImzjPJuIc%8n&tE+T$2K7GT*0t{U0+Lx`H%!DMLug$_are<*v^BJ~RvG} z@6c(4$$Sm23+FXNRT!W5V4hTkR`gl2{hFvs^G8moaDaN-dUf0iiM4yB6d@+HfE0$~ zuZP)LBwICog_nm`3{`KY2Y^f?>YNsiL zM%BG}VYFc@2s0TFtpKYFIEx>!tSl|K7zgji%GH$C=JM%HQq)pN#G;Tny$%z za4%~kaS5~kx$-;Ulnz9z2)bVIz6j|2Qv!|20egzp1Q{S6r~K{%88KXWHF< zmC{TtMgJF$moAo z+wO5-u)ixHZJ;sjfQ<%a`4Oz$ta9FN>S73&{N}w5_9ma`3LG5%oD2AG{bOEE?(DI$ zQ}d#g%D9MA)39y!qROx}9$3-7-J^JiUOThQ{n)r{Rvfoa3G)o94;=**I%+3`I3_M5X#FC_-3SWeMMrKlP($x z&e4l!-JYl%j>w{G>4Hq!ognr}>?+a35|F~RRoAT;JPN|e8ZFc>nr?N44g;Y%kCK;H zJbx7VF`2L_u-%njG=-ag~zB3Wzw`(HZ$os4uM!_`AJh$?L;H1H(# zDb(*{GEq#U7spO~R3S%X6SgwvlsXR&Nx%F*fH*uQMT3fdDLN3Fa{)$=PBN@~%Wb8w z`ogg3JHNcG*ACReK?7R!{%ykSV_^TondWrWC#UuntiwaxTqV?8{D>kdb!&l@s1UVM z-@kdw)p*Y)TY&D3?jUhiQ_bNJr_FPE?(oVUxF#ktDZCg%R&h+C<-Zj*;x{ajp=UFG z)WKZlQa{K;UWIkks7!VnyP?q3BB+7K!qzOjY(32bPi+eY2w;@DXeelmw?S@zXg>>d zaXwNIc4a*RWn7mwQ2HJs(HwN+pfTX|a>Q1{E5XenMY_@vpZ^&<&I( zcGNk!25T6bsiA|(q$W)-A8ip{@Eo4nc4g4MAmo3LV>%3q+zqL61Scz%FHyTEHb((E ztgV+KeU(!okbCE5|1f5G%|jMoWS(Apn?2->{r|=Z&x~286xoF7(-*Oq`K@-*XcO!3 zsn|wpK$@*=ZDWpj0%#-m-R23Mw*LpTKYNn4OK#)8Xv(u7O8FV-g0Vb1(7*Isd&sXt zR1&jI_sMS-t^xmAfXA)~*KC_kb1M%TC{y_AN#TDljiR>c+DNm9#5kR|+_l1ATli69 zt2KW%-CWA_T>C346#{ILu~|#NKGft4UJT&KR|W&L9KOey;uu!A9v}8O_Q#GaqU35e z?+fbiFe)9(Y}5@_U{etPFO^e3X>dDuQ(DKZ=g?2JE6m8fe&uECWn~$ak64E10C7{C zV4PShP>I4ALB*8@+wj4)&q&z_Ey8EWE;RZkfH7{_vNW^j{m2KS~VRN}NBtp5rTd zbY;%)scWCjon6DVP!jC!KYee}nTQ`3zubSj@4emS{E&pVw(m>jLVi~9>0NyD`9-K| z#EXggTfU!Iq(5oy8vWxwlKTe-4vHduP zIku-{zu2je$4sX&-8=eKRs(jmw<~|~tn3awhk|pfL^frxK@aM8wr;s;DN2Zw<*;;R zGpw(sR9AA3NswaFwnxt)M)J6~9PFm8uXLge;vsJLF}ww!y*bh*#8z@55jMOg8ug!` z|4%WB6=dQHDJ|VOiYev-q-pLn&VT%k`d8x0#erzJ&X7B6Wo6|{Qpxg>11hfYJTE3m z$$bWvNGJ9@S2ko&3Yr%_f}(VKg*$8Oy~j^Q>zY0rD|wWp9UxP;RO;{u?@*TeP1N?C zcQUCbE0LokqsY_3HWxL8oVSXZBaC zBg(&L`)q8u67>d1`WYE|cp!D&-q5#u&3ikWC~C^47Me>z+0@V(0ng7&nW*NI4woW}adguYo0WFyyo{!~#?GM&0@T|4+{bZc;0-@g6hn+nG~ zd$V^jilW!Cwc5ny>;p^JpAH$yIc1RB=M+qi{rO#o;lB9Jz5nuoPxfBA2>nL^djiLd zMlSBjV!ou4=fu=h2n!~p@9b~;KicUM9=}(zH9%N&s;MaQ$$}K-ZD`=TA1b#meVSSJ z%(Rf;(0>#0&xJJ*es_G2pXH1=(Gt}T0XC3wRa)?-F0 zM2@ZsNyGWB%jhDGQ|pdRNoU#9!?DC0r434xnK(s!;w(~B^U0qnd1`NRYF4G4iYT!e zLJuU*qZAacEfSTce@=9$xSqE7>INjQXAx>Ds(RoY;VADe&3C=Aq}1;II`{7t_&TI{ z*g+{j7TD*#vV)-gcc$#Iz2)1mEMD0-V$sh zX4Ln>JotZGl`bTIw@qcj?>I0aDZ%x)TCU2@lwNV{~+I zK1@-lUQ3pNGcqs9W3L_nl(y}(3hi0Xn)4A@v-RHN9Mgjwo2&PKr`O+$ryp)94-N%VY6fFgVsy%+A*z(S?~R zJ1i>GkIDb{Jm-mE*V_Be6%rBvZd%+}FyEWAELWq4;?7oR+-qbUqx&QxWRuR%Q>Aqv#MhDK)M*# zU(C1u_I+OQ`kKo^WOa#DTMs2QYCp}gaB)v+*E&OE{3C}2K;{Z97I$aDC7R~h+o@Lr zAP~2>xAxJlQOx5SUjK<$Z5zE0ogOH0yvi(6(*rC{{99UpARw#>5Z5>y+EBW@q_jNV z_j3M!?w!9-&Hcfb6cC9Sj0EKTx;yM6-*>+77(H@!=Jf5JBp=%uONEG!?~*NSV_R-R z-!Kcx*VUxiLiNzZ1BMIWmlLX5*FJ;d*O|^A6cth5M_xAxVkNt_+&EZE*Uhgwo_@%6o-;l37mU~@b> zk`KvBKgR#wP=$uoznQQ{ON#kf-ORetwLwofh?mZcW`crA7c_jO&pT6r^ITY^+2pr3 z7R8>$)vi+s^~0E1kkyzB)oXu#!KISKr*I0UXJs%7Pn`y5q;GG#TWhI)3{KKC1bH?F zt5>h4@+hjy&V(9ZH5mF0?fV7BO`mvst=}0EODD2CTBglgc?aL;7?&Iq;~F^m&~V{z zGR#mE?dzNDB+PJ*_BAq^dPnVg_{Vx`Eo5<_OXHp|v3d-!hB|j-c$d2so z2FRgW*9_1!aUK>n$T~f71NkafoX<>di-m;+9Vun|m}Or<3L{-3MW>oKByRoeJ$+ke z)ktjES7IQ5GTe`Qw>&*_F)ju-lPAPP-g<#tkmHwq!I|0UTun+f2F*@fbrM~twA>X? zho0%uAaeRDwrlBGb@HB-1sbGsl^TtkhgD+k{Xm&m($LtbCwO8C8M$i^9Bc(1sZ8jm zQ*cmFi}zr!B4W;rPk*4*@U*)Ja6>gpi8u818Qj1_P3%ox0aZZ7zo~rEKMVc*jt+i6 zp5u0_pTcMZ{)<5^GYgUpW1iOaFB$m8yg_FdhLh(}!N}z#xTw7|UG=%Pts+0o?%iN_ zzQn-a?D~Npx+g9Um#OU)IAPWDX*}~}HFG85D3B=hp4Fr_s3plRwpzbJn83Gt-x-NS zl!JXj3YTZmlYTk5sGyQ-wKtWjLP%zEihGwo(8Ps=vqGNvFgQvJX#c_UwNg$0dYK%G z&(B?3k}#8#Uj$Yip)d@Iu?3~wqN1V}U>xsLTX88n41H~_QyrMh2m5rjQguI=JXOkw z)O)(;l<{}9kx#1n?OlX62lr0c`v`Y9cTxr9-6FbE`7Y|dF4~|KVYRhzW^sn*hiA22 zefMs@{4*yyv_&ff`w~LYL>>>*^H%0+zxERU`d<<^Q)@Tvm#&T|O2EJsmre;c7@T8_X$Kjf#&CAPt;W@I%&Q#8o;p<~q2?^SfJ;uJ04u*1@eS zXg8pafRw3QABFYbe{DgfE9499M1FKlJZ<6&PAncA>97HSFy!0o~| zDEjy|yh*RueqgzTF>>2*cCh276r$;hVe=##<4NBuWND$$Ne}kn)Q*l0F>!Zd!BRe- zf281s`{L}lbH@g}pg)A$Eg&*Kyx(6Bn@SV27eX+HZiSHi&m|>ST0CYn?`6GikoYD=y5Dxi z$Hbg1PjR2)b{mP-94m=G9?0 zR&@OCJKa!;jTaRYGv9SIa}h_|2qXf$gfS&7PvXIz)mp#C{Cz6e`gCfaean>qWS1SG z9Z1e$&|J~E32~;+vj87fBYAsZN!iyLs7flc!zrmu?a8v|-Mu!+ z^m)(i(SvSeir~Vn5vX5@HA&1O)o`)_lzL70Vz=vN#m)deo2}5x zUanyYY-?CLeUB+vz+(>`%91WC`)N6nk<1y+wauX5h4vWw-j_VK-ikfeVrkqz{^29* zG`;MC!otjq(~~V=9_RxI`i8yKuZDdt`l*OBVBty`49t;9a2v%DIjYI?Gw#?=epbex z^D`NjTe8)qR)Jds+)IH7chna6oT#dT7sBIgu&ACpH#o=!eVOsg-YvF6sq(4+3@T4U z=_2*{ID&(h1P~S8cko@hd-LYad<(bEUq=7w;3v5eUr;wYrdpf_GcX*54a~-?6Ey!y zqNXjCCIdT83932|O`;N?eT?i^Nl8OZc^0*`LArq4)#K44qY)1^VvfQ*JLe7E$zn+% zu96egLNVd>Tb`cY85o?uZ3Xawh!e~~9g<0eyFx{n4*^m5mUIMPU9~!m!m77HbF#4! z&5?2b{3K?D0wpW2sx9pA4aR{ z-kG4Ij5eGQVFcfhoKi9ICCHaeVvE?M^}?_z*FKs}gI|Am66;cH6tmrr)b9t-?_>@g zc$8h#n!=hB930sspi7|#@g3Jk9|~XF2RnQYi^t{22T17Z-?G72T%CffJQ>D7ql>-n zGxGMW6+7eS*b|%8U5821A>&9Y$W>1~R$)nkmLM|#)Q?Pu5V#?yaqP%$U8L_Ehy0>o z#izZCN#%0rqI0tTU^6DNr?ZX!8eqJ0eVK!otmhYmzV9Wn9aJP$X>XHg@YD6-KPW1r zqCvrc89+O!hFgX$IFHg2kREn^t&!_ey8kmD*4}?+YvB((Ap+FosW!G>9WqcToZpKh z`y3T1oJP!*LHJuj5BF;VIvJCjr>4<7cK6>^qggtNj*LajVP@_*6E+)qeSN9(m7VdC z9gC2-j&h-0qY?aeuT;=mEyOKYK-ot7uTQ0hl6|OrI4yc0Y2{yGxeo+Z47elGL;8Md zUpGY)3wEczI5NVu60Fn!?I77qkaX45o74FxoTE~0X=Pd|m);BhVj?c|vUzR1*9I8n zr1!GI*Oy9=sTVU<5cK_7G3boxzVo4wul6?(7b>rwLFiXCYJ9YRsZUtZcMy{7i%|*k z<>y0a(wY8(F+5#JYy0Aj@g;oWiw@kxpP56l_Mi3yUi%d~UX4J@U09O}p*hWcV_Egd z`rMn2&{oVKb@LzZxK3YzJ5iM=$%2zGR2dwSYhvhaVkFfT7u)YKcd(oXl07>3iZHVEcUPt$Q~MJBmbfh?WJ>NVd*suzl0u z6p99B`!AKM`}75|0_p3}z97+!5a%mL-khK12x^wFF`_p{|D}={!@;z$WG3d)n?T?X zQ`Ry|*Mx+O2pRU0LSj<%qjgP1tE>VTMfigQ{qK!rr_?|cg=~IuRM<1LNnv|Tz3^@Z zH9tCpIp_?xd?OUN7gB;&NC-Qes&lg_x&-0Cd))LzlCY*T$aE2hxu>JCx+$^3p9*^j zMa;m5!iu{IC?d9JzbavQCG%{-QJi+YS;s~^j>AO$9Cuv=s( zw?qwOECAE9MiVs#w@@6T_BvH>Wku(!^qdL@H+w`#twfijp!aXa98Do2p^2eCnOw!1 zVTQ4r!Zay*WicqQKzNWJrz#?ty)7p2{8PP}#mjc-f29WB={JD0Ep~BnA!LL^7cEeg zMnY*s*8O^|r*zx&q>f&__;>{TNX8D#r@DF~RIp8-Uf>J+o~HY63;naz+qG!m(qpjiR=ZEW& z^d?@GI>f>sf~Cx=D?>-qjkugxa@!v})9xYpMk0!n9wAi^7C>wQ&p%8f9sk4Y&6>b~ zOLi;9GMo?>c~`zE*>JopYTjI6CkND%$&?!R^TM<(1zfixUrgV?{5h zI~|{=!XlQMV6PnK5*$i1EJ1{=dEEmQ|ggZE2KXD>djf6G;2lyedp5rD@gK?~X<}=(0U&?7FQ6qdM=XwWV z`#hBH!xttYj^#f-UKgdJIg;syeBl?%+{B|LiQNX3KSBlv;EnoIQvgy*r&1SI+t*rw z^;)Br8WFYl>1X<(aOa=KtKW6l3=c!KmkghoF+nVSrD^>pAkZzP&StDi2fWEowhazJ zKlr|b44OePFr`hYaFTi_QE(fSI+F&JoF%e|sa&m+L~rnt91Yyn_V4fSj+Eq}bCf6# z9zT|ZorZ??p`}xkp8UvGI&o|_>yjm~JoXDC)u@kz~5PN^tTL@pJczYtoJ8SFgxas8g~3ei~o6yIxihv86BxjRf%Nht#zh^r94F6?IA zDCXI`z5Jb#fC<-6PULy7If$+Hy&i^$`=<=^LA(+93TmbXE4?X$Jg2`|s;NS>o$hWu zHe2eh1>GVZj=Z`c8*(hMHd*z~MQ_1B@At~B09z+KRq5x3viXCHTT zBAc^VKW9D{{v40Wjq#*cGFLLL9m>;gg`%qxy9cS#0$D}}=c@R7boSv@aOT`HS^C2v zDf^~E?Op!kd!UX8t%XTl7Xmz_*?xd9m%<1k&&DGyp?I(|UFCH;eS_mN*J{}&By|4g z47{;%nY^s228Tx=vq(l6u3Hk=u5@|=u;`Q8sMhqj9$BHYi+G$UCgPIpS{lj5Z{=p} z@#%bK?`|Ql;0UdgEILFpskVr+x)xZ7tJ3MC`Z8mz3l@PisML0Z7tp~&J5p={<^3hq_PVWuH9=KD5p%{;gQ;i)8hI*Qk*^Z zkthiz(+9HZV9PYi87-BV-t)=#uwCRs0kmazo;q<7k#RhOEyf)k9*Z2KdM+yz0Gwl(= zzu$9hCAB5|vysXaGS2L+wFl?w6RYJ4_(AGUsM*rw<5xF(yvUt)VB(kXY`v@Vk~~yy zKLO5?2gQd$1M1{i!9Gv^tQvfkb=Pr-(7Rp@R~MiItm;I^%3Bg`6NA#HN+)u3N6yym zs2It#2fYbup8N(1eL@mDP;!}VnT@K?jU7qXPF;|Z&Cy$MmyWX9fc7*&C`ZRsFCt%8 za@uo!8Nuhgj!?20U5eF)TU{3`+ip%Hy#8dD2o(J9Ot7A}(8O9o$^SMVDY_yjI<`JL z9>pd4!UcM$x{XGMEKcrUoU{*}aDFA7&tgI!+h5I{GH;=xrEoOr3c=U!oryXeA?Ng2 z_M(_73F6GJ?1V8I{||%>wR+ zcOXv}RW_6u0dXz6dAg96Q!#()`COgeUhpfT_c<5{OB&YTZX{*sKEeKcAlp~uLVGeJ zc@7~3gmU)-D}*Pq&fF2|KiFik*{|tiipGi%&=tF9y4-uR1A_9ynT^a77D8c^gvQY` zA3s4j$m=aL!hE#cg#%YASVVO_kcj~P^*~XA9 zy+Pi85G9;-i-(L%YH_?mMpZjl)k2ZW#o*`a2iOq#Y}u^R$hG_X^6~p)z4*Hr1LQ+vOFbpbN+#J?j~OXmH4J%2{YrXGZnEZIz*-alk% zD6OzXgFtI1mpwbJ$Z0;5q@M$_5J`Qf_L5mKLFtd1DaW_}{h8HvAdb|51DU7UPWQv1y zZ^d_fH(MW*U6Tnz%sKOOBl@u%KTN`&4^poAitAg#WYRwIrjMr|Ls)O-%;>`H=N6yH zK{D-IKXc2H0iz2cmb|n}x)NPv_-H5eP|gpI~}EApLFA3KnQPBXtIk;+Qm% zMHnmIHPKx!IY;j`%3oPbNIXkl3B|z;)u{0C=Pi40+7g(X^e%PqCXJ?UC;sf@4v zbsnFFfK$7<;M^(2IxD$s0t9EL=|x za^3b33v5=LyL?t_FQBY2m<9yGDtBD2BA;h<92~=x`#E5H_V_=AVa-IiqwkO7Tq!N5s=W0YC^t&(&zpN=3Qi)2fDR5rl=9rNMxy?H`7ZCxNeG`rzyFr`=PHgLhXO9;~ta>$$AMQD;d@?xbI0h0f~jLx}w0oZ$HwAR}$ ztjN-imB7IMg>_$2n~ zUVJ$0M&mFp{BA{y$~9vi_0k3q+n>$2`hlN@GL0v`TM){(I`O#ZHc!^^JL01cRXl6c zWto}z$`)rl0)8B+V{;en1zi*_PFts;t~HnW*x6icb?UA(zz1_GA{SC z1C1$~q7VTyL0TTN%E4(v?!nHJN&aG+(vQAf?ZvXPZgR@gxGzmvvf<;FB;H5lxh)z@ zKI||NA_#U3!A4HJcY3Y(pnG?)_@2qSx)-;C$L$T?yl$!~@1LYk5T1O85 z0F_PI2iKxlIOx6YBU=gA=v5iy|2&Wj`k?uX?XWqLSS>|bUrziISOm&c zJM?N}RpdE(8!*VOIp7=c+~uTN1LXe-JSkpnw^}@qV|0#1v*fPDW!K52V0_nAX+{L@ zz@ZNbI0YsCM|b`p)Hw524cU{rA>@h}` zCW|hv*MEXfrGvV0oa^n#_;6Wj6Y)&Bb-HG#Jp9PdQC<|A4*CH!#Pec@;;qTsA7PSL zJh$N=i6y#}jYMPK1nij*8<(@?!3VQ;#}RhT`by{la2k=?9G3itYpcljXU9Y8KyS^T z;yX4jBDVSCPf9kS+E3(q9VE*sfxdA#Lu8==*!j!ZXOJ5>9z+@;8uVRN@8sC)VZCe@>F8bVJH zqBBDQbyxAnGAa|^Ew6FRz}py67JhC1d1BG0%5R{3K!IlU&fPv>#5lC477^DpKmmg7 zqxF%ix9PITQqU`Z`^+?ZQQ@D{3s=dkx26$nEAACARg|gVG=~+jQ9JtIupC zhq&(D7$T#(D}1Hv7MjJ2H%cAkyJj_-kheiZpD8xAtShaw)?uJewMVhEtldHMdQ4{G z+qxm>hPT_@H5r7?w2AbWLclTI&>uA5xdVz$()bG5wBR@~!(PCuDDF}p(G0@FX)-g> z`qBrN5K9usb-L>V(?cE*erD<_-IQPq$nKBR1O)s1qx+H~6b$i_063?~!Z}xOWdn<( zZ(2X)%SOX_FN3N=RNuq>%?yu&N0_&{Vy#eab0BC$Rq2_H>o{5u(-+xF@)BrLQBh8+ zTiT1h(S)q8(D?(VLh9Ye;nj+FTOGkUMd6qcmJiZLrD3zxS%{Mb%i-+I-@|1OI4>ri zs9wq-7naA?c15x4Op-hrsA2M`A76vR-^z;a82p+-S5KUV8xiUz?OqOB@2cEHve<%W z6?cZ@n{%uLL7H%~@!7MH6C7vc-mK(ccls&M2(gIdx}G+#?nEozq^G3l|FscczUTMV z=k808-@mD+qX!oOdcR)^U#3*Xp@HBrt27TzS4`<$vVCwMo=hr0HG|yl^0E-#_0x7z zOR#+xaVEUE9%fT-W;RvdgPL>Y_GKrnKH~fEbLgM%%ye?H^`0PfrZ0U3)LqASDhmgL zg8(R{<_L--xuv!oyQ?UN6Y_I1^$!9HV0y4a24f`}OCHC9QlT<1@+hx7w}8SeJiV@r zpEv#i<9Uf{${fG9nJ~M=jKOz!p+Au^t-nyT8-5XOZ1TU$k6;0GLATk!D<@@6 zwK(rwtzrGSEIbv(z>~!CQ#OG3N}B04IV?K)ty2O1NJp+iJw@^8Vq$uDq#8aJZL|)( zyBU6kF6fYd+;a{*Y4~J(^?4TYk}hM;y!*bQp(PkMTs$|eRpZZlECKe)pHh(ze60BB z{5ZPTqGJpcnBC8wvM*mjd=z4_cZMZTD47hrIii*qPeVwRQX73^bNRGpq6@mJ%0Fk3 zxifW?5)|&OVqgDlAor2eIYq2$g=j)u*fJwG`cIxMnpW!>Au6tuT%H_=LlvbC)~YIg zf-`wbAi4Q*a+HR{a$7a?Bj_Kx45HC{`4BdJUqEzV$8+IeEWMXH|L*!}!V8Jsj6SmZ zf3^Vz;``n?>+N_8u}o^c9m)5Xf8iQHl|pt?tG;u!b0gvHzdQp=UnY2+X>BI^4B(br zYu;|k<$uyhOGfm>v)*o=pG7(2&MU9_r9z07(T@svD z%jKsKrTvLI;H!8UX+CUF6vA&=(Qi-`OMFa}CPo1@kgeYP6?439^zW=~;STa0R zW9#tUt`cuATp?g%r5*HKki1nUAMiy~^$1&AY}!iv_0x_m`%elge$xlQEH`!5d@j-> zimyC_+;cj&E^dUP;%8hQuq1}tH+{dhU^BU6e`_$<{%(v1C~G+557`- zCg9KNKO-9oL5METtTCwk(wpfm>3RItDwaQ$aFrgR>cHZ@)*pn@OEFNo(D-;QndK4I zi`5!t$VphRRG5*2p?7(2;J^0WcQZS*H;Dh^<134}T0l{^Q>S0HuyZXadhhWO(s(Zs zd|l3N_Rc+?4_bNMfzi-R9mf&bb z@LgY_1mZ*`$%U4f?jogal|d!V{*R}c(GH!{8wM5;f>tVa+D!1qZpQ{5kDN2@Ff$vc z$;0wpx9OMD>{lyo27#gaGkKI{%isO25Ap98Xs~NiTIDayPMyEJRfDl;CycAj%-J40 z(?A|TFGzR3yH!xR39Z+G&upUDc*6JSl?4t*!B~0{GOa4DLzKARUn@AYCtydK!x$_W zgnE+F0Mq(unj)69_^(e^{IyEm2iVu%(G%k~~Gry~Dv7|pV#!pDS#Dzw*WxY?hEkbaeVmdZHv6z_b zvyB1CBVz%6Zo?=&the#){P5T%*wWdVx_(W3*|F0ztuOX)d%Cxccvzq2gr}Um8Nq^e zcF*dsa~r?Zcw!;m8P{$v$T&)#qNpZWxNISz@^MuM{tn!edPBS4>3;s9+t#ji};^EN#4dQ{v0wvma^QB`ga=(t|6 zH!hsw;NZZ#fXIO-21Fs`zai4i6leqyZ51eF;i>zI1*7G)Y$~?e0OM*oN>(5q$fm67^rS1 zTUYG&tZGx|SyJF1v5O^(zqR^z(z2%}#~2CYf7mXh{CT6Gq=Xq`<1quS>-D8;$>^k@ zpdbU6=V4)7A|fIr13q&0L16gsXgrXr4(H#LV8T0aL=*ni`<_f`g%_NXQ+<+8qoShf zB!@8S12a-2*4mrk^{7POgS_`^0pAYULlj?u!A6ACGHt4`my38tKdmLC(ngA>{24pn zX*S$-xSx6B#rL76Qns_84Uok>B*xmx>OB%|U>0EHUUaf~E|2u;Bm)Mf62o{Agw15G(ypolqPM4M|A{iA2c|AV8pasYS?&&OlRIdc4ESB<{u5q6+B3TUdnFt$?3#N0gfv z1gb_wKCTP0gX{15%^OB!F#)Y*XM9-}!~iJ=$DIU{%hecnCN}=#omyHq@LDk;fDCWy z$zUxA!%*u6=_U3_0NtUt3~M#6aqqQyHxjcxyZAHhojO<8?jmUCXJA?K#FsYZG};v_EWLuZ3qJ;f9S>i_qPQrKmm7lgG~1OU+aT8snXmN` zz;240PrtchiGkZGDJjaqXwqL`2aAGyl2I^l1KX?$|(~AII<$uqDI+8 zf&O*4JX>N7M!90lgj_`*mFz~dQf@L!I~tVy-C%GCqe%?;{1O0zeVnYt&O<9*dVe8Tcm|Iyt}F9%Np zK2=H%7mqbWxMc&tjRhmT*`ejYURK$hCpOVvgt@o4V$udHuK?TT82c3F1%9p&#EMt= z0&+1ANFE`eLh$2I*}0|xZ=8W+j{nATj!~g9BtHX$GV<_{@EVBh!R)*wT59l-`Wef^ z2%SSZh84rMIL@rWbYK?CA9Wx-RpAl;{C#k!`bJs(t;C6q&J+DN(ntEvN~UczpB#wm zxpQdH^_Ijw-XqIat$?FM;PcaK3Geq1tKERKb{M#W5x@eZO!nyKfn$M=Nf<@a;GRn*6w}Lt{24hSl zvU34|nP6U1*$ul75cqxj+lG);NF+BE)}sRV#eA(Oi2?}Nbf4M_+x6)R?=DD z+HqtsoBh-ug!iEZ8B&Lk-BK6guQ1XZxv@IZrzUAr>XIxQ>LDr1Z3x*K5FP|>Y`tno z7fKuO@;;<>$vbRe(XH@u1w^}GLUSP7+00lsh9R}%5D#Zku^U4sAp`LK9`q1W*kfA> z%EO)uEHHR|ia$};hu@urrJRu|f*bz*TFMN;gQqyHc%(WDB* zb%jV=pD9;&iye0jJe}o9Y9M5E^KdRUE4Zxiy0VHrb8$SZIP_k4Cx2>W)+-{eI z3P4KUcT>8F)vd{X-TGjSI7`hXzF^_)0K><{8c;sIX>S3v3ku~^c)*|AedTbJWA!8k zA{5oEa}mG^kYeZ-z(1mZ77D)9T*SMKhI6-~BK!{lGA%*BHTmX19LJI6Mn}i@Y9`u- zDS@FJ4`+xU>Q2`0I$K-a)S^xrsD8;11Nw0?Tu_^T&8^)4tc%QZ0C|EIKu~#0XXlI2 zH`rdi4}Cx`wM^lWDb~=a^*DEPawt20p$F^f<4}PJ+E2aU^7{G`NZ`wx{XN)(&MSS) zsDZFngO?j1OdmC5WZoDgh2{q}V{7jO*2gPg3W&@@&0T!N$zlj{52$*0k|u=Iqz8N9 z!(l_RShzv?`Vv#zNo1Q=CGh?wN7n^L1Gj?{03#wki$WH_{jjg)c((3%xC|So{zy@W zUgu)3DXt^V?pTTZTpD}PWxU%~5a}tHo{m!y%AIV3U8VimbQ8QfPeg6b3D#9605DX!&-B3CKSpZ)Og~ zhP?f52OgEbRJMy%!~YT=5~IE1cIZp!O|*4%$&c@SX*zL?82%U^*zjr0FMCRJbOCSVA$Vc2DH?;6Pg;W@E-}9T06w& z^lbohID$&b6mlMv{yf=r=q3Gi8Y0{R&zgNzkIU+K?CqqHT*KCCh*dPfTTS6u{CxZR0?C zjxouxdZUo#2JC`mM&{ridecju_$fhg&I#`ZyBcY}PTF7UZ1PY1`mwlc1zdpMvncpu zm+Tn`DC`07?tPBSNIV2T0|Rc6roetW(IH(}d|*PRy17eqsR5yu za9-Zf$~vv*bA|4!z3a;xUHTd|6)l`oZ()ytKlJeuw=)lFVRWCRPF`uZIGIVS_?9I* z&CD^f@5fr&kw=Bqs;(BF#W-I8PbS8IEVIV|UJD3tH^{~iWZ3BLoH$I|2lQ}$X%b+C z6q~e|c)m48Q=9cr;TKl6v+eGhE^$1*rzxi$8gBTyK5{LY6k6f(QYUpYwn0^Xd$wV} zb!a)waQd6Sliv-c9#a2KbQ;ve60$h^h}XI}r@w z*fIzO46f+_eoe-SVt04TS9u( zBWeuCWn^TmtgP;FY$nE!Ac7p(#Ut|KfXz*4q7M;fV1}v$2am=<0YQ_=E?f|4@Z&Ab zv(8YzgtC-{#D)Dk)T3Rmi|3W5ETi1e^#Gh_;1B~P$YJzB3{4#-3vj>Ap*UpH0a8#$ zKQ@GUeXA#325#|>t;s&yKY0JrShw)^&JJ;A%0J-AWqFPC4q1@&@RR2Q2`76DQvDeI zh4o*>MRarSE2n4Ow-4O> zB){9i*48%rK5r27$&+;nwp+(iIrHRdkJ3fdY6oS|(20u1Q4X{^)QxE)Gk`%h#@|9p z#SPMz`!d$>#uisp3@tcv?AWNGWWRunOB;$)+gYCpI>P(ZKhqvfI$hx?o0KuX2XrKt z+@A*w3!WS%3C@MPFvK3B=na%k3{3m)Gy-u86t7O>wxc?JSe5(b{GQ&SU9OLLm?b6&&YF&6L?4ub=%PynUBQ+Q9F zCJ({M;o$j$T*x{XBZgL5rnSAg_Xn}7CA5x?u_X}?jKF<*vVBiv8w7&KST6>G8gnhj zue2LnAprRvMixunwpx3vVt=9Ox@koddg0^TON|@>9wg6Btj&Y zn|6B?yoe_wj))5jYe3f#e*yJ%@tv-&E<8QF$oUY8h!g;bt=yp=vs2U@fJGjdM-X}b zP8gJwR8|hfJl?q=!^!$omtv4cC2+PjfX(F4)`u~&Fw2uSBrS}M-GTNcR6=sV5JJ2y zDw9(qBDNp7&2j>aKFXUOkX|!Y>4yWJkA_R%1)ZCsA?^vqvh;kkUFLP-5c@+K?|TBv z2~M+GA;QMIB|pZMrM$KX@iXBkCT{WV6S9@wGTd8SSjhPF2t&l*v7@D{tBkc4SU=Ty z*~3{`SEaou4JGz%F<~d9D&JTT9o3a}Vr-JmZ9OzKh-C88 zTM=0O@|BpXF%gZn7-tyPIcNZW^n(oqz zxVXKLM}!$k?ml@!?x|DNFaefugfdjs5E<>eI(2?&NlAj;<&o=tz*qNNn>_ml4aoGzsOmzr?8@8U0SG+jot+wrnatKQXdLi9%uRsM({3o zI_B`urbWA;vi_bk$~|jdm);GA;q})KGA~(oO(eChJm_s@md9()VBbF-6^#lOts&@m zVcZk#?d|LPixj<(iMt~SyfZ+Es`+Lpt@}%OZ2#-muipdfN)Fw{xIc&?fovc;QXvnL zA5Ml1uCc)XFzAX`94C>tFpNSd`ba;Fng16Q;IKhN>B z8*iIhqK;s%rXS;%JRFp#Q@j-GrIWXmBbb83TWtvQ4Ke7lOM~+x-z30dkFnb#7!1e= zgAN?7aLCcDRURA#I)Xsly+}U-sWE0sW=RsKV<8j@i6rj}R?fic`RGl~4^{B0NLfSc zlaYMgU&ul`xPjz8L6_7ro=A_k|HkL|@he(Sg6|L0G@Y`!J$EGZ%AabT+Gi3}(@ICF zi_1%zE$`yUcfV|4%qnkATFRHi$(Pdd1j-8nHSC)<38Q>CLRHReQgWhI(SSUE4gyZ3 zxQU)R3`B_iHji~W^k10*N1rEiCEOQL=^`BK|4a?FcY%W!Y-$&-kQ8Mw$nBS_0eUfl zc~pH59FDinKR|!@@n^Y@NNv&@7OY@42`ta|(wsAB=%rtsI&MY^{&Yo=hF*hzE~5Cz z?%i1}n_^$MRM2IxC9T0b@wR;DBv>O}#IF2&B<;+8D13R8-4@d5Vmh`5P)!+-@&Z~G zj;N5zR?E0=$hsRL81czylutk5G2)dsSF|)Q-B=Q+YG^wkN~~S7%5c4eaIUy>dSo3N zL9v3NXE1?NJ0|FbA(^}uMba>Q5h%OY=?)w_>+SR_+JVGQ!K@2t?0nN|)y=4-!>PpU z=sFuhfhSEOIliPsMT1C+Pj0oCTvu4gq{8Ltu2IC5sVM0n?da4*bHa4ZW*XuG6X|eb zL~5{ymRaixsx&7h%?%+92j(W*C%_Ohr4$6XWptT|rcFX#W-(tob)ftK8Q>Q^Po8JU zlP}o@sR1|yG3wn|s|Rjl-x|&XD}w(i>I!?4yJSH|-PHTX=ucJ&hfu}S>(03C=Uhv= z7&>1UJxNVX?MU)b5ZR94kR#wxKH^*A1^C{3ombufMC%H;2_q%CfwJl3;3xvjAyund zFkCjwJe2;96WLmnzVJ9vJ0eNV@GL>8?zus~?;g5o0q*rAE-ntz|3Dg5go={Z{>ihL z`->dS-IxX_N}?N(zB$^GkYOZBg7k7t7v37M?|CnAF+j`dSSXW)_8~21E5h82^a!z8 zT#5AZL=EB=cg*@dJWE|#zBkHAWw)Ocdoxu~4Ne{U^kRGSP67!$! zJoPu{jTLzp?mYH%YTUfR4VWf7`bQxGR=xAkonz5A`#ZeaKqh zN!vo~EDk(nXbT~?E_raN4fg=WX$b5XtDBlco`MQX@OT+-Z7#XTHJL;Gf4cS zOWa1@`i)Ry1H+1N6A&bv>Hc-f;y*HI8=$GTz;g~ecQtrIo+@$Qn`j1Hbo8e)$PmYL zD>F#D4tPosINe8SYRMBvS0QkGv*(M=j%0C`WQV{u9h@I=< z)={YT2PGvQU1A{Cpf{HqWXl7^IwoByhZOI7BBL!4`V3qb4`cN(fz_}dpv~R8rjS_z zVYYeVLuV>1>m~;ipDMLRq7!K55fE@L&i8+-?ob~bxbOU_j#9yW*WG(x#L3`gA~@z1 z(x5ivx5K1{6_zltwqnp_1h(GhF%esxi&g(bSJ9s)>k;w?Y5VmMzm_honaBrW|>y+ZL=yxVb5rJc3$#cBsY0UQ=vNN`%< z89yUX817auMFqLNA;Dq;z~^$qBV8v3tN4+-<#SWi4KV7+%)!GM^b$%ocN$XbCd`ql z7zJwoNTbiwo+kT z;p{Oryvo8&FHAvppNzZ4w;P2OFKFQu5AMn!dmy72V^`tv)dd#gb*gdiFnQKRny;>| zVAxIc0484;^tZZAH5h2Ra6f>wMPyDK3hi=NxOFT#-TYrt#CMPLnyru1EZAFqA zI$+=mh=$G$PIOra>;sAHxZD9Cwt5-K(G!`MnZa1-N@=f$z5Q(F(41N(KVKQUw%<5i zOK;?sW<45Y6H!&0H$8E>V#1yzquH_7`I-4^TGgZUUrX1xG*7R>U9#iq+=*aI*=p&dO0l z9J_!@t_SY5h))v%0Ri;@ce6sGEtHnXYSJY={q3jizQ$SyL=tSdmJ*40li7GTQH*k+ z&CJ3<6H)q@ZyL$?!N>D{2v~b>0fXv$n9F()88^sF#l$lmzk{Xe?BZrx63_RTZ%Zdp zUAYP15#BN%i?oS#+}{WG$GBn!!uGZyQTPvX5qSblSvE;s1>R&mU{gR?FKRGwNp1yi zfF1yaUx6?AJ@6PcptNAR0#BgdfSn+Il05BAcY#v~uuHe#VjJ2HMh&D+N7B7%E`wCC z^M5{4!Ez@gnFAEnE>(JlogK0C{+BSFHY`0R3K6(d|~ zuMQGlEK1?|rm@Q>O`%<1yLEtWGJLZ3)-?$@Da*d?@ zaI#R^{e5uwKfwe6Rv)%n*v+;F0{ynDt-Svt{&0?Vwb5{*a^{+XmC)hd`?JOw23Kr^ z8QW;B&U^aAfI~tXxM#eN)%MOQhEOi8sA2PZQK338mXOdWxt{?@o#!`)A&e>Xw4e8f z;4%x3&YCo}bc+-8I)JYJr7G=Qwu%_Xo)XorDxTlfBd9BTjAw{9!4-ls8t){|*%^qC zZ};TlV>ln&e{OY}y&XSRoYzQ7z%j1%nvx<8_A1F1Q5fKq3`=27FE|af#9LqQLp_Vf^a%7`~lNB zUq)m#4COc|n%2LWkcRCgDHQz_rb#-y5A?s+ zoA0w$C`9uehhZh|{+Ks|`yMLaGuAq|3Hn#8X_{+`QvJ_Q6eC%Fc=EyA%h6S-MXkhd z#adQFT~Uta>+j?PN{=XI-csbNO#k)CZ^jjheq74@ENXA)@(lD?paz=LCm8naizu3! z(uW{q;KRJ`=3kVH=i_{w+hxULUIKAaoPP5=3sIE^UmTNFJIz74#XB+yXfBp$bkqNQ zC^uAi1WvB_3MDMaAXmT7Jei@~3oWHNg}cCiO2!3eW&NB9O~T(y_dA>?I7F)~AxK&K z&w}{BMuU{Hevq=Y%E_?L$8QBmoqb>|MeHhzt!%=IXp-VJelx+K3K~;=%+wVJXfraK z4t7n|LbTYK zSmHOQ@@i|cE7klQ7PypF@P{UZURVBFze7ozNy(@)WNpmK{ABKsbxizEHizGq{t&LN zr}n;}eCd-Tj0}uV{#v4|^i*iclk@Di615E$>ND{^S#UbzM6G5eZKt!a$>hp3iU>r3Cun`ern=Ux-|+-m z@h8R&Z@t;Y!7q;Sjyf?vL+ixbwSmisU2g-_ z<_aFM%P%h4?vYH`)cXY)eF3X`KBrd+C}<574~MBKGEXid{2S&86T#Rf&up=U-PY~9Z5J?SWb6Z;92?w^lTCzDt4$*`gwwUen+kCrwV9Sgpv1Mb7N zjF*stZuTKNeXz#4hq$N-ai1Bd;utUviTZ3QUdKsP8@oFa#O=LRoYX(Vf0ab-vbxPcp-UbVCtV`=IK{XC%=H@qZ3_0H@9ZSw!vFML?Y`ZII1*! z7MyjXgFq;(&(ySzDr`k1sC3(G<(zuM&zu|}7F*L@Ak2jhOAtiXgLyx5KJFqIGRzn< z2tx16FNHo*7yqZjdMxv%8J2rnV19p+cShM?wGx?d{?`3E@HdU}Rtgi6rTxLKAWci` z+B{F>Lu`8MA5?y_8dJHRUS#h2-@)3opvkIvr>Y<<)t%g>wp(4X@&_Rj>X(iq#fV)%1m_ zp}iQj`{oXuyc2P4b7zNWW4EoT?9ApJGIgJFD0_ED<~@xA-)&~aDqb7Sd{0+bg_oy@ z{W+UhS6ff6rXjw%&0h#C`RNmFlcy$pgR|1SOvj>{Z#4-ta7>M4TM)VZuSd289eT(auTi?th)no5(t+Xm{EX`Q~FYbLbq6AJ{zu+Buz z&V0n9p7?Lo*~xR49fvg&zYN!=*N&(D`)BP*6QXV~=Hg9@T+glVEWWJUFKcke3fTQd3Kgvt?i4f=FRXf#K%4bI0Rnpr*LXAwtH? z=)WIR7Ko%pJZnzG4La+Q$Go)>B=)ka%UrVa`-|t0n<*nHZq?kyOiGM@nz^Jk?M07C zI3CH)K&@t)7D6#gdrzZ7uAMyaG|oQ73fkXlBG@RJ48RCLvHZ2Qhffat5r@I+QpWT8 z2~CCj4Y<#Vo!5?dpJqD)+c0zDQ5h2)YFKRNeH3D^Q9}D!J1khxvD&z}Wd#I7Z<((N zm$dX33WDaS2jiq6_m_rNF0XC19y6lN==}WNP#0r0vDGG+%AvOquc_^R;I z2baU|2I7)++Z*}ygt;r+4Br-I+c@`Ani}m&;v#uRIA884l^^@w#HRWP5ki>|HJueS zUqa5@S3@PZnw}y6I#6ex*kN0%B&y9zxf!6XjK68Cg(h^<=INb&P;p0se^K`$*0nYc zFz~#j04c)Sn|(qkI6$FGo3;Wo0HuIyp4m~X@JQX(mg^ibygl`cm%%NZ?JP((JNr3q zCOMJo&y}X6S^pf_VqDIcz4w3Bn;T>BLy4HBCBJju+ebUXXaJ!sC6lf z)6LVe-QEc{cANaK9dwDzAEWP1<372;CEq4*NMn!W;Ms&-r#;+akHAQK&Nn5Dx%gjR zOZ1M25VKdwrgSXUIBnEmc z^Z~#QaH`KeP<~cUd|_A5*WCgvh}#T|bH3HNpD;jYM8q6> zvyPyg*!YVGX&0n{6%*Ku8Z(4*{`e$EZ`+z&^Cv4M^S9&k7RRKuf^*I`fvd>4t8@8E znEc;-q{??Ix^30@&>}WYA{vM1>bzbOamDLGXp+#lmO3CPJEsq%=1)!(m8HF?@|)55 z9vj`Z_h))X32=Ya?HEl(;vF@NfCc7m}xB* zv>+R(aeqE&njC%;H<+)_RqHY^nlyNSYORWkWnS0P%H8QD+>Y9sAjXudzs{~k$?EX} ze&;FK@v~hy?#`5{mzNws7RLm zJMZU}t0dD5^;!)R*h=UFA>wAkuf2UUzPH;+UlZO4e1ei`IIjgDU}x?HhRHI?NJni1 z5RsH+!rbZ6=@lx{>J0NRzvnbbXz%>DWahQsZN`iiz|Q-dA$nDIl$j`n6_G)h-uXEIaK{Nl5bPH@ zy;^?#?R%_ycXvOd0P$N%5l8vB&8WF$PH}iF>9PxQ{zxwoQxl$21??1>Z<>N}RYGSV znzoPO|7vJw*kZ6Qej`1`TzP%UdF|VbNjpJj{(R|lSVKb-eydMX@s#eaJrT{$K?;e7XUm3#r*hPlTbUNEPtdi+|n7c)Pe2PUo=N|Bi#!-Mbk zrPNHSCeurpmyNvG(!7A!l{jCm`{q2Ud|qt^%yOw+g}0sj__!xvPivBxH{;MFhwt?@jl0 z=uP8S$*JzNwcU(2CG0FaQmqagKdySl5L((f|0CZhkv&zd%u9(4wm%+OmKKb01;Blw zrO=6iIU@?>EbVJ>zdsBnzif8GT)hM)aIf8A+Kd-BWMTccmJ7~b{~GZ_wqu!_GI4o7 z)32JV^|ERcv|qsxsceDm(8@G$PK6-+nM)iDi#yjYBZPQjc7pCu`1Pa#(rSE*4ovSm zU=$R-GMgs?FN=1tz-FlrVT+z-bDZWxc#v3cVQxUcr>8<{9d8m)_!wj7ee0XU^CneP zEgG!~Qd3-;*R+gN?fvfb6ipAF%{gF`SYyY2KDdqB8NyL|g^7^#f5%Go<-Z4O%v~sS zU!VVGuwIq6GOQ$3fz-hS`JZKiS!2`7nAf%}pAb{T%bUd&zl`x6H5*%7%JfQ7p5Gb0 z7l1*8(R)3AUPeFWh#G^O{C4bNvrS1AO{+JmKl$`u0Q&p)&EExI{m8g)))VC*l%1eG z_41J|*dFGtIMNEg$gTS)JsY^goK$se8?((?Ymp?{W#3ZZ>U!b0zGaItWFb~=^uqOeKDhjztp zU-h=8GE1bAn)llLhE{$w$yKzJ$XGtkhPx4=xgL>r&}*5X)1^TdnaO#-nfo^{hYSTcI^mJBLdxo!)*#_;x@ zFV|=8``VTkt5#mTczM$;H#bH=`ccy7Yn;#9Ya;N3{2B;Ry!}1qFN;rXZ%{w~ETQOF6#;$|u$H~=&->V4C1v70&DR_IK>-+5?4PRuz+4P+xt}t#Grl){ zIA@%s24bUMKNWF<<1;JH{pYN?dIcH_WhS5r>NdYj;n1oa@E;ierX}D6tJer>WXLd3 zSV|C8^HoOEJq3PC(q;5(iKjpHIo`}m#g;HwqBe=OoU2X1KhT?t0}|3TuLBtm3tK}O z(A0+`-7|xRg>yP*ygko${0$yqNgeV_&%eihkQ0rnsyn(TY0HZvc5w@c4A1GnNNN$6 z<-+{nMh-x2cL7Z}Hr5EQ`n zAz%-wetS9$B}F{}S%TN#`&d09UFIC3bfiSvM>+?KP>qG&zy#X*`gcASns(O+Gbq3c3fYj6*`PhNv#YlZvjOg3cB#2vxQ$QB&W_ zFwyk^SU>eL-I)=?=M;|gBQsA%QjVM$`W`4Lah40lJuv7KQaiCD&?{>FBI;}4+K~$L z6QnMtlc+X7<(nrq2`g+98MF6}|=8JRy3g4U3AS|dnEK!Dl8 zz9>)^QpfkSsi%wd^v@Qb!Py%m);(xDcvQI3W6zj7&^9>0mA}~w2qr}$ZOjd?2WgTD z%o7dAb0N{?I*8`BbOa7!PZ;pe!;|fRvf7U{tpK#**K52J3-Xi%(G)(lNV5EF&ZzIQ z)!%yFSQIr!Ulny77#kpkG{oEQ)gG%X%Q`^Mp*lPUEb(X0SQQ+$geasewz}c0q|vsh zFeewl`avL+;d^s6|;2O6b%^d>R%{PWQ3T#=ls1)sw?K^^FYvQ&l8fQLM)MnrDC_z)qdWg$+H(Z!} zb|-daG+<&+aBX2Is#R*uh4|Bl9wG{6=HZSk;$K5dj!pPw$tc<>JTU@WCdmzz88g4* zx20hdZ|b_UA!WP3Gx&x2P#!dncm~@prK42I_dsDsZZR-_#ps=(+ueXqw*13~`X+RB z_#>$1wtjcGs$`gb8R&fjdxC&I-E{8DgrfAf>GR!@+gPNR#AwUy?hc@CKIA{A=T|m~ zfH^y-YRIRM2k$|s(7gAu6xV1N8CpBoJs#5Z=!L|6ls%xr#k!gTEglW_osV0m=ula7 zW8ZAF9={+@!uXnXM1AO=@qYy?&a%D!yTvbt`FJtOgQ7zcuDzgNs_ zq^~&}akBu8a|;vuz8xmcK~;Q?%`vX=*5^r`0{Rvy_OR=@x?-eV7V!fBMB>kkZZyCb zw*Y$BK!QJkVtYd-?FzA74YtTQ4I$~bF^eZ^hAUl{gGH|$oz>DT^cp8?HG;0f@(x&# z0msTUY&=rZXKX4AFt4Feon1wawjkDkfn`mA05$;Yz_R?S0SO+8Q9l+^Zx? zJsX$Q+A|jqU|PVoIcH{;&327d;_U-ry2fMKMYv(>6qhUg`6>~DyOThrK6h&7wXi#u zTs?7(Af{shU_aa_uPTYzMR5sWAWKqD7F*Q%*#${q{Uj#>t|$LV4_6yVH4Ag6duUNs zB|rpNAcm~qb$18!9f1zZjGow!W%4_(LZlz&wurI^o*wFxr5YxwHZ1z$h(-^XP~0-8 z^&|HP3$J_WP}BaTu3K@e7DAnLd+IX}1w>AY1S!0MC(TkIgC#tQ&7i>P)D5?qmoX z9md8o7(Mw`q30!D|6#M&ZG``mxf&4iiV2v(1i%?BgrwHifjEx9D$vbNkz3S5QPmy;&3S8PY>#oJs*m zX9L8~j=%24oFRzwy|B-HLgw0u0oV-oB2ha+%>i)h>FVa@7W6h1R7J!i%^f z$N~sapa)3$0t?3mwmZ#xr|3N~CH1sb1u?|C25hb_>1csn@`?z;o{KqO4p9 z(pzg`m!o;!u^X|dhn5TL|FJr>2zGmb*ScY#s(IQ#DH-&5<)5Y6yUd1dMR4&VVu>WS zr=e%x)i9Q(&5wlR{tq9rx4`W#_3_X3jD4F%BeyrOVl^5Va^Nqy?TZ-c9zZ(pNvY|2 z-JJ$eT3)yi4+Zc9q4>N-5HM!)X-nR5GTL>+)NpnW7(>Qcwy;RLhQHEFo@$#DQuz1Y zv;(XZJTS5BMoV<^9i&xRk14vM)<0Fn1U@C3$14EE&c<)|@mM{O4g?IQLAaYF;+q)^ z!`}ydv6>P}zfkaGxPEOq3noRx_|>AfV+cL3g}}~i$ouAN3b$6&$JMoEMIjNb%|Jj# zcVgM*XJze~!18cvfaP)_8iPRl?gf^cUgZ!fFpyOt%*=8qAi5T|MMbAJm7billY20@ zxvM`7;a-r1k{zI{>*}rI644qgjeF!f{s@ZL3}M0vHGLofD8Id9>%@J0e0B@OPq-L7 z^!ImNv~-Q?u2saYvfnH!z1lbC()}QkV1n&VA1ND1>(rLqByv4hNKHFGWry>@kLpmFAQJK@5Mx+n3mg?#eBjC zM|m?FA<_Ksay=x*IO?3Y@g_SXa96b30!iLdi*brL$*mL1&BPNXkc z;9mrK=%Hip#~#QT?NT{}iG?u(0-%yEL34RAm^dz1#AMo%f%LQu-rHu)VVyJ9qg6sL za-Wqjy(G{Fq4cM46zup$VL@v!o;S?tWr=Yn0P=k?!0_h2it7G^#5A)kTa0tvczm{? zjHC~?Kcb6vz@4Aa`yF6D^9ri!D13sG{f`?$@72>sON{DF_ObR{=Xczw4L1IAqu68< z;4JX~2($cHF651poNHmQsN+3L6&^ZSc4J8*m~Yd4M~weq(9WEC%;lh>AZ#G3^2I3| z_zYeL*V$B=y<0bHBT!xm$P&}e-c?1gkAIa!iiJDPb|renwW75>o``2RbnHgh8)Wxz z`eU_+7Z_Z}$3`F>+NQj|53#1Q5F9{#cKLO-1fR9F|7#&-V(cVZJZDePe%_7&*k~~C zeM=@U$OYu;#^d|6ANAZegpxoNuL0=ix?DIQQ=eivjjelwoO_g?&u&yrx4{gS#8B~d zbz=}=yb=?J+}u?#tnubb&+TqRch5CzD3&E0a79zI^5=|wo1uWP$QnWe6q7nmNjeO% z>KRz`T^z57Yu>b%cCU#0^{cxMEP7^tap#&=;Tx~_pJbAMA@BA`ZuP5Iub<1Cu9jCY zD%r;C+_F`gm)B^i*_K)!59Xb`<*WiqKWrALp17vOyHDSWdu{SZi46*G9@3iYlslxG zbdO9hGR7Ics=dj7z9)BFgV{ga#n{wTtStbNlBw#&W zwU{~F9*}$%7>z8WWecfj5kbPU>%`Om*by77zd-sNo?UZ14kg>vpEwN;eW&|sZwH#x z$nxN#$Vz^fk(^;TUfCC0V=OHqps*2eW~n++_BtWq8 z3xJGd0u&$O>Y2dKwJys9HX6t`;MaS}0oXTgIj22+x*4K;dFGml@i8lJPVMZOv~{0y z?3pU_f7ut81wE31@HwWAUYzTIpSh}*?1dHb*Y&?&G+>W*s2HgPAfdB;AD zDH}*&hRF(V#R!A(Hm`LP|8!3|n3xVX=U$n3k*HVxkyf`l|G+Clm!9CglT)niT7nA+ zDf@*PQfeB2mCMxRlXkx3#=BR*EO-KG4-fj_ksQ+_7YO)llaI{bH{0HR`l1tJj#3E=GH#Idakv}5+9`kF!VSQ)H z`TF;6h{;_dKfB_I?B@~Mr@7V%VO@iXT9+K3bLz~_#;X}@jcg@2GZ@Kae~%tLY0rh6Pp1-0HD1TZt6hkF zI|haed-9o>mX~KI+SHwDUB(7G@!Vg?aOOSic!1v#wReD_V3TmXat7pz`N6CpQ`+w3 zeBWbde#l8M4^E-FFcq-?A|~sCy^dK+2*3@)5LV6vG(^k+JIyTK^c=yYOJwdT0JNM* zXvVCN0J=pMBN;6RK&u{x^iUP&XH^#Et+5s9i@qec=GigADTLJnRoB$7o8@VLcLADu*Ca1x!8a7C5=8mW(M9}Mby2*I5 zuSwIYAn@@JM3#FHF#bkP$KP zo2*(@0N^x$p18s8xZ}pMb&O#_Hm5N|9pv-UYt9WSC@NZwsSTsgrb|qYmZfJwRu|89 zJIvw^Tl!95xBAqRJ!iP@UYH(kMuN6qMbxIl6?V2vU>cHpJM{Otcl9e=h7aKsZUsmi z^`TVW%V|kwSfB$p9F6yuNF9|2m<{BK*687XN+Na^N#Um&63j^1VyBO^D!Ubl30Id{h)SOE@`D*@N* ziX<1^6Kz0lBJMEw9@1>qV}?MGbo5_7Nlq44keujefsC!lu!d_ADVq>I**oG`F*V1~ zS2Fh?2X+fV*CGROt#v>J^?9zlYX5P*r_F-JOTosF^-|%P9SkDhLLdpRi5Cio&RRGG zF>%s|4PW-2_p&!=wZLY<#=Z8i%`8Hf}wP z6wngR{bG;btuvXy4_@YE+P$mfnS`6o{j4-|><1#BU(4a!x`OIc!2_^`U1XX6W4G0# zO2$Na4j=MIX&iu`59j6NGv6PTIOVolPWf@A0Ix7bUpQiJ2L)Qk_g2=8btlj;^t^g( zW_hl8dk-LDSd-<}WJ6sK=l9`@@YL|dlvhSnEK{#fg;)kW%gg}KTrOmIX=~8lGS6Ou<3U{O*Ec4kXT$tCx90oAN zelg6<&xaCFR0#9_pFe;8zDd1sB7m)LYt0Hc{T-cOJv&+Xm-&@{S%oe7<&T4xLTh3| zcb~0<0QV3O?w=JyP{0=>b5aqM9GhP{bPnh0mp|+Csn<^g1om#N1(FjUFd*g>Rs8V& zk>8ES7b8nl>}vBzPoK{($JZ+TJo!cD{5Hw2%lGzj)H3=@7iMG2JdsgSIUUfe;RV%l zNzbcYKjz-hfS^#R-$jUY2^ag%M_7ZZ(64`H?fY$6e11D>w7-xu_34+HDy*EI*uZ%c z`=RXMfCS|HUVXi=e#z^{_EnbD?L8;AZ&1C zC|L0C?M;qdZ$5m#v=tqwJc{!w-SRkw5AfiH*OEq543E6+8s1cUELT{3{X}KDjEsrO zgXeI8{wX5Qezq3`L9rDmEz9JsdD;-L^hRde7mLhFA)EJssY4qqJC8D0?{3=sSAE@$ zM47U6o#qf#A98+vCmL_JTyR^(!E5y}$SRxj*-}tcEEQC(jj0KGCAs z+z}BGL36+-3SCV6knETPI-<$FDKRlCjg5_02Y$BFReHdUj)^S2 zqxo|>X$HJ`WtxkJOGR1PY$eCmmoTwQx58@9utR!v9#{I8k(I&U$Ce|2|DQmtDdZ|H!sM6eV?%X*l8mtcV zWFG;MGRR0B-_~#4x>e>-anujUiyrc$$Nx`0>Kc#M+5GLDT&R|&fLWybLX(n`ELKfo z86nyQB{;|oIny@11cfM7Q#@Q$aVOMM_D)3hFfseocvjRm7L!?F<-sWQ*x6Tr(LE2p zZ18!E80+h+LgHVmJG3JI$F%1rmlDWT=PnxfjVaAyUwV)pzxqTDbfR|H(4|kVk7r5B z*H8NUF7p@eLchKdSaQF*`eOgx_mKtp|7#hxQF@ovUxbX387Ne_d`@gm{!JzGf)JG= zFjF9N?u$%f7TCgW$HmETWJris*Q*e0L$4*Jk`|D^9*R`&M*;?9`OM0}fNOIAkGNnl zc5WzhRu!ws_VbC}9+^!fxk3^;?2qB}sdw!R#OY8aX2)0Gxn|-`#PBqD8W1vi3QZdu zo6av^kOx#+7+R1+z;?w-)LcBK~vj_Vk8j6%&&^rU2|Cesm5y1l8MqI!mgJ~ ztT9AtTn&<5PRD!#0Wjq=LX(Jt+cjz?@+Gh92e}vAe5JNW>{lGm`do$75b@em@d714 zFG3KYBq9b2#4q$bsk0to3&RUgDGO@4w<)LW>&_`}thkM#vv(U)s<1HO98kb=!Kj(z zJ!2UIsRMmhR_ll4-V{^tols`cS5&qd1td>CU#>Ni>pGqlzkON#q&BE!M~abN)Y5v~ zIQm#>p#55Uz~O@DmnCv^G4x$T#mV9Mmv30F>M>v;L-5GE_`1~3fGezt!+*%C#Heih z-aQo~fFA7VIQ8_jFl$rplQV+EDZ|YeKP3~KJvD$SEzh+FcTG*nZX3TjM<4!(Y?V=n ztz3l-OMUGjZb}ts8b7auiBlKt`;wII2l^l3{%dW$cM}uWfPh(q&~Tg6)HAhq4Fe96+5qyNG5)w+40sfk0O>=7JGTVO|;%cAPFC^2SzUM zCF9yibu;s_2UeIH;Ft-TbnWRi;hFT!Cig?JmWQcYMO4S$*$UI95it~O8iX0^{Q(gg9hkL)c{ zfK=fEvzAG`C`9u3So3#1Pny6@d2gX5TO{9LFe&g)%~(MEttyElKz6)RZQ&3a9h| zvgb`aGboRH$0%{w3Dw|p^CKD4{9yks{s1vI6H2t`IA$ntX$nHvPiM|sA4D3f*6z`i zeysXy0$DESbVP#U37*&rjx5W45y%ytiRMSV(h+>zabPjO)OLC~Nx_5SvLT6lIt5Ij zgck9RfoN^na%1fZ%HwxuN~li5Q)_;31YadLA+&$_r~I39ATFAFLv!n@K{Monattrf zLTx6A>X$=3!=g%Arhts*cL^8xTW{hVX98~`eB{WHoCg*lF$KZc5*kWCDPvWK4}=FG z%A~%}9%{-l*9F|m3NbkX)jG<@E|>;|kdOM22qqXPgG|Zjg1rWv?c?{(b!2;Rp|Rpi zD=Ov_GPD{~-Oa!pKd-Az4F4Ks(n^L{mrLYZsC=6`xL`}K%UWdfd7Rs+sj0E%V%dytOU?I#gP_tXc~JPG}UH9 ztUU=;hLn0k!!sv#O*LuD`!mUFH>P?uartZsRqccqo%C?qeE#-u%y|N6Y}Vcm@Hb1NT;RICKvc#oQ-4srUvSVP_4I}K$1A%8 z2Y&crRe9aQXGgvf5E7pFD4=xHPwnFl_`FiKni{g_YEW%ar(wy`Wd+=*Q(C2sCw_2f z)RKC=ZIS-P#S^|c*PEsHrmw{H5(#sN;uVp)b~Atwr8p?he68)&EQ8IbJg!F2Tl-*_NYUy!Y4_LRrhYh zW=YOPY;%D)Qfb%)Nt#`}Z^!SkE-ls!%NF+~%ySK3Gm5n)pXRXi6uf!()JHKRcXNRuN-^LQbq$@Qn zj(K(d*CFZqmPU~Gc+9zOnW-0jslKsskajwZQFMiT>i~+UYPG8W`+F_J`g^-_0J#Y~ z`3YFCgC%J@V;($^ivjakrYu2zii?Z)-vJJnrT%9iqedSUCs-6b{P^4V(+dDEa$6T} z1Z?O@0$`}_gn6kTGqU!qUpLYT9&cLi66}0DCmHbwhrszn!SIGUc!hV0L zkH6gaaLOOqKREnuHTR{Um~-JjZ$O%rZJfB2`w}%_`&YfbviY0Xv4(LAQ4z?;l)Cc^}vWRdCknxF@vMYwt%a&OeregOpJnVQdS$ea+&tS18{QgEsdgqi$|U&q^*rKbrLp|TwOdI0iRmh5Ol4g`UpiM$-AL(^yGidz8x+rHiB@iXG| z+q$8uMQ|ORH8F^Ks=Y8PY$}N|_Y^P*LY#Su4xa7p?Gry7NfTgc)P6a2`^T3siQRNy zEZupWQi&45A4L3L5AZ$=f~NfwUR+PXAZCwfCBG!88f>k8G)x55zv%_?)+Ni&0|zX! z&Tc>PkmoCM*bUH{+ExPY5znw;lEQS5Qw|+EM8Gy}W&0OWks65AW;>)qy!|=#e&Y|| zDYp8MfS-X4jflE?S6lft4ny$42Kbt0F4%8!okd=;)P+7nrHK{yARS={`hOZLLoTf) z==Fjz0l=2nWV^XFx5L91Yif-=!D8kK=DTzjIbHij4daUB#&%2aDMTpfYPoA7_^hS@ zOqtZAVxKupvsUiuujOtF)(Noa$uS7VvjCjqGIq7kNd2aPiS*}8db=fb@4zq6A_N2% zDj*q8`+QbfuECWAqO@R+)#^&jrpOuxqLrV@;2fK!!Zj#D={fkIC4zzn)}<@CTU_u( zs)va0n~?mNDMS-|dd`n$2@BBX8Peueb-yccok?7_%Cc6k!W(d+&a}$IJ+$jjxhPEv zsCzl={@if1AS^CXa%k|^KF{YDUlU?2xJ;y&1W%^iM;g?PUofHNo4LHya&2MECPc)0*?R@bklelr=)_I}xLIxb!LSztu zqnKCN52U*Z!-)@PiIBwS2iLOHW$4&`cNUK+97>eNGN->ZXUYP<;{}Jm%Ae1izbhpj z*}u|$MdUF1bvGtPhkfm8M2F{2(@?(MIF_F-dglcqc%DDZ zS5}}IB3T4lO?GTMPe4*;j1|seQ_CYrcc6l;8L@ck8yH-@pN>V-Aobs4c77ZytA*r@ z(4<}#+S=OHz~$|H0P1por|YB~0zP$YT!OVzPjE(Z%JQ)DALHRGfa{;Zoxr84q1iZl zK%~!ejk>I5WMo7?$3cm7Ki74gzQXuHRF}olWy@+1O4{hDvBIomu_Uh!(l^@xIbi!_ z!YmDB+o~Ty(@{FmJM4-}Ed~erqiZ38HWVqJ z5$jvv#A~{esB~kE^-SWCCMr-OE_5oW#F7wbiOmya1xz95U@&*-8Zl^IL!PdNdQ%MHVVH^2OcC8=6hSH}f>TLWub{fKZTCg^Gk*e1Zr z${=O17Rtb1?9H1uGMF1dJfqc*pbB$?KrjQ2>o=@ko=QPJQwpr zn0>W$9qs4-*RVOXLAuJ@w{I6Bmr~mc7^GjYNy3Y;YMXXphnS$v{?p4$du*yFLWWE& ziJJj$25?uszIJGXDRh5@q5C6wu$herP36j59I(yoQYeIvw__fC3L=TEzK)NF2TWv1 zPQ=5j$KjN?I~13cWQ$+hGkuCmr(X3V1kzbFlLu7e`A!qDFOo;ke*RkH!2gmcdCmVN zGEJ3N_YJE%Dn34*LQ$atqTjCo&?jKJ0L$+tDIGQ`oq5#J(+6DO-L7&Pu$Dt?-NE}; z;pkNxd|NQ5#|%4iwtx}0CZtcy`r%4#63@YM3UTNwqH=N5U2WHi;QZ`j9B(qK-q-O3 zwIz;e9XB6>AeN)z2z{PS@Ydiu=GHqUaqInb>%5^`1N?91g2c|c!DALU+4_6;-aMHt zsKip=Kt~ye_Ug%lyrwr&cLZ3ol}Hl@k|u8Lt9Ki)=z|B3$0xE^YN4_V%7W~8Z~sxn zruH&SoA6rlBm|>VQc@~pZPNQs=*Z4})-QNTh!wVyhMJl6L)C7U_?A`JfP1pC@*zR- zZ8Yc#`I(psdx8l&gGM>;)O=cV)w5r|*2Xy3Z+h=XqlvM=>Kwnd4NC(Y+1f~Om{h+> zvZ>7EE48Iu)|tu*E24AmO^d(3RN9s66R3FnP-;Czm=AkC-Ppc~79=ZTYN&jB9^T-) zYmBSeP#SA$)(>1+zSSVVHC9@TrG5#CrzIthaGSPGhYcXTmGzRIx}JJhFm^-kkhQf? z!Pe`m#lbBb6R@rSCar_Vde@3)67&vxW+Ig{`y+-sZDq$I2#xHAX}@7ObaTM+mXyHl zzVW|qUQ^{Ec0Lx)xBm9+mru4*4}fW3^(_5u+b(U3PnRX*8e52Ge?Io?B0%+-xd7p~ zu7yzZnS5@JSSYzpw)fy$u+dMUc;_pbnfsUyb6V#e>8yeNUZH}U2sQ}YX<4$of3Win z?mRmw8#1p;C+uNR$#(D$UM=o=q60TP^~|kvWl1)s%Z=g}bA6|rV7YIIgPzZHLVj$U zHjeH15xL3u{W^`{K%S15wzHL;knc^vdx|Eu#Sey(vv1;8cWO~6`C`Y0d@)Q**a&5l z&BxMHr{cOs6=ZKH^ONm_-}{QlER;xvpHpSy*1Ov*byuv3lsNYKS2}1fanQo54uTpz z6f?8TAmv{51kdXJ(B?V|7Icf$J2htcqGd)zb|vHd>KPc!B!ckj>qx3Bl}NS73%X)R zJmW%Y4&zvx;=#5a#b$58z&O+NfL9O#M)?^)e-s{*PWil^#^~I=dv|)lO}iITT6mo!hI!@nH;&vuKlhC8pj|eUaru6x+{adAsR+HUOp3Ujls7e-nUjn(}>PX1d z3vu8hd!xs3e_}nQA(7JYvH+)g;F}N_*VWkVOeg#cGjQ+HarY)yLC+U!`0?Wk(==ro z7m7J2Ta|a|>rW#n^W=Go;Q?${M$^iDs`qmy4fEGQib8&cPcKG;1FNqCh`;Qf3NXO= znSAPGMHMRdkS;5%@g$}TaQbKVP#**N0^1hC&0~&KHjdQf3Tlx>YK!tknf3&0q`go) z-W0Gce!Mwpu-G^?n{ej9hSFMYScRE_nSAOZK{M7%?N}r>ZdceC-%vhfN5SpZ*E4qQ znbzCYrmJiZg?xupKG`dE85yYjGabYh4u)~U^XVwdBPmCI?p%!Qk`h-^V8q@VvbmLh z8ges#^I7>=k~Cyo8k#4FO*;M+hgyyij##iA+bUFOVgkE!94jbf_t8h<2lIokpNxR- zYdg?W9~toN@YlydapUWed1byHO<|jqOQF6_@*5+8GM$gFKS^IosenZ*nAK+N+BXyd z1Jb-CgysQJ>$XR6J*f%|3thl{3FhS6h>AUm1(80WjfX()aDtz?f+jaQ6}V7;D-KnJ zKOSTwtwRhsuT@SMK}GA%MJ8`?2nX*%*y*B3-OzwbYkWzag_xbHz*Y|hoFAtW7yFCc zT%m$3L2^=vJ}bj|O`W+}1m~^3jv&iP?U!+^+1DChM{2@Xsv-RjN90quCTu=osh41G z*P1nJye!}@x~hu}pmd52Vc9)_6nys@!SYlp7T{IHLzK{KRgG~F=h47^C!o2I1iVTT z$qC4O*h!D@P@ZA^KrPZUXzdN!juJk))rIQ=HOt zloj@wYOR!*ATQgQ#tQ=RyT7INU4lgp<+aEe7r2=Y7;?=YPbcRZyTNlLXWA}{9x)e- zSWQz%Uc7jbX}>r51VOj6&^CE z1u?P6P**2nmM;R!`S>(@V67=fOXZEpO}p!3(XjRq4?U$@ndQG1-jWx}Df5d9DEoO7 zEzQ2Xm3tp&y7lF_&2_k1bXzkAf%X)Bz3K~ktIg(a6(pE{$)ch%-q|K%&mc&i2J-YusnhKynY*yTu{XcG1n8E+T$`U`3U-3&6;G~Kl*W^eM_ zG?&vU=-QTXY%L!@Q1U05n3qtN9X^^;Km$u%;6>+?e6^)gQeLVq{7iJ131Jug7M)jE zh?6gT-#F154K9>RMy>pJI zrzgdKkTmCKT_olEteOkvK<4#M@{u1Q55m#cZS^p9xIrrgKz&R99G0trS)!~3o1uSi_IrJNHGRg zlOQK6EA?6KOUQg#lC^aImQIo_8AV2sFA$_nw*F>Zk`e(eaMZPJMkMpN+I^%aN@R0gg;IU+D zkZ^2DyEY}eWh@KBCVn8`_(QP&Q?}HP+GmV(zGVsDrJ;Dxwp5X%T_yeU!#qVf;|G=( z6X%bg_=6|a6KU-5_p?^|Vs!LIEiJ8*R$%=_NV#o*;bfit3vy~H$!H64j$NYQ|8a5mm@?z5Ga9dZy~VJ zF)`=sa<5T|lX+lJMyQw|QGF8qLgt7!^mp!@0Y}IiaB&TEp5A7&ms1droSY}34{D+m z!sHPzAzft|Xwi=TQc#dn+DKssJ$4!bUzP{OWI>EK4PhC*^wfjuD5LiG>+>MlhQD9# z<0voq)%Bex?B!RNR(lvm0oiU8d;JFcqeIu(NucOTkh3HzP`9regFEM(~p53??o2E#E`E=b} zk#Efe6yl19Mx!Dexf(Q(-b?sGWvdF5*aAj6JNgrgnQu5140}*-43$OM_q!2}Cxxm+( zPhrdpuc3eK?o2@hbE!AE!Wd+uJB!2q0E<)vB_AMESBjL9C^TGOq+0C#`+k%@L)N(6 zp9(Ozo-s8A=En&X{Q6zGbV+gW5lTJn^Q7<5I6(O7<~I|6+;A=vxQrWixB9G+8SZZ!5btB+tAM+Z7x2b|J44@LKph zwR$N!w(hZLq2ZLx?~|nKMptB1$vsPe&zFhVSGL5*N`NM+`(PYlYJQo%=DZoyNBhF- zJ5A_u>g~Okfa3b&?$E)W(9x~w8P&223Xnw(FqDp%@R8se*kKck7MhrXd~IZK)E^)L zsPsfpr`RYNJQ3yy_@yMq4ZTkLlac*Z4-sF%!v9iwe4-`DEU5e)szcatmE$G&#cUcl zC$A^a1fPUza?uH2Fy1DUTH?o^=a&(!zo6jKOn0BgmUMLa?aG#atAi#kxT@Q9b_7yK zrEem&q*6PbFnVE_t7q)97w+D>M?62GoUC|O3c{Ssq*7PjJ=3i+TldXDmy>g~P-s-b zpF}8yp!(YA79AOt^L9%hO(?AtXR`eJ44UG|><*X+URPrhjLtg!efQc{WDI??y6vc> z`BOzln?394xMQf>!vmiu%F)V=+4`oZK2!|#o2Y~@1VO+&yD`DoI`*xSRss*0)pde9#rT5oJAm!_Np~ZXsAJLir4C-~~X1 zG~v(O?V%_fAioRvGr0W-926Q)6^Ib`?)9N>b$1w(>C31dY2t?2e6;v&+j4mhIt@J$ zp}aAo;}v|o#3=ee^xeDOnqn?;v_eQ~_`;V#WX2QdKaBLs+*7p|ZC}ddWYXZ#P{1)L zIY54VaNQB~3j2zwsS;U-A_sv}(uj`u`EEGc0M}OjIJ^$t?~p{BPgUro6cS#Frrh65gfck^JPqZ(Im69;?tOxiUDn+)4OZu&MeBAMny$=5^s@H$x9%bK6L)^ z5_tJF2=Vf?Oov`_LHd}?=s{ko{q;=#Kto&LI7wmcwWlHB?9H*j?~s84e1u z{sv7t9SN#plta^LZ9!Fw{95yVWJ_L--M@X%OM2+L)Tft{9Qu`RTW3YbRy-sm}}hwG`<#}o{VX|yb!US zyLZna;ESOcU}XUT0sB+isK*h=o5O^F<2crD#)*JPDFZVg6*25HzS0Y#FowCZ*jQ~| z$l1>mKT?ep?(^yrUB$-m;LcP+NFnLO3$cbn9gJ{ChWd!#=BUm@f$YN5$x6%1{yZ`V z@mm~HSyWjDJ@YW5qQoLUSd@YrZL6U#cb6Lz{@-yj zG)|rBQS0v^upTr|Znr(5xe&8N|D=LG-FIQ3xe-)7iwp4)uOpHV%qzTlG6GhR2IVnNG-LxFHLHDa`L> zO9Us)7Dg0(vXfKV=Fi`;V}}N6=|lwkEuHBX)1VH4aKKXUH<1u^6@-*67bPLj#B!>m#$el@lmmA% zcN_m1lUuJEwm~hHoQ4Ts6K7F8jvS9(2h8}`t^~dN-#fMM$2s@FTqxvOI`1O8M z+!k&6LL3~wT&Ds#Uh_NIpf$OD)7)Ir(PThZm@UB{n9H9&4XmvAN~g6Gd8vMD;Rqr5 zrNiE3U~n+iB1n7l=G%BnQBK9kC$jF?x*Zz+bm6xvOi~ogj{r3%wdA=UW=k(FIo;WC zkrzUV5TsxCvn$~fP+5SNX4M4g%Pu2R@|8i_Jhlv-D68dQX!MOZRge=1zpl+@s!7Pb zEx2`IP@xE+_5#eg?{%XB|cS?GSD}%g()XUxB$U= z*)W|1lCrj-`wQ+YNaVZP@cJu;)P#HX(^2=vn|!3W5@P%(rq^Wx!2A_Be{TE%B;MisBr zDexHz&C=HN6}boxFS>1OA~K-)Ms1`B39CWX$uq95(3Nq}F$`!K2;vLS$Jy|PW|f+p zK0+f!bFHT6Kp~r@LRC@igSqUeyvJPX+5qSV8cJWC@R2`LpR;?v%8oM=CwX5pagy5T zH~Y$!UV@a7T66{)_W}_D5=NBL9|?9{PomnoN}$3=55^-(?=#l|arkF146We?P^BD-YQaH%iB+uNIb3mdoI_Y8m$m2u_4z79r)0K1(H9iY;n1Wn8UB0<)t2?&$D zKfmpgs|_JE4(2%vDh#c=@b_aYwaKa1M#DB$;32BpUOWPF-dw;#*y%&rTpSyWt&E6R zg1X{NA}%5DDibwAf+jb__|1`LYTUZYTn(N0qu^bGYF}N#+5LDpNSr;(bdUgWxcq;E z9>aaI{eRp5KXUikzKI_fBkc0Qi%~I^{3OCL5Jz4$pzSJQp>8nHHL-5});jTTx|HtO zG=lMwF3UY*`?3I$7KMYjGo19KiGW-gB6U`}UE9u*_6D`>eFS9*U92JIP$9d7z;%Gjb1K0CV%*qLoxE}hn#YpVf!yU5%HK@6nn{AFF$b%Y_l zz0prw8Q3j$aHlEEnOW-Ffq6qwn0rM2=-D}sGqr+fLVS5uPdy?7m&_xU2E*OSCyoGH zERiMmjvVxdg9E)Jt)c}fD7q8ggxzKG*ulz7rLk)g^U|!pStGl{6cFv+eIw39Umqvm zVR5RIBVNX@eMQE!X>i3IXsolB#oD9gfxI-W?=y(Y&7q}i4Tpg>0!!F8W?#(l23qVX zIDmH+H%7PlJwS?avy|2sV$|^Bk;c5&PwoInN?sW18vi-6wGyN2wGIJD{|fW_@UaLx zcL(oC18W1WUOmW`#t=}v@4se`7B9x$gn+ z$}U40D#YwkCn1(};QRUVz<#=txzik1Sf{`@t|X9V{U`yyI5cee7YvRHM(tbRDP&6! zI^!-5;wvIhsE`8#%_Xy-=IFMTEW$Jy^yUHTX?`TbT|freZuXbqv)E3U3FcBiFP=K> z3wj%TDP5B#*QjO8ib4IQX}3G$jzdhZB=)X8RpTdLO~9dSCy&YVNWmL%b^&^Vg2{8k zt}nw5zNF5mZLn(w1W%VuXIn~KYZu(H&ZalZ%vBom{uH!^n8_S1f2hFC6e2*bH_8_W zps054+Le>umz%DEqF1&oxvaFn_bs4x;9kMQAxgs%27-%cKRae9NvSN4bER$u22ypR zMO#YWDXlw8`XE~cB)mp#UBq`nK`~WIII-!fsJz^~a@rIJsk=B*bp{gXrqc`d+C3LH zYV7(wys`+JGap7PZ)D-aRs{g>Qu0Y@*hZ<#yhjZO23(w*7dLGh+yfs#Vi}u*sL=;1 z*g|=?u`y*K^6g$V?}nt4I%Z3oq&%#c&^X=}b}dIfy(dr6nk>zKgqCCyUmHo4LqlPe zd)r=|P++=Mm_gKtY=sI!z_Cod4|8|4@_)b!!@=HW(L&ag0{>A#6CMj&q^Qe>Zerav z38Bl?m3xB{d+nlc-CAf~Li}X5*wy)V7ofJ>ic#<)FbA0_q}XqxdQYuQmM|D}h>3NF zN=a-$Dao;iOQ{?-KruG4`cO@b7u)VegiWNM;?m%D6V|hYKWqoi-j=Hz{*e{*8$*Q% z6!+Q_t>xFR^lpT4zjFH3XTmd6$AO|X(E2tB@hs;sB*@ILo`bsW*hy@(xf`^yglYSNgDro7+(NbdkDVZ7@*J_ambt4a1ECN`X6F< ztJw-U1%%FvP$~@NC0o1EWKRcz>h=qZezxbRx4VA5FiA_OKI((cK?ssL(F zg~|QwL9`rgf&U#0I0N;{5E=4iUNWrVY%~f)C6pi|&|T`*U&`(pmZ9%FMpc3^49!Xd z44@}6?M|%tPmXdn70TeTyIQyZ5m*2^V=*f!d%m#pLuH zZRvxqhXDt}4vC`he0-q%iyxpcgqmelP-1gjyH~34k7v!3U0mOOGGeC*q-|(>H$psz1HA3jY><(Q@kY2h;Yk zHMU&NTv)o`ZFt!D z#wQ!yd)qdt&(KZ7+M44QpLjhtH@5-QLq0w}=aRMWOb=CaJD--8w!3#&h3buUA)kF) zR^}ZY9Ub9lZf+izl;pT2sPZk3&_@WEu1mG^uePUMDJUWp$`mK}3U zK>(JWEN@dG{BUvPhYug-)Kr3qZiH&8e45Ef@;Xefrluw?J-zanE4-xc&c^MXU0v7y zSnBco`SZ8$-dQQc?pUgS?@cwFAaV9^X4U)Ch&-~sOH4^A@9g9A6%7mwzB9R;^W@1- zue*`qJ9<=ShO^xYl6{OodY#;J2^S|zdP%k_?=dV4)-8WErkO6(B)VPpn7#* zpR#LTchRvf=*{UfXKHop_qVY|}$Q_3M_WvhM%s=|=7mmv5@Mkyuqe5 f{r~A{dKNl2e9iu;&n1{iG+ICFXvD1l<+uL<^F93p diff --git a/tuning logs/2025-02-25_02-59-27/plots/cte.png b/tuning logs/2025-02-25_02-59-27/plots/cte.png deleted file mode 100644 index 4c43a9992ff3d0f3dbce2343a5deb347405bf746..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 153700 zcmeFZcR1Jk{|2tpPFrP0l*)+gk#UGLh-@;Fl*lHVk_K5R*_7-VW%f2QGa{KGWJmVS z`rWVdIX<8B{ax4Zzu%vy>pE8*dnjC%*|mda2N@aJt_$a-6v@c; z;E&{gZrg(2V%VD{@!KXV$qUNc@XKl2jVJj3?dIn-tjNf;&Jq7@IPl`E1imO}Ev;^? zWOmcqR?pIa%tX)H{EnIRo!i%s+%>SYx@~64!@x*P$N60QnNhsTe{rc{B=jE;MMU%QLnSP2lcAXFAI>d8d@4lDEkzY6HZqk0@kCxo2 zw{>tgO*RXMo>HmMrdS>--e-3#8fAHtniRG?H=t3_%XxTM_;pP0&#bNg_pWF>nHJVq4@7f{97p2kK*4# zv3?T&e;0}&p0cvCXV0HE^r~U3&Z^i%*3GV}qqCY?_)f=lW%e6AMeW7vm#0Q19j5~e zmkqLHHj$lg&Y$mW?;Th475i;Se1WX{*shv6;t9=<8=0B;t}M;V$jQkyHa3=ie6Y25 zG`q_uHa6DK$jEbUZthcEov*}$Ez%Ma5?*vd+~>S$4h}{*ntIU+a6H;Y`*PIxuXpOl zl}4Jn=rsSKYxJ)3aAU$1Rn?atJ&r7CUcK5I6R6|qyfi0`=WT3il0JL(?EClcrHqY@ z`vwPPBqTn%I(yUbv0l7*F)BLxSgp`t*d5nRg3N~xA5J&xDrkLoOP;hmRc$ddRBvc# z_+(&U;N;1ZPl}6+PqMOlrt4RfFHH8n!8cl3T4spOQTH;eEy(=(_U^>ouWuBOcOUkA z^ym@seIyd;Bs;s;>$8u`hw9(xFE31T-Tl={C1PiuB{RkoHq&;h)A#(M=8QU>0N*z1Kwzf70=X|R= zQGtt>F6sZC`Dszf99a7Pc0+Ca8t-2$$AWxzmy09bwe^S9{BdW_2MvGTB`pqwPL@*0 zmo}$d?e%qC)+gR&J${YgS@Ord{r&x^1WdJLgSnZ-e%Je!_fWO;F;hB`0$2#yil#-d5c}2ibT!>;U-_6ZUJ?oA}$K7_5 z3hlI%6z`?651eC#YpXlu!N>e*)^BZNV`JdB4JRUac(kifoRy93O-2THgu`&cP@U`b zJv6*0Z`OuUTMgEFC#4m%DJ^X{uWDgoK__e-U!lL7UW5uUOdT>*^ZrJqf5VjTd(+(h zm+Bwxnq*aw-FsL3qvWxE>63lm=#Tau!bR*6nfTMU;zeL!#V&!4FTGqX+P2#Gzxf|G z{*+HlOeEgv&%4gGVM13_RGMxrIgecJ@^l=}&#p_IkDQvCViFe@pPHV26CZ!_oDUr} zezHZU{a{&+Mep^m(HFS%irqhb{yZAEA}?*$r6qX1^hrG4Frq~)B7QzGDM`O3h$~-s z{_7=9Z`}Lr=%1oPzkYe)=c;F$YK!0kEq=A8yL>k*y0?MrW=&9#u#Hhom=KTHY=Zo3 z`}j^iK0YponIV_lyROr>0)pqO*wRXeo08s;NFp?}wDOA%C6D*`hME-!nHH|hQ3+Yz zV34&NFfuXme$3z^*qp3E!CA1-!=n4w%ipREQzzM3Xj#`wJD=8D6K)vGM}D3>b;>(X z$Khwrh`qi2Byyg)+?zJ=M&O8Z6_{YHAVAai>|A)mifocSCo|xsOi`nh%9tJm@KC?yW!ZU zG>6|ydwsE=I* zi6bFW;3bDP&6&HuhUQm(tQnh{`k1*)hjO_rFD%six-_2HaI>_K{>i)RWu8<#H)Rq2 z11~ybosYL?7+iYs@?|+?;X;|1hwIVRS*x2Rk9Jv1mQhwLFHZLs-QVbJ`Muz7Y^USK zt-HMf*wpTR=xlC2q`Nv5$RoH92Nx&#SKgm6Y)RF&_!$#ej;xNtn>BVl`K7ImW~3#} z_bF$AAO~rpxHZQ@Uv+>uZ8AX>Hnmi*kdP457BkXhx!~IJG>?G7md2KrikGLZ_Po4m z>T%`GIcW_Ijb9zPJnj17{x96xaU6Di&tx)0&-vaRZ9AwGciEfPjKnoJ_C2&oBQG!S zIvye2X>qEdM=m@}83k)vN8Cj$uAT@tuxb zbJDW!4_Nta6(1GFgxH`gT%Ao@GV$#cY#7fsPRr*PTb=Z^{jl2JwaSk~{?8lFXC|oE zd$ty+DLJTA`l#uXkHwc6+k2M-QU5to3w{p=iP&4-Y0o;<-dm(`yV9TeueQ|kbLJ%t z4&k0`LQ>Mxao4q_{{)Xe^CfPK8FfaAn)Ia zo|BSV9megA!>h+fSC@vb{;QIkUQg+eCzy7Xw9-%~l&-yRX0dA-NLJnC25``b#gVS-%fB%z~MF5?QWChHc8wd+es zmFC%uWQZ19WM*eqL`gsGN&PV9nU$4=*V9nBa%JE2z-J<@yv7`dzPt_+vbuSvt3dS4 zQfzc;DhJ1hUm11-!MC{c%y1y=x&a7iI0svPVX@E+O);W(z13T zdyQWH(xpp8@waG@6JTCZsOr7I$mB4Rl6@V?^Nqgua9ewOFHhv6?DDT$;?;8}{cJ+{ zO*|ixQ=XHNkx`v918&fGcQZV|?8oY$_!@Pfu8X~D7k}Z+&mp$XJSMI}wBz}9&BfsFBsi`TE!CurnJx3W9&%b!_qLgUgt#9?N zC@AdRym>QGehu&3@j`<=V`OZsKi-+2Zady-H}~z9eudBBE4sQ}k0S{QhU~~;;G(Da zqRj^}$GKmqo1eR-ZZB5KyX-%8>eS??qrOs?FJI285MtycO-L>;*17szcz)c#?lmwt~v!;-pe&}qiwvO#+p7K*k;y?uLn2RXSuE)b1; z-{;St3D`n36hN$svF{&x&0LqRicHt=5Gh&_xy2zZFHcx(KDREs@#@>hyJ!y~H74;y z+#EUGZgyQuos?%E?esuu3nH*ZmVUiUH>iFYpO`58V|0bTyK~v zQ73*BKTJo9rx3e^o@DXOAh4_>*Gj+Y19q+HF8n8_WtuXF72WJ`Urnfy>Gz!(8sDtfo>p{IMWb&t=!qvxd1 zhtODiU0Z~Og?n-bBc7t8F5t-N(@<9~)cuuVeo=*ME92=dE5GS|@lPDNdFAHOV)qS( z+jd?EZ}{?MuZ%Cf_Zu1CayD#w&YuSFc znH&f;E4M9}4qy1O$F;S0i$Ep}Fa z{_Oo>ERW4Jf414wR|EgJ!@5C^>&7QPm+;Lf$DNfwhlhu&=Jw*&{M>-=bAUJX2W!Jm z*y!l#>2)B%C!5k-_&lFJT{6fDKVw@?{NVWHWG{3kdSC5)hs-$Mvs+GSWE>-)Aib|f zuB8F{BE#I62uEVZ3d6!JDnIQ%nXgFf-88?sev`nadS2TrR~T9><>Z_jm;3z#LK1S7 zO=BLtIu{gO85`^Ng1pC{e8#(bbLNJDL4ue4RG)`oWN_x@>fEhll9H0AZ`M$4XJvBVD|z0; z=I2*t>z`jA3ew60w{ zf|E>ENd=@oA|^(U^Vqg$kBosqjAokJ$pcTGK0WJ8FZw?50bgL&9TStuq57j#)YRJ* zo;mnGe_oHCk&@jzI_llpsy<3y%pj)&q$sVUL$5^2%@qQK_1Yu0(48rFtBsYDvtqKh z0$pSSov6bBV9_EB$xh-qOHmUWYn7gNknAbO#>V2~)V0Ew!MCwd8Es6b@!WB|l>4JcOe`$hm11S@-{0UIbAtHpzg~jTy;0=n&!5}K z$(5+z$a||}@SqZR5!uZk=7krii4eV-a_$6P*SMKIHue;Yor6Q7)9SZ(x1M-<`p1V9 zwtuiqs~Q{~9sSYWeMF9H?N)zPK+WgEaABKb)RniE{THu2ZH3l8=e zZO?wA{o!s@A5)(S3kyr@``Z*s$#HQfdU|?zjfyti=!b(7egP1zSye-qC^!J?R=P!@G@LajvX|_pC zHi?qr@3;Ak{`)D}^>^Iu8yvZZL9B+Z>y^YtI&l{|)X4`aDJf3^R>G5#*b0`$&S;VB z_Td==*g5|`rN7Q=n;!ZRtJ=p*lw+f~+&DHShEY&3h$ZW4wyB`iz|IhU6IM%=HT~PSJM-O1mqVbQaLOWEsQfH}>#*ET3wy?*zO2R~2m_U!}}F-J#76a~(=Sy=<# z&a2BpV!wxurcC|JU~pZ2X8&;1&u_1tqoZ*+=DKhyVe6AhzX0kK)Yao{YKOn1&u=Y= z{dGb!(YcR5GTx2}E*&SFoT(lwnfjuxECs133oDx9RD6E}ua|NF|>aeSSh- zbyCtc3|${DG`hq%Kj*{sK0jyy-H<9n# zw-2M>qdR66s#=%_Ko_3?f6a4@A-}b+&ny+E0c^-pUVyi zxUM?wq~@0L3)}JVkNfxU%O<7Xx_Og8=x%*0Cxqu#nlKYsb*$Fd4kvamAWC7tT|8PG)evaE)Vj?Z}EnohCj zg4*G^sVTS6&`{p8=D8W~ zwAz+wEa?3E{jtpTr`MC&RkU6vj53k(N6|xBvQQ`mEqXR3Cnrm#UKAZ|%Pfhx6nNTc z!94fUKU2l8B{4p}2qQrXcPs)uGjT(GOA95%iOV;9_K=fPq|@A0RaK?pzY|nNRq#lQ zv43EoXE4%LmHO!Ha3PRJj_aD3Ss0S>oG<+;32FCFM~@!eD84d7VHW1?y-PJ!i{;`j zw0Jkggg)=~T&ojkfzk;Q9La2XE`X7zd3Y#93JVLx#}nU?O>}?UNGD>a@TJ50*Gl`R zXGgE3>4*k!(F&Lz$ltvl=Km+;n-i4chh7-}9K9`GUCrU&aD zOTPB|K)3$Q#3?O?K6$cD#BSnG1Arv`V~OW%0r|u14|WFyQ9Vo2t7uVhoE=utDs<8I z*F+su(A3l%okmNCkH|0jrFgiI)guF7@1{iR+%te$aWyONfIg5N9qpRG#*`uh4i4+|?B$XZ+T zHf%byeu>d%|8b!yxHayIv2X9Ta&T}kslE~2xN+khgvA;VT_4B8^&lXwboIEPpnCr_ z^5*C{FTZ%2@Ab(VJTv26kt}ml{naNqIVp3Q_zAWU)2(v(`OF=sbt3@CJeoUH!b?k~ zVskq49iLv^#>fq{MrP)vm{1xfWF?iN|Iux;tOfgQ^MNkcHBmvIUhhzzTf3*F4use( zjbyv_h8ARf9r4B?Zn)#}fYggtU_dnd?=aQTP|`H^*+0 zNhuk(zr3;{oqAqy7Y(o9hfU!snwp-7L`FWogY#qG&tAT~+tbriK}%~Vjw>iM^o{BF zJacPncNAC6Y*TNC+2Kmc$@f{sn#P=cWsi~>tC1vHK%)EU<=+w?xhp%jphLX0p~AYF8}_)_SwsqkK*JbqjGYnq@|@5 zSOZQA2t0oHaPu#;>z*FBL#H$+__z3l`1T5RATaPKumo|4nwm5bqKI&_KZ~@ z-)A&B_{i6H4-*rUT`yQ#i}^9__eM<@-4c~~PMA!U{@I*D3yfyh6?)=w*q?Xr zX6Y=aoH};QU7)e(39#K8jPHr zX>CE>-PhQ!X2~`RueZOqZ~oCdzoPC2_0-hVyuICU{8>`HE=n7!EU#%-fp=fujp(?z zqvGNW4_&`kfM(tH{e9vTFiUPcM;I-`0*`)9NLl^8r0Lqcr+qF zb@CnbK)Fs#PTp5cI6yjQ0+js&CA6GCt79EPDK}*VxVhaB&Utr7cgV}j+u7T{2Bh)# z(da6FW42?*j=dBV4-m>kXaa_Ps;xbTOTaArTH)k1J-rQ}K?DT_uZ?x&QgPpSqAH|Y z;N(G0$#I0A{}3gIRuNE~#oDTKYykOcWo_+lymHyS4I58m=xuFpH&zL4#4GKiruG0J z#&}DPkW_UPKN)aQ@XVPvmjXG4TGAK*b>eKj>)qqoxVZLladG81FYzlXD*8o4_<+wY z)K0@Gzs5k1z@v6q__4Lp*lA{H-{lAq4;1es%*>m?8W5lzKMC~ZCS(9m0+B!F=H^9e zy3WjY`u!LnP|7`lGTl0y>NL19NEokG*BUY0? z8{%A@IV|b6l9QA38h#<$y?eJErdX-M1XUxHfrZHm2JjeMfar$+3)DttchT}o0lQ3~ z-IsKA=}xJ9+ZJlvlFG==z7w#As7Z+ZMu&V93DlO&uCA^mhyr{r-2S)fB7Q(B$hkX8 zgLiK}SbLacH`$YBmGSyDBm1dS1g^wIbib<;I}3WGpCfc=pHHuOf7QV-F=rYN50CS* zvQnz5&AKg|H*ekqzPg{1a;oF|_j+(|Gd~-)BFUl}pNEHg6K4P-JI7&`m7AN}FEH>i zI*PKYYH>#g9e{;AIeke|Za%mR1afoS>K{?3D=YDT&`D7O5Cu369pdm z`g@*H<&TXURm9B9%=RFY>ZjCB5Wph!uO=(`#0k(gxCivnQA_5v>XP~SkDi`8!bI#9 zGeSzI7AEzzKHT*dNCl1HFIxaTNWF8*wQgVib5FKh6P`;{Lv10hbZLG(jsG|z1d)0# zE-o(qf2gK(-+J55tm&@~6e5%LEqh8?t(_XJKDRv*wcZq@Vc3HQ8>d}ve&Jy`qWj*Y{pHn6ql5F9Y$b+GTHi97)dI?I z^S=~8JTo4mX6ZFvTg%imb;xG>!~T_B_sF+zfA&FHBH+b~ZI-DdWShXPTDnwZSX9_! zQ4tZl>;ON%SC+K6)qV&WZ|Y}vc4al~J9w~cabdxH$3w}t(>`b)0w!&|V_?SInkor; zk(7B#D@UQ9zpA=A7ujZs`JmU!+q;QIpexJR|J|)ROMG=;=dN9w&v4-Dx%cjojiDe@ z#tbB>rCEY@?{n_!>wDs_tF7y@$ZVE^`G5Z@R|$y?*%rO$Qi00dRv0#RC#R(3GGBUW z9vmDT)wC)P^1m39e_T3|cLo~I>2=|pDTW4<2_N>{gU-!8jUj2s+OT-#4Y_37$3 zCc;hCgF{1~LcujUvSvSvh^YM>DIRIuk(1swF8WaNI1MBz~N>M9xah9mNkEYmx%amGimJYNTZ40nvh>454q*_-M zz!tpPg(zoEIDrRTR0p^YG_-l!w>G#~UtN94V0q$4iF8tSRFs=>WBjwKWfa7fc4PJ0 z%FfPC&6aY9!zzl3Q8paf&sELlr9phu_?S@#ImZB-}f!ze|{v@|;7#)QML;tDag+xd7 zt5>Zsk!4znWTtP(A(6tCdY*C$qIr0asKjj$6cr5z=sG+&Hpa2&f@y(m9&}`4rdfWAR{`HN=6vC~MKw!q5tA|m6^l2XR?}<^Ylnds52<|Poc{bxq?1r3-41Wv=acy$F z?Cq%+P{4Av}jn~I_3_`;1fF>>!qsTHW z^yTA6iMKa@h4diBNJ}x87X6!}jdvB%Rd5y737B=VYwluST(fss22rV8j=-0Bzx^O^ zqWy^6<;$z>#?eM(cR`)BMed;&`63+1@n%bRTT)I=(9djds8knJmF(?>)KI5l>xM&2 zi`}=&j^_gfTvBa-CJ|&LY%}~q)qbe8S4~l|_=7KMQ3decCB;4K@zb>Pzl2jG69R49 z_U(F}hk0)9q!BP>x0L47m6qPDnyh}GU<B{czmn@cp7);0wJlP4}R^9=H=K7s4yiRp4yj3-ypq{jywo zBQV%~a4$PT=F!CsAuK_>@(By0lgM6?$GI=eG|1PdYM;4~X4^;*B=7Hh+YeYIb>+&l zj($H)R$kr%VBpH};NZ6zKk@hW^nCfNNZQIrh)5K=tem#!k&2Fu-Jy61w}Dx}9Sss%QCVI-quUP%`#KhZ4g-*4dwcZ58 zjJ_uu2gjk@{j-}kZ7OPPeBU-$T~!5we!~^Zty{JvIu)Q0m|IySB&gly0eOFq7?r<9zhuN9Fc>*Q-T z$L209*jbNtP~(vN2arJL2sO&Mh2zS!vWm(N$QB>BGB~}W`0Ua4HG6U>6imz;wKSa^ z`{~#lLgYJk+z1uvmZz)G14}hAJ1dP|d&dSt`X-3=rS)%Q43b_S|6nt6NJLcBVziB~ zQyp9p7#My0bA^)!_AATuO)W24Ei5kTp=)B24*U@I7jFU}dfK4sKz-<#vi-sYqr==U z5AZIp6B93HkbpknGNC)fu71R!#5=FJq~yoXpB{KqRob3+EUm1FOiR|vRs3p<{=!rf zDbAo@?zJzu(g1oAi3`U~FteK~I3$yFroX zE~_Xnk3!w5dHySYq%lE>pw&+5_fO-k66uH`LP}5Xb#$&P(h;=3^w;q&OAjBP0qA&)PTp`=@Ur^c(AFx7?U&lIN8`rkeKP# zKNagONgx18Ng9pEF!DQ3!3}W@g*78ZIDx!2LX;dxSA%APD2j;a>b84Y&mkkchTtd5 z=15CRdlab(PATveH&a|qjVvg3CJv6vV~UB8n2GPu2lmWpe)i&pJDBk&1;c5qp!Yr^ z53O&y`HdGW?FI;YPNF^^2&$yGx|$s1e_+a^FJBa9#=c+m3t)suxdqm(PC+5H4d{Km z4XoypeD8G*)iaF( zhU~>wW|SauYa7&H%$&rm(+grSs@W2AD%jOca3nUK zCe&*IKeQVao>hP6&Yi@R;lcV<4t;Iy&__$rqkIL%&jAU0z&N-KEUzw&tE@gUfHDmb zAYqkQ^6}$+ma#9d&t}Mb$vmM_7jH+aI)P9b^!BEF+3(X>|@4< zagY_@lWd|iki3}-LvMUHb&Vk&CO!*vZ7a~u9cs6mxnOR78dA~5-0CmeTherif6siC zW+dO|~I(l^x?YYCQQ(&3N~oJrxK!X6@}7Eh3I{J7KVRwi3cXwtxTr z3HZxizk2m&(kK-zEn$EnSzrbVG~qLPIiOETNjdZDo6?9D!j6j9(C^paEAjlb)umS8 zqGUdHjSTnWY)lylDr(@(QyK;K(*umhj}K(lg@cbr9tR||%tK~T&oO^}EEfo>{)4UA zjT<-4`^yKQAEA2v9KBeC`5h#N3U$Nlvs+^y9dU*hTH&98&WKY6eZ0dSp=0HjL_! z)WXBUPTNgfLr&46ex7@C&YNh^U%x71csT+(Y;tn)iI-O?JQa;?bFf`~AzUTl!YU~( zDwuCCjW)5sc!E42h@00qVPf3Ipbl>6nyKmTZeQ9RYfd+A-Rgz0FUMs?7^v|+!Dn^8 zNMLcM^%e8*^{x0YUQqp>^&WU4P*>eULlEuAsc2}TUcDkiQ^>Iyd1;u`!g^pwPHyfG zgeaj#e1X!*d;9AqAi}p98EzgP+h1H{hB)IF8u}D9za!6voX{;KCI3JWH5&DJdU$-y zFsOd(vf^;1d^!cN@`@tv5U=XfHVTJIy6L{r5q*5TJE8tb#-2M=8S*8NG zt3Z3RKsqj?Hhik8+OKzPiV*mKFG{VKg+XJqrt8ZJgggr|LxrpnsNuuIfq{`qH++ud;&A?F=po5%l3hI9~(Aq z=|)L5$_Ey7fIal|^78VRER(CeCT#~G{X-9zB6>ha?gI>)M}&oGFeXa@4Nhl)ukp;a z8mwyG7KG}`rC)w}r4R*~;5)&ZyoKczgOLIP0%6`!;7p5C-mlC~nwqi%zkVRw^tffrE9&Y`B3*ua2$;g{s5!c^+qbELu*G6lOPUo{Qc_y@{W}V% z5|H>Y*rZ>-eqA#%!gPKg?H&pQS+-eMd0OGBCx*Xxn|BkSy$I;4QSf~0)~)*J6|(7Y zR!GCFqi1He)-vyp%R}er!PA5M-TzKGs>1ETgUN5VA}7n65|p-Ls&sW;HK%)=oXif6 zk&&5MI>k5;qzt0_AkM%oJ$+JlEg~d@DAciC+9ABR-H0257mz`PUqHaa_wRYZ zYPsbeB0~UdJ?BNW0o+ffPMi<^Vqsw+K0h%%JpAzQ`Eg%?E+-0<+p`U^a)eTYc{U1o z93H7ppFR~~6x#>d5{-CZnt18c;P8$eJ4PrpAv-VKN|*iAisCd$UT;xZSy__~Qtm+d z{?AlYR7682{HmE;TX)kH!Pa%nFn(p!2s34l(_#ihC>4*g=9o*A1FhgD80hKg4LeD> zPhen3fehYB1)CHYu?r|k5d8@CZr*l>cBI1PgUxOIf`d7Ec|B09NfxL?HEaU~W0_76 z)_TuK<9N)68(9J@aQ#rL^N#VYvrh?I*1?B+<9VVDF1w!WC_o@bW z?cAAz;5G+8-b*j)5X}wxcsu33eIMn*1fTJ6b6-#8fmsHAPyN-kO+_|CU+#k?8pNOx zJWa4<)ARFcY`*E~T(+=R4A3Rkgr5l%GD8{71&XyIID&rAi~Zo+auKx_U^v&R-sxBD zrl}JrdV;M8=*uQyU-e7^=xIGYbV|7#DfQxNo;8c@kK)a#B$AdvEm&+*VArsxPsyiq zY)9K>+epw`x-tLO92T+jtFEl9H_`>qZ3X4L7oi&DdloY~^RZ)w0fBY!Q8x)!kag41 z(dB@YwE*Iy8O%rZo5!SNi88y|GS}rWaw?^~5hQ3Qmx%q8R1zIsg#|PYm?)-$=C9&x z?8O6(_P?ALAmcc8OlnMVGvG(@j0Wje9ewBg{40qEIUtKB=zY=rIsnOY*Omvx!$4yx zh2xeMdBFx|E9d-2r}l^I_khPRDW4%+)l4>Y5#Cu>!MDBLr}rD=)U_4zWq; ze9TnJx)*@01te1@ebesKfha`^GZcu|JAf4(#9%71bWmf*W4ZxG>we#i#w< ztvzbW%F(J3iHWQn+}!^2&a=Zrerf?>H0v)n0P)ycL6Zo7myw}J-GJIj+-V0MA{XBg zpkHA9bAR@oZ``%b%`XvRly}(kSQ#1b|6FVS|6tjGQo>?l3^MCLOa+E=>2D#Fynsj) z)^8n{NOJ+G6K2KMFv7025vl`Z_%i{M1qB6!uV)_Qn2~V;+%ea$U(Z2kCfFSQf`5?d zQg}rMRkbBnjy7}dGXQW7ruRgr@xsecma+}155Rlj=xSPJbibMW@AhSE24y z9(b$D8CRwmzS}l1c~(1xp%h8J7gnEAvvrZZe0jim6oIih!3um1>omA_Wk-5Fp%buH z7;Ec8C%k27_-T17ecbp0 zvbC8B`a(wIad+hJ=}}ikmp3XcgcfA91mS?MP3*Aaum;JF%S;rL;PYhq^}#jmpPIWj z=xLsn`j-0oD`ScVB^j=F?%YXqHihWZ0r7>eDy3HL7vMj~^e!G)+d82Aq&9iKL8Z~c zi<>uc0o}&q`$5eTjI0NFGV3wN-wg;%7-3#3Q8eK^9g4ZOdDSMKX7%M=Qj*5XO~mQ~XD$!Mvl%+WV`edtB2ka-E=f%3RB0mr#JmtQNK&X0uQ zg2Qf?Yo7U!KjM^GgX>N~hv>lgw5f{|4Ub^9*76t&kMoitv&_+zZgkobSFNKHp(VG767KrJ`e!j{ZzE-WkU~}z13rh(1a--f z<)GzT!A(ljRAxbEi}@p!pk5ZCTIPCr?ev~rp}4g1ZQ>dw`uP|r$L1m7w8TWu53Xwk z*Yx)(SzEu?tSCd==RzPg3L6JF)PkTHJWY-Fiig(pw!rg{?167GBkoCQL*(pBNdmK{ zIr!~^E$8%Vs#+R7B^6b?%~2hcg=~{{{@T{oAeM39|4jP9NaE4+=RtU+SWuWDI_JS# zeJqbkir)~#aOs@}ny>ECIB{zPyD%q|fJYOu_0F;N$=_wu-w0&cnGT7^W6qXJ1$tf39Kvqo zKe7ES+l;~N6p({|<9cXEJ8U_!?nE&1z+}W-mTCH3v+tr&)?boa7jAB{WRLg}2xh0Q zW;GgqfVE220%Ug?M$w7`#y4+18X7W0X9CR@vbK{OgOgT)6E(o2>?HI{EGC4PFOnSr z=ZL5vSs*COfn;APoP1xU7LJLE@EH>j!t)@T0_c11tT$%8^(WFCC;X8lnQVEz=LIsz|=6sL${t7!&glAA` z8MdaqhYx!Lop@?d*B?Z#!Q8smQg~HUvnMXnMbgmlq?WceUmO3(?2e}`;jWN^2^uv_ z+?5`}0gXuuGGbKnhYlU0Y1&Li7#)%Spw3GU=qf9_ z3t0^qhRIVjIdlA8SU3V97LKC(>FMch?J6e^KuG>5=!?#l$|1&{3(aU~uijd9uYG0=U;}P=!$pZDdnYE6f zgV8KwTcMrw04icBAw#t*?w)w(#_{}ldY6@1wOHc`44yxL6*c>nWo*V*Ffsi=$0Nqq zbL}uqo_(-o*LxQ4MkWx4D=mdWm@J496;eaPe4rYdplpN)H3s;{F)_?$PRKw+s2}{8 zsGMsf_At97U(MbPVRm9-LLuo;x9`Y3Xc4c0s%0mE0Rq~D7NEOxyZT}ofxf4=w;s?i zWm*%A6ru<#2jmUohY4ixEHE(6Mn{`aV>|2afQ2V43Q?ZcN}xcd&Gw*d9LS{^ozPB_ zl9K9%Q&F@3iI2}Yh)GpJklk(voIMFtuf|pY`UNTR=*^p>H|rw20c<^$sTq5!K7G38 z`R?62iroF9QyD&ITi!N)2N0@X-TlV1bt%F}bQTQyeSraFKl~K|uV~hjt?8c*zH&H& zgL@jQsw%2kuWF!jEuQqikslESp3uQHeR_bi^oE7Zs5afF6eb()OT}?g!aa zPj`_BEIM8PA)_ZQiu08$HPo%3HF{c|Fu({Ly!bFtK8|gA=XS8y5YCuX3Aak%-p;gK79yD3~@02ndu`RJ=iX(KH#v zv|bAGBDl5%@Vo>zVFeYH*=$zD-fba_e@;^|$QFW?qBIb0`q$CX?gE!}=S2Z@Zhy;Q9yc2V&!^q6KK|_6!$-F6 z+DhP~7jyb_Ag*$kP^Jn7?!EN%sr6NyAq1U5FnZT9MR@{ok%tr_XRyPztzlO;r*1(h zAO>%3S;qBQ>;v$27BmuC(VfQlE3F02ADWX$32%U{jZzM=AF#Ex{neQtDlmq6LSn0q zCm7rsxiaL%Ijp@kcxp>>L8fI76b6H^18(Wq<7B81PAju5>V+=(>}(o)zXOW8!F~MR ztV;(}U0aq3ZMn~3whM%K$b?W}xeJQajc;wW5{d+@J2h-QcrDE@%fl1X(}ZKqNLuM4 zs*u&YD~M!lv*~UN=|b#cRKOU2%M<%%bwF;fEyP|1Soik!f`E*+*sV%eL0E+aIF1~- zmtc`443)D4l8{|5VE_V;RsxGauU4YY9&pF+bRMslTJSU5a({xTUT_l-(N%l_uJ zKTfSS;CO?M$9#j#4(>%N=`1T0b`n>fOE^as2JvMy8rgKLHG;A{n9DTU2*^KA)pFB6 z0Mg!3CMHRPoz*rG$}cX)H1ApgUI6QO0&ATfxVNSk~?wY@7Pd0%Z& z+oe+bX3=JXd){lOYwga&hm*}sCRKm>v@Jz5v&UOMH}>e?V1kL>h-{tNRb&Gh_X=7k zOBR3fFXk7J*yvD10(lvpB8`YW->Am!A3yG6jUb2xMWj&r@@1cM_8_QL#MZFvSk%y< z^v0xG0tTrxP;76})-{_>Q)3SSFh1T3BS{gqkvCQ6I?Niy)kbz;Fed!u_jiIkGPuX)dFh%Z0*L=a=1Jv~fStV2Z%0wNiy-Nfb&ciQr)W7wf^T3eaVj9R2514Zlo>(`x5*m#B+PoGwJ zQ7I`aCr3EoV*}d9A#`-GPYYuONdmRlt~XkJvmgvxFyN6a+W6lQo>YNypakqX!FJfp zN*QU}Y5(~4*9T?=i{~1Jbt>xW_JAdOA;QU+)`p9kmZDCEaPhi6*YT4dBb=>|US$&W z6HbO?0oRIKACdVDr5j-&EC++MxiX=OfNM)@p^=ekO@m>n*Mj%@#Qc=fC5-VXN%}e~ zwxFZ@FSo|B6d1q6&+5jTr!iRq7H2K22HSHTBLI!bRd%z&75>=E;jFE5xF3s&ZV7fB z5|x;k7-5$Lvw0dD6GV&2!PKEs;KZUXmH^f4++5eGRi`JjqB;C}D<7V`cusHRuhvjF z{wX1Ae5p;$MeeQEQ|$sL4Y!Mbv&8PoGV`tn*8@m$6G1HwsN=x*vDGu6K$HVjFjoiq z`xiGZ=wWFM@X1578iI82>Jc3+EiZH{Z_B=c0mz$#QNl!xgOGqSL8E*#b$Ui|=|Kf* z&F0F0$jCa<@BsAQq5KU;PM+KbPU41U{Xkv7SM(1?34`e4gwO`>B(p6w>$ld{(|pm} zV!(TW-_ZA5K_p~qn!Jz)e&jOk5R6rCzNyCuL%4^%!69eDXwOxaf^yS1E{iXIgiaoG zJyVEq+hD<&sxyc1j|=o0diJ*!H8rUuRR*SN<+{O`+?j(B^U~dw^qZe)V9g8QLJ5+k zxVNngxVOt?$s{FY@8h8eC_Vb9s%~a2m6h8;<{RagW8)V1`Vi?5nJh&%ah`q`ZeTb6 zesQs602jz&3_ks$oZCNQ;g-Q=fzd3Cu0>q3M{qYrtX}VT+1Y`wXueNlOS7cCJ=A`- z84i6t;7cYoW-ka-6a2Zx!j(I^MsPCsfrX9Un{Z*ROAT84FiHVW`S99ZCzNj7_ zp?48%CR)Tqy$r(-G;8p^2bcvIoAgX{UW}|%g{Vc+-s^9h2mFJ%)fI{iTnF@?F%=s)Ju7g-i;fZof^PiT-8w6Op>1mL% zq;l}!L6U$$aA;^!{(l4^6(~JlU>?e?_LIgOMo_N-T)@+AylcPOv-iM=OR|7)Q=fa# zxbH3M2!T_H7fC0um*ZS=G+P73_iVkAExDJvXMa3q;7*ZbeSxV%#C0|7FW(!9Et;Hw zUk_mqG}BU7r)n7fDLFYYaZNK^S(lK_2>HN_pno=L=O+s@I8AH-abVXAx59(JCSxpT zKNJ`MEgoqb-rgb*Lh4BMSY7478#^Z)#lt9vk&Z!<~ouau9V+4GH(mnV5;Pl;_3F)uGKsnjiye~JkKiMGOm&T2HR0Xhz0Ar!dWaBx_C8L~eqNs$ITIrb`P z2BGAY;r8li=MjNX0Pi$|^~8#=oqn{#I4up$#W`nxzhS~@Nw`Z*2xL){j!ozwev=Tx zOv0;CQu07x3>ZVRU&v&e#4(k<^;>@CTJ7r zFi^z|LV|i#fMcI6XRDh`^7Y)r_TUON1Gtu{MQpwlx3s9Gm|Uzx6N8V&Kjy+BjHLvC zA?|wjVc~12F@%$XdyviyLO0>q4$JIH!&D zwv_4n_G|vakbz+vg=u|;O8e)!#AX|sd){ydB}<9F?eOA^CSV^6i-$m}>)I-|241{k z`V&-G*EYwgz6+Vz#9moIT^D3sznfACgiI`lt`A?u30vxnVSIpqSq*ys`zmmT51~SK z3c{X^u6H&GK>(XSjA@?eelJ-Hzzh(Zj1U{85Cpu6x@m^j`#wE`!ju{*}whR?_y z`F2U+GXtzfmB7$^0mreL(+y;IfkXRaMsW&CPxR*+9Q_HS%$D7eCo|l(+VE0;ZRVh^_k9uOCZ@!83pc@H{maP8jhZ=W#JL|r!BNr|53jUbD zh{^@)MkYP@KljK;24Q>>3-D9X=g+$cz68@59CD3Sg)nf{*X_EFIOx|NRSmzO3Ps-T z1TWUen0D^8UQ!i=%Nqnx4-{jpTs)6?1o>DW*c-+o{fKyAkUH0vWHv;8P+3sJOT*2F zg&|`I&7tof1elH<4eo*c=pO3$!0|1Lj%c>ADhB=h_&kma(*!btt(9Z}j`e|J!i!f? z;!v4G6F#1QZp7uV$gye@$pB7+}pLx{#@vnZEo1Akajq zrft3ko3EjwR-P!m(t;Wb)i%2MC`deHXEET#BwRnc6{-PZl>$ zn6|PGf=N=wW48O z&WEv znV012c$=ilt3L^Q6c$MuSS!gUP$-$OC)M1<`ee+~);2KancQLU2zd6Fym6^IN-O~v zchU*^32?xb4%#-VMX6nk5>sr=jPr%z-ap6)H!7_X2sy-{w-xW5*1bS&gWgKF9tx}C zgPcguAE2!2;j=w7`}KkqJPdT7#sFoJxDP5Blte-{i`&e1&!BPv4aff7) zD!Fb+BrED6v8Q7erZxB{#N*CN4mf-pLs}IA-!6Au5XwC-_Z7at(y}r=nC>kDqXK{o zN@{A7|FZAdsm-n^UAy+GYS0no6`YVtf#Sc6N40puoLc zmJ&}-z01)O{UX_QtFmp=UF}yROZ3;;*Fwe|wHXRI=p8X~%344RVp3brzGz`<8J@ol zSOfr5amKm{%XMZxhD%4|z7TDmwim0D0-bheVFC0paK%Q}>-hNdDWmvI1@5xX!8}_r zNi{BtlSWW&cXcHiXM)7!GTT|57@Vk;Yxz(h78`0AVby(y06HK)VGS%mKs7=6Iso>< zuXlCF;=LM`Ew$3(lQ6EqX%NVJqM9!N<2idIdGgvVcKt7^a)K`IrFrrgcv!HSaJ?CjLZilvoY zJtkdpimWkBH&P%L&IW(d2^wC*BHA}UhZD$xRCBWN85=sYvOApyi>j)sXg;)QqAQqr zL0#Sy&`1Z@IoPRU%=+Cwf3nyLX(qvNFfMhR{dqFs3Ic{_)mKj)v<|?gBt8Yg6YMLo zSUXOd-rbO^c^=zFgnw|QS#nc}upV^Iho1sS^dqe4d=@1c8XW68#N;=pE*N446Y~idD%xmSAJoFV7vif!bSl=RM`0Is> z1GI!`1Y}ph4Fh&Lq9c0b=R13ATExA5yB95r*rCQJSoq@OyD)@P{KpX@2A}k`8#gv# zdTxG$!b{4{ye;brTDf7^-I7lF;QGi)e| z+4IS}b_J%?w)Gu$pwJ0Z1JI(NlcJR-1%oiVU(*!Ujw)5cjFwhRTV(8SujYYtL ze0otr@qfgEhw?&=eLiLFiADY2bE8i|k{&^2Cbn3G26a$!zK170mmBS$Z!x=x|M ztk^ykXCN$u1`IbPTb$A9zg+_`h7d3pQ1|7VYV_D>$}U}LVt zxlmei;|HJ#&xec?kf^%4*W378Mhs4dcEmesIJNmYEO}UM=c=GQbm%%Hj-kc`3T)cl z$0sI`!2~AU@FkTHRul{4_$;s>j!*JA05`0AK)^w)77=^=PK*74#Ah`)If)Q{pXbjX zAYtlFJ5l%R7cxOr$l6rq{*Is{21ZUbI)-iVaQfR-tr!ogZv{ z1_(Us})(<*fb?QB0t1l@h~)$cIVFMwRcg_`Wq6x+UO~P**`*JvFim< zQPC({?Pieq0ScH={%?j$4{XtW3BO6ol;MMz#Ze5s|GQUbd|XWpEs)1i3FbSQhSO)r zs)gQS?4&W%-Iiy*`vCc+=i4Bc{Xjet#Lu(HNKRW8w`o}T0Q*$RC$uRiMa8d|Zo}4Q zqDHVO4==A2s`4cMX)oN6fSnac=C|Ms2ulq<86qlWcdpZ-CF1x=hKZu%TYgSOir5LX zyLSW4|4Gf+;)B5@>t29X{oLdFi@PHKZh21x|JnZFQu|1^geJU?EnyLO@z`y#=1@9( zupi8Hv*410dU$g+tT2583@JN!baM|wss0nVvISz z5^+-noeJ&rHL*317D&kIB)4$&_rXWpY|4)3nu!JOsIWjAXCX`tFpy7`3!nf10uWQo zrlx()uaX9{)GDv^LK3pm@5_r#REpaTAZgcIYI-kWdxg&z^|=JCip@oL^G}tc(taJo z7LhqHWr`J2u@^p2x5iRpae~AJu?uGE3{fDPva9+M68D>zBm>$OI#1-uB*tES*_3ac zaL6QtN4@qwO82u_I?Trooit@)TRk7fTqs4mb-QS-3qc#px9<3lFsNDv9z6*L7#|cQ zVNio*m_+9^-F%0GNPVS62gcN3>u?O;u(+PK8j$_fmPw8c0|~qWV6!`jv@L`x4~q6w z>y2}SDi(6`iQn*B*{KbmS`Rb0FP6 zWE@koA1}kDH#?4W?P_msZkBbWx^=iB32G!h^h+{wdy#-}UM!oVSe z4CTVY)~3yye_$r1F}tcw5LAq_jv>Tko@M%d2c~^?t(?7(WGn+`0wD~0>sGgsL06{m zwrV^EBCP2)RGnh~jP?CTkpeQ+rNRDkn zC5R#@S;-j@5GC7^5s;ig36epw1mPPCrJv?`>-%%-y>+W@>5qm6&OZCBz19q4jya~P zFo73}RY=UKbaz=V*S%N`K6{-Y?u?211CJuRJ?|W-3S7g#ywK_D*cb0wMdnbXSAlAo zcD2by0gWMlJcv7j+6N8VF|7MdY-&`o@9xCK#ohI&(#Mhh%h7Rp=-B{QIM|&iU!uF= z9q{%;IBqfLYfEsp01N&W?ODk^A9Y-py#CI+2Jv&d`0cRX>5S;;)u?);8UL`6v0JV8 zxm46kxGlhg#|8e)71o9vL%5|I5_>h3VVELn=K?saDW2~a6>A3ap!J?A1fIJ^ipw?j5 zxx5DObq7e#DwXXK`+I8QN;ib{o9~s3|8kYl@jyiXbjIt4YO?!^)9WSnEy#;3ejxB> zR}3RjCjIlRx3^@EkEoK?6VH*m2A+-ejnTLvZBp5+u0G#p5dIhpPxM?Z0g(c^;(KiA z6X~bVx8%xJbQiibk;)1*9q*&p1Z@<%6-%hFSq%d%bC74Q+qzY14c~DCc+U?snfdo) zBRGrpn=N&YwK*W(fec52My1lT?J_zp53#e$(8>Z8hWd(h8w2RDC((Rj)cAx=ma}9C z>%8O0>z&D+)ezDvXFIF0MMv&VCdnkWWyp#7@2p z2$9eO(DLvVI0LuX6@p|DHm+)&0|+~TDEIgIRvljGhl3RN6_mk`pAP3f+pQ6jkij^rVLfx=;$V_WkfkTNsPj%%jZDS>vLBZ zkrX4f@4)u5DSlRTU3$I?%}79zRAIYty0hQ0#Vu_$REaQr_g8z5>`~54|Iz z>_6A9A5OM!Oa0OVC0Z1JZtp%DM@vW7N}xkTx9G8nsMbRkO`6^x?b$iyY&uqsZjDEK z%MKVxs!-MD=HBg|cF7n(cM0eF>yo+G4HgKV#~DVSN-V5uk{GDG&sxEvKM{L7{FbQ) z4Xg(s&a}fvqpQnN+y}HtL6go+fD5v!lJIpJfB->8zmwCc#-l?%Z>*y%ELKL;AkVI4))k$`djbZF(oChd=I&Y9icMlH+wg1X<_jR zaf1aKsz7ii6(z7_C13Vu?&0Ctj1Ti3OZF1geUH7S+Tty_$7<09gW^q8`fwaFDFm-b zw^jge;e;SB$g&r>KBB|?zSXfH5b}*A3@*ITMTgZNU~#$Z-M23rCBtiI%Ny-)P`Fw6 zN156U$rGxba|z}FpQSx|8yw?qZ#Z?-i0Y`r@ol3lyT#X}2gwABOFu}-iMjcl{zT;( znSGx;1LcnJFDbVkJpRaVJ^ywG8F#low+${=`|fn~%V~B!&Brq(ZJ*w24k(p!wbfs` zs@YWPCtX6Cje=O{XprulLnFH>^ti6{A~SsfcM#T93qjU%78Y-c`K`GV&}dZOuSjw8 z|2k4SsZFsreQlYWRRFG@A#I?d;(H-UHw1vaqVLN5+BczpzrUtB;|{?Az?=FB zhLFNz^XH$bi7A64D^Azn^wsONuB@>XymhUo_gik0((acCr0CG!s1lg^}t5>aABd@Nm{))?9 z?YBFc9Iwropnpktokt6*+AIjLM4V6=i%sfX0RH?jAZ>(~Ag^!G+o&S{$cnB4M zrJZ$Y)~_E0Qqwa%n3>GG(aqRc@{XgixjB!nf3bci5%e&qhQnhyk;&7XVXKUEIJu~v z?b5IS0II}`HNR05)Td~-i7btgjaEGD!$r_qbQ56raY_0M)@dG#-qnPH_b~}|Qxg+e zte1O?7nhzV5~Coboy^KLK_{sNSc+`wla1oUJ@(L6slL5_0*3k(?>crm;P+q^)kcFH zZ7%A){33n@km04$)A|*Ou_*WEhnLU}W@5wYw%C`XKS|))KSj+_V@6h#qW5uLu$Yq1 z3DKKMR1SjbfpsYP{vHbbB9|U?7wa28c03~?!CBAPFlt(RMpV=R+bbG8yDo5ZQh>rD zi48?ebrHgI5yAt&7RErNtUVmzwZ=aAI z7|(bM)iiCLwF(^Iw%g85c8VpL4>U@{O>rVwcao)|m4zX3;XZe*n#*HXkWV3_t)vI- zv$Qa;{=s-=48Zu#AG9*c_|3#9{B( z(NQ@Bxdzok93S~Z-KQmdq}T&dQ0xWIfjhG4jd2jJpl`gRw@$aw#ntsZN;mE?Z0Dn& zAv83~lk<8AIW)v=S}OKHwO3Va3)-WWkyh-DLN=5a`OJBURa^pU!%Z%<5 zs_ga$`wFfU<1NA>>YkV!yebjrC@bJWOP1ZujFU32S<3DKv|~$EKNz&&$t3cwk=U?D zE4&XdD%18wZ{Rwjf9^4DjDx0 z?KoBrcAeJI;o)*9?K%5sRs7u(aTa(9S0sm@gWIFkTMmiRut*&8?z4rU5f(`v7V3s5 z`!)@1Wre?%EYq*%>-8?YVW6cZd-XWWU<60$D)(N4y(O#MBd(*ccwR!nxoijq{Zc|G z2nS|Hn%rJ{(9CX}8oPoL`**w6Clmk~+;*9;8>}zrldMIZ={#(+i|+C@bit_EU+~Sp zfY>P#dOfeWAi#QhdV3*ArO9 zVt%bYIseC|OP4I!C-s;eur?j1*6v^5`DG<#=6ShTZpfBnA3Pg`&UA2 z1lidp{E_WeHFC6n?G4zBh+JXb{p~GrLb6^vBeaW~`#j*HmzL2m7{n29_oCZc$G7xJ zL1i#@Rv5SCQU`enyWhc4tED>49tHrf2wEJP7d8DUGmgN@iy9glG%v!Qf~?ZxaJ-tm zPP;=Iz{=>~s}9y4lwk3ET-rzuo5W4$LV2G+kAhw~B_!Bx*~e9V;)~4DPJkF7T+B8%~+Wfs6H; zO(-CDIdINhvAX3DQq5veEoGsmrVi=^?WeI-F5+pK>RGW3G&C9}-cGxq zcv3^9W2a@>W&mb@i{WE%wgW==RFr-=`h7ujEeLNSQ2nD5u}fR}n2Ppf-K(nx)iYqK zrI-);FD)0`y;DUtM1iFf8n;hirurN>srk+No`EiFP_1OF+FtbZESzeh5|8cF4IeIo z&!eQ_9#i1M69>0>m9A6~N7cCpq)+%|s;oM)%0gCh=&v^w_5Q%d%Ui2i3}z#PTXqs$ ztORt1Bc=NxRT++&sS}M-6zuZw*qCIM2{?%{DBB3I7WyJgbM_u(W;=Yitd%qW9&DYV zT(U{0l#{z4QH1B#11H>bK*T=$e2jOoHx4%&KYu-0hvDWkUpl2O1eCs=5ODwfQ{GnV z4^*eg(o-HDU3!Ro-By8e-b3joI9D!EyPPVrj^{ksXiyDW$5~iRV;Fv~#%*o~)r2>~ zfKcg_lVWJD>~U1VwT!(J$#&j}OfC6sg*{BT^s&e3i1o9Exg-ozz$a7=&4_q~`|%dB z&wwM)ug2JqsD$L3pfTn!%x*Ojnlx5np$%lw<^l^7)hRKjLQ=_N&#-Q<)TMw0>L~v!7 z2N(ECu+%aNSyfV=g!R&F%mr53ms?W&6h`aPi(BJth zbLAg@oQseN(XU31S$wIbpHQ%%2E*Np+)!iG`pI6skI(;-ZUX0Fztph3M5g14HESd* z_{lE6zTeZI^)lJzqGF;8D-8eS2Xmq)Cjk5=l#=SOM?SJP8qKff-zp37;r zp)5w32fd@&noTH5-#|RMe3!Tn+#UM^r1168hyBiLQ3F}8212-BtrG(`5|wD^>7!r{ zFZkzp2tm*LLYhT90s|kE zLc~4xDP_W@?K$^c^c5GRn!M36x|68|;y%DeE}86)@>U{OYz_dNJDhsZVRc?GmEvPi zG_;K$e<-@LB!GiE!1x4GVIKb_f~fuG6DAP$00Vt?n86G{{;%)Vx|c8Uh&@V)hi3U zg8}>z1RVBT7oT^KtY;8zX>xh9i?WTQ6^TBZkfgMIsdZ;0vBq z6yJ9(EiKwXPB_~ngIRm($)w=yw>EA)^wV#^0y=QU4uWINshjBh;DPvrtOHmB0j~M=*lmeXy-PJgmt;Ke%>8!y}Mw+N719t216m1L_%5^ zwtZ5!+vOr;aGNiQgW<&wA3Jpi8*S~7&vKH`)zx_vQ+BUFGCQ!#%OLXYknsNRrHU#lIO@Ei zL(q$^sI}tl^~0T|aR8y|t3oH(van1&V0Az6clVBXXORd|csipCTQ+RCVvIb6ge?fY z4XTN@7@BlFH6ajEjR#>+?XgE*9PS{I(`o0M)YM)tE&q5W(*NbC|2r|uLD(|&bytN- zgg8XzW)h0M5r*x-9G11G<{hfV2D+d5qYOxpQ1;svRF67(1R^?5dn$cugh)%N!!8;iL<% z^>uXCR&=LP`;4YyFZ#$5VdhF4>&jdXnIv6#q48P`?p|)g#&Ep7viC9yLk!%em?<=2 z4%b^OVS@;I%*u^>YNI)HgbVgTby|B=sRB7MZ0oM&yIx5l8UVXhQ%)IqFw&*cdQqEQN2~=M1$#AS3YswvWAtNibS`=&F>y(|!b!k_5V= zk13))3>^yVd&Sb}PwTGt5{F)3+X`Z^w(%{5){?jjp2#LFVbR%*Dlpb)CgSL; zJXJxzQF!L-F$g@@v~rfCe@>lq`wL(WYyGb19%SKZ@oIGL+7oRfG&$Unpk&fr9zskP zd!6MR(tx$6cBEte%37sP>VxT{kIN=`!KMXmkaydoUhClk)+9*IbriVgh0kIL5(WsR zUlGjtJzwA7e%2D`QEjvjI+Xy&?_Qy7C*`jUf{~;32Rjh^+aGk88 z;VDS+flEkFEv-CIA%kj2EuTVnTp}mYJV~+~(L7W0Efo@K zT)LI{nip+s(!gdqM$xS-aUkZ1p>M$vrN@DjJW7Z51@xg3Np>6tztp|4Ljf3mqx>$jKXcnV!f`Q$OKYh2-tKed9WXk~6OJA)9|Cc9YMPsuBk2^{AW->2gxZChyZ5K#}~Is0z?KKegKc9W41*S58a%@mGa#?@qP*o`T_jra>0~ zg$rRy%qG^OVi?#J3Yq+(a5Lce2=3y0r{F|>fM1e4LE>jo1dM|fYlw#Mrw4Q9@>#fn z^GA=?Cn`0;dQwgwKO%RtI0dXUdV?jt>wT>Y8elz(=eUWxoVMRg9=K>B6j{kP`J>1H z5Yq0Ut+D_5ZaMiZ^I57#8XUGBjCiDCd>|e{Ya)Ydb*8<2N3l$W`xaRfq_Bnr_FcdsyX#Q^@iALxb3MigijB+hJlXwZtNT@Gf;MfW6H>`=S=yY+bY z$y2B9p=ccmoH1w$utGS1j1-ej*PH@}(GXNop}gZce|$G?-D)_o8g9J`bsuM4)G2oZ z8c)^Ax&`pxg+8XmW<(OuSj7M>e0(qh`7KrB-4%Hj>}f)%3BA`WMzCQDoauBq+VS+O zp`mdCr9&MTP5qD0kBHIhG^U!L#Tn%ER@V;!R@?=7UK8ElDYUoXs);fev2ULWm*AP4XrquU=5ggY|^ z0WSixWAFIQPC}*UCi3fVom^4-0Yu683tH}z^5BEo5AFAYaFJD5Sl!Cw7UO+NsfMFB zfQBH-I1O$Uw_bon>k8t$4fWx$#+Qi(v27NgF zuLsnwj+-3hgPnM#1dyL&`L6j`w)US)cw}g(3^~&_Xd|_C?o)gzia@*?nZ$|?I$W#`AO$r&c5mXPnhmNOurU~hF6=>;5 z7S7}8xEu?!z|xDMBQim$20fx}KlYNUswxg%EuO)M znIgd~fRbb~FRfdK^OnO$5u$SUB7zBpCU+OSkeRYIoKCL0B&k=RG+S?Auxk*ri4N&< zBAj;xcy@uYxeG`cXpTH%k<1xy zZ)+nGN3>N0x`t(}!6V-vWn%TvI0e-1hWutxjS|5>#fk5IjEzWOXAxI!lTIx6`Oa+!l<$V+{lEIf8JG9CqgbiF?gf!P@ZGXk23x zwiB}!vX@6-#^ zf!828EVCt;Lcy>cUH4i2Pi=M=gQ`F%0WqOxC^m+`<~&;Ek$Gwvvv2!;>NL#@B*n$c(XJc}V?}E;K)UloyXY8oXc!pu8x^Nv3L=1ZidER?V}_qmC5C{u<$8by z7mi|#jw%oHt1AV8*pl_pkX5-$QsRVI;IU#p`Lzw0XBtMXS_Ly3iTXRS=_Fb$hE3g% ztu2XlQ-I}2gl6HHnx$@hE=(e-FwJ5~*rd`Z*>M7sC}K797q-2CwxPdJFpGto6KFRP zJ4urJ;$kh|__Dw#dO?eqz&Q-6K{-ARF#DS5j^HYw8VFgpZDf-c_iCH#?CW7E~`ZWu3Y?5Ix zJR##wDQ*luGrn(gVB)@jF9hN4;E7Tn7-MA5ad?p0n1m>%rtR~<*}0P7izNKktCm1s znA8wo5rt4f8=<8bPv+@zSaEqw(IP8{6_y;b!b6p*ij;R@of9udnu~hj(1y6N-2gGG z$WRx6Gl()IQRq(88|j11s06Pn{rh->7>_TPQL_s8BWK5~P>DPxgTv#}LtH$zl{WGg zFFW=#Fd{B36X=-gf-|hd29!-Yk1i+VxRF@l9wgb+F~+%TTn=W=yc&AD^LukP5;CPV zwCuYidDOpuhL5G=&~(P1g~8dxsJvw_&btwenx8hZl-$lTSnMk3)TK(iq_97LHQ2jt zTUPiuf-Z9UkPL>SoD*shgVqiuBnUOAp1T+YqLo^}UCdVohP{1 zM}(Zj3rtQ=;~1&dXWC~rxl&W?AqX9Y!&d<8J$x1+4l%0YPY=Yv!?JO6R~srx1qjE0 zV-$rGfHq}NDc%!UFqN^T3iaS{@B<2}A;Qpwgk`Px6X6Zmr|4Pbj%4K0-Qc4dvJ;`d zw~+N~5@jQjOdl@X3v=#wQRJXAfFbmIj#bK@jewbi%FWFol&OpLo~}9YSEdi<8x66j zA*Yr{s3JQfkdHuD4(!{u-#;L^(?%@8c44Pb4?Jy8b&Q@IX|N**7a+E?Wprp;EQdl> zWu*MxHhXtaEus*ChG_d$ermM-2m_>Vczp!W~S^ybRzn zVW^9QbXg+m!jt#%xBNo8ai8KjbUvq%MTWViZ%H&kFyIFXec)Lik=RBe;qQvi+ggE{ zyJ27v1%K(dq9`9Jce-rNDQH;MU^ZXqdS>x16cHZ%a;R5l?PE4c@U`d z+$A}}s0xB#7Yvi#fABLEZO0gv;S96*lS7fHpN1gJBt<1at};Masu5mA5!EPoy@FXw z%yljIt@419*WBUQHJDunYfuIEYKt!EDR{xhF`0dB!+Z6!&kLX1Q61Hma={H?Kba9U)*IjzP3+*m}L@Fs^Yo_)GU z@#S+&WY!m?wZnOZL3xDc1Vdx?8bWwPU&q_Z0Cec{PaC|Odx|-x1inJRA~ptNLF@sb zf^c-!XanmlFnkHEd{golgsg!$F9}e5n?3+e^#@+=7}ueLJeY0DPaEw`d!z$zWAQ^^ z$=QU3XCEbjFm(a463{>m2Ft1!2^x=T7{CQ@0rS|#Cclx5TBz2Lu%RIurDKV4W0a^( z2O8^C<7GaegN|6O_{%x)yqhvzhzxQs2z$3JUHCzGh!p8j{(?M!FayJ;KP)1+Refvf&?lIOz;E_ z+j+$9Byu9)4iMDSW4GUqhC(ufTMrO#9Awn!r6^|yF0@`(~ zkR*>{UKWuQ&ZW6Y=m2PgC9xE6#MG4=c0VW72LO0d(py2(A#XZ6I~!ri7eRDK!t7Ot zCPc;?+i5aUcJsyI&{D|+$r=rK;b`Kk$NlY`n}ZBcIMz4 z0EzAKc0oAUTdGc;I1vHU4&JgWG+SbxJ$rVt`mUp+9W4%w5y&~zZUm;%~7f4;GJd(oAH zl|Zcw%3n80JPQS$Uf9`)!ubeCM{WE%h#IySi%BiPdf?o12SA+r5ZVJ8XTw1OoYx%C zSq~3yI^13$Cwa^>7}Od$9IJ7w71XCnvyd>YnYPE<52Ktvg(#u&(0$m6xSvXX!?IW=-u z1C3*?ircv#g!ClxwC>&w)lT>e!xXi#zlp`$#fHEW244nLhK}A|j1N5sb-|fQBha|D zZh$!xrFvHu$?HUEcLocOVn5VeAW--b(5wf}=ki^@sWi}>6(nP3BH(Uvd9<6~7#{;$ zwgR03Br3=0+6#UP`rZkuNyPl2c|nXR!jUt^ELbICbaE>u)iJZ;2*Jm3S2~TKXqlMe z00`>f@S@>T21PPC@)YwQ9fPSR87={6pgtt`y_uBP0Cq+p!eg_G6&eG&UM#DN6VmOr z;$#7vT(}#oWfX#H1okGmr9{JwM4yQ0PEVy@O2d@VJr@$g5e0?-+b94G1fV_zzzhKH zKu`vH;JqR;G?!DX^d{l;MA6}27y0yYEKxr}Ag=q$hxx#T#N8)+?p*yHS%W;dHv}*CNdh542F0Scu2Ojj z%o35&EEnEO04NkZ0T@R@8a+QR?<7!4jIydgof<#WNrWqhHiS5k^K^kqfZ;3))I#pLC>0tZdyu4){F(^+8@- z966cz8+x^+s2obdV!NlNP6zlr19mTqFtH2~u_=1$92pnI)6kAIEEn?x;U9S!p&rjpsgdY>x?S4pnQl8aSQ!ihqMNI;XT7ab~;ulsV#F{_B{#G2S~H-A-hQrkj% zY?lvB=+JXAnGa#o6kM*3GLU9eiq?LEWnps1{bj^~jhy z162eAQ35!jnbcEZ!doGs2@(=Cd~^GZ;pZSuWB^w*5*%BSpHFz(Xd#vRp1K9jfKZo3 zX1@hpeAQkWphnNFe-7~CMOVj4GN}YDT5+U=^ybkggkbzO-(Er&P5`u=Y`5I8A=8!+J3BkB{xQ8Ys* zbUE{_ox50APSPcL@>5*H#|u} z^^M-@;v+g_uTWST{TS!Jp(uC&0mGabHG*aoo&AH5f(X=ukgE&R&##*?I2xOnR6r(b z45=PJ*GX;daOh4v$9WXsa`Yf5CQcBaz}+UrAuD1JF@X$WLQ!m9aThe3eAzq7aM&Rg z9Dzsp`J*XQ4ygGAeSvrPWn^wD^cMpEQZ)vlf6x>n)Cf2u%)EOActbc1Q$y{g3{5>z z9@EA4fTnzO1^cHX&=0|M+@dGY9}K&?8^I0$$)v+R(cS?qeoAu*%eiQ zCe6IjU(as)MS3Jp$7-4BCxsCq44n$38adldr+dp z*M2Zsu_yYTvGia6@*#r63ve|DlD%9wd`hXVtVNz%iO!`_)E3_~cG|(bUo-nHl}tQ> z65it&FT{zr%7YK0E7Y}&i|A~PRw=0QZCj@gqSdP+qkVf$6Br5^CsKKOt&>Ms+JIOR zvMdhD+UbFJsGcD8C-onW>>1+p(v{y2(Kszqa6N+cu zh%Z6!4=ZXC>?=g{5r$J9c{%5SXY2?8*Z{Wcwq&G-^agw4X#vKIb`~(wqx>P+-#kQ z8xWyZ11d%8vM;QI;%0fJ$Ws!v{18;>p5uszX|6!pi$ov}i8cxKBb1^)p@a?Nwo7>g zS&S|`Gg4o>4F^>lwQs)K<+4@Cn=R|WC*b&UpvaOK1L`~BrylJnaUFF)bgv6Th^@WM zhxTtB5ZXAwItF?q4#dbamJo{iYvYdrM^3omH`)%t=JP0C!OLlN^JBApB+eYWKjp*k ztX^Y{%9tI1z|&K|nBFMu^Yi)I6GgW1uX%(osJ0A20QW zn!|OM;k-fonyK!)*mIyJT`(w>DEOgl!JN9aVI@}L0#a2F*kWNOm78xXBxp(!pbb6P zqUM#DFr>Uw|_>37}V& zJbH`I%Tk$`#xZFt2IsIBg#m(2;(~n{n2h<5)Q@1zdSjBCWl$}|4~4E2JU#(jO>$_2 zBxgv+6y5Uez^96W#n}rfHd22?*?{4dA-44B2aeJ%NWu^?+zfPR6Lw*@&mUCzDxma6 zBb?BNUmyqKJ@>KQ$Uo7I90l`_85KuyhY5VlJVL!yQBRBSkD!Os?40*#2ZX4&{FlsR z&V4VXy07j8{tg;W@nl%KNgZ+3stSU8;(!QTb(cml25TY>fTEc57Y=yOcge@VU32hrDX(QT~ghH%lz~> zv*qe*lhSIg^8^%tJ6|3$4?RD--dtTgZ)}1!kjm8HlShH+p+KtB$Unn@GT_77reL(s z#cH&O$-;xl!Ab+w6vZ?3Kn>%ft6v$HVWT2pr(m;_;1YJX8#!`>us=dNQUCz0G#npd zt=@4=OF~AGPLMHX1SNS)_LVpSvomP6RZ5K}9BCnNlyuQ{PWS~y-trvvy@!c>2J&$o z*c&8+U@WE*#@}8+K^3S0)xb>O0A_$tcQ^8LBob0ZJ$tYrMh8*{2^n?@aRevIK5{%) ztw8yKd4iRDNQL|cyWA%BN~!-v zKmoe-i4icek?_wAtS?tVVCo~zPzUxR@~ZmiOu%3Ow4wkDM$I#G|9F!D3>@f?B|pYU zlchlytQ6oH$+01fKiWt~7m20m0y5Z9&+SL>3}Csz*w=cXpHAWa6XB`l<{H{zvcmkW z!~p;h4mv~iHShBPZ%9xtGs>XgKRa!X=UTxUU=v6!{7sbPk+8>!mvdGUl{7OxI}{Y; za16Q7DTzey9Q=XG>(BJBHy%(?BwZWDDF|=)x2q#*MV7@2z z!Pqbo0n@$a`4Kn|W@;nA;ACM@E1?m_1!aAcB?tB*IiN#F z8;NFZ(TC&BXA+7Iml&WVA>R~9=?lQD)xykrarBNH5Ht@qSux^)$>S+5 z9_)UHl#SfhclcJ~#8Cpd0X|z~^{6^>~&V zUFU$Co}{0%JNQ2v~GTcc=soA`7 zV+cZ89T*p2A{fFJhI}zZB+dln!5v6#3CaR7B{-9nD^^Iu=gK2^Sv_e&TTU2`U=Zmc zzlJeTxN@a^Y39qF$oY@xjZKW{>m&7oegbj=}F1heNR62TTHF&RpSW$2~Yz{vQ$bAppB6QBn; zY&mdNNr@Urz&X+YlC9}ZJJe|1=E5@y<0dq03`hv$+{JKM@u|qUI&|a*y?OqOk^eYi z{In0^#j*T61TvAJ5AYsZ2X0306U<*FaR!RA)>n$*F`~h=$@?o}{*|HHlzCq7!eu@k z!iFSy8&2eOzBj^kf{@R@r`r&^&XwRbZQI+xgR20D<{@Nlwmft`+J1K3{7382!j&jq zCt>}@(6F#enFGY@d5@X@47I;7ST$B<4oq3`wkKXR>(1dH^@oL*IvgXJG6C`MfOhJ^ zg~%Z?oPVQyUJ|*%2MG-i;Y004+J$$GDKoYJu!co{Ct{uZq2&8ZF<3@C_yjEYlw6;!K{K)Y? zWgRDP>QMRLcM+EF%@vga@av?o9jZ2@X#E$d{FKMR1?WH_@1ad2QZEwsFQu7}Yszo_ zEUC|b3j9Z^0_7ysJ%%4WL^G@kqG)4vz*r8W-RN*H!zwUMenZDqENs>MCxp4!-v~4D z*q8A~GWPRAqF(^_o<_(a1vHS_HVtVzN$PIN;%$SO;1CGRO^(OMJoIix1Jyubwe(%V z{L3S9epCN>ogZJMHX^bCijU2JL#B(Cvb7Sw;SpzGD(Lv5;!Jx%sgZ-^PlFFiEZ*n; zTt?-OpS_>|{AA&q%|D4L3;+Mm*H1_P>(Ko38*qdP`N}3hHYuQ-h|D&_u%JO$>J-l9;(ympAi*8BRxcF zq&)X+8X41GPR_~|u;8L%@5kW2ul*Lw2U}eArWuz%-$ve1(WQ4yuozliwpz_uLTitv zoPvgyrn-6S{-5Pp_-=;j|3ky^&AzW8Uh0X?mb;&8Of@bA9@*m*!F*drLX=*+O8e%f z(Ld?Md6&}MykjQOw(cBn?e38JI`tz*Z^|l3TneOGajR^}%O=gH;(;u|LQ`h@iO%o- zG;gRVH~(;0{8_i%qx{z{`t>K|@&8(v`9tt)GyK{N^BaNu=htTVwHbbGhJRMz*Jk)< zDSlaoUz_3AX830Xer<+-mg1LX__Y~+ZH9kV;MZpOXDNPJhX3cAVWw`7O7t#jCkm-e zu~K2On4dj{k{-YPtPP|RUeLLStwAd}IDb<@9OdZyj%qTjDJhZa@9(d|h-(Zqjt4B(nb&_2{fSf^!59G zd#Z`5*BQ_TqA?my2_%e2KR>^KSrH8AfD|ZLn=#%{I0e>8b7AGb-h`4B*Y(hjnj+O) zSSSu!a#C(yUN0(ON%8SR72lF0dp>=74#`=iw|D75hDLZTJ|DHEB7F>!GTUsX`s`&i*k`VYV=r@Rhng9@7 z`;4T_OtoUo1pKHM1TLE8ZrsO1BCeh#nLUh0>={Fr@<% zqN=LOzgaRqHB}jcJh7M+(PNe>l-kg5re|lD0o^Cr)KvVxwF(rid!VfZ6|rQyvy0HX zZ~ZGAK5qb5Ar|*K!KwZ|$}m}(^zLaUSnivc?f{{{6lJ~(%E|(-c`&?G8ZAQMm}kn= zK%f2hZT}^QHoOH@i4%0?O_Gw55nnjDxN@MS z!|+gOTrraG&MQ<_p|g9Vvbs9dAF3ujTex)PG&5INKwWFdZ_p+zy=LKw&VS{-yqj`t z9SU(uD9gT;?`Q#~N5pQjNG%tXnaf~glzsg8C%!m=0+EMalgpr_^9^ca&;p)h9!k{1 z@ph>xU%d4$qol}JYKp?3VM=$X#dw`o8yaFBVxwoHSWCv7IYHZ$#qiDNyHMpfOjw%; z&~RQCK)J*kgg08W-WUj`ot|^v;PB!UIDI>FA2KoFsNU~HHFV3t zw690g&<%GOwN2jM=!8HN|D`cc2K>Z(pjHczH6lF$n9j%x`jwl7nysxZhC&Nte8Zzs zwJ@USx$&&fm|UwDx>JtJ%ga|*Rpo$1(^{l9dmV$01R%Z~2px5>K55h@3l&-+(czks zl7d-c7fKqz0LuZ2J~F1)o&%91B8J_czNieIweAGfmIsyKo-vx5n%>t!Yd0;r8=Vf? zd|nlkVglk&Jm`dPzW%+6rWCt72R-E%QguUZzI}EyuDNK=?B5M$ir{3s`;e2`%ns7z zF;W5s zg7b74#ZlwBt4|q6oA8!SpaBRDeE{KUJ^m{1NQ>WHfq^$cIqbt&#Fc4l{{8k@kB(t2 zK7wXQ1}5(>!8_1`t9=iI`{eFfnAdEkxo>&dMwv}$&c{s%8Kh*UV;AQ#&3<*v<{-2K z6_67RO5U_S*c%9;@}Uo4Dz$-OsB0oN&lw-;RhvtxtMgD$r3JU*z*n(`_E)tSh(_ ziM)_gR9CV8K4w|q&3;wf_j)1Q{t{{i-aj$gyx`3Fdgw>cadC0s_TF~-@7}vtpgkH3 z)Vc5M9JE3nf~v!K{k(D`nj_=Er_j_AnJRnO3J%l3|NgL>@L_j=Ds>NZLRSB`W7WzS z|Gw*>B_?ng7wu2p<&S|q_tB)D)*hmRUJ+^Z4YbZc5X3bOZIhNoK8G$H^}Y7@iv1<1 zKxtrEEQ|DF&^8g2W5gtkH5@*_by214`PG$K=Z=HvxgPzty2h&K&u;<)J74b$2u*Eh zp*A$mK)ZkidLxIuz3!4-V{BKwa7JS8W1xA4ABqX5gL8yec&G}~kqQ`b^mn?Y)!aE`F z;4W?$YmHvxNxADI9bhFpW311nP7ebmf16{8Q7mZ6-Zl8PxDEtQ z8^~c9nL(sv?wPQy)sgWL}?It+=Lcg^Bm=FU_3}%*_Pdg0G#}B>Z!Ux{AKdv-ibkR?9WDld6 z>qM&!dI%%F1elcY-5&w}BGkL({Mgu7JRD6nhfc=DSaWNTi-RzNBxwc$o7o1*P1Svv zXKy(4=@xaU=OT+BIzp^^+U!*C{SkEN278NuCY^10epMEjlT!O?J)bi^;R_qNWsqcBZ6H|_ z@r8QJp>4()C??B|H0-HKMRdSJ8gVYzK}3$M(|xUSt5i@I59sRZdi$+m5*8$`O78l< zyf1}vDwMMNL@VsMq;CNF_#?h_rewy(9;ljmU6`a$KUnSU%-L)RW~?zNSKI=7_wRQ> zOvz%$ad_dj=D&8A4cy%E5{q7&pmny@%Uz0}t%^|!qDXfXh@?=Y;crWQgRCo}+ba#8>L5)QZKFM$B`{)mPvAB!tQqvXsnuks-pbFw+! zj_XsuH3Mf?p+}&-FuyaE3lrc$pbiAvrp^)`g$QaJS^oQq6b3<cee)`c<3P|uVR7Hh zuPA9SBAYsu_EEGx_pg+vsDfhO2%dCt37Qr+Q45WpQ@y_SBpfNmTl-d;G}}%0Yuaak z1*-^kqn^ntr65aQn0YHgLlG7JmPSR{aI=(wB3f^QdUyGkk>4q9+yOk=PM))klxyuc zM?0Xn-<)lU){9lIPNHvoeJ5E1C5zOfY0B^bh?n?47Om-yaZ+YE$Jw!ia7t zaP3d0T;UGo4{cOh*0$gARhTJ$7tyVrY zS#71=@vm7BBx0%X6JIS@a6GjdW_~exswOr|AS)f;^rQ z5Z+h5%6o_R4Eb&dy#yCT(L4fCk&zEzg}0V}U-bI+rwB*?Qfb+SzR%g4eUJ8bh6lOs z$=|ws=PIM8Us8pJvT25(O~574i`FlUpbIKCUli=Sxwe0yzov*WU9zod=azlKP{M3W zvO#br*H0YCZU`AOMAM(Kgb#O2&io$39+ouU>~q$(M;2oyp8t5rn8njFH8rfbe-)XJ=xdU`YESFMF`IOQp-nq_8nT^}_{0})fxm_hb(@ZOMFtp-it6+_P z|8^{3ZYmKD8fs{neO*^~IFEq_0U3Xnz#@aRdo_9H2(l%7H%C%@_p<(c?Vx!>s<{yf zG|DO~EBnao<%h5{-Om^M(dXAlNXTH_7k_^QO3iP!S?jlC2pRk9m5#gJNiOm*emTgE z$V3r>tO*H-$#_B~ysn>{Sab{L6yf`Sb4B2nJ&9mR=HM%YCR}6_mtKjd`1bZglfZXs zEdm2^U#1VKpi%F!o2m$adBl|3pWCu(ktK4wdO`i%Z+rIcHSwQ>LYiOC+L*VQT-KW| z#QK%nC0AcTz?LjO0fpji;OTEbDraP-ih)r`FTNZZTojjxUV;}`7aks-Ke<01q<_Om zf%cS4kZ?)+u$;NJ6Z`>lNyYp{fey$|dYkeEm2m!ygyOJx??JRc)OZWGCb5Kt({`dBn)G!RCOeM zx%YEMVTW?jown)?n6>};m-YDw0)lK%p_OOGYwq2{UJmun#A0So;%BnOMo}u(=%!_c zj`Ak*#F_2k&xgnHF84Pa0?BQ50ncwCX&V z37LXsMC#FaoI?`u+3Vh#TSHt>rl`c!+_Pnoqj$JL!Ux_?Uz0!#0M402zVP_MBU7AZ z451p>)QKrq#>f}L9{W)TOgDC}?}T1}jBcI%bVCbluGu1!@%$UP79wLOuwZxjTVg1H zY=Iq=71wueR=IZMGT+;D7Y06dkJD`TS$lEj2_l)~`w-95qtS*|*v0}~`bjyHcwUzw32a&V9f{$3_)s0=W;}gf z$RdpRuUfbk`6~LFY&cpTLzPw=G#kVtR7=y0RZZt7jxL)6CJJ$ChKHwTZpc$rZwo|` zEQ4>MiE!3e&8+S!lGpm4X-pdqM0l=l-yx%*@bue+QSHkYRhf&To2*C2u~qUNsFsp^ z{Js`?TKsB0fWpjN0ztZU*qx<%nsl)#J(1ay2uo?<2R2Brr{zbvGs4)qq zO`1$=m`m&@Qd@Emk`6y6(wW&B82@I0pLjiu9<-ZCjfaEX)QNP!MghNb$@>AA5u`yA7n zi%%^=VL-Ij@#$em^koQh+}DCx*-9`Dc>ArR-$`zU27_GaAJLRHA)!NGp7Fp*&1hTD9!rN4euy?fLCl$PvoJ)ntnvFbJc(1Pi$2*W?V+dQ8 zyeQ6YEXue_ULi->DBZ*2_3PK%vA|v4z&n|2Qj5bb+k!VZGU&SuQN&@R<}@77GlI$5 zWr3JedQEURf9L#zE``7atKEoC3o&tR5Jx_pmH==C8VH;5I)nP3t?57R#-a5biT%3K z3~Y!wk2~TU8!9U|AT`D#rP1;;J@1QT4D#`FFz)xj^B2R|NZixjcywEwze*g8E9A0Z zo{y$(VZU8rsY(LSiWlxx{E-%w#r_rnZ}_4%`DiaIkX{`4D-Y4Zav?MT<5TR|L-7Esr*$ zee?mq0}+zb`)WbKpiL1yN&6s-QEUlapL<5Oy~+l&(~G?7?yZas)>PXrBE=knphGT> zx=b-2q;538*O$ilC|#-T#lCzT15gsGG=UVwR)Cjhg%)`~hxfOZ9Aco7!jV@5z(@9q z$Miv@cO>)eVQw48jK~j)FV&CiY0*`YmR<*{JP;_&_V0#^cEnn>m08zrL+k&fAPnA6 z{?3QT0b37W*TR2W;eK2oVGxJkK1^%$I-xdQUqkZQ!@$_mn)o0}0vt)wnV#o>k@=zo zn{4jSe{dMLW?OXnnFpq%@C%Q4l_qw(f{1?t=>&n|crqu81&y9b0-JJW^|#oe3J>!P z&;$mKGmSE0mY*>a{5%3w;;ffJUS|XMBJ2L?ngZEGcWU76p8;->@M32M`*m}v(1Z%v zR8SybWU~8qsSk7S(aOe%edG#TFNOwv4M=Go)~|i}t#xze79cnKYGX;-1cQCEqk|p4 zcm|1x+TOT=K!?Xxg!v%M;SE#dHWM9E~8z1XtLB^_&`cm zAooVc1YLlN_eYTLZPupw_i{V522xg^d{ZGMuwP1`KXF{O?WL@$>Q=;__n}dhII*W+ z6T`6k(-$qKsB}*)KIr0qb0-(Ku}~=N@EVK%=GRaDy&k_-5`1#OHB#>3_&GV6hKI6if~!tL5w5{^@)Z} z{210km&aft0d3&4j68{Q(7QB9SstUSYBAR83cJ_t-MjChh@FF?1|#S+(Sz$2C})DU zs4HQ?6Z$^1=S_Vd?#mrD%5dLHnYZIBZNe8}< z1>qkX*IshWfjZ>Y%q5*Am?) zl0|dk#0hCd#VzDlm@v4P-Af`SfM#gUe=WL5zVV`1+J;fc_p$fd+o68*pMMUw?ohU@ zT>?slOVNSU=<`dfFA{dl0g$FZ6DTMc>n+->X0r~LC)?83Z-_8LKt0z0r6b9z2}-6p zX_h0`H+>&CjlUtqQOGK902js7?7)BC1(Xhros_#`C}bKRzMOr}*YUZR1j~Gj1IoGA zt)wp2VM>uN_^|Qdefb8+qyGT&$jzkue^X&X-Jgaqg$T7O)OH*0v8HS@hip9) zsQyi=IhnW%;|>o6F)#thh&(8^GNN(F6&#`*hze@Vd>a~qhN@<|7>oOTaQ+W~bGwn% z?}m(lt+SOes5iNoCaBw3gM&jT@~xPc@(?b_?Os*ngcZ0g z#<{dw*&qaLY?*GJxGuPehAi5)18dd;vVk+MnG2d^!ay$+lm$`1Ca>#zjoV4>0=IyW z?=ePpU0m9*_-c@Dd)+TW8~HMd^6?lM1M9>4sZ^TD-)6Yr8NaD+wUDGY=Y3_vx6GuL zuHEpu->?_fzzH{-1Nz+t$gZlB-hsoKAD%_m_@d;Cf;J1TZ!9`8=yHr&h_i&R)0YH-BucZ1i!oJvzDdJ_s5yx!(h9hEK1?psLxShxW(8y3^Ir|M!k?xb=V7 zd-JfI^Y(rG#uy`piAX3j$x@_|(x$~IP0@msv>8Q`HYug`84r_Gh(y{fiL{K;zM5$v zDn$D>-Bh&PlJ@O;UiUon{dnJej^leAzdt_T-|_p+AJ2G3-S>NWy{^}Fo!5Du*H5%5 z9|c;BwF;7gBi^HYQ{U4osy-7U>}F*J%*|H zHdbQkU6HZbIW|(A-()#9YKKL67Q85F^Am4l$g3`Euw01~kerPwZ%?n-t8|0<;ir^z-DQw~QZMd;uMO`XeR@59R%lqb0x85#0e z$zE#JOJxq}uQkp15u}L24IUUwQUcf6xg89?knhPetVN5jV-B(u_yaq-Pk@PIiP0M5 z`#+xL4M)mW5ageZe5|LJ21>$U=ScqnFd}+E)VFHf0LxaeJsx>SISs!FEz$ECsf_nn zx&6v_h@O9WNA(86qcfu?tCPa zy5?d|AStRu-YXDmiYR4u{o7a0KL<|Iln8p5Tpr2s{86)|PKEq4jwKwaOLtfX!PeQa zv9b73BJe<)q;QRKHPP$&SzDHGz+<`tQk`oqT+nD)RF@hnCk(R9K|?|CPd#dw z2)5cfXs4oFD)7*5Lb)`<(-7=I+kjZ2#+5)}H#iyq%2OeDrYX&wWW+U%V}jR#0RDCF>uMaeTM^t+J7JuB zW=&$ojjHl&ELc$bgI*;Xfkv}UD%Zfa{Y@RX?S|~gY6~Cb!IPh^T$apKJbHDKYmq6b zYc6hps2|nuuF|>t=!f5MvxbIM-~UkoZ+Df>k<@DQCGf6Ibu~xAb2B4j$oHVO7LMkd zAo?2*=3vH#iwuLJsP^Yd1S~780pn^ZH(Y(7am*1nPHOepEtpVOZDyn1#uA`6xI#sWw_u5s`?k zR`}1op!-=hI>QLG?R8g5x#F766E-$B@#eW%#cB`oo`PxAc_Oi=UandMDNt%>QtrTB zQ!o}4l=3$UyVm?-T%B%LZ>V|k(>rI$9GTkUr4MEOC&oPxpjN?h6a>e&;^9Xb*GWXk=vIB4d898p+@L792>`%GWk z-w~w{>9&q_JNTT1pRINJsyzp#ua4&pkSqtk)Qe4C0($!Ki5yT>*Y7LvC7p^Wp25;3Inm3{@je%Ggh-A3Sw0>7tJ#-h-6s0ac?s9D;T_zY% ztvCStahoB=sPHm;*JNyxo%N7sJ-sF; zMf9}}BnIISBKBg`KnZT)U8muNJ1AHVnsM+qx)n*{J!3=zuk0H%(ixk zNCeyTN!F@Y9_jZmW>T6+w(%bDAUD&jK!1cWxd%;jL3`f$5pL z70nj1Wg(rTX>!)LPHb|i-HwjDd2n>o?+)VTU^n0WP|okRK0y?Na<9jmv=gL9zKnG)Q}+cRFN z!fNu9e?}#f@@Cwbh3B&#i`ETcXg@;US#0ee{Du#9z<0%njstwkwgq?C{`A8EdaQHn)kdtPpkm_J*A~ z4$U=q<_(Y+84qGuc9D);qk-n%j>rGpl8k4dBFh}=GcH9CLjxr8@XhgmIp{oez&0bn zTFo#kEu!RoEY}E+fsZf$GOKnSANIlg`HXjQ_gZn& z{-}sm*X6wbV_M{e2MHGWD%`7&c)CMh|GX?K(WZRl{2#gZ-UbM8>gDY7#|KEcSEXES z>a2q)FI8n~|6C>a-+^j3XZvEGa&vRc*(*W5F{n7!C>y5?<}Q~9>Gr;b>da&BUW!}y zxq?7Vr8P*A4Z|r2(1_LW6!c63?)K0S&r2UTtc45QicDdqmC!qma2 zbsiA9L$kXcWtoRgal~s%?G!&9FW!)S8ZjHk3=xE_8Y>a(-CF)NIQCHvj#{V2k34=q&^$mad`7LDz5m9gI zqmEZMQ-X$Zt4lF0*Pj+)|L~4S|3VTU-|6n|QaMt6OjpOb>NkNNvn|;UL>8xl5A$!5 zdzSpTPptvV!9`}lrwdMv{rt|<7S-{$di=eU>}m&ZVgAWJ^#+W7%IGcL9-4dmA1=TW zu4#Zfw5fq|O^a~m$E9Zu?nYW{2`=r9ojd0tTJ)BvPOK+_b3~Ms=)j_>xY<3JfsB=y ztx~dT#!kOIgKgn2f2#76;a(q7qNZ*LV&S3KCrx(Y1d1kBeL9hAQJtLh+ z(TR9Wt_4I2Ck8Iwa$e*rWk(Fm394K1ixE5``4D! z-z&*{+dTHOtW8*D?2?X@XI^HzV>|l19egUh^5!W|WOQ=b*}iq+&VAji-G(QGA%-VG z1M)|hwF$jqNV9=6@f$}~V)gCGaQsW86El7i`X^vjQacWeiv!>gK9c~L>L|+jH;qEBMJ2r z7czhfJSdn^iM%vVjhmT;fG?rf7yo1q3K}=qSloQ@K&E-eonH_UpSmdc>7GYHwR z40A|@2+@qGcJA%s>(7*gVqO$iT7JCsQy$K-7bmRA5|FbXX-}2wRikt5n;&ZQL zWkBi0!FF0pge!`Wu}~O zjzMZ1YqrZPoT*{GBgp8J&8^0<;An@jBY#@UGV1SA0R$OuO~A9Xc}2f7h3;_IIvXLq ztwDa+zspJ8^Bl+3(iM#K>dq2~L>3;xWR(yPQs~4Vyi-1Y@8X8)xYA4A?S>ITnoFJ3 zt2SI3M%K%IP^o*C6e4Vzo>~ZxjGIufDrhtAUjI0hZ<6|^rlxPi?=SOwzu9nufy*Q! zlLkU!O4u(Jq-XaAKS&fxwU+ndpu9yko=>=5ZD@{ux zV;79Z{bduHDMEw7$DVB_UGPS7wFzOM;;b&MDT@xD!9a{6tyK}1oGJi-CQFZ=^BJ=& z?j)7x9^LZvxY7ivyrKP?^dj$qoK5L zdvN=eAAeY>8@|VK0|#a@0o8hnZ*S4g3oLtbdE2^7F$m5~-}aM+oK$H;FGBMSmiN)Y zjVW}Tdru86lEZ}C`-d~`HOT$)$G-`+KYWY<*|J{6vT~MDS?dNs6Pa6+9{~tJ7`cTG zUR~R!ZMYj0^WhaS?+LK8oH9f}Heuvgiz&@1Du9+G^e*OhB|jPP&|OD36>?a?HHPs& zd!XsoO-@5a`Q!EZuO8))dYIi@3xJ|TJT`pi@)S`~tfU2i!1O{!C;BZWWr3yduykhZ znHrD&55g^KeP~V;%T}Atr=HtV_yKWy5?1&FY1y<_ML- zRzRPz;aH`PtaPWv#2X9gg-r-H!r00Q7mRBS4GaXZ)4ht7$$SSsPHy?u1ZIe!HVE*b z$G2KSqK;$C&rkk9P?;r`dZjnInv8X5s>WSlhNdp1=`DvbOKx+xd)rlNhz-3;@?Nma z>*I5g=?w-FA)$hosxirp@L}nmVJwvSdWhTJWmnO6AmJE05HujYGnd^DpdEZcHV5aZmeAJL9&j(lc|z54ncIj1jw7}Q8YLi90??#nG}(*t(-JWi*p06rY$RDt@H zYLD93(TWHqIm{)Dbkf5My|-3WFbo5p7i~DWy;zwHu*f*+K0YruZxSJGKMwC+h`6mA zj@R3zYdAUenm6a)&=heOOUxaplNcOFVIN;L^C2VlzCJzG@oPdBk#rS7yN-kXSbD32 z`Wp?4N9mB^7s3=J!l?r7$yP*wb0|PgB=smGe}#T>1KCpv4UT^Z%@07Z=e)|Dg)Ym02Gh{l3#KWR{G!eBpIv+XIt=z!v8IAR+PCBP@Os-B2M@^oAhfi{;&nh$I zSi2`u7>`ZO{#C_s-=B7)GH4#DO5YFjJ%0Y|5bre-J|j{B{`4K|FusV;v=|R+(9%z} zDm4%5j(v<(4MaoAFzYykgd|;*m=({@je-b9R#8XWP0*Ah!w+5gzy3|df6OSiB?UCN z!L{CwAV>|gi(mBAqZ2}lh18`~h!odi;s!N|HFxZI?(KCNPz))*7eg=mC?g5m&k2Ky zicwzWSo94P!|mn45Z!h`<<-BLaKq#QEp0TFu6Zwa(}4vqXl0XIy8$2ip@dC zB&0_xSPcFQ^XP%11zcp5Kk|yg5vqq0dM~hcvZdL|)S5Y521_qnGO?2F=l?*)Y3nHh zK|s5qXY~D_bJ=K?o};QpSK-Yi0_c{)FzJGr764&I9ERVa{*D{adI;#>4-M>t`F;7g zg8R51i9tz=yiKG$ACF9zqgjj0xmfzsr?<#VU?mj7@o9~6e|qZ)#INN+@}eZsrv4QT zk;Oc}n<%z*XRJ)ZAKAbX&%vpIIxF`YCdq#Qn;@^EkJ=;^s*|3$Lr$MEU(sORU@l=D znA?3f?TSIHc9&&8C6Ut$oI!N6oC~uWZ^Y0oQuC6o6`w((P*4A))l!`JoapKsvhn;v1 z1do#XIKE+$dX+}z?kgy93mI*%q~;tZe^r#;Ek^%?PEWG@3v6b11o%!1o$5H9^!_5Y zZ=MuTADVi2KJt83t`2z8knd?v?xtMeyh^N>bVIsWm-OT8#><&A~EkE278XhzM;Y z!WPg;SxCk-_^E?Gh%>HWM%Kvi9Q{KJrOb0o-pYyo{YIT|m+C-oK3tl8SQn`>``x{y zpnFMqic|y96UZ5;v+YI9DI|gna=80|91a2Ap@mqNX19bcl9JAH#m;znKw{39Q*k_H z>$a@>itqtqfS|K1fGy#V0fU7w6cdJk{0#8CVr)B6(Hrn(puDsL(;Ery%Y$6H1Vh%d z^ost?wtS5L7ICKrDglKC7i>=25(oHKEx5VXX%He4D-d#i(7Vh0(L3FE##Cw$c}Pra z9>0&$ba~NM%H_ZsS%p;LgAgMkv3&PxPmw=KJel=qXg6vXXayG%@@{J}x;F<@0(V^o zWW-XlyU8*=g~CnFZsrhykre$2heXS%!daVnIfrK<4I)AU7X}CAMZK_DyMUjcs3ruB zQsth3?kt-cN~jVh9NmdnK)9xC?y?9}l_#`89?PBJq zpZDS`5aQzK52p(jQk!o-r!>t!llhrlcmvvGG(_15dT^tO(hgabUJJaKPvnjkUxCdf zIK_Y%&`4~&m^aNIikgoVwIHgXhoZCK-^^dAS%Y8TdP4$*dGMy$-&R=hm>-oy=!glU zQ+5_TEe(XJ8+Y!k9(>6BW%(BD#q(lX;g0zH-#^8AB!Sp~EIh6AWplFX6K@gp^78gGuTx(W z(dT!N7aN;aVcYSO&&&gx%9YD5{MYBupYCkI{nQ{pi`d>Zkbp_ntxdO>pG2`CF&b^M z?h^>fN5dIiP;?!Bo|5q^R=rzN70>Uj#6xvNTWxEwm`6O0%y##mnJY%k3|n_IIzp9+ zJ|7;hQqX0_EH$%R_-l~XDihJhsn7hD=dUC1*AEN+HH}b(Y&vy+4i=-1G5H>fTx4F1 zz90o-bS*MEZk$DIYpmJ^e@)bg?%E8~43?T1Wki&3_P-k+e|{-q>L&E$r~~t*C@2Hy zYav=oWg@XGAJnqc-+V33K>S%Omw!!lT;UBDTXp#8x#mhKO?N{{)7v~b-t4}efpQ_3 z-Da7dp^5^T)_g!#HHoPP5)0s@7XVgj5fJ#ul4Hyl_|g#D&JzrqAh?&Pqe#Ks`3;%O zbffAP{+ZP1BbtW0F3+;GyMee#1k4G};<|Ns}WYe$KGhk}F4^+K{9{(7wx zjzzQ#%iEdDLO%rydWYeMgu{BZHU$Sb_xe1TpRO;22xQ{ig91~&RAx3!D3DS%;JR4k7pt-OW?cd`NC{$_`#B=Tw-tFhA)3=z`Ag-OZW+!u&z_FJGGJ+pffXqpXlS zyQjB+t}IQ?M#V_``h;V?r_RoE;B0Ok*MIvU%v_?r+Arg#zK6FGTQGk}gF3fBsuqEW zGaO{_T@%_PLv3>TLb2gTwW-c%c4A)iqiDkgzE8MxMc9IAfS<5!JIu4 zsq9gFNqiS|{7bphl>h5uX87$jW(8p{XT*P#gCYej!X-C}DvpNM5Maa)!b!#CrUtqm zxt@{7p*YnXHL%JO(@O3%{;!XsKj{x0wwsdCRapN)qlNNw0y0obIKc(42uH(yczwF- zX8EALTTGpt2X^%v^T3KO0j49M6?{u_LShPY*$d?1%@HMvST07xvZ7x6Zuk%)QW8<< z24MW&o6E*mlVw-?h7of#0`yu@nC~X?CHZ%A^E7m8ZDNX=rIF`R(LOYgo*(hsOXj5; zXeLOon$b=r>Nt@c?TecIK5DdxX|=*0)!(Bha~091kZc8BSgu(NLMt^f9HN#-5ceMr z)=S8msTH;TIorg{mDIUJOl?T`XfjY+x-D32Z|dO%gudp$)r&6d&D&kf3(yat;;ND= zA}YUBL5`*L6i{rh{i@d6N|Co(eM6}lJVKU-C$`;{G1;QSVXxBt}@I&U(*5$m` zEK7#Ip9t~*wSPblBUQ7>@8?m4QlBc^LnL{^y#Ru$uUWt=+v-K!x6?$jU|jkU9RZb#Z?A8IP`pf zlr;GaQ|U*3ec&9sbta^@g3=!VNKpx(RKDhI={J3s&Gd|p=8<0*xU=LQ=~c?SFtwgn zbyFSH)p5?SN1G?T33KCODj@1x_P={&bGCp#B=ld)i4VpGSQbb?E-}llRRVk%2_sAa^?;AHQWQ8fOR#tn2d=~>t%Zbg_L(7Owcn%FHC|4Qn zg63s&>OtmKbKHm1@h05E2q)&sOHj$3LvmAye4H%NX`KSuE3qGa!k4>yfyWwcqeWn+ zx)AK%3#OnlVHHEAMtRAcWjx91v>;S8#QT7W^cjFU>gt84?Wv)5j;I!YoSJ2cHE|!y zj$SL4VCvq%?J+y4!wFLU7GfwrCqfyV9G9Zheh%35h&Rvj;0vGn-W&^K2e~3U0m|ud z>Ly|qlt*MPxt~->fcJ0*nlknc@}OZXrk))Bs#tY`t-2L!;KO+l#xwE#DVAk=lH1P* zS^I-9GYtDq+mq|b+>b2Q1o~5q&tUz(Ar<()E;srA)&-e9Jf7DVaR@Yty6Q(4miGzs zLNkfpdD8^KD2O2o8{DH8vy)^&o5YyGj0;Qc1EJ-Dc8seDj@KZ?cXv7fxkv6~h9!NY zmru~NNCCXfEmNriMUUajFc<3f?h~k>zFdLg=y=dcXx*1_HWVEXIzu96^W>+pS}0yY zCq>})h=QS64NOEwl zQ%mTx($6d!)h>bqmoF%$comZm(ML0`7zoSU7%$yv-8u zty~0-(Z|kehjabFyrhT?`PsVyFqlYI_N~z;=hXG*bqTakuK=O8?+Wu_`POZpk}(gF z?;Opj0N7Zy^R59wG-PNBin5nTCC}S65ocNd=sEO$sJ6m8O>?Fj`he@L9-YrXGnQO3 z-M4=U$)j%vsaz1<0VDp5u6Al40WYVNh~o0t*UVHu+K@0UO6t(XSJlA!7+5{U2T~(y zWKkJQD!<;8sPVN3unW=medK(Y`HJVL_xA}$f7g%HsCxuiy6bp27kM#L1#m)4fgDsC z*#p30NTrCPLX%__=DA({3A^qZtOeEGc90o;zn8t12scoa0}_{N>cMsA)@6ng8*182)3X{6psFuu69U4u;Co zc|?l&^X`O>px(H^VZJ-o%N^*0Gk=yfr1U>uYQCTBYV^7E>OjPd_Z7!qhkms|En)GT zKQ|XGJGEqJc~S5y4gSIpR<8S%7WHV&_xat>uq0XW>hro2Y0JVs+NPume6{PC@@=iv zw_h)uTKjHx@|0O`50%apDqQb4)Uzx?$a>wN`Jx=>{7|K&YK6f9ugG?liqWf+&Fzd= zEAd$kZg5`3ct(dLMs0CZ4?jQ3=>IiCVU?X2nIuO+o>K+eUW4no6{G;S?he1=krcYeQ)v+e4}FO(h;+PsAgtu zFJvS~>IuHaCTV>e8x>>$3{sd)B||urA>2$54QmfEIp*hu++Eqp8ofu^JmoIM*-ib4 z+}avQp}&kywx_6Qu$cJB8NWvFYD|Qnng{ioA^CMUu{;f25JNFP(~qd!?)aNK=8k&(t=|+7P#8{V_EF8k@5pA z1NU(*{77nB;@v)RF=O6?bTlhR@P$ku@P2vH&$`R=(p#QSs9ZvfvF($S^`e^v&~2_}yn^oZ`#vR-DYMaZuzmPE3}! zlWZX1^5x4E5f{qJDmE}L<(2vrx4Gml4K<~AXsDa>ll+KnIhoFIekOVNoqPArVgT3A zl`?zx?!6Hc!!^SPqE=^@~8Rl7ik{vIlk?L1@ps`0Yex1OtkwHqn$F4 zHFQl(D+g4ZbG!7EWpSDd;!HYAz4#6xL5b{M--fhRZ@IoTw zc@F)#EXdD~8p-zA-DyLQ^}Oey&-M1hJBOZO{3iN2Lc~2MeAyz2X+*6y{qAE$wU{il zYb-&5Sf-5s-E z(K4_JR}D#!2(D<2I}_YxmFi8AKZh={;p|0 zE_n-7Er8BrqBQ;}Xj5h_jxM9LP0U5{aq0Ayr8pJ++S=Ou{MJeJY*i<{EeW%6O0Dro zB<6we@rLI+Hua2&I;pE;oFXdCoGzZW&T2_~4yN$c*jsjMw2;p_RV%Z1j+ddnr;@f~ z=UDez3s>g14@mJ9DEQ~zP{KQxUMU`aeSCLodD47Mfr>edA1s*IJVm|)6l2ASC^4-P z+icRkV_r)9ewRh-_p5{Pu#vN-AR>iX7ya(DlU3f^t~%+S9_oVj91$dhR@60u8u;>! zhsO?g-~&Ru9aRGXUuRMoafbLcm+oj2J0%SDtb56<1I#0S-y{w~LImAQX3P~a#m_A$ zeSzthZDNcIXI;Yi8U*0GO}H8L-qni&X()_y*fW+os$J!62p`77Xc|aMeB*es@id-`tH zUW@}0(|XaXtW$}82?%Z>zeq5DSDPL-Xmqu`ljRyMbSg}nyXm~ft#vdvjHr0aZ`kJf z`B5N0`!n-bFP+EjlGQ~^18QoEVzI`GA3+9}X6iOs(W|h%=#Zk0Fuzu?df08@NunC} zB525@93k)k&f>=&zgmZe#BV-BzdcQ69H}h*#q_X-%a0cWZkqVH^1%}~kGHPiT2PLd z+zxy(me^=~KGTzyJQpV; zDHa>TOey!%G=q_jds0T-z$l(=f2BL)UH?765!$5JLd=g{tvbDBD(1Qfk#U0hF)zDx z=b7?4l|y*w0?Wo)W>^BW=nYBoT!A611H(@-v!a9$S)$hvQiM@SO4@nD<+{OQG>H;4 z*~cmv^7H9GY6sq4bn(>=5!2#ga|B46L+KOr!mjX|6vuU4TO#yYWP3uH0PvT>3@0|} z@qw#os$+-&Mjmd(%nK|F@E`+mP#&_eIYTZefGF8>eTKFWVc0UiTtV@i%ev*1`glW> z6Z(e3Tpeoet675dnT0eZkx+Kfm3j=P2KhDmquY;xpJ#~iC*uD4Laxdhi?`{|+`?{C zOs9DOq~%}cz})U?E8^&^Q39Q>H8H!#A5l?5z51wqVRLClCNhj0j>lCZe6D3Xv^!VI z1X4B!kW-j=fC>{#2#R&-0@8f4b07kR6Kcxi;+?KlnNOEIPo1437v<^kpmUQdiY8+D zf=m}PTaI}t(GB1Vya0n{F@tE)rhWto=}qB|wyD;${nvEzvta%MIjTvt)n*cbBe58~PtW!Fcxw@m%ci>#}nH==FaQm%28}y$*8XJ3_S&{iRsUwVo zC4l}^5XUAAU3fy|~`Esz*;Pl=H({I zAx4v7MGhNPg~S)Hjchf%_eYPZd zOa;wz3>M?(CodNA^sq#8-MEmz<3#5dbtMjl3ozcS z@8RpLoEbP-dZ7v~0)O=RflVNaR?1MaPSP?q2HXWkL9#|2g@9n59seyY`gtJNkJsB< zVo)YkbzI&#UR2>Vx<`@+aJ3wwqU1mHpR|tZ92}T;5)uN#!Xmp(NO;M4KF)ln9qxPu z?v&LFuW0tH+m_G&{C;9z4YAJALgr-pPUme{cTEcTp6xJw*H{_W@W=b6v9wG63wSV? z8Xue+7m^H2?$lfxm2gy;mHB4f66TY9=8R9Nsormgzcim|*HH+2sdU}g! z4lgkv6R+d^ZJR2_2s9R};}p*QLw0s$ip(d;%DseTM}w_C`wIgd9@-7dSB{q;rZ)Yv zRz2Tmt@;I@aR(%Rrm8lKisoMAQg0%bKwL=U@($=S&oniM8?10P^{tSRyotz$h=7+r z(6Iyg8bnV^Y{GgrHh~XFvG40MjMc{K&_N)e7VHJF$M$SWQpm^Qq&oAbKCZ-5z9WO$ zi}N9OT($*fXb1S2kKNaND`FpT*AGGGmMSFwckwF2gw6bDeQjLjL=R_T9X9|F_wlm; z5Qq$y8~`{&h^?hxighJ~g5;oFX6-zgj#mVxpUY6 zK@`!{X%cfh(x!WRm_PY(9xfKC>wF05&&lWAc4JI&kGX#&7r@zKIxxXBt4Wh|oO84f?sIe3e6nHSqQdhkF*6g#gS% zT9--CDVRvqtC}LQ14V5phnfeQK&$AzTH(2p{O(X51&f{W^OMox!rN<2($*3-Ln350 z#!jCj$r^Hy8<>H6*w*$Y27?_wd?L+38OfVS<1*$&M&c--iF}$5<)X@^rljY89e&$} zYimNjSD21wo_I$X-$rAmyLcH*d-)2cKM3_4JgC#2?C2rH1fN&~Xa`I=WzH%$>M8T$ z&u9<`Vg|}MaGCfUC94kZC@j0-$b;5Y07GG1DGT|G6ie_gUX-jMul`Sk$8MrSUD;@y}SP@CY zz}yzLvg#+HHHBRa(8QMNyt3de3=jhdmqPAEKMMRCkWn#_ zlrWhwV9Oi@u};56!$9V=#TpBk2S^PNiIenDg@7}^tJu`H{XuH#0#lEIDKiSQ(J_%H z=Suiz24ZGxW`Ne3Cs13?JKpGGG)B@*!izvh+j(r9gr{U#fSS7)R8m1uiNtrk$Tj-x zOKIJ#&d2cM5>zD1D5rCPzYm$V+&?rdCwe0xL2?2!&5MDQa{qR|uKW)G-YsqyhWthP z6GG83Nt)X_foR0zoJOsmAK5b!wiGo~xC--HRo3N?eV_+ddfu%ft`}B0pZqh5{%eN@ z*|)?-xbDRqaY^W}doK^{1-FU*ADK?Lp{cg*((lsnWn42c-aM%sq|kN+MyI-%h3yqJ zSO=FhI5MoF|2kBap0@z)CW&7@zuP+t`3jzGYe3_k7*EB(hWEbk3WdgORk-6%)RDL~ zYUoeh7W6gdM~!z`v(a{utj*&JbX{J-fp4z&kMJ1Wo9s2XRkn$NDn^IV>vJSF7{Dis z7s=Mv^lRMS5xOZKA59p$1C?fzVb}~2x9F1c3<&MmUK|gLBQOmtDes71%weR(`am46 zmo}d0Od#+G=&@#nR;3IX5mRHX>Sp_;CqxS)<0gRYBC4IF-UsWUf9PK3E4NjjJYtsb zVPr150XiQbvOQ<_@E~0V2VYLyc~Y*>d`(ONU#h1vY}EiUyAz}i94BP#TwiFoY=ww= z-zGmRNM_%NRDTQWRcb?$fl4b`Hatj6)*Y5H;_?5sAv?F!Q1$A zqYvlI|Ma@lWHHxR;?;{6^OlWwXj+1nt5F>Yn_uGSmq3fh)wt52ThgMFu?Y+`$fCg# zh#Eiyy+Rs$D-ZSj*`9QQo}npUjB+3*N7uNKZUXyA!0e)!mgl=&QT{}2BaIdzts^5N zi{O2<6jVgw1`QD&sS0CVGOnhltsI#ROe^E?`dli{f6AD3nwj&t-|R zNQpO?n;AwPx?t9l^jIE73uhsgwm0+azh}`{e`moPQprj|WT8<_p#l|XA`yv&u{mqm zkpz(~amZQU14;um?VhKSdF{>2%uJK3gSU7W2TGRfe6kxi7J~z^kuO4c0Jc>}3l zb*gIu0|QBMB4FlB^NA6R(krYzUoT&FM$hZrE{$p;w-dd%!ul9*NW9~U?>j&RIYqeV zvKDZfBvU?zx8X#f2Bp*FSQ%zj3!#tcv90}5<+pMT-`RvM3}2>j)XEgU<1ic!VKkLA z4~MaofpED!X;(LBkN9*Evf?79{%CNO>=9AU@|DAxRZ(U5vEJp^@r1Hbi}2Sz;Qi~Z z%fo}iUsb~YMF1eAWL6ug{b1J6A{iy?*ixW;Io1J)6LwRdiDE3z`=V;p=nPsl*24ed zdsbDo5VVLjS#4-)99!yGFlB`T`Sy@dZ=u-+fYvpswnkdzom#LqJO{FmK)5P!cy`pp z+bC_ERB09_{$HjbiT7XgU^1YDzI-sCRP zKoM~Y^gN8%%$0EhI>4!sFry%gSv+iEW6j65#QeZa`+R8Z@ejw5)t| z0Abkp*aQV*I3L~DEMIpDWDmgz&fWa_rmo!BoyULp!fj>vkr@hxL`S*=G!l?PEN~Le zSM9j-JsRtr$*5e9b1#zP23Zpx){a*D)V@;RHRansr)m^E+59Ny;$V*J_MCs8cxg}? zWE-*T3Eux z?eYN;6;HR~;eovLotv1ET@$V6&B0>5P=FLe$Z6EEy1xlW8P_eIsQU&IyF26sE?|3F zhc8n+c1U+n6|7H>PS|{UD`7?y*ngRS_4%dwia4o^c>ts%q+c^xZaG z-th!}|6q74)KB_Oo8y<9+%}n%0hk0H3eUd$ZL{8K7jV6bF#KBQ;ZZVNAVMhh!n}s% zw1R(qbA1R#DDv#FSe5>};XSHgdj#~6HumjA_p28kAqa1*MpBqZAM}oBImn0xD?0J8Iar7;{v0{wxy8uOh6xad=|Qc4mRV|8>Z*CE%WGj z)7}(KlV&sVNM@$8da%ZIFL^>ms>>lwI~&&h@t; z=U?3v{e~tSQVXMM!8F5{%65|ElIwumcIe*aCbPt56Wf79Wj@VmoAQ@O&eVQ>M%7EP z%13{`N&02Et83QWJF_k&sucKn^y?!vEq!pG^iXjo<3{?Ut%?Kwn5G;hrx+5`dd5dp zQS&j&cmHj03DfiX6Nqb1rgb*k3LJ9#4a1MU(CURsKpn@$(O~rRzUB4<$!6;Q*l3ZI z_j>Zb54YM^!nIWm$G~!rE}ZNNW%|a(LU4{GXIYui?b{S)U60v5yn1c=1H3B}yesYJ zogA-4%j~p7MMDm5JX7=jm%QauSSy~i!}V^NXB#<6(jTim(KkJs;1wn3Dxo*%!BW%I zH|$^)y@QK0xnm~e4K3+)nj$C4?UvFY0CY5y^Nu4@ah-f|>9-^&tA_s&%=-?CY>SiY z6>p=5ZN+Q=+TueYBEdXUeu>sE_%7sG{+5?AVRDlE}f5vcq`?mfQm|85N?OQ zVA@-eg(1pyk^X`pzfG zF>bd_ahleXo4rCac>~&%kOeo{aFh?mW*lh@docD1$SPb{m2f8Cwqdi^&@XNE*Qcx| zp|^pdA({3qL|tS>5*oXiZgdL4285VUuAD&{1drFWgeGkif8Y>bjFeNl5o7J_sKbX3 zOP3#qmxGi7rm%!L<;8@b(x1&)SI;wZ&(6*jIU1<$R_bWY1yENIqP>?qakbFd-4({l89?}3X*N^Ko(qE z*`A5Hh42n-5S*9t^KAGR}$d+FNS;P0{bQpN#JLSIj7nMF%HD6^I0(`(EHW0te&tAI7XA--m^20fpH2)qs^jPp2D0_{<5A#I z_V}b{R=rRG$>H&~ptRMekB4>-8v0u^I!YZs3;5Qzpc5Sgd-^KDW6Kv`c0p&B>qG~i zl+0JQ=1xTms9zWGrupO?#nt59*@2oUE$F8+HgD5jA&F>Tp}B3e3ze|@5t(Qc@;8LF#DHtJyJ}eDe z{I+H89p^VL{1oKYkb1*ed|dy)fgZ1~Iy&$m{vsPB((|L_v51kJl7xXbq=YAR=M9V& zu&E~JWD@M+p(7&?z+juLh&p}FKf3ObY`hH~@3qjSN_*dKxFP?aT`gWs-H?p7Fx#Vf z6}T5mr~`D0Q9LguiXQEu^(y*A`clE=Pc@jX?Y{#=)O8z5<> za>LFUgdH?^X^zOP+_yv=JV>kpx-j_m(1k^*cpdc;&{jhrEFMO{&w0Hk-`lHr`0~+( zKdsNnK9c`=Lectli>t(%HD{?E>-2PeNg=qfHLq8aypn(jDX+KNDBGwC^(X;Rl&U%D z%RZxn9Ihu2YL{%99=MrwfZPuLH%{O!i%5< zN!}VH)xwd%^<4l@ir5W9;CTtsL5LM(?$Nzq!@;M1;OZ>sGVO8$!W81^Tz>wR+BDy;gCTxi8o2_xQ(mJ7=zpGIlPmqN%O1^97G5ax*${s0l$tNYh_rG4xnt#Y_E*Gp^o?~DBOv{2LBiE}9iInb0| zL^u_42j~BGTdvEB7JTW(q0C-qx-RPO0=d%>&O>bGNfTMu|4yK@p@W0(wP!{5YJzDJsrx`-%PR*>ClLXh_ zq9wbVkuQZGJY+KtdqeIlC?qd{m!i1IOG2$Bri9p4o``W<`RSMV27#w?mhu#$6L~#O z*S-CLvo5=99#MqA`<3Uoi%Uu_kN}tzTsdyCH-FEps8ik!3AHy9IEexk3|!~gh1D$U zS{mnsiXuU3yh_VxA|Wo$p9%o7cKOvR2F`6KKf(Yhta2Q-D&bCfdmJ+C#j6p#mmvFl zTsuK-p)khZ$lhS*b^J@$I-?lnO{n<^n~U?_r@d*04SgYT@)jXozrKIx{?l`W!<@X! z!xa=7eUN4ewai&>RA~TXtAB9t3t43O1rR%ylTrT&_ghek zE8NzN;La=iWy{W;dnH(tG`0aIAg`@B1PTHz49BvOWNAJK?}p1-X>F5aLSxhCp?@`+ z?6-1qHudCBP7uJeoctoJhtpy8Oce%UboC(**cv_(FoX5NMK92M1jXH!#|e#{?qygulNA;+1j7H#$V) zn;<=uvd2IG!GT4Tus*)Sq2ehgxtA%Om^*>PY^Hi|Iu^PFY&Hx|6mDL1#AVOV7hL3YxnV4 z@8SNnACz%pi|joWI^GfZI-ywwbCo~plOwos^B~k2kK`=^-i+CSwzigRKX826v~%+& zTrnkn#*KqqiXt$_+F>)-+L*>u-JjKNJFsIjVKuYE>y7l1Bb~sT%j8wzbm|7T^pvc2 z;ww_oF!U5a>BU#dDG8*|$2oM+^B{(f;XeG0Y1QuiS#mQvE1$zKyg0-6%H zONtlqyu`0o7_-)W49vG@-9AqsWkBB~h-^#9z^c@oScilo2}KP9F%J*PJ=#sOcNDrC zl_n`2qyjR&d+^U?6F&kFZRqlZeN-!mQ;mtrpJiE_wHEr$@?tw&w--F^$MvHF)uFO$ zjJ*7oG!Jbx92kKVrsB@syEd-gI7iNrW!)N&H+zx&5vmR_B5@~iOgWGbbb|RP`K^+4Mg`P~fQoT4lSKVum}IgR zAZ}72VTcG9b^}+*Dh@gmHjY8k%BLT0B-3ZIf#MQjdNV1{B!b1p1NK_HA@Ndbcbw+F z-<(kS6;Bs5J>PqkewiEs$tDzIBUZChW-VOnM?RM{j*Oe~SZl(*m7L?QZ4f+(p+IEL zKyCqDd}1ux8B~n$n0PuPL#sjCUJcN)FDNvgl9; z$aj8(vaB71^x~g+h~!pBL#Tkv$>9Otz!O6zk~-8EHMtaHT8`cuAj3^zT8>rxd^GKm z?9zwQeMZv*DiV-{ZapU=OxuV}VkUYfWMGB7pN=T0{PNrJ`~Tqrj2(Rnqy3^kjzthW zL;A76%cg#hCAOfkh0;adh%3H>b$ZTz?ASoc&*+82p5$?982-lcK z7)+z1)UGKtsUp}hSnP4Vx1~WcmVqGhDqka6o~6G@hX)`CY96X4i-J>y=>Ykn%s$tE45|%C$NrgnUWzy zbriOFOvET;X2H!rav8H!*;SUu?7T~c5y9;|T*KEt5vp(#br7-s#k9gak=(DLAeCdC z1zFP#3{SAxpaZQ3$Nkf!mc@GXEj+9MI*T~u4Ie~WGm_-z)AV38HOWg7@4YYbE}-~c zcrd4`l%!=snI%YwbQANqWs#+x4cz;e+mry$qj+9nqp}fZE+a1-EGapOtYm)c`C0e{ zSgGc2e!h|G=(-+cv>FuHvo6Cqbig0yKFCJj7K68p-LPOak5gIgEmp%Lj7V%HLkzz| zJ0FabZMU!bw-K;!>u;`JaB;aPb)|6LuQdQA>C=Cb)u&`!z=?OgHj~D|oYQ)t^w+=V zhhd0Mt##iOMw*WDNuOnJg_0Pb*_gP5|2fJOlB)k8D*GeaJskk_)McIu@{`lYPwEWh zg7y7b0pBGyrZ;qg#gM(hi0OganJ`84aFEBYWb+k#dQB{rlFIa!t>jqiI<_HdczfhU z84fjuF5ZXtI@&SQc^&CCinHXB5fI@#rc+F1&eU64Nq_*p^-g?3O3R-L8CmV$S7VI& zx~_M>1WPV72I0O!i+K%?HsTuScznRdK6>ID+=jC{M%ajl-%`_y@7`%{9_dQ_ba&ks zIiS`&V1s?_&TEX9hMzMm~ zQ*CoHs?$G>v>f1P2!6j~%YQ&T86mht+(%Wl@OvJ%Gk3KCsx_S)Pvat-G$0a7078wq zFWV1$?&<|_GK-&qu(N#E?!?kTh_fldBBnO3yKd!6>imwFoLQoTz0w!{38I3h;d^8k z%l0#yfWHx|qHRX^0aEoG}RC+UvWO@*9|6ue6eW6{#0F6ZzfAcS`TM-RS2>4pLM* zQ@&H4Vqj!c0$gPw8T*b)7S^}<`;m%_B-{!W%x$FBgEhn^_~_y_*G{g>DsGJWawdpJkx3LG4%) z-s$jV)?fBra*kNkWIY|Hyjak4N%O{V`>{@o$rGe<=$7Z%Jw=d!EZ|D9DXFHi?xcy& z^2JS6^%)uU88z3mvX-2#EJNRb>wHEwSlQ*w>riuAv*wtua8U(DcMZMO^Vw@rXqWiD zKI6NFx};;aN3tOh*9&+hb7%XhcUZ*ZT4UF-~jL(%x(^( zsoX?JKiJQ6+6XM0-r`E0(!{7C%_q$>q}G{^{RcbK4!gH&Zv0jDkWBH2d;qrCLb(RV zEm%*P=QWw(;d?#B1&Reh@t8kK=_r>qg3-BAt*BT7S4FysQt=3XVEf9wwEL&ck^i2y zAu*}~7OlTwCO4BwqW|3zy6j&u_=>BKfyxN_b}Ij1MZ%pf50%ayOwl0^2lUk!@$-j- zgwVa$pkTO3(=}+!Cia~r=6kGr&9i7%!|GSzckmKQP@#*^tcmM4nJ?w{lj3W5970(w zmb}NJzB*6yffeod87Z3oGu4RbXQ~m6&r~D+pD|bk_^0n(%2$ttC$qwf*pR$_0ILjdx6CVqav+f7lh7nIWx&c{IIS zQFK4*jAVYhRn$~RB_PfcG+~QsLgJ@AGz}J;{@CCSj}I|L?2RjugQA=eoFRv!)<>d7wQW$4i*p$@pa@fv8n7SddL zSQr97?c$fp{kRiwm2!W@kZo0EQT^K&`T#R9+nhH8cD=W)d{$VR^=7a!4z+(Rq7 zhs@$#p+R#4pQn{fhe&5l?1!&yZ|}TIbURX5dk_7&jC>s;0xg*#Pu~iqM)V?}rfYj} z>aR?HUll^KZ}R>&N1aC6j%%B$ML>GMthjk}S)?Fc@BZO6u?a4I=mq}7J<2e0-hPm0 zVNp<$0lQ?6MNYzKO5)fx?U+`s|6r#{bE$T(Tm&!(>OYc+9a#siTtOWc>M9eZZ`CMs ziR;T#E)NCp=FH>uA2@<}?@tX4LiL&Rn(||++2}lc;7&KfHSNu@VlK$<;Q_GZDx5^f z8c_5`-ba&IXp*Q+g5m|kF4!1^sN*sJeTEa8yH7k;GFB+JXu5z&foYHTnDGx;O!ix# z;XANeEzXbZmWZ*48z4^SZX>f-`U^Zz+A$v%pB{c2qT}1bG`II&bqCxnQ=EYj z+m*kpftADs*D+AIntM{2?`ZW})COVM*N@{8ZTc4@+Le_fnNKUbx|k+N*7ZX1WH(sH z{4N1>ikG8BsH21-=e6%>D(s7{2D-70)`#QqoWAwejoFETC1}ha%dTc_xai+0%||P@ zt`|^E`iVgFA!L;X0jNAs*kzjwBt^l5Cm$O_wRQ^=plwR(cP4g2ZkFQg153^N@VocX z?v4?r20@w!?*rL}2SPnr-aD$wb6*#onrK#R35pdf zHoz98iHaJ7Sh1lJ1VvFnqzR~qfRLhs6dR~W(STw>K}111NhpdGvCyO_RRuvH^mdk+&z-*;X3%PgL7Z6LOkwMWKhtOjr zXI{w=3C6Ypgt38U-G$kPi`w&)LWFhCVhbdVyRiSR$M<<)kwvMC+uJJf;HfT>9ipi< z1=oPlp%gakLDT^ehhr(>Lx4Jsi=2*?m(4>MHwnrSMj1ZrYebqT$>t(pQ&QGDoBjKO zvSF{C9L_n?e1M4tRnTSx%OjcNq>ETqjnu>g>`l_k&%0i@uGc}q;@KX%v%v5+u@`+y zH}dX_DrWnHLi9COnAz(a@bF1regJq%DK)2Pf!Ed59G^n{P-dN@t@gs8)bEZ=T(k7wGdJK`PRAm;55nCKV8&!o@}*gjxy5R&3Fj0udU|6QBnI}@EUG$=~7O6zOGjnV!gqu(D}=>5ED!mCbNisO$M z;j^K*8d|5|VLy0L1$+3UvPWkFP>vpPn}_N^-u}hVpCZ!NH&+r360q!~S#|W~Q(1tf9i?wQdxi z*Y_ABQqa{XKED(vx-;90RCYpkuy@~|=36JsE!0X(QSS52Cr8R1jXpeg(9DXz_!?;4GUy9OLxssT3jpBp}q#8oAl6BJLYA?{y~1~$0xyl`|NQ?3=+Y>~ds<)NQdunSyThJwG=*hiyhZDtVh{{|UqX)cb&raAA37jf(pxNDb(ce}P zR3#rS)1#^;S&)G2)l*OcK!a<3>FCW$p23jFwOixVT6{kvBb_hC zb_1X&g(x8nce8*Ng!Xa7xavaZf*SGSyBjI2bR5U%iovXyrkTw-h-sfXP?Zci==Iw3 z0xC05e7*g2jM2g)R;C?si~GPBjR5D+}|>4q2Td}BEiH?Mp^iy z-UkiCm)?#MGkWKAwqm4`jERTUxO+W|RmU+X7yBN#T6C@gzZ%hG9X3OA$4J3vI*y@T z#M_nk-=2tl>HeZ~&BFeXtv!V!PR$2u^4_%{t15cv@`W$Mj6v{uBGEXjFZT5{%jqL> z>^7_|`sLQl+V-Cu;vPKo9ooCdf61=zC3_9r_HE)JmqS0ipF3D_%Iu=Sdtb=zH9mW6 z?|_3o8*a|N=&^d`_1xdyd5pNZL-KdYZ_WRqF43pgZ%)_uoV%*KIia@pWJktppD@F( zZO;{2J;^bynD0~D;L~7J6yy*u5UiK;(oDEv>-zBhW#Up)CRWaM3fo8P}w=Ab^+s2(1e%a{rJ+oH#3 zT;5|JSEGTxlzs(>puaS7{>U=fV?x$U_NK^t*>eY)TPWiL1~>~JMXtA`qxD3MXVsPZ zM_*Y!N*5j>36(CrKbY-W8SnYygY+4bwDfzd)0NKx3wp_EUmb2dO;so+Akz56_~ZZO zQ+s8<`eI;tPYQqk4WgnHw9qEEBlcHULPF)-#2zoo)~ol2g$9^4F3ov~URCM};hpaJ zx?e*31$0@jy+J})sG}mxT}3m#?{#Qg19D#spYoa&G$u+@ZCFlglJH}i;CW{M5QvJg z%!8b^!sEdS1u~eO)3ti^|HQwVh)ZQL?pE{7i0>{B?J)~`vH{Y~1*FJfGVX-ZmAr#* z!Cx=z@}7-Me$Ex)uG?-NBxmh-?jUB0)%UeIEX0WH{e7DxFdfk)7 zsr~X4b!J{B3M^-0GnZNkWA2lA3!D4Ag7;my=kDf>f&0AMYtgJ^1JG8nxF#dRvsKEn z8KR@OJxHt2&M*AXOySemQdAiy@>zdtqmKJX+nYZcsaPGUAx3{VQ{$j=G&Zh}-hKIB zSb&fI_VRA~9sLqCBKtfD^*5JQ{#rSwW@QQh1T!KE22;^>+7w|^AOZG5%CY}dqfuypyNrXNY27d5I>xhcSJPuMRJ~O1Lhlci zulv42QkA3(Gdr5Hjt0_bce?Nj7C&w&818s{pj395w{0Z`jOc`247BNPf&tf{d2cQc zTiG_1NP=oW)@VQR1|{}rG!U4YG5XW~$Sf;N_zGm=GwpjFf|j{P7y7TJCxVMHvF7Gg zQ0^gbrEv4mvmTRBnf`sYfAmQ4Bb6nh5d=OBc$%APM4oaQ&kB3E0xe#(PBfFo&$3ZR z0II!b+2d>D_8^9mCh|WSDo@?C{A&Ao?tEU zpGWR9(*LozPo)F5F%S8>NaW z7`AU3KvYPCiO*oF;`tyCpe?jziZDmMeDnc?tLVJfTI`S0jwmV-%Ffm)liWoS~>;SZX|R z8>G0QUJR3$pEJ2wztSM?{NJo{5VA&7TL-m5L|Kpcv(XQS**fR3I6RzkH^rpScnjt5 z@Ulo)+d7fA&Ci1rVERJ0N1babtRa47fsRKCeAZTG2%q=j^7W#bcfd>_6WgUItsS5M zMM}1wG3+Lo3JkZ(!V2$c5&LvoBn_OMD5g`3_RD0!IV}=hu7@ZO)j6q3Dsfsb9Q7yR z5N9gQkWE6cG5%$}xk2oQM}?VoQyaR77e=kM*|JB}kz2JX5~5EWCvhE6 z;BlR_Vw9xI#IB9+h^ZwDk-F2WhyQY-k{?ksOclp~Q`u>HG0*}VHU+5W01YX7Gr>x6 zwD;}3?;xY!+SpesdDxFp`;E4(SJu3z3Jk(ZzewN+=xlShLHeMl z1NyxrXu>4Og&Zj0!iN$JMX}0|7H?xPHzo@W*hQBu@oayDr&(4bGGWgJ4IuOvzwhGI z88fKIX7OR@R;7USE)I%LTO)=To=9YVKw;v^hQi!QtS!vkcP9i4BtokKi(DZ{d~QKA zF|^V5m7AN2U;lYL1!a5lo(yyjB{*VJ(lJYBs}-Efl^Mc9aPe-4zK0s5UsP`ft!CxL zNJLvsLMHm}xB;t8W++c%Fp`MMip5$|HX0^;UY?i}5SJ%a7z80BqY7|r>x-<+dz%4i z1clGZ8W)vO=gkFtK`QOUKa_iD)YuJzTp{cOR|VLTvtVSfqu1P$wc=?$CuAJBJ(53( zE{}i2*R!@p-Miu{{PvB5Aa@l#O?3Y77a#C8i{B9OuJtqxLkHy_S3Og}K3a8A7$X*! z^L}w)syAa^msMs%4j=9eW#iK3OdtZMWV$+Wg4R$Z-%$1L-OB&;_gOI0Rc|H=wakW` z-SD~4W7;P10PqcpPW^RC?DOJZ1@XP-Yt;Xy- zVa>a}7zE$|-eC=f7PnS}0TF(dDy5TFY}nroK$Yp!7+suha#2M%7taWBbfR@5f%Sg= z{5j$O<0P^!KbQ}c*_8B)vv;afl|WkhsY1Fp?j)Lr=pz*jX*&I@AeB1PW{U92Js}Ca z45$@Qvd80Zf+w#S44rHC>9B@hmTJRw+vv_Y+1{kB>nO}jLV50z@g9_hNAki$`T788 zS&=&`A)5-Xy(30lh2c)Fj0C`!K-M% z7f9NYn(<0qt)sBGb1M*}@;345oeQA4J_4$Dk6M{KUb1h}M&|eOD4G*1dngGn-hCa} z_snXb;VaF-4<%$#bxgFiH8=bE5K{9xw4xHxihA-Y!mGBt zsLLCV|0Eem7d=hU%FOeM41);ntsX6?4=PVsXRJqep5|Ty&Fa!UY^_%Pesrx_Ys3d@ zs*H}~icrbH*+pltw2U-gd$7tYhW;#kwYkt8RMrOy6L^*(60OSbD~hUhsvphht|)pw zA0dRvU)UT~Fb>>md|}Fweo?5c$v9@FhS6UMG6h$l4b>Ba|1eimINWX?T5k@0UUdIR z4nSwr)2EV-O6UV99DZCo($Hspy@_yz$Q?&<^%sgf!qor+n02_p{I@@1p;SPf81%@M z;yTJ_DNlQh)kT-60y}S#Zaa>1Q28C z&;4hT@wV%6oYytlI=8*OCdMc~K0k}DD@nb+8vUfY0eG}AoV5PZFlT8Qkfe9=425^U zZltc%%P-l+0$E}TUjC53Esnt%g?ML_b?sPe6qD0duumM@{ny&==Wn`@>=Z~>3e)l@ zZD<_*2IOxR0Pw>W8J0afP1Cz!i-ga|vEEp-MtA|Dgqi&kg#Wbe`%fST|Lb(vkh6Tt zBanQzXAx&uV zI%3`HHsl^VvBm4O92&Li$YWT)soX(WXm|*mb7I z&c#4{2cUnie3JbNYBQ1dQ(DNN`?l~&Z5)R9LvWNyo>GIF+Wz=~0Mda*s8C`7YCFNcn_avNA73mSM_TWpXA5qb|Xf=MKlW zrkf`tRT)PkLDaHet%pRFSjGsiX{r3~m46bFjV8%CA7OlRO#MxyyB%7=Hh-%zi#^-n zSA>iW(?#(Fzi)Zr>YpM|t=7Skx3&&BVhZGW!is63h2ukPE{Pfjef+yskrAS65cS8L zU`3wrd0d~4GZvnZURux7N5CfWk^CjlnXZR~0Mfgz0A&G>4{F9AoG;dv0tL9DbD?zx zggSIBdvu`?NB6ly(g*3^H`0J+n0jl9y3);$oNe~g`EDV!q$zm#dTe?mB}HE){FGO+ zuL4~g2GJnV)pIn zA#Bj|A^Olj$*ralo9K!cOG7C001^|lPc1P5N%xd=DNsUiN-R}VkQq9yN5Wd&j+6+^ zuB%zGfXbgS0MkdgRyE?@OMr}c(x0s$B9Lk-{=3l-9)A8mT|mI(ehK0Ld>=t##TnY8 zue@l3KH_lSNPrg3R0vPTbt?GI>R?d;l7lk_Gf~CVW*6&noVG%~{jaxpmR@>VT3Szg z020K{UO_{u@Fid^XDe@ml?=h=OTNC?SZ5|tyo;GGL2y}(D4EYG2)CH{QE}|%R`b5* z;H%^g^xw^qq>UVhq7|_I!ZI%j2_EfHacFe?H`jcs9o4_0O%ZBft^F*UG5bARxtmrz zOLMHPdx9$4nc+r9_d3*CU#{V&40Q7HGgsaep|Z&@vl)prcE*37r*f>|Rujv?^2J8- zKH6*J$4MlaSBwD*@Yx^b>|JCv;(eVL>Y<1nQ;{Q!2XQ|@|4mxDwxS5Ow(iicjUg3Rz`YDht@Y4_+Kime)uzh&5F7UX+FDi+8eYueLCcXrONjTr)j z_~U7BDvs0uW&*>4n`L%X&UpUf#qO~3n>gTXdX)7@;2$K+P8mIf0AF-g3kwE+paqmz zGz1HG;1PPTP*8%xzMaE%254VFtp6$hsqF)#yU= zqz;s+1swgy%rQ5Mv_@NlX)>*m4$hLUU-_q3b6Rc2qV5iH@e)a;JfH|N{7&0$#>@yq zpxCk=fpOz8anlBXtN0ec3jFM69UQVRFxT5=jwi)P-Bdp4 zgH0G>(jmYI#bg_LoFFoZ-K^Q?K~*g+?T-|QjS6wQ8{Ru&N0Wb2u(AMqn$s;DDTzGJ z_TDG|9%m{=@>+0A56N8EZUQ!Y`0v(Yi#K%eZqd+4%rwyJNYYCrK*%)z!IhDMNA$`C z-~u%&4k9^7rW7EfubKip)gDS7kuRRs)X6IbK!t@aE3*f$k4crB(=l_VScGlsEWyW# zE)R~}7Vf+d*c6I@{8dvppBt?O=xC(GC`m9%d4IO9GVZ)rGl0!vXL8`N>wq4gOG&-t z_#WuO?8~BpFGFJLS5l6i{7JT;Fp^Q*^*H+KLUcL?pp8`_CUio7il*U~T~m8p(owAV z-}E})X;G#SFtnxH>IgnP4YU)ZDKNxcHi@hPh>d`pBV8|p|k zx++p*V&*uXnS%D?%dM&NHlN_h8J(Ae<&EQJe^G%G zGU6m4YsUZ$YrZbg?cuDh%|I&A;fw8p`TQk!GnoTGZGROByJM!BO$?*nV5%+Ljs;5F0uBd?)<101!;Lj+pgBBV$8eYp|me_aT~I%)Lm zL1S{N@>f2$5clmsG8UX?}^GFHB7gY_0pV2Th*oOXC@ zCa(9$EzFZPGoA-;tP(J}AH^A(P0H~2iOQ|$IhZ%<3LjbZR+JWyG4n?He{T#%C_aGA zm47`lU8g4ekSZaYNk1xTzf6=~q^FjM`+3}x9~KJ~Py)Ep-deXb7+9RC*yVbo z-fhHewmahh3PkG?zn~MhuE)&{#m!+o0385HM$fYf!J*TUznPTx7*i7x&(}o@`_a=}EdIS6>7u7{EV15&(9XY?|TH}Qd3}^qqmpxM;%nu5jvo!BIK}toI0b#`%$--G_ zg9O)>5XWV^e%Y9zXk6@9Q`?rMq}e+T#M=@St0s-Q;~Y9H2(p3>v|8D4uv6P0N<_Wr zpdMxY_Sy}Y#R7qlHq3aUG?x`=3uNCB@wfT0cshwFMjElr)nbggN^S-P@4ernB)bQ@ zMCmwaMlJ&aRa!r1MndG|SM;5rycteGv%2Y2ArNZ_g2(kry~Gs-Z4y)7VLb_WkI{xM zS*6#up`%={YxghS2d!2mpj+fZl}+)m5Hrq*9C@}F>U?YMrmj(Kd`{+2Q}rL-&X{3Q z&=#${xEwK4FgeH&W1;b)6>8sq)Z1bQPpa;l?hoHsASf(T>oSeT1*19&O&RNgQzDsD z`9nz5DG)sQQY*xIk{}RKihDl+R3v-M;bq<`A>XYH*%r&*?&MDl-)^w&{Q`9Y%{HiV z2ozdaOmDLtvesyx)ZsWv0Uvm5A$+4bVPo%qZq0*I|G>a0IGb3XlKtewx#r`Aln_DH zPx5&wrM@8^H+|(x84rDZPun)p>w*Rm*KKx9J`)m_DHm)y{u0XU=wo=8ZKY*h}}xA|gVD5sOfUGIyN$?b+dwNaBW-4ks@ zM4Ivrf6B*)*3n4iVmmAL_G+7o3VNH%u1yTq`86mgh$8~d?ORg72t|_cgG%>);RD?A zQ}2DwJd3E3tdB-b9R;efMYYrbCJZYt{NviXoyGH+^^<(M0Plx8klIgTWJpVYVX`iB z8~}#g94wKU5QVx+?{I195|$#A<79P6cGfMZR473*lY=tc{8BYFREu0GoPo^6fF%Gk zWU-ziD8&JK@kh!#tc2GsBj4v$Z1wd3_Y*YtfdvF9r;9 zF*)&Y%HH4nr;pS*I{xyAE;Z-pnir0RM|vK;@?w2hK;Y8X7cWNsy6eoSm2$nMXO8&! zXJ?t8SI#t%`_6Iv#K#TorMBbGc~$PP2_LyF#A@zC`>j?EMa_i+D&L+|7IX{l%#um9 zc3jec7_;ecEIQ;WYlO!{LfrCRhrS}t=W345y*;N(d!D;s{#&m@AX*s$QuCse9w4;b z;mC|HBYK=(J;gd|+xqpVkN3p#8RG*!pt=lwT7~Q;)1pV((X_N*!hEjkt2x7`|9I*@ ze*Y6dj^20qET1IpwK^G{n+6ZzG~UtPx%Y=bRAPe^{i`)O!)NM_FpsHIAKL>#d}r2r zQPKC(r=75&mCrmXTVu=$_CNhra3Y99;|{!gp4V2XCN1%3*Bm03Q-HT<=xI225w?hf zF~)F$MvKWcO-DSYaqKpcQn~h#aP3}yE9n@tkDwF~U1J+Fozoh2PL_aGqBn-RK&F3YE!m8gp! z{2|eKhDg-`8euJfh46B`@g>rF=A=S=72 zm&+#&CK1&qLzpy;Z@?4D-SAE$BF9;St@0mD-Zs*F;*IYYLn4-FLszT{l;F zOk77dSu^*nzG?8|2a%tkjJGar?eU4Cj*~+iHTOmJ=m>#92iK zNIc;MtXup^L&xzGI&-g2FKEM=T2bU3%kot5$R1q5O*L;(*xJEEJ!8ksn}o7K3PN1A zdfEamJQBfq+aOKht)A-NuGXuCASv2koL)XjZtJ3o3p-h#r&`>+>3Qy4GCFjPbIUz6 z^)VXqtg(RzkUur)DWNxajA9lVKl;Ea(z%i#BM@O1qW3o(^t_WydVV`TcGTp_?TLEB zZOb5t=mcflM9S4+a<*PqcQk(u`&OMN9@bl{yWoYw2clHUo;pNSSjN>MZq?kww>4lU zG}RyEKbz%R_lbwXY=1QSnR4lfof4D^qjIgy%H;>nt)3z#Xi;T~+6oYE@$9lQS&vvi zn&SXU{d_Za^q6`3AMVKiBW%~BGl!6EmI5SolKK?oMuigH&CRPJcE}MC#hld<5v)8E z?tineWjy7r$-*PimSi|?BaidvmqEylB>9!ARt4ZHEg&tv6eW=OP{%>W9I^z6hqUI2 zg0=8`xni8ij&=w*a3`K#Zerbg-yAPj(5Q&`WASdY`p5eeU6_rK%AvdUyx6&jB%t+41L{CeMe1nNgZGDbCpySBfT-kNdg;_1(lT1iTAanOnKmQMT@HPmz zC?N?Pn7HctoEeZt=KP)Jbw~|Uz5#rIi!A`qI_=fbVeE@j-k;*ECCo_PIpYH>}{>B2R6A6S-({SL&dniuFeuG^cBi=Z^jtiPppKF^1wV1 z*|@yNoqb|tCuYKPxwkda5F+j}@R`agNwhX`9T~0o>xcf-7F|#_0Y;D6N zH2k7hl^1V3^Jo{@gH$HkgKU^=koLr8L9AIk^ZA?JA2gH;?`giZcEKLl>{4%nTr$Ge z-Kkr372YS?lITTyrTn__D`-9I`~_Ji%B;B-HKUE;OyU}3pywPeUUC<`t~a3dcEAp# zFsP)~oj&6&8P;(_sP07(;p#XE2@r1y4JNQ709{w+tL(ANnYU91y?~RH_M-A0X?%B; z1bP2_YW)kHN8-!a{MYuj0BML;mL)*EJkC|sLUN8CNXVRR zEo%%RMrDz;ba)cxYol-l8E*x13df6Al7~5tL*tktC2A%P`ew*C*pdgp#;5Yv=t|6O z3b%9>HZ|{>GxDF!tl5|9WY(cof1rT6mzTl-jUuIxZC>q5p3|Tc`8{DZkRJ1C)c&W8 zp5g5)zQ$BwK|VB<05!X1f)IKA+{*ef<8?^+mdhckVDywnu7k$ROT=~1>#{gFZL|c- z3eL%Vp#E;NX2pb&XcTjk88uJFx`(bmTTPr8@bvfa^h`nsETQ5VO)IFG2bQmf%_XRR zimw;^*eooZ0jf)nFp7xRF*nyibA)-ZvkxGKOnt^+bm~q3E8c?GP8v?bhafrf)bGQ5 zP~|B>$`FwDd}sAJXtSuH@GpTyh%@94)G<-?zkXeYdw>WXpwd(D2*BCYKVQS)Cue}A zR8WQ-$nE;Gvu~sXp3Cl#Y*M-}J zZWBA^eXtmXyA)6iwsvn<=|O)HO=Nc8IU!(1L}^+8Yc1?B(%V#I4lN7{MRP0oU%ArO z)mYDw8r1o`EZ4#phW!w+`s(^ETcQfL;9>#*;$;7J1Q_rXRV2WdRBz29E69X0-tib~ zY8&~~2m=9e;2$vJTiRLR(Ol`gh_fh#jZ%0M+OyI7z6%rxa`+h%)6{l-9I74d)z`;; zvFlH;4MtpY=&})KX1C*~4t8#V(UfQA9^0#!0c7DdJ2|~iO-J6##42--V(1*2vQKMbu_r0*6YXPdjd)A5gc1nLE~CUf<2Z))*)u(X8pg3i^-xxyeT~G+E zB5FH1HUWgG_-a7|rzyY+MZauba}~%0akQXRAYnonoKpe%ME5~YCu+&0G^V$?27AK>`hN&z_HVI4DR;=GD@c{ zW3i0r5T&+0%dfL#8~_y@LaJlQ-7L_AjI=|`pW~X|Akv|Cn2fi1!7>xQw*c^?Z5QlB zrD~CHbnR+^6{it^2sIr_9tNJh+bTF_3`04^nKi)zw)UB(>O-R43q~Q0vgEv(_QwtU*FH zfJ18vARjy&?&O5-jQlswGL!fuQX8SRow#DEug7U^EnSPH&p|*>Z3HK}1<1pTr?n%$ zgSiqLd8w+n=0DdYwW~6hN?Hq%BM)0%b}quh*ur@1)H-a6$%7zOr`pz5_yW6~@S#*y z0-D%~n`$Gt+MCg%v_wT4x^AaomHGWSDNpl-l^qg4l{HHy$j+K|GG&~@f^t8;wVe$V zfFbvILro-_QSwS)&Yv9XYZ=S-A5JdU^l0F31Mc0sm)Zy_1ex#r9fTjhgPAz^ynhk) z0$%93O%u)1zI!G0{tr;tI=Sd%1Qaq5_`gkLX3lg605-6o0erIx83B%LapPvF91@D` zX^e22x#LXr4K%l|=4h(USA2;avlI;$jYvae+S*>eHF0OBXr!hVtiFiuY-%GF@PO}- zU)W4#W`q>2$T+n4sd=AVX|M`Mqh|2=^XDsN1O&dnzY;0Zrr@h``J1M0QeAe_@R|W3 z9B}A~N^L{|6R7HYU~OY<@uKoJye}!5)~8mlwgC!HljD?G)2y1Yf(gP)RehWK=;#$J zH`$!diNdNsIuOrQ)6)*wk2fA_81~o7kn9s83q_P5p>b#=7L=7e?DfUY-W^5n^~%`tcY+UcjhCVD6a zhmLGBd;ljbGZK8&%?NCCGvw-?#)Re9{Jbj*!v_gxHT`H~bXD+SXRoQ1Jp&M}6z_gj zWaXVd2R+_X{le{C=_%0)dgZ*1OP3r*BoAKTc6zc_Ja1l$@ zsyCkTg=^VD>D|xSv_|pZ;?(Wi5xw+gy}V)$a}tlLq@*MZY+wV$KapMdSgLMKwp)4r zHadXXnWt(xhaT>A2sHzFNY@IU5o!XsqNT81_xB=jaw3!GrRUBe&g>4gKv!xE7x2!z zvC1eC<#O^P%r8Zcmvlw7c1_nDk5_W&?&f8&ID2Jt$VK9dO22dMX>9!d%yVDAHMsKl zf;pVLcQOr=ZDzsN^NGgeM5@UONWpm;{*M^kF&p5x*)-%5LAq7w^bb0_P6jf}ewM1k zuLakny6#tLxH>N;eu=%cM7OnED-LyU%eC0cr8u)P)=Pi?zB_0lOhsdC!yaRU;4XR*&*&-7uy|@3**UCnwJ0 z>C5V23yk_DH6*(|pI+OvN7jxeZwjNE*G$g)XEP8<{vnhs%p_Y~A1pJ2ss;jaZrk*i zU0s;Cm_{%8uH7BdG=aLAOMki#dqO0iqfldoSgxIL?niViFU_&~wf8VOZZ3uB-^Zc8U&6JAH!Q?{{HdGT`VrUWuoz! zCs;ZioStZAt6zigNn@ebufva%VhJJplTNw8Pex0u->_luHNV4qv4N1X6L8Mf6A?NrFVM-zyJ+t+W9cjKo)t$a?)6Cdwd`!~4}O}WB75>|NvC87 zz@vRjgxMGllH4~4%E9N;6~jdZkc=bu^`KmunHa5)N30L5U8_^XW29I^@#D+j#Fzk3 z;VQqAIBI~SNj3)wmDQPvg+4$?mrqKmS>9YDZQ0Ou^I3Fs*_l-(sDf8UUPJc86g(Ft zla)umkMHlY!K3u7%Qkb+czA$Nw-Xe8d#-!Uq`^#8TIg+1d8L*3pk*MtH;kDWz?!$P>*D@vDJUK-)|OVE+i!(( z*7NM>=$%??n$wfogJ#y&AgpxG^nEuU6bf1?4H8ZSp08Gn5;1+E$?Z5iwuXaK-VhI z$R`(7HOMYNrgr-;g?cp7kmf%AL0WVG1uE+z8nQ`;M)b_b2W_%}5VGA@&Xl*<-d}u2_p~q;zd4pZdE7`B zUCKo*xN_yxmHA_ufV$6I;r?!&eqmOy&n<74X0121eBg8iFzaj&lf%Hz4I8gqW|P5I zw3RG=?=yUteFotJ7{Mg3$$6ZbT7rReW}98VOmyAYL7l&~nH%xMf432si zrpw>|LR_TWj9^opJDsRp#M=GHEeYbY93%GlrNE2b>;8JVH#(wA-^Sx`90d2576>;>i8agj~%6KhU0X2pKL7tt23MeAA5ZxKEd5B>$;w% zKg@}?1wo<|)?Y4Yw|KO-HNBTYhU<3b%qWNJ0>s4PHP!N_x2XWh=G=w37A4ttYlqE0 z=Qy#e_W5Jn?o#Y?v2ims!zm_)5lm6gXyn1}@F7znE`)$u_IQZ6G0L)bF%3Z`ngo$A z>PO`Vjeb5_p*+q+o$*)>I(_ zWrK7*`Z%K}3s9@qTbsOk@3XM5pw?$!JUGfIU!DBQ$+!OlobaT@Z$6xF7PX`X2R~&W zDIvWhqEc&fwZ^87!n(3zY#?z>`_jtzCYVH8ZEKnp->$j34bT%#CXh*oo!fz%lFji} zG-hF*p5GD683u6{o>g!CW(;|nz6XbCw!8^TUn)>jfwDY~(S>aeblcL_3o2hn`(@|_ zm2JUIP|yP{k5|S!*(zEEhZk|^kj@9E;T(bCEa|=T0ftrzl2F{ zQ`$l;v}R;vWu5Wu@=!kwN1$`rH79cG1Z$n>4JC!XdYcNZT*fpXsLq|;1!pgD8?`)Q z$$?E65#C#xhPlix#UG;DhgLLB0M3iYr{<{_q+q|5;01;c)wLbg2K~;|6qu$ zS!0Y-g>y?B*S;?V+gH>cWgjIPUFR^>cnyA`3!r&*5HxQtc&jWWH-F^Z)5{YvE#HZ0 zk{IBzV#SKh2AW}s+(#4NkwnyocvMowGq z@7-r0c76O3d&_?08k}7W4~6l8zCh(2o!g4{#V#kX231bN4G%**;p0jXDO5 zUSj?p8uuj>9ps?H%YO0Rd;9ymf_}hc<1peHp)Io_^4h8X30Q^Pj8}ojSBScOr$kHw0%wxeLAIbDnwht4eL;#E<2SXP#F* zr69`Na7>0N%`a?Ub>4LCZ3yjB9OB-!ADFXqH-XBTwo=e<6dl}*!RFDMIREQ{^g89l zy2Z40LTA8@4+4~{F_b(Yat$e|b?cFn8Raj<6wcMrMK%xaMpD51li z!BfvZBGgMfByFh%b?}-lR2m$T4Gp%?&k5irG{F#nwY}QO!h~)4h8o%mBv;Z)hSLz3 z;4O~~f!Cqf%N;qsyr1ClI^Hz8RP*x`jf;tNPDGbgC&V=Wo-FN7DB6#fP7?fNSZlhV zUR1|1;EzVZdVmD>;8O3I=$LXc$ z$~95UadadCaDi-F+b#Ra$*Bdo&qy}xJ*(C(s8gft^e82h3!z@b5+f|eq&8A39DU|F zO0#r$k`R)vc}~9@^Qt7+JD<;rWWO-Ak!{+Mz7c3Nvpb)!>5YtROgEq)0hk?)^!?`J zYe@)}O|=${m&b|fTYoQ?ZTU<1Ro9G|w}IXpf-gbO3W9Lw(B?W*v%f65CTbc{d#>s2 zEPcs2O;s&!%Z`|%WR5sqciY^48V*p0s|8x9GkDTtUcAdh>Emw{MK9|$Vy_d@!@2k* zwC2IVBPwfR!?q)>F;&-aZqs zA#CU2%(hbPX;Or_(!TSxI-ZcpO(q)lUOWHf-c>`v z`aq-r01Mr>af~=ytqX_d=vrw&$#zb8HA>W^G1dj4TCEeMIoBjFGT$C-N_S5A@w@kP z|NlDAg;;vzo5X0c-da6C669qk)dx(V$(c#45IF!Q= zOt8fsPbdyg5{>Y*0JVtO`8B>X_LD>h5!ZOJEO&Vv8V5;;n_@yFjW}^&`vVseiVa1= z4QHH$_ax$(Kg*boPBX@$i?-a`6PnXnndTL?s-34paeGm7)8V2TByX355XZ%%u=;-( zgQY_yaZ*kKVqzAQ7tw@Sv*?mF4c~&Tsa`FJ;p3iEK8fnuQ zwYXFp^-)b!RWPV4Lz-HIyshV>31r%}mKv)l?8UwdK~@xPNC9+gXLo0F<~twV{0*sN zluUlyT>1RwrfD@epXMUQ+?^+wv^u`~0gw9uPPb%2n~AvIT;o8i6+rKXBX3Vn?QFR5 z;K5u>TH+JY#^?SV8Q%?*{kJrABiE#~S%AU1+_ph<%ziP@+B-2%peDj~gc$XjJbcL^ zbbCsXhq4-QEeKoJ2^V*FhG|YuT?;}mFD8II1qd9vM~#e}Dp=Ku$9sQQJ#ppAl_g}Q zbRZtPv3x>q7Q3vO8=LbjVo7NcC+~B2-x#pMX75h*5KA9`?1Wa(-IvXKFn1E`Y!Z@! zmEw=AUVFKq9kTd9MEgLc%Ug_*OzT2Bld&O*CgX?DaiDRc8^=uNkTGF4=!|NH)+>a? zWuZtR2ZPvcl6wftvAP(6VJ*flR`cXN(Y;&-`sGe6{n-{JiRdp37mG5GQH68yW8e}F z`Tv6I0?yjU;3R60cG8552 zsvjd5CpeA@{J#^I_WwJe+~*7Wc#|&v4^YC-Pw4-qC-ka2%sfR5Is2vK_O;M}1^9Wp zS`R}uM~PlSrxcO;m)k$SOOa@Vgrgujeg2To&jc&v^E&ywcRq)L&!OORD8Li=911>% zg3qDgb13*63h)H}w}*m|-lrx1g$3aEi~svvwtP;}KcCD0`#0mi_TT5e!RH#;DYkvk z)4MTkUmXem&2hZ6bnf^OL!@Q&zc-ONG1PFQ!mB<0$v^k8bv9Lhu6#n@_41O$Z*3p% zaozf*cHuvot>UG4h;s)M{)}*k2DpPH+bbaG>s0n@^d*F>09?0 z)Pa%GJtV*X_x{U<{3rcI1I?kUL(ea&H%^E9uAH2l{#gwrXN+2wV#Ko(AnlV+H#ls4 zUIuKUiRmcUcpozf|o!HNAL z@Nc8qiBf`c$SQbAEF!84N;I=xh3Ap1+XCD4krZ+jbB{rUNbDjl@%yjFNYXl-SO84q zw_Vl{H2L+(LiY12xnNzBO-5F4X8r#-x8CsbR`RpV*!8fcgLb@ z;MfIoF@(vk5{SPzMoEZ{4NQdE%uoysb$slb^2ks=?5hY^3WZNfb9bI}17fVg=+Ek# z05Wh4dl1;^LsaPmH15DcV@z=Ahtz@z{}>Rmw~vijT}*T&$ZP{+1#_>(XQzq=NI3#R zw+s$nCBW=uR7H|_R*fkh`P4Cf-jj)Ej{ z1pQo6gwyi~81L?#@E)Sar6)@vX=wCD@xKB$e^45M4^)F1lO|z%KK8Ilw4f#%=24}9 z3%G%MMNOIx{5hY=13)hPAxxu^sSTVbIg@cEhWQ= zF5!R=Lv?o=oC60r66~u(J|OI8VQT18Nqk}##)=g?J7cy`#tO{X_1fBbPl5#3Y4Y8d zj=z1~hN)XAEip6VAY86Wg%8r)2^=6?DHrHN@U9e;065MCdajfYAFp&0HNFW;D6yd# z7sh^yZFk;agN+5CU{$p&pmCJ$5VO-U`zDK$QkCSM5P(Agl$0^nx?*z!tO(ADtummR7}YwFi> ze}SbH{31@f9vd(bz=a{U1S@fDOA~e_=mYr}lH*o~$#*iCjh0P=;1UFdqsXH6z_-AP zxWmgjFn+KmQqtWS|Zfn)oh6Ga0w z5=rmFmJSY$dmsKX8A0n@ju+^EYi`8@4p@hcRdK*z6b~_wmo=(YN?qma=Y>&<08Xrv zn-<`i*!X%qCTRCoSjNrpY;5EQ_@sVOLg3f2m3Wp;JOo1*?t7IWBPW+ym4*`vbW7F2 zwv@$*$yog-!1&*Sk!kNn@EPM>QRP^$ik%w?w8pzW-yEqJ36X|UXe`_ahmzDC$|C)K zP_RgIPjS1h)7Bn|wX&j`JYcynD_^qaH&#?U!}A$Z1=P3JJpgoTt-b*ep3%Xrk(w8z z;x|XWutDT2#rnDx9uC9}vG3ZaR0TooTfC?pcr%1hkE#O5?`B z3z0NU?|9Htre;5jiw2lR+6>&`y~czVAyiFyA;cVZC?inxUWnC^*oNom^R5Gwrb*dh zqeU49tU;7AH3`o%xRIWDz#1w6?l_q?8fZbUb)=z>1Q%oYLV()IDv=X1rmuS;1oQ%@ zd-bhakoj(8fc5l#NL6H$@p6JUZ(Xyu2I}$zATEi1h=*6_v@;RHE4-bb4}s!RkPg@G z777kM!eMlpc;pVyHJw$(NVUQVIjy*^H3yE^m*vlRA3Y7|d8lSgZn|ROz%*i7@B{z+ zd1_Sa>SoBzoExzruf_e@miF+z;SWXw zn$KrON7G^mWX>1a1V8423fG|2BQKOSebdLWO`D4<_S;_B*yp(r%cGxovfuQ+jyO#R zTf6Vs((4t%DK)w^O>YCAZ2>Mz#qKpbL2qVnwA{OL;5+}oOHv}G(MXgYmiN08jwLqUmU)52 zd0ktjUmNpoeA`Szp~S-rYl8j#r70f-d#M-M%iKn7x^u~M`W8r#(qv$uk^@+Dv}f(> zy|$?Z-zokMnJ+U(ix%fE0JqPm0hGBb=?#5X@QivgP4px|oSq*!f;=Meu#wRY%dW_Z zviz_Kw=&lpeGtE-0NA{3Qdrx!!np^NAW^@*cBJ6hm+=I&?458R;3xeOIB9);n>IuN^Xz0eXbrH?IM%bdDX@mP$@SE(au24 z5Olj3FCz5CW}O$Uc7m_15BV;n?@>v5F49KziE-HrBz`|u>7A{5AF9}AQNxTJAH2t( ztJh0aH5@EnQlNLy+WMtw1XCg{)7z9d#3RdT6{x_7o=y<04%mb!jj*`)jp8U>q|k$_ zj`kCUAQ2ArGtNAAXW{&zC0$RWqA6g4I3IMIqE*Ni$0Q|f`*NH_Xwop9L?AmawD|xV zJZE#rwobj`SwIfrc)q&uQnfY|o9>%Wyk+u{=*Q)aut>=}{k0QnX63l%7Zo!5L9%rt^aupR+Ri%)-uj%?d>Y`d zF9;=v>EkeAT3Z9A&`E@lO*->|lP4Md)(acKpG%(OT7~Gus#}>bjBgx++TncI)SzCk zlJ_~>kBp`Q7jyZ&#>n>Fkz~bgjuza>x*CSW#Q`?IAq{_TTzz zVL3T~@DHxiF$rBt%(Ea40$iP4<-;lk)Pk)$J7G5HbUQr%=70E#Cl3#RSYVimoYMQ< zAXFO~`kkcv-E63u_|Lc+(k_Jp!7V-qm%Gdd+2s8qK}zoU$24(J%iDEU!=K~^Jr-UEKj>$+73n?AT+BF)4CuxSvlYk=J;Dr8 z;W{_MWk4P7XASoSYLJW1PC(YS7@PuqBpHg?@hv4T8-F<`KK-aXa6hln(>P+Jyn!0x zmgLZ(SLbvC{kr^?`MoUlP>||#Y%_olUSBJ}x5`yMWBILGEU4ZIf;aa<#*88QC05sv zDheyzY(P%dnRu8vfUn*-RokZ31Da=|TM~y~W$Ei%9xX(3k3od~lD0_BjqFO0tl_1K)lZ=|JPgTU+L z?5V3SoJuVKhE$0HM7fYq5j>5Hya{Q`KBkb$dK8m+>((t-==n|wt%TUpqxJ$jP{j4{ zoL~HS2?7oHm8mwD+7pMYos=DYpz2&}#8kn3opNA_PRTEgTk%j9p|oC1hTYq%=k<~7 zC}!(~n~Ve@>(DmCK%DV|LXq`NX`&c9J`|PWlx(X`zb-vW>S9m)Y?lsw^~!~j8RWg( zUMTSCN;tNJ3HKL+=8ms34Fxk%EN~DakNa#&Y@@yuYN52Mw0kVyog0B$O@`P#stYP9 zP;tRomEE2qp=HpML;pa^NOeEr;q^07x$0Ay+N&8Q80`^;*sf72_lQZ8`xV}yQ;vBe zc~2p!xk0HGRUoo9kYhqYbt^L!!m8cGwH;*)O|VcEvw`>?LW*{5B@C02KnJ{#8-{8~ z4NM-CR_l~rnuN_oqhp8|v`+Kw>U(osr(e`cf*_Ezr zu7SY2DMUrES`@b71t-!OjZB+SRfH(B(&bK>=i3cqOu7{K<~~D~OA#Aiw2qjulHd_q zNwq!ZmTM|Qz{hb{skqRB=Q_BZ!m7&<^n48jU-qPh3H&p>JF5E)wuSDf6zu>(w+q^A zc=B&j{zHtl7m^aPvO(TW8&=q@e zxboH>tdj!70hKS(K%LM-e`IVONEFlHkg2n?m>M0_P(UC_p?=<>ieWk?66hG-c!neM zqyH4fTpbuII^_V~ZyipZMCA9Q7)#ykai11gK*{v>1?D>x4S{4dXrx%1QM-q-Tgb3n z5F2mhh;140w^4TXu6?c0b4=c(wRI@Plk|%rm9{g%u~#TG_0-X5qWlvj+r+&y6cA!n z0JzK`W0kHPt8gB=tALqe0ng-x4j5f?%+8j!R?*ODbBGJQ-=!2M2bYu z%dA3jvj9sO4do4$@^{PVQlJkHJ_{(`msf8^n~`c02mCgHOizjvyriyV7z)1V$$m-Y zzj`k|OeIkE(C$Hh`GpD(EB5SAq@I1}v!rdUOf#0B#(^~m)KmnufGzBm9+ZS+_Ld&} zvyZ6{0mD`09cXQ+Yy*jK58B*vmC9Fe$1Nb>jAazUzKFSmXVgw272AC_iv*TJj>)S; zBa}oux#@jD{V8=MQT3JvXl#{`GlJMKi|w!&AFoX`NToDM7Md+FK3a$}lpLeZF1ot) zmQw^bt$~PPG9Ij7_HW!n;=AV2_=w-+oADOy+y#)SW@n$`RP`~t4|bC5Pm&>^{gPzR zd7L|!-R6oaS>YI5ooT3z4t1h|x9Pb*0tMfsaPa=xJH6btP$C`NA}8!n>4iwX4zV_i`PF(VMhMRCXE-6*4vv z*o0@hzYZPv`Ba)97ZzNwWniz~+xtR}jnFsXS-?O_m3*aKur>p58vV9t$u_YP$)GX$ zPmF~ZzM^-+onB;?qumtnTh1O2DqpbuNwwU8u`7Qe9a4r$4PW-RN5KE8&;0y3AHS>5Pvi5``1=WbUJ0L9!snInc^7=%1^-v?f|l-3 z>)P)(=QMUF=tV!?t!*}K%a;#yzf_p$_U!<#K#Pk0Ckie~U%Msw`0@CFA?dq*bGz_- zqtY6sKNqi8xLW$=ACfZankPo>SpVJPiT!^K8$aOd6|bWDKQy(Dcj!1~-u1wzP_HPayd|o^Meiom1*1w;{=eYClXYn~I|NB{dKC}M)EEa!0 z(f{jVIR5IPps1)g^zc7KZ~nnv>+x^KEv%~Kgc8G=VcVtqy$8}SD>wI0b|w%#>>KyF z@DGuUQqw@u_;J+$1_b9ph*UQW=zvIr;_*`WFbgOIg&iqEH~e}?$gBi4QJFVnZOT^I z*tDv2fAz81!4`kYnqV@xP}ZBe#&3a5 zb|!R(`+ql3bo4S1-Zpm~y1SN~T&z#wBfw2nt13BxfOTx|)nAGvrP}+7PJMH5kZ62P zH74T!enNRNGydvviwO?0BEdLK^m%#y`w=<*pUr>YZhV7D(Y%|0T_s`mm(kYx)xr-y z^987^2>6_&?L%$*%3$C3lQcD=aqPuN?n4 z6Tm;Nn{QLU%cM9?HQXd`F#aqQlf>L;Yjea(byHJQ4$2`|I1C@|LVfi%*gXGmY=ARC z-n8X`4*serg=xk3ylGALKpq{LtbzZIj_obFd_fh0gmnSqI%S}ZeW7uFaAd_r0=Y}! zg=8nSrmyJUa11&7#C8*|4Y>F4{e4BRI^cdxi{flJXi6!WI8i|nh})76um7yyzVJv>*d^GJ>1G+! zekpod`O6p)Tq~;c8XS_mX zN})`d_EwBTj+7Q#nOVLD=3+L6@H8sSs6B(vN%6?!=j6^CiVVR~pC-l+pwzbIuir8r zSYTGF*P$=gkp{96Kpxk&wzk|zD?{klIXD9~I*)L{x-nRz7CBq3lW6ONA-qwL9?#wJ zm3Vpx&+QnsCjt5)_UYn_n|xk(Fpab^pHBMym#=nWB23g7X-s(~*0g+b11A20yy2QP z2Ip{%?N7%x4-`3`3Dk9XKSH$lt94ph!zlocRBHDEWw2pd-mY~R)!neD`&sq;ZZJxc zL5|_FFOB5aVb;o->g|goMSB)Ok}jj&1WMtv0fF`@S_F^~UD?*uibNTvpclX+ts@}4 zc>bOzmk%|hE5GcBoiTySQSxOR|F=TNhvSP}3F9yI0vqMee=%c9hFoe<106`Ay$E1; zu`eDuVxt!vx|7#H@WCJbXC(p!uw{Yms)x#=%O6hI6l2whuC?}05Q$8;1F@TaAce@&5n6 z9meosvl!)24ilDRk*G9ts3BTI2dWh%Aw*~O{@4tiG>u3qr0h%H<%SI3m zkoFk_iHm@H;Z)S#(WRky2U$s1_w6qB#7`?-33~wQA{CNzO8C`H^~u#hBoUVniA2wF zBuxZxCBrr8{P{^_BFwq5%i+7#t8M2sn8H2=UbKFunZW};YN`FnzO6KQM4qxm3Cl29g!dCu4l9)P@fP=Ba1QYw7MEVIuFv5Q$P3W z)vKl2PS_VbjvVeW&1Xn)#u3mC;+laXuIp%X0b%?w_sG>er@21gB>==rNr~%c zm(-Y8y$ImpkMh;A`D~L7yy2o^5XBF;frS?I?*oJ}jB5&oEF_WqTWwuje_UyRy-B<%*%OY$IL3s5okdB;bOP{{^F2K}s zEP!hXhdjU4M;>n_b>`p9x_#;uJfEw`q3(rLhLiL@|@d9aWbV zz_bMgdwUyJ^}$zcoC1%IGWs+s;Yv#>Ew{S*FfGqto3K^p4C4t=BavxlQvzTn z01EEd(by?3ub4@yd{q}(^D9ThFexn<$)~L+A-;cl;Bju*$K#C)8H>2k11LAtUZ_y;ztIjhZesT#?E?A|?5KlwBk z0qE@2uZ?<01}(%^IHQlhrIflPx2%(va*7J+if#Q?Y==*O&f7hX@y0|i`JE?vxJXN3 zvG13)Jxufl07@%SSYJ`;e5SzEn<+F)GcsN#uKO2Cq4R>JKcmQ*UTO#q6U1e z8?>{Ny*olPren^}FB7IXpC8Tg+?Kf@QxF0jUI5N03 zGAwsL+0QHRWE(BTCo98dR19x~GA{UzL$VbKorf__bNw}5tA~(r1zw$Z=~qV5AO!$*o&q@k%&=pSJEpShg|1VycPs+!Iv&I;k5Q4Csap*+mPN_N zs<4uh-ol)4GMH1Y<~O*)x`~3`JXNfT&k1bf{tlRHm;pgTKRfOoa*SV25?91rx50lw z5Mq`a@_UD8OK*CPKvQo#k)j*IBks3ERFpHAca0AlPhY$M+SG<+mUN0%; zuwfVDEI?yEofNjG0S?=a(YHCSZ>=bm76YDn;u8}ZavhA;ta*B>u>-Le#adJ0us`Sc zZh-d)A!0ahk;g8gNsJI+ByF{gSFIWfm6fcI^2cHQ0=~3tS-dozcghrZ<5|ojulFoC zZ|t=?vZTs>t0DY7r);To%xP@cI-^yq4%c`RD(P65RP*ye&++8NX1K@WNMi6*n}a%^ z_m$Uv-b$@^V8sJs`vWKG6aO_x#H7uBAYU2;XfTj1gP!`uvp2;M1o+50L)$^NYKerT%l~&Rv{(??Qm$=>Y31wuc_fvHE7oB7Z}_QxTFc zmwp|ae(L(ku@}{*O!>I3Wy$2)j1kQRw(*VeD=c-xC%4C!K23JIzTxmwr?!TmdQL(y z4%?1tf>O^uE$~NM?VA#eCN>~o_u{n1O$5J&rsW2^W3o-cr7&(yOHs<$j$qbKrxrl_ zyMX5(%36qdC%c0t*vhm|H_(y23I&{1NUcI?hlic6$n)Kg-7bta_<=gn}2KcN5Vwg1{h^a3M)Uy zz=(g?O$3oes`K9)6qH2c=oB43k~w1U`eekV6HpC~K8^|eLsyfq>IvTQwLk#VnZ}0I zqzn?GRY`w<9PpvLZHmv(e#?6a8oTiAdNX4AR^FEa8cm^dC7njfMPG#XO~|muH>XTm z91kz1#BMzYy;oV^w*t9hXzj_ubsDZ5mxFb7w*D zxprp$;9=D#y*bkS(Le<5iO9|2P58>fdlQD<4!C2`Vn5ArgBX0p{tX zB;E4(ehL%rVp=jN>pO38Nya?vS`ztJQ<&Ja9N7lG8nOW!qBLhKqc+AN5VMYw0a&UuE1dzW2B!QhjHcc7{KMwg`vK(xgbHyCK2*5C~X}HE)Z@dy+qP|&usqNTfG$ibNO^M zQIna2S$S&=?wMwu*mkF%=z;KW3L%^Aux42rv(9!M3~_VyMYvjY)FvR^y#%Ksb7?iK zs9lsYfZC?XJ9`Rgw)kBmW8u@Oras*1dcI`6F90lk< zZRgO|tG>qbS)9K_z?ehxX8$xdM3yr~D*R&C@Nj@OVo;P8>F*a<(oNZRx9j&#GuxWmr zkT*-TzsuWd7eB5*%G=f(aeBj@ANwg>mT`>E1e7O+?z`XK?(5(F>s7>FrDui-(T+Ee zYFne6VVW7bOJ+)|He>|sam3M_)55JPH)KvCMFb+a$WkiSaT0+eH7C=Z5Axa8#CR6y zAL37!t`4n*TSbf;Zs(-_*?uGVgD(jkemT@G^qQo z*HNdsL(u`%hTk*6NTfu!EmKFd=!fy!%2mpOiVk-ScI1INsywfCdN|8JtR*kGEsy*y zJr!U8)3CeJhS57+!e-K7=7j9VS>}X%fC6x1IO%|uSLe#>ro40e1Dkl`e!gvs5R9C# zkfq~}sKXBqg zv~JJZuxi0ctv!S^DQ~DRZ|EFL>qlqUaC{d>3R4;+FnW!QVnI;lDB6mH*3AjuW4CK? z48m&KRmj0sp@b4?$5K1~>;X!p-Q3lP0UAZ>mY^IyyF4DHJ$0&Pm?H@I z83D&#sA`8B)Zq>8vu+h{u=VUAg?;Ya^4JQl>e39D$e) zr>tCBO4|>?xt&>R+>!7-j$)Y;7W zFzJ^v-xD2CAZ*~4<8sthJX0Su=Y@oN9vr|KJC>9KGz`ULd(m<#xr<4)_&g`hJ+bn+ z*xtTubeoPKNz_Eymou3sQ}^%RPZ=BV+9W@1#Ie)6p;4bXf?Ok#TYqzdv=fz=tRH%n3i=d{GD)!Ax%q|t=L;TiZdjhd7Kfq zO1#Bz>Y|*we0k=j-GXGdG1O?q$-Iu{OC3He+`5kxBJ{=RhVfs+7935z84UI6K4S?h zh8$aS7Wof3Rx-Qs&OtU~L_AuVtWiLS=W91($t9T=pZ z{{k;rOp+kr`)?KS(1?LnjyZ4lYg+DiulEd?x}Q`+O!h!Fb8B=yQz)_1!U8rEaILUU z1^o*Hre0S8yTB+|c`sfbCgxN2+OQn2A~~F9U3B*V1vG!Vc#*Syix4GcRP_~dM)B%l zy!zuiuv|ID;?=)-Q(j&^K&LkxAg5H%vyEkXa7mOd18~)~#E|n1!uN#Cd*btI_cC5W&L@ zCX?K_fH`BS82THcnmWtAg336UJ}XDQT`}&hn1XYbbFJThgBK=z`r z15v`%I#>BO>HYiTuEV-=`kHmSR&7S^bM7gJPOqa{Jz%=g*~4}hY4Qfjydb_s=DRxzL#3H$`@_oqVR*?gCwdIyPQtjv&yWzr zW%ADf^f1iVx|f|DC?h0-Qoi_QLv(>=_St=I*|E=9L%4$oQ2gv=WkCGs6^WXlmMm>ld{W+{y>)nitqFKPai7(t(6m*e~O<;+j73&NAvrGH-yMT z7aR;Wrg|Mp@#k;nf>CEMiPUf_7Kj0htJ|xpl_IB@M5~MjJzDo7^f%~Qgos-ZcOJ>4 z*+dyEFMG0I6;@s=91W51ML%5iZrbOq?;28fox|{mg9ggjw_{QG!-I7jz?D`Q3iheY zyJi0$&|GXf*wJ+G!#yqfa8HP; z1Fu>v>+ynhFvOZqtSS-L2B0ghs%>;*Eo3d}Ir=zg=I=E2M9Hz=imn&5r|Sjj{d>az zp%H$C)tDC=?_(Kmau-B$5v_z*=uLV8-_nHk`E#qvA3o9D@7;3Ed#USK`8r2@ zN*5}A`m31>*N=v^lb3A0=blO+5-^vn_VU2vvQxfO@0qj&d%q9PN!snP2l=G<*{jm^ zzE|qehjAF*CeftlEhID<&2_oqt*=!383t{oi*?*xZaz>({bUN*DTH-W*y(rgHN75F z*4@xR(>f%^LQT#Z1@-txR+Xsu9wfmB)&%?qR`N?nT<`W}L$cs=FUx$#2x~1ZmDw7V zy2nMAC%u6?4gg%C4^pcJGmd0;FW~qOJ415$BMEv^!^!uCeUSB#!Oil z60F~%qLy##8ibSc!-_ZVKAb`PdPK_fiWT@AGtP!0egPlo8au(inuC&JgpZ6zsKZQb( z%c{;*kY6b$mxSvWy0*G2tq`Z4&vq| zfR(7pU)GJK^UZ;q;_8wAHmR-BG4)zfebjIe?J(YTtc^p+O)e3#D=0;-I5xBU1o(Vs zup6I~`{cKQ5@fK2yFIxj4m1FSph?}?0}Y$gAel%Z@r}{W&1L6OfvEYpQE_#o$zYUJ zM5%QyM`*q|D)mf&$ykwrk`2SkjH>onR9K~!9rc!)CSM{?V%-oNSxyCP=HfFkQjDI( zpCfYqeDY*`?j=YzieV@yy)3=nZy;Tk&2F?#-6}1CZ()U$Tqcg*EqS3od5;^5eeyY0 zStNx7|8HRS&5nv66%6--U!ji!%pBFzOU_OcFCnbN>5%^3ZXOaS6}!@LVJwkv2n4G$-+@MLurPd9{XQ6xuMHfMVmaYHc+$|u{L34blJu2;q0qv0 z6Q6cg<_&kbNpI& znBrJj?ci?Z;Z1@)swhGXWDnX{V`C3s{JY`)-ud6}^82SqW7u*$yt< z=r#+vN@TrfZ;3KAVwoCCnto1l0jeCk2Y}~Ys@nVj z?W~!7Bo3Q45vX8f_Qt#O%}A^tMY1a=eky$FrDA5gzI`!aRJ(uLXrYSS6{we&>JZRn z8+jPbIhwn~K^^U9QT@9Ma?>GjlK09Iy(gJl-MDyhD&@zYw#&az?{fE+>TmV(&R#_a zytSp<4n5Dq{-IH^(NSK};lH0iIB6~_sLH5S++SL_KW%Bmd+!Us|9;Ob9NjsKmd-o; zuvYpxKrGqdPb-!q!&<&AxN7Tu%cSG_<2SCUYQYVlIVLab_8rJ2OQRPSpy z(0%qt{yP4%m3zFvPTCOl^vRP~33i8oF_2db!@3-A%2|7Fht8lYtM`<(*QeWTL7laq z;UQ%vxiWVUjO{3hMW+CP=g%=-Afrh^$hD(D(*Q-*Op_M4l+&m`-L{wCjKs5h@9AeT z2L(6rLlb3mz3CjqCBSYu9-OpfwA*@VE|H#ySu&OuovYZzD)u}bFG3vt`F~b{?n&B5o z=!0cdW`tpuxkhM0Eyx%9%T`Anl{#*99vIXCl|kZXYGIq+x68}rxO4~99U1rInM(>Uc}Z08f+1TUHV z301y=u@m>)q1I;zkYw(D2Mq_QF(W*Y`v@nh zc6NEypp+ZK|5u?P*#11RyQfCDx-)?-bS*-$1ttY=O0et(}p z$Be42eyW}M(5)np8_926Wz4fMK^vevIwx$<6(_@mRy(#K$hgc(4+y;0z+3-SQN=QF zVMkkGDjtNjV6B^)Bf3`i?|Wl>o`M9D)*&y(zyA}AhLQD|x-Dua4cgD3p~-srLinmD zPoCUGcTeQeNAsbwKA)Uorvv6rcDO!o&E-T#-U0@2N_Tf!1r^1=hkI|?E+s>8j4qgu zd!I|cgt&Z;LmS#z%QhZ5fes1ahO1gD?B@HD4+&0LfeuMTDdDt9aSWYXG6>FQs|bF? zAEdmmzJD`6y&-AT&aAH7v+va z@@vYaj!u1KeLYw~G`foSj|;9%zK@w{Zc4kISL^UCHsDYP~_WDHoQ`AGBPi!1wj=jVA)gPjE51e z0ZMzVL0}VG>|Fx7<@@*5{B>r(DoAdB8pp`kHteUyB1DD?rH7sxb*YYomzSMnu(qd7slY#{EM2s#laJ|nNNP*~A zm!WPx6r6wta7vtaC~T{8!H)IyvqRH-7{FNf+^WG^Z5L(dfr>6a60#o3zg{Ji2oD63 zisjf9cy7PVEAHjP%mjJ%#{mMOxCm(52ky4u=+vq{K1Bd2V&5g;<=Rou8R}0Q*|pIn z+U7t<%9;VER|pxe<*)OzbNZn#`Yk`?kvh_8nXDPS-bb>%VBvkiSY;P!H^98hoCkF; zSQtTNiXve&Y|r>P%V!3FMQb9Am&v7z7Y*@BV%RQp2xGjV!!dCP?s}^ltd6sK!%`~wGI2Nd6=f;=M()rzYX=)2MwF~f}rt;VJ1_p!>@kxin#oB?A4%EH-Y6_ z*H=F;VKk<7vn7-8Z8o0Rk-8UPL3F!Ak-`-3CbOddp*8cgxFc^nhlguK;>MR`=*f~oZOBS zV9BCIDN_s0*R2~xy#Q*`*VI3?wA1lG5g`>c{L$u4nznCW+-AS6j|0xV8!7R$DhbTS z=gbe?+qUP_>o4{kow?zgjH-D^Vytl!S~sULK%SYwkUkX*a#x<}pd8R~4YX~G(4Dsi zrVIIiB2n!yFN<(ci32b)Hy;5KQG-a6n6Yf6pog1(wjHO>7Z8KjKrQ>Z1L?wk=IH-k&D9Gc`Th0?P(C_1LP^ZDfu;;Ct zn`oO+P-1$MQMDQNgVcCh13MPCmL;aIM__a(S^m^3?}l(_MEpp0-zH(1*?ljf4Mv$pHVVPv-R z)Qo?HR3?BhqyX6PZI`MyeX~L+0KIH6h;`FVI)Hya{z4<(2`D%zqr^+?Z!YcdYQ(v; zDM)Y|DB~vauGRDostuFhsNUbcdm~^B(HsaBkTd#x91oTl7(2AtxXv z!jg@na04|!^GH!vJanxqb^2iN0!0M|6i@T4DiMPD!l5HshV`_8Ii~~XCLvQ}4NCy1 zl`3J3g8P@~XbhgPB5WjZ&yLZ~QbjxJN`$42 z?0iQryWfA{QS9j@hyZ@LicvNM-ru;Ms?!3)t^D<}H^{`UtInum|FFM~{7VF(B>)Xq zEt^WxGw%sHlMVAX^C$0A{}HOKo&LGy;}u=@OvR}1eTGXBP|CSw^)P0sz@U&9^rNGb zM;U6@+yw}=+3=F4gG`P2KEg}2Tihu{6 zGrAKyy|31StCJH!)pa15x2LETaC~cU_2SO`hW~-+8C~+BMnL^b&dV<@Sy0p4O8%qJ zzX%vYKfr0L>za`m6k!nP%UcWg)(|*8yxqSkJLu5f&a~gEu(;o?&R-kyfH^#!&xpuG z5Z;OsA=*ZlS@c2A0O+My<1NVF6o0ra{|&wE^4U7^-zsjhVowkahU2!M%f*`YN4J6+ z5_2lAWEVlEDet^95)@3@%YR*EVE1};-huG#8B>C)|KroH+!e-j{b&8b|NNJ(wZI_K z|K8PTcWiN1N>r}{@p^B*Nm;eTA#wtN5me@WT)yuGto=hxfrq9Za` MWVrC+0;@g$2e_IcDF6Tf diff --git a/tuning logs/2025-02-25_02-59-27/plots/error_v.png b/tuning logs/2025-02-25_02-59-27/plots/error_v.png deleted file mode 100644 index 46b303e12ed9929762a8bc4508a152e87dac422c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 207875 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@Lgd(cU%(k`BGT}Chs2~W~D&~Yl0Rdag2!f!JQA9F`NDxWgwhBlvf@Ir(fC5TJqDqo1 zC^;x7NEXTYdsYP~&hdQXj{ED5aZioCZJ?^&_g!nvHPd>YIU}S9;2MdnA4(4_37``m z%XRbJZ7d)7^O93};cF}5Fy-tMQ)GbPl`W(YoIlRO9nZL%eF|a4QirR!_un=E;QGSn zzh(FL!cSg39KGXMuz_k*%0`-R6U9EYUvf6!peqXifIn7nv9Vo4T2nK6!x!kvg{yYU z*n0m1&g(pc0H4;2wCLa*Qq*BIAy^0bMk+z|={c<{-&cTCSJ>%~!&+&a>rrQqppk)@ zs}4Br4q8Jas;>Qsx#2e|+jiVaY{9&Fe?5Qx{PRPk=2~iZxNDo08k0PP)xCS6`-4A( zZGtLQ6c?(ZhdIM)2!7#s{9_L9FhngrV#bP45nMl1^s2)E&a2f7pP!{X6f{^ye3$(W zEJ)h@P1wg)?qBnb^a#Ky)&A<)8k|@2BN0*X>jF;iaeOMAy!mkdUp%NL_YQH6VBU*O z^CA9Du&qYI8}_a)dVK|>UZ@(aNwpT(EP8GfFRN(~=Ptj`FjJCcej1n|>b7=W@%w)-Qsh$XZvO!Rvamk%xl0eXFC zpK15&+mV_i>m~3e*s=;~t}3U}g)~HC^CEXb_l6JcSLF>Rf%!v(F3%mMcW}Td&1R(7@U0xs0=w>I{u4g_Uw?VJ-~M8>Z3>-PWwZT zj6dGw`Zuth3psXCkZ*YhSNj=f(RpyCp5U(U5&&HlHGUp6Hx>k!y1F{yG|gMJj(??@ zx-M9_FlML^0HK2jSA;?{=^L~~J}&fR+=nt&*gZE?`IF%w8U}?i-UhEGMhvR_StCm7 z5Q2QQzx;V5oPU%)UxNJEbx?egvM%+<_V7*&-c+jjd(HyEA@NqE=t0Vxg@RM(2hJGI zVPQGikuwS*ZvYYUJ+i;;g+4%$A_E`I|7i`Z+jk`T$I@@$VuVr;41-m30qREF+L`JM zWn8g$WhI#@!qxfm_8OrK5L1(Ix#e!FIm!NGK!(45zIyzyWf+(NZZP24IR*8dP;T-o zOdY54h&8+m4hfrG!0c{z>l+w21h(7d7nyGPf{_c%X*t7*%hB7k3 zTS0my<%bdyKiKET02)7g?p&SjhD;QJvP{MHAmCDEopik*dluB1_?(zy1FQB90jw)- zUL|pG-@X~}g|DN4%6VPgBPmTV{>8m4btp{m=VwzJ2-pGGCHSPzS_<58DoF@npllHl zBn3N2WhW#y1oO<(aL##@;~se52)=bdb_R*t(=;|`lSf(Gl4APotPz7!d5SlX8wNoB!lI=ophyyUC_+Rw|C)XC!qlncqYkV5igh#Mba z(Qve!Q=i%e76%{zFL+LeQ*$5KCyQXNv)Q%m&XyKlgpizhr9Fe3AmE5rN-!8lYayp2 z16yBz5JR8^LhZv(v)C!xIM9PAUej1|7l}~<^X~=&vRZ53K4jC#!eh}LjK`hbVPl%O`dk!x#24mJb#7FwmIupDF% z7QlM%j=wYjpUSwY@gT%_ zoOZoS0CF?NxN;e<-Om|dIXu3qVfdl_M0@@clXW!ZQhrV$W|-ZOu4%Sd5o97FQ1Lel z{XV@^DGja_n-8_S05vz_I4!yx4z$#o^qp93xUH8Us%ow4mHT`lCSMVa9>f@n0hL?Z zh-8Q}MxcZI0|q3e^xbBxubdy{CzK;uH_J6=DuAO*$}hBb-XsU3WPczAJn~&>`5eNi z0bg>gxarR0-u6m1fTiwxct6`TpMZ@K6YlFX0t3_uMMNIK&=Z(TuJ_KJeQ$7}`G=$= z4`6~>@SI6I@UKf{7MK04fDw_{}0 zi1oi8$y%cX#$gV2R@SpQ1&RIS01&0)cDTLJOcBGRt{*FYI9K<=g|&d`A%UsbCq~k! zU3J_z#y$Y;@{F?+&YtN6Qnkoa-T#_WqBb;2MrHSYu@n~ z=<6fZf{UNa^P&XZyV}~Zf6Yn-XOA|J~xApS^jCIE^iSv4TjnIW>Qf!4B2EWc-&&Q|2J%E67|M~MzJG0gG z;WV5{wt4;eAyU_<%9!7&?s2}!B0rYf+0*k70{T11POKnX495X|MjUWK7y>wX<@`w-Lkt@V4qAn{$%>NOLII>;#$11PAh17y=$;F zIu4s!RCb9s7dSvLXUSQhQBOU8+{Nzzw_DDo_zIi2lAQ*7c<985rNoDPuo2!N<`pSg zu2(2CM-n0Br$8;j5AUn1)rN(Z=zObcHBM^`H>VYsD@2fYDvV$G+vkbwx|BmlG|EwI zvBO=%OJj%Yw#Q%Q?7a1-;y)X%sI769u>CVbFh=oYQoy~c(3ldBY&qZW&&00$>+!T< z5$gf>;jsJc3zxHg8-6io`GNI!DeS^l-nx#C&KEws>)hqNMBFob&scPi&p@+KzOg`b zp+#N&aGB}4uj-(US)fp4$FDq~5!zpcgohUlZUd3qQvGU2Y{#3zzvl9AeE$6TBLYw1 zl%lYT zaTZpx0T~z%Qhg3#x}vI7z@2a2slCrg*~*frQ${7M>M3SGfta_y&W;U8I^-&aHR(RwDRR_d0Cwi=;z}G(nT61-bK*y{l z62%b#W)`{#@Ikq3sO1?zwcO2c%L9I0A$4IuuwHi#RN&2#AMt#my~X>bob~D_#;UQ9 z$z%Q1uMzwXmZyz>4vsD9v%CMTxezr)fnw9o50Xl&E$@Hj#97>+P&$&LlQ(^fZOMcyWtb^%JI{bf;Nm0ECECJZgkl zFdML(@TMeKa`&01Yz=h0`{dt$|Jbr+OTT`0GZ`1Exwd1Q8~AUtCl!Wk5B4JyqhD&8 zbM+j&0drKg?b>~??xc0Cd?SX`BCZ3?W z)f{)OFj?>K3YUkZ!vt1NU?RQ}`N@5A z6um3h)x}xrRjVaw3~@0Cc!DD{^BVK)Oqlj6%M>;_(LdU{&14)Tuyw!mi*rKoVwTG5Q_EeXr_Qyign~ye$q#5*Ba&mGu+&RSK0x$l&XOZLEIqVt8l$ z+Ktqr9EpwpIK7fS+3iOLZAp1zk<@N?LAiSlI0<%x|J45LVO&Od%S9Bi&H$=UAj%5r zA7#V!&UZMIW(gg?eqrJS!;}*b+9W;J=_r$T?WG`KPHXtQv4bH8e{pnm3L`rD# zHEJNL0vqIIpx-BenYW;>uYYXzFCP!h@4o<(^{VL;^J4;0nSyA;Ry1RO2)`l4fr0mwZ1!EGlZHtlATb9FaJ4#C9xvi z2B2wnJ46Juz)O_C3Ac*9$KJM=(G3u47eIL~bodYD+xyoO33)r0*A0m3okqTSv*)=YI+~KJLq%SG=-WZLVYngDE>w?qRW6I%&3H0+Rqwt_2 zQfZgGvq>59ReMCR05KQ3#SDtqct=C7L&b{kOB(6n^%<@I^& zsXyU`^Gt^W1p$ialvIC_v1hgZhNs)%D}TsBai>Z`Inmku?<{=ry8# z7OB#GVSTD3u_*96U0|zYA_Gi27CE6baz)6?m$DT2@2}j*&wIDvd3OKJ z?`<6$EMd{CNge+F1QcA?jvSmQT4H4Ms-}$lc6CF^v7PS3D?sihFixnN)b%iM+u~_!quo}8 zs3MbrdRNVZZCVqY$euV5JG)A}JTN38!UIe7s32RfNoUCO{7#R*u$A*o>nXh}zxb)FKtJKC&~ zPR4q0Kou4Yd2=rP2#nNVzMdo-u{G57Axu}C>o3I_>J_3y${S;kVcVL6q>)9iKBQ~K zEv?bD@E4=vo?L)6X++lot=&oE%VajBD&hX`A8C- zMjigM-r2H&5_?+P+M;*M!#s_C+bHEyRaG?zL+IyKA$4-bMGXxNiJ$4Sk|dgNW%hFP z3%G5WnaD#nwUfsSWXTIf8{P0ffd=$6a3<0KU@a%sP3oj(G;n8Rc5$OW;ff9JvYcB2 z%mnEhfuoo05mA^SV$|VsXCpIR z8sz|sx7zZP0_o4evFFlxe|UncDr4iedm!N>3N=YQO&of1pq7LOnF}&iaC^E@mO}>P z5fl`RG0@AG<&d!m zq03SGW4mcmM;s*fv#BQ_$QD&aj>J*I5k>>b5IZCNn1Psu^ilCZ1EsyH@sA&q1!{;6 z8Z##9%qZzI-%uiTZqSH=+Dpbu&C~@=ZFV6f@-7iW7SA2o6$uZ?;U5cSeR(zpTvkMR zG!bl8sSHFGJRl^T&z)!@UJfcUO2P+Yb)7-Nc(-aZI5aDPnT3(nqz8DKvxD3-Hp$@HC>U<&PLvh>@8CJ zKgRz#vhHZjaUZ27jmZO}X7U{`%OhzXKNC#17D*+ZR90R=97a#a(I*AvP;@+wM9Pv)!GP~rx)-D#G(_=TL+j6 zlhiuctVWBV5p{Kts?0N351qgGuJ22N^c=yl^A*w=st&b9Y=Co>8XR+WhNI<< z9A!2NeXyjLn4svt~r%$u@_4R$MsNg`|3zyv7+>nqEXE+TGOBXES*tG`drb}^(kXz+(`RWVA zdk@jL1U)9UViDPiuLi$(E0+2k0%HY4N+kAzD@WYng{wt(5pPBm9_*6@o34?FR-&hH zG|mn9?m6Nj;E;U`>zpO55sBF+vLo6NQ`+EfQRqSp`1^Z*wuzODc#>nJdKA;cOb*SR zxC*E#=?Oy~8zcu3*5j_QZ=5j5)acc5VyyAi`^C5L3DSzfu7NGc8P4|i-ndtKVkM2X zdJ+@2H|u1%xk!z*$cJl=hsxV;0mwKY)8(!ie0$RMD8_aO=h8axuT=a=C#$-3w0_>p z%t&B`3Y}mjs=QQ-r#=PJ6TI#H(HKxR%xA+x9S;|z{hMvo@x^|{f`S5+jeblTsi50P z7F=*0^4LmB%gOV?r6Hj@HG+mMltB_d;trb0%|PlPuS5nn`pHYpt>7o}`msh1Rby;A6Ps02Mz?AW9mS#T=38uhBxWr0V@n#J_5dgMn0mX5-G-KFBwb_TY_FgL(P-=GwA==n50_vWV>u@d%J^UHOl;7? zJuek5PAB)Ky^7zGHNuvDLORfRqr&t$P2{`Kk3!9BV_rD&$k~6~T)hnYLp&uJp#!o1 zqCXy8i;^JoI4UxIG!{qfW2^q#6p9c{>yc6 z@-9+)`Q!_4fGUL|-n52c3Dl$p-!4&gcU-sDq3?wjbrlXToc=vw6uPo$4SjB9s{$ju z?aZq+NYUQ^9vWo?=bZoYk7E6fC#57KfKCc~^G;#}(rq*cl0J)njdhqg-tx3>*9q@* z5JwLj;tY5_&y4`?B3o{BgZAqu&|hFUw?@MVtI}-dfsLW_*I;G@H?!jqxYxzZt!f7=Kx_k9mCL zueaCC)MmU(`|shU|NA(M8TtSI?A&fpN88Au$2gcECdhL%`RUX3pdWc(b72eu|2_Pe zgwqH#C4coGXv>BYve?B+sXT@LLnU|H{-CVkMVNd5na+r8rmt!5RE9mmF>65|2j%>} zvk{DjaE#B4@Be=#mdi>0Fo&IwkMCn~@y|O!-bh`6k&H)5j01cQRnA8aIS}0lXW+wI z8H)6w#y%Fx?M0dv6bgz<;YR~aGun@#(Ce9UQjVI6ig&LWP;%x#c+Vd}!TNKAX|K_n|GQHe6Y{@`gE15Tt5&CG0+#WAjn3qB{I5x#oQnS+IV^|G zX_nJzy=_Opc7FS}YOnSCf^AI3yz~u*e(=v>{b*MIi=*PXn!lB7kZ6>(Zdvo}$$1i^ zH=?yW+|%#%u=kx&chAI#nxJuYYIWo3)M&oIp=zl{kLFVuB1VgEnU$?x$#>wo%ERT8 z-~SOp^Z9=M5x+ND!lCysAhdoD<`Y?z99eq9egOunprb0WUK zcJOyyxQBGv|r9UaXU>u zsgu$?>MzapsdlQJz|d2LFQ|$rC&q3H12Ze#)Xp~|HejpBYCHLLBwya zzh;&%lM^oOO8e#2{$rf+6w{gwOkTYrec%gU&Du42`P*9<&(7p|9DYFi#Y*4cNWH3i zfr0we^Wk;+^6s7<+pARx-Ip(R^ zk}n6DBe2ah0g+}AG&!avJM~20*cnrIk9mHUGv@ztXXRGr2j!#w;GEgtoI|JRMQ zX02*Ta$Q`<_Sg1T-<+N^d81!{(PnG+Q-dT8rv2B?MioQc|Gai|U6u)L0jOVlG)7;& zKaLly3UQrUy~Xs_?5j#XF>hJM=P`|U#%pc4rp-O$J~srbW^g!76x9XHRZ$6Y;c+b7 z!);)&a*j-<)8mBMYZr&OynVRriN2tZTSJJs%gFhRgnZu3+wX}U$=wnzdupCs)`$EA zS%3Z=M@(g91Wl4P%`VRPWAP3S8MnVTom*<$(ivSNC3xD+zV7{=u~d7xdqvN;D2I-x zBo}$kSKf2E&wEk_a;~ARlXJ+^G>WM0ob<_=lAc8$_MN(OEXw?oe}7d#pQ?l45|CEJ zv=`$-ZoSKyFT$9+JDOZfv&}-6z;(>i%u4&k+4(5nnDu<7PakA_y7mCm@}H2R{URg7 zSE4neMlDx6d`gs=9`cwllY;4EJUeY{)JKw}}iUG1BhZ#_)gHz?7`e3eCX zVLfPjYt_pYQ*#h^g)xL}inYHV@LuK-&tQBUBj!%u`@7Mde_GC>O`l>4eCl8=dk?dYhg@xZDQOt<-qUndS^VYF7PgsZVL&b@75A#ojfIKD}N(ujAhjQ zsW>@r+I|~pVh-s%R**V#@{L{pp+D2wsEW_kModblm_oM`PvezL`&UeU!)YHw6>j$0 zs<5Ma=9Fpqbcm)gSrtOhv$ghDFuz654zFruo>fb_jgmPZJt6Wq{{Cmb8I1clnb583 z?(<9!bs{qE0!g@{|F>?WX}d@NlI4%L2i@}cBb9q{M^ipEZCp&Qvu5p<2gY?HEr}D& z6B7gG>#7^yC%L;>NJ;WbzG?np%rZ3#*8*wN%#zc($WN#5M#1YZA7ag$vaLJ;*0^N% z=(brulS{O+@%aLB{YUdmM?1m>znYyA9N{F-M14swU<^v>@$N4IX%lUFjV<2w96u8o zpP)z^(Rbm!<#`XzyfQY4j+`7fC5D5st=U#m4#{McNR7VUb8Yf{Coj4|-k=(r`l9mm zvn+u6jkE-KnCw3|uZgJXq8sFS?w%=b&I zC#4ehk47$#;@SDK%k_C#GAsM2jk!h_^UfKxplKOt8KuYFOGSc;GI?~w8cvRMaq2l3 z54>>*XWANr7PQCEKM~;>x#Cx!eIB!CG`ffO#7{#`G+WouhDm+;^dN?zQ&McbXu_nx zhv^R2qTKIw6R~l2yjrp+wt1g?vuJX@UWL>3p6f45mh|sOW%$DT-cP=pF1(K}{&!CO zt=7fz#o1X=g~^3Tei2^DPRTin!epQ{N}x1LW(BC8mn|(xcS=%wuKVp0hh6=EpjY77 z*w?f0Akdb7!iBWkzU5Y(w}Q&LS*{E; z0S?sua0O6j(O^5~PgJrmR6bM9EJf%`G^WD$*>*D~E82 zeT{c?4Z*;Gl;l}gSBD3(r{d>2V#~8|45rw_{op8HAqbl`_+n{-!%2S}+mh4KaND>i zPu3C4NCMh8G=fFw35vyLuo}WKS+1bB@T33wa)L~?>$C{E)!*MAZrcpJ%rdRPckIJG zYLG$>rTL3yr}HssuUFTJ1<^K20cMSe+ab^_8!P}uu^#P_ny|3@buY-SzS2XylVdKA zjrM9RCc*P$5%2D)_C)Z($su^~R$MPPfT4u6g$ zNA2fsa$EiA@u{_{-fjgvh&TLN@?jeSkvT#dd)5urnAAJ7bKHGyu}4VMO){usd2 z7KdF*9LP?ksW|F(dXxrllf@mqId+2&;WL;Ipvx){H1vbI&9s2hT><>s83F|CP9$gD z1nwH1Vt8!R%3IyQ5hXTRfJ^8~)-VD%k}!M+i^Enwm?c8RIiiE{C%bVR3wvHlO#a*j zW6Gib;67)~!I@tkGb!DQzbPCX%L$$ur7<-d1gPK!&`Ykkt=fTWzfcYAwq(T>RYEtwo;^F2IkSfi)JEXeNiTXlF?}7%vMV1ww1E6pM;5 z1NsLbu>wRDQsK$BG41KOoCP+5cK_BT|a&}2LYJm!gcXh z<~h4Yu6q3+V+B6}6-;OnAo>K1+}HKdWIrc-y}_lJ$VQ>0YnPYhuzZScVPRp09?^-|FGo$9 z2$q?^FqQ=+qKk*3ALjFR+|j3OUswL>bIc1@TFK;EcEMlR4vfbYg)I-l0s%s)>$Y|r zunx`l70{DwPiziUE;{y1Q60GO(EQvI6t?BXR+6_PAS-!$)9?vyz)9E$rn1$7>`A`z z?5O%bXVsf;Rc1DONwd?Xk8OQ$v|DSUPs^of^u5&R{^j$pD>cQ&#%A()tKS{W-yUDH z?E9rX53Z=F;JCiw$`0>aGvk>~(*Evd28>jXg&T7+ow@P5@rraD|sY9n1fldF@S zPKFX59W8)II@y$FKWA;0s3!{4zXC!1vxqb4!JI+3N8zO}I2EZWfTvp^M-kCtaSz!W) zJXWvDUTq=UAQ0R6*%&Q>T$)uf(j23J!Q%@|>nl_9DL|m2Kj*sL*o=!GnPLj<1v9lD zJ%dcxyEGGvw!y*(YjCxz;Jm3SkP|*Obss<8sccv6;^99hbAjl+;U{-Xu2#)=H>SuL ziA_G%tL^X(wi^-j7?6~Fk`{m{U)VhYTEkHZEl4(@V*2FEy+=t0wjwP60`f1E+ggVw z;erb{B-%K(`xVg~HR=_eh|=HQhE0A%f)|)XV(9Nx0!V$R9V*|Yh=B3Q)f`4T*c1QZ z71c_zGTC5(1un3b_ZQ{ASBa~HKi?tRQl zRC`()do!Rx+mzLy-UqeA2_IeVVMq1h9iX!?J({UdZkHILsVx zjuQzoLU9_GW}=gWdj`;lE~AIw&P#{Jgut!cw0ypDQQAOC*MZZgPaF0SdI<;_CJh4Y z>NCEj-G|#xIU=)9>Eb@a9z0u#*Qvj&%MMfgOZv~!9u@y;SL4}L%TTsuS<%MhzV};3 zRlBqjFX;yNj2Ho2<#|$mZ*1!jaCNIsYgj59_CzHA$|Y5h!UDn9`$~XEpPI00F=5F} zu8y?SJg2|BdI_=y2J*pRKBjAT%6oWnUN&`~KR@6|j{BQ9Jg?zioZg!@-1>r;+13Gn zf~+OXfcRGMlCP3|J{AbyZ5M}N)Qp5Pv|xhv=u}N%0K}G1P^GT72CiO~>}b?kDGMTy z$HZvSgj+{kbwsNGfrP7@XRd&XY;$mgzo~B9^2{6*hxL-y1w!Q+Hzj-jeN&Iq)LplU zvoWMTi_58$6V34@UtgC<8B|-0pmFYQAovr#>K@+ z7Ug|MEBe0AuL*n!BspF{Cxz-!Yb^^f5r?H9xVdzJ^zKrmiKjCEz~?P^*&3^V%DZh{ zzsXj?r4;Wu>5Q9G(vyZG-co#xQM<>b8RnJa_Ek3y{oh6T-u{ z6EsUgdsJT3;C8Z}FaOkJ@*R6Up=OQ{>QcjyG)p=(SA?zPnVE3w2`uO}w#Fa;L7WrA zkrSLyH};a{@LJIV!wr;1VF}Xov-=6}*d~I=yHU@7o1o>0uhL|J(wHBc%j*H<`_bN> zZzmbv4Ez6b*wS$W#Yu25St01NU#{hZukJ*T6n}f{^ZK4x5!+VJD?zryK0n%9N4geL zid*fPD3qwC9vsFC1&L6cUJfPiTNgH#IOEGsoQdlnK`{XqfKlMExj>`8`gv0(>R%4M5m@|3+{T_};m>F?BbWD3x<_}>~21r&-9UgvnxS9Rd#bQ4mIiz(t&06e? znao0U^oIK<O zGz%aR%zylQGm8Mx6X5hcIkPSJ;z>wfnRi>G(NJpYnQP1r4jcjfBd~(q$tN}~%-L&L zu=&B!S(iKoQOEv|LLe;(Bch>xyrZ7r218TRl(uAoY0jY+V0o&YnC`BL@vhKRuuHUG z(Sk+Va}sY`RWZCEX;$pnxHA7Gc3)=Us^hjmiRysIYyN(b$il-hqp<1Ou=rd-L-~4y zQCMIH__Q=!9SLOHnFn3-F^=vhO}2NQi)PTxxlE z=(!8qp1&V% zf;F-JB$&m$d-u8&#TZgX0Sy%IwjhnRIN#c_*szV&A z+N8GW6FbG5*&Rk+Li(65$OZ*^Wf2;FE!=TUV`>&ff5jn^N&w%GEodnBbn3E>j*ieG z9uZS2FdLBo;NA*5yiW!pCscg2wU#n13xE?J)e`W94Nc26fH@7e4(S_zt&@EaJ0sXy zKLgmyr4Nqw@vh#ve7-rNq6@+kz(m_{cfNl32+n%f`1T$4@gvf@CYaga@`E zP->(-+NUtGZ(Mc2$cxYbx<_GS^bvjSjvgX}Rho17>CHM4*(jKNH1lIpZa?PE*i{^b z=4f|q#=*EeFXl*fv|>BUw~=V4VdxOzw*0P(P)ZvE;kcKg_#)Drng*tn!Uas{5e`&G z7ra21W)$SL3GQLvsp)SciOnb5EYb>O>M@CWgXaP0Z4LZ0Tai&ME7al7AL6~?*0ZLk zXOJf5 ze#IDB{^TpUb+N6MqP~UM2e&4h=W|^h&rKd%{RRO<1!fzfyFf0==y|_bd>g-hbe+JZBZhgRH2GXe^oj9QNY(-dr z)kP9LvS9+=Xc;Uo(Jj*;fIO3&u^u?#$0ekIF;^4Q9($2C{34?VJS)jQecNLJ0RbOt zYXb)J(O^ixkLpxjQcl$ju{v>pIs0i$mO9y@aL>l>QK|7pDZ+UU&9?<>hq%EbGh_*H`pC9 zS{8)rlknY34KY7@_YqM0m~RgZ`k@`($3}}tKE|Oy6vQ>QA|xmLFTR`i8hmWz6iQIo zxB=VoFKL0CWfoFhCB-A`$m&9$%QXmq zRvofxZM-XLQ-50cfCvH#Z`qL^sAGYkmlkD`950Ej?MwmNS6eY}7LkExck7Z`7dai< zTsU=($AY89U7Hqy=9UT&_D0EQc=BlYb*ctQ9LtmulJHp#rtfP|Z8DmvgdU=I%aiUv>`wzz83TZEPcf|ZfvRYK84(wi#~6I*N;rkiRxH=Q{- zNu=;v7L+0fs__^$2oU6Z+IU-<2Vv9^XFo#^#`=Tk_xmRs%*LC{2%YM%T|Ws3;Qy4{ zH(waeb{x${6}xi<&4gkC61uaF$DR!_*~D3`x&O*=9l{5fc|D1i3AdKi!%f%oM5cqhiHVsd$wjq4JHCcr zo%M>zl2P-J_pz0ilME=4MW5se!kIx>y1pmJ<`GGRlI$>a?I))Ke=wHN{&dq~@DpeF z&4Yd}4l|+bP!bP$$D9Z{hWvGL6>@$$qt zA5YSlSb%keWuM=Kaz^Wjco83}9g^q+P%}ke_qv$Ke{((3A6b(POe%=LQ@yps{>T1B zDTGPSPq<#lMA)IUy8O_M@b6^ykyepG-D)tJ_V9xbhnNNv?~Yxb@$UM9M#3>GKK>pn zU~oj>t;tp<)`3$N^#IP`2V7e6agvaR#V0gdQV9V?*0yOPGw{1pD3IM(lekdczV+m5 z*u5nc8UqzNo*_!U6W3}{l+BGW!95*%pAhZ{;c*2bV?+vJ5JDOH%~p{VJ;WyG`z4b2 z;}AAJ(~dS?{K)o^!XP@ZN1j;i43s7E8>=Q0<*MGxJ=|n5Q=2NVWT6 zh|Qk{rI-XeJ?KS|nB^37s+j!Js0(egao&GXG95piTCa3$cLdz)6 z6aSuyH#k1gyzHf{22JrpEHl5HW2S{A(~oEu*AE z>MNOauNnQ=_Sz+7v3i_JL@{Xt8#)g_vFrlVz>AkKX8b5$3PnWAMCjt*)6)F(Z*eMZ z@A)s=hJIkKiwy4$=Io?39f-5GB;TwWnf&T-bsAugHZ_cAd=j<|jssT(MV&c&$9Pxf zX`)m79ZJHqLjcB`7~Uze7|&JKzy#4>*L-P%RV=Gu`ErRxWJ)Sn)-l$eucSJ?y6gnS zzsiR3HH!9arb*Lcb|=Q^Q=N;m;#=Q)g_knjj2KoE5G})o*DWxCD44C<8ikmr6@a| zUzr-S_6f$Q!nO~atf%Ziq&PX`^lI8Kw|D<;xH3v>Qz-GUrOBcNoB^g zG^hCFPHB#ZielagjLY6o_Ox4&I6U)V2pE|rffOyF>6PU3af^@*qqN7LcdgfLC zHNs53V<^s5`qM4n)S?Z<6BEonXX+u+=~G|)=xJ8`?Z};wFAe7H=0zV=u~%f5n%Q)0 z%;fIqn3HVTpQaGS6y7oP5a<0{>Yt-+VfS-sDu_D#FD51hsnnlh{*LLXwoA2LUE|$( zZnNvNUsqGT^1eSl(R_7so~8^(?gl(mG`( zZ70rTKHP*?*6gYq8=s{ii1!;!e-ov1ZPxHRc8sc9U&ap9DK?8~=mD`>wIvQ)mm~m`(W9W zncYCo^{##V@=D6SG#``_YxuX`#K72uaSh5Nd)k_X=-1q?fBBYT)3`vKQw@G7{iRQb zRYcnfog7aQSR)#)DEGn$o`N>>Sk;Z1wfuxn)UTv~rmC z!LHA=`8uHxDKZi*!h2a-XJm0tQ}BYR=k1{DTA5FKPYyi2-eaWMt@V(}Q7ENv)D?Z_ z`dQN_T0@4qo335pthA=VpQ+E{6v{9g`2hmXMaf;cqmJuhw9uIf?_|0gYZndVusCVtMQ{I+Si;zAESr7+wjQ49C%B)Xq3$Ym1TRLNg_X+x|#3_nEjQ-j+k0FV+aY-jYA+wp_uq^LGM*V| zb^F=e^bJ!^V|p*m|B^nCqG_9uB#!xAa_g}d7^d`>(+38Af76o`mpA0TZzQHYGkt-! zgz1f&#bPS{WR`u#{BxaG22AF!dyLCcDEFjkpJP>s6Fp&l;_S?erpyArohI-~pN@4| zSsNA0rv-EUZczFvUOr6s8(lEDPtM7Um&z}3x_RJZ`jN@IIvt@M$ve5)-r?!&lsokY zMVNX10c#kYXnr4vI}Dy$#- zC2Buy{vVb!=7ROhPxI2R?3mhdP6iAoqU`?Ig*pZn;1I=+X&RG}PAB(X(Py}NhQz&R z8lT-=AIC8Z1>LEecU$cD61?`Yo7J_dedj0=xy+l6J`X1pRHMY})*MR;<6>UDlZ?nx zA+Dx$gFLevnf{3;r|GkEmd*N-yopn6YG)MFT{g&ykyZB5MNT&pe>?Xk%`pNhRmvKg zG4|)k=%}wpn`zS=62ji+PLT_sNH7H?Q+MTf%94KNV=!7$Tqq(sss=z!2-ipM@fia)zh=M?Bbb{S1j zWS#bTt)w(FeUb5?@DjEU#9VWzQm&5^+FUO+BEPFy@5I~dGbW1i zh@N8z2`NA3X{9HSQxe%aUAa$Et&FeuQcc5S{V(e$zb{P>zD_9E_c*SLnh)n^n!Td0 z8r!4X*FM%Y`DQ#;73O( z{>)pwlzvAnQccO?s9ww_Eh3{nvXcS*w$PW7vDU&c57P|gQQ8_gJI9@@dif^>N{U5p z=Hy@*N=o^&2qmFp_7{aZtGFqbT9A$fXVbp@OzX4zd}fU}8MCXzah0C(q4+cJANu(d zwwGLYhMSFcxqPcpR_5ek5(gLcP z8q8I>P7&S7Y?!CiPupjaSPg%g0V*Nbb*R8it<3V$+7%44ZDM4>E)#>bsY4+rVRQ(b=LqT`w$V zvSxHQVZ}3+q^rAsJl`$~5uWsACxy^?)044>!q8CDtS4hloqZgtENgc$&$1xhX#A5C z1v7YH|Hc`UvRTF0Pn$MsKkR%Iw36cKIuCsY8Lt!Kv`L0hX|o*IbZpV|o6-eT)_I>4 zigYupE&4n?TzYMr$;^wI%NGSqd8_(#Qs$P{1FEl*HmXROr2NaQF&|912@bMwUy>s7 zdisl|w#+AbYIQ|lD>uboVusCmX0e!@2BFwI&CPpY+f9Kl9R-&#t~zvPx&s@)4O zS)<(j(r!&Xnqg3B$T*ctKerIQ!QrVSeJ|Y`!Q{F_MXDlH_TZ<8z-Tyc) zSc?&m$hqf1tmAmmO>R4B|2IF12b0k3RkYiAzo8`e_EytwbXmFfy;byhokn@e zEBn)Qb&qt}UC?3WK zDX+|ED*^3Qu+C|&N=n;Ub2X1gc;rGO4PdS5FMT@OYJ-dho0HbSbCaY7_Ox2XHebdE zDAGNXcdVZ4?EF$|!m@UM8g0DP4@uL#5bZy=iP{AB3r)Pz)$1^tQqBd8y&*ajvfoI{ z;-UOIW1Y#%uenb5gxBWw@2@<$lAF`a_k*E^z)n|Hrt)LHbjsX(+mzvQ|A}Cq!IAG9 z%ic7-(w8!x+`g0&Mj*I>?_Nr~7B4q@z?)ZbeFvGvsaS}vULO55BRw*_x-GN(R3PWX z#Scjh+k2YY`)sFuc+a)CCDcb9jn#}~-zulV!7DoCJUG@A(4E7p>A{_Jkd?KYH*F;E zY3vQ=$mgVn)?dN88TLb9!VezW-E;BANThEBe+|5V#69_1hO1QpH(?Y&QZzyC}B4?fIPaD`%P1 z$z^v&1l4|cqc|dm7Ur3%rO(us5|-|=3%5n5E3nHRjPJUc{u8Cb#0hsYUd875QaoO2>CR+6-+e# zWRJ`kQ?5?ho9=+`M;OfJbc@*|6r|_&SQV_!A2xk9&BORXpJ%1pfnUpXZqwwO`pnu@ zbYaI8|1Yz+`wc%|Jn@_B+|#DEuMJ%y!wz>{G*ZxoNv1s>^~#TqO=?ld2A=lN^mIWm z!{A(2I5x{kC-@z?`kgoQ69H`z&8j_a-c}2(N7~bU9FleG{D1US4ZAL&PzvaCbo2ZQ zxXhEjI(N^zxYLaVm}wmX|$VZB6r&`DJH#4Md3v*<3}80aY<5WhY`((K6ljk76EO??a- zrV#1P(@=I6Zgz|NC5An9G99eFCEjpvBBpaucABGs(*5rGF1xi3gD>>BL@~g2HJTLs zxcw5NR+!x6#fv7s&z(SyHFvOWHC8^WBJ9_ zNOy`cawWaC2CSw5ir6h*-_sNBuN?WIcby{WZb)|id4qD>C+}|3Q|a2jJ`a^pQAkC9BTR{tYYE@!@Z88-Oaj!6Q z9I0*u%3OcsA?D?>Qe-A;I^5cxv%eeR$?vGPe~WkY%Umj`pXbWAJ2^deW!BN#Zrzg; z+gt};R5k(a5{AdX*CQM2Nrhv=vjr$qipO!Z+Xh_2MpAf}JPNAzHWJP&z;%QJxr{W5 zS&a`-%bfx_xe|=23!u8Dbx2{3v<(Y-M~-xP+Eviqj(&k8>Z~?`T&sl6MwWI%d0HO8 zbEkZrkPB?4)?Ft=2d&`}Z&HcRoRB_Hc9lz_|BjzXtOIVHlnL(Jb6Dr;pz9B`yq+g}yej3s( zrLN`<6Q%#8|Dyu7C#jN3s&jA5OiStk;#Fct>RBv;Lj$ zlbxfsJt=R>*1(oPw)N3T(o-PeSMJvO6QfrF)X7HuZBD`zT1~oh0Cz-fBLmQ{IjMtv zT%>k6s8ID4Lb*|HgmX%j1K=!MhXqt)0S6=t2u{S;MHAK_%O;ST%jdunCv9w~W!MQH znRKBe`v47tEJ>YXPwZ0U+t;vU+bl}@ zQ>fd3ZbGJl-0Fy~_OLfYAxYAjU>!=cCr@-$`hiAB>LG8_cq15ruB243TG)#SSArNU z>jMO71u0GqHsX>Pu4swMfD|gN)j@w zM0UVevU@-^ceigQ?Wo9iM~8aul}VCf(Lii^qKT$O`&E=v-cKmmM~vj}0%R{tN~Pl~ zd%Ld4laj}-TO$(IMj3ZGbQ+_xC&){z)-~pb2>+1qr@KDeV)c%1g;GYKY?N~L>l223 zn5cX(a%w(BnxLrV641ipoFHexupRnqk+xo<;KpwWcLee_+d6HemK3nov)2>k%mnOP z%U~=nTq8+1_1A+)H~Z$tw|2M^oE@;sXGX@mY_i20fLn~ThiE$q_m$lES!P%)UoEjy zOi6_9p^k*VaZI>Epcs$dLrG>_MJunytMwyw71pWXjS^B(zhMvogn}~j=5<%irM&F~ z|Cv&yr^U7SX19yH-C9@v(!fHrg&+zRO*Qm*10f08QI`#8UX+cbbP@7I}jkPKcC7m2D78PVrFTq8>s&GO9GvQXwrYp!}jGwO(oOBljj% zq@83^^v!1fghq?^BuWUc^zoc{Sm8JDHe_QYiWsFz-2EZ6qgwVn*( z94W+h6}0m0TwjT1vUXn=XmN}bV$=1Z0KmHbk1n`U$o?|<1x`JaCwZ{WW4adQw9DgU zLNm-0iJ|fTj22_((ne=+Z!;(9U7dx zLpg`~zmi*QIIS}B{96;%4RH9(NuD37hj)mGfHy?I#R^5&J?&9{{TCr;gkLQrwH%<= zUw5^)sNZ|E$#t-*JXN?qfXJY2N=&E%zMmXi;26M(-27DVa9LWV=Xrs~Ol`O))QKT= zFxq?2lTswAE3hmDcyF%CcsT+nCB2?}`i6k$Wak}BpW9#i7cLoc+-uVP?msU|G6luB zn)bQ9AXjt)ef zkg_J|(9H_+zYDjx6#=O>kg5Qr@rlQtriY@VKi{{B?Z$2AvDi=gr!6PT{ts8z9f(!m z{twz)r9>!7(jY>%N@-Z7$d;9CDTR#csgzKUQ8H5^h3q{l5fUoy%v)v|*?ax2>)baz z@9+HeKE1bd&i8w+@3pVbXG+taf>~NpzuZHclz?*(@ZQc^ZlGtq{^W_dqGROZ3ez@! zM#6gQGlZ=(+5%9&V<$VB7a!e@Pdq*klDk^CDmC1iEPf#9GsC)hcWdQ1WQ3G2PE+!(NSLb zD#u)Rg{O~L_RaptnlvabnNV)Z`}0lub1BDV)&+L;2aUs@-0)b#ykUXxKY~w<_ng?j z%kI>cnS`4x$4%Cq4!Un#RdVOdZ7<`4zA^tiu8lO;I1ynIk$vLaz3we51cU~-R|&4L zx%0SG@PloZ%IM5biJc$nb4SJPGbe*{!&F$#I+X_wN{w!ale_bV?7Ms)=X1v0DIva zOsnHm*zuoKH!H9zXu!!?MPZnH4DNXci(Rh~&5#~7m)VI!lrYW6yop6fQNmk7I5*ClKRNz-ZeN44hmj==Xoh8UM@=sCVzAtR%Pb`n1i=5 zmwl`-MW*N{u=s4c<^l>I@^M*tlUe-=ZbJ%{T`N0278?0TZ-8;aOZ711d)N`Ot@-I9 zUr$~;`R&WsjlC;=_qx#@L7c5(Mom$u)zV1hhi1dv2vfX|5HU6MO{Lr^$D5%EICy1e zT2*GYAs@-JUK0RG={TL{fI;7q?ZUAW>;}=@sT{L503SN`@8|& zafIvez!A1D(>Suy|8uq50R*5ykJvZ&@hRZ{b6pD)J)CtDaF9}Ms4}U;uQ+Fw;p4Rr z7KUDtEc1BcCYMU(qL$m4YVdF;zK|U(c`a#3ow3bSTnF}*h6^ylL^wCYjIyAmj1Bpx zi}HWXGc8C_3${Ny(*Lazh z-L?k@XP(6mf^q){s3S9X;>Ci>kO`)O66FM}Qwc?dgQiKFfP;nogE!%Ryk+p{Q*~!v z?g2;Y?6>lPlXugeF$8ot%75NA9r)4nalt^_#k)rt@~@A5W*}Asm9rE1Z^yG4R5>QI zzk7MS%gYOjc$8u^K7gXM+^3v<{i(v)-o&|22q|i{-Z>;Pfx~ zX-jNg$Z+N>&~)W@IZu?93j#dGE~fbMlybXc;}2yY@HPTSjoTOJnVH_%+@UM*g-6ug z>e-Jy6k#uRd+AI0EeZKFynZ+fH;9SGF%ojROF)E@fw6aGwoDAsr_=QrZuX=%6hq5% zY1X>GySO0Zf-Ivevpc|#*ZbWCN9BQ*(}Faqp54h$oEd_T~Z>4VYbKF%mPGw_k!5n(ysMA zn=Ii!@LKLkfOiBf2`kQgh3RwIz6lT^nV~g(NSz}rEX>sV%82Sk5nm|=ei&Y=H#gaXcWa23da+nAb z`!4;tV|=itBN~ugU|Ns8mb2Z-0kS$UBDjLQ+bOgCUk|67Tr~L|KYVGfw_5I_KL@4f za@p~@Rlj`svfYy60+YpeGVf-Dy5%!0E=V*fh5z72ND9Y>QE-kO&76_K0ZjH-v*%%L zIDX+C5+RfI)qfAU@?KORq!AR+csL9pB}eCky|i2I!Mao05Xe9p<=U6YJDZ5m@+81} z5>Fn656-KrzJ;h4nM+vl$LSAb6f))$#P>i#P*oE>rTnhdvQvGk6gQCPMS5WtZY^KU z_8UT?#=bEP(7&GboR=y8}&)UYWp>mbh9;!gGwaF&V{P9kEFvO8uK1|o z1D1TvBst>1)kG26?NqHyimphuzkpRg!BzJjGg^%ybZ*P6?fxSTlG=`VL=k^;$5_ zg)@vyy%~@xxRW>nh$7&0fg3L+7%XLt6URUwX5J(X=rWXwYRFdRfr#QfA`HQD)lR?* zANjtMv(8eKJ7qz7(0`BU{8zh}H?S*DsBZ!%S)aXeh8wNShDpq*)g}!>R)7-JG>p^A zW)|hc-JrRg$iwvDgyBr;<=BD^P0Hm4^d8gbRM))vTV9fmc|#W%iTr3h`Xi5gt{XQE z<8UG;K=1^F#m4ln5+4=NCAA4RuJ5#({ha~l$b(;1>W{C0*9J#$QikZ{M zc&JOfrI?EjTA5sAZq=Ea1A0qb`FsM7#78SjkH0x*as*%z8oi``hA;gzg5i)~*Arn;tG zh^7ZXyQPF3ZR)k*ydT1E0=qG|NG}g`Bl11&G>L`86hD%x-WbJEzQ{KsmYM-&8I;5i z-v%AqkrfM4Mf#*-+r2+_cTbhxe{UTUr@50LhPQzhYD5lg09eX@LxBUg$*pg(n`(&` zBHwfawM=yv0@opk9z0=L-gI3a2l(BA!xKmchHc6vfk*pQ_wHj11 z-$~ids)s@KL@=dmlCJ#t4lCeRifqT{Hh=VN0cyhTd}mw+qVkQJhv59Q9Y6)G%I-io z4fMw2s~v&b?s=uzim48t*)boerGz2RV2fJV#P@t>jQJ5?YQ!lP7zepsJFdE3Xp#o6 z13=TtyN9(v7|%Z3khe!)GJzqTXHFCCmJ=pL(GQN&a-<`KEVfgVG^QHky+$O#uTi-^# z#qjCe9&HyTW(Qx#7cr?Q&DP7xI?Ysla=!VFcBJJ*hVBaHUOorm=oQ$K@9$x-x1}7Q zmliiB0n^|Ch{0PRF=_fW39>KoMab`tjKh=H^s`vN!|b|pKb z3aru^0;Z7piWY&$24;7}jKxwXVv(~G&J3WMeFSo&7DSxD z__>m+FQ|9gRTjx<$9^fuvSH@c5(*4WN$g%n5zmJy$O8|{%SQoudvtdtFkBOjzXCjs zMFNF)Xdx^1{7&K>mKvu_cDwmRbuUIh%F!Wr>pcoA_$FOeO>Qp3yckWq0dcb z1OW1YHX!}#6|faK1AW?ds&exY3}p!xhNdxU+Xg2 zCeeOv2?y8h2^$Avb-649nHps{bJ#{R4 z?@XN;No&CrKcq*({Vs6Y<}+Zeq$n+SI2JSMJImihpic}4BU9@ZfGpuGVLll#PWK0WoUu6%?o2;q0;!)&#D%E>N>)8 zfP1D#QX^odUOC=dmj2no|4bZaJ^SSVj5NAGg&Yz5-kp)nt1vxnjc1+aRJjTVm;Qm4 z=xe0|E+?F=DNBFQUN--qU$i%ks-{0pbE_#;Lnzs zy)ZE^iV68a)b}V^v(k6^+&Nr9^e&n+?C~>rn=VVNX{|-RvdlYKIOTX593)-NI80aJ z_5D;1oBKD>IuQc2BVN1(IoeSz@1ml3xDBZvd#+91-(DI0Eq^27zVIZi|A|*;*GUWF z&j?C7dHMdlTb{i(&!Oh()!9)o0jnZsYJ&dM&-hrcTN-=WTfV?k-zHP1@Yn83MT#F$ z9E5v@I!XJ6e{XOoCp&4Kn6>L(nZAv)J7z{l)4ZJ}p=3v22wyn!#b>p4<|Y@Nd)j?B z-<^vRW2jsWZw6A7IcLW$Ru`;JRr0Y^0$9_nG0WyNagEa}j|Mv*^OaHiS8zlHadWAI8=>^T=HMo2c$ zcbqlHj-|gbZMdy}H|#GH{de+;ms(T&BP0E@#<$JRwd}f*ZxM5hwuj52Pchgg2VIP3 zkj!a(=)j2k0O6!`j@{YSP&*~iPl6rzS*r=3&sCPYca!a$?1{wfj2!0!2MZiY{89h6 zimn&tCcj-ihUhFOg$z!$V5_f`AjotoO{T*=jygp<=+rJ`%-7waL%-8<`SRuU@n;ajt?jwj55IEu=!x>NyXGrhxu)zO<@1H#J zh_k>-zTlvZ*4o867mNSIi?B22{G-s;{v52N>V(Y*!v+k|kb(W;3<3{^Vs&YP^~5HF%$r#JDnlKAM)3PFc&8pMjgqLYEEZN}pnm zUoTgs@o;C(FW^+yW8o-EQTXllSO~dH<`nH$o|G1~7YymX7Uardtua=q!8QTcj$Km0 z{hqt&x;X#;U8o2V%#Px5khU9Zn5UO={z`p1|G>^&7M4LzX1%g6K(~Y3@cd~SI^B?P zaibaW=Rh<4JVmG1@IEVsH4Q@LFh+rPRt(>>yC)4%+;!*D269R!Wyzaf_5bG(EZlD@ zeKOOj_Fj~>g8b!RTe?Aca87fvSXAhv`k>Zz&p|crp{d3vwpMfZ%3ol^*&RhP9jLEOZ`>ci;jQLyGIJ{x`WxvzEqSowEvrALdJl*w&EAraIv z;i!Luy;a9Cc?%b8+O^Cp|KQ)@6+U4a^v_FC;wqWr+CtaZ9y1Hd?UN2M7|gw$oOC4T zzx9|HoBQbD?nB3V#`d#$nO(RD2+ZK8Swr$E?T{LDdj)kYkR2AW=9o9*pInm#b_#dJTvBB zcK4O(^mE1B_4u-~-RnS6t}^FU$6&=y^Y(b19=OT#=4PE~z&^7i_?3nRXZSXll>)sBXtMhl_srI?l?)PeCJ__!cN3>eAQd%AVMlxSglBvqEuzg zIAr7Icdy_@kuLlp$2x1=4$$re6Wc}ldA${$Tj1%ZD`>cr`O6U7*m>ofS##et$yDo1 z1VupLI>@dGUHvW$_pb#26H=N%Z=Vs>7P{sh$_$AV7J6O*Wc;pp8hT86Hpe9Cd-o$L zu{{;AhZW@I_cB28^W(hIVcc=lN9}ds2>)L*2U_Q4YMJSyMFzr<%#Arh`?%bOUllSy zHbVZ2fr{o0rVw1bs>qz;&zW%J(YnXb6!&w^n=~|0+KGDE^abpS*WA$oKkRjWHpM5D zVa^<#_tJdo>bbzZOaVRy+nfgYr7|Lz27cXU=E~p0ciz%RF5IO-g=%jjf>p*o!y%fW zZw{lW__55yTFr^q`PSC?be(sGVrf)odgDeMdA^U*7PG;f?tp@CAZG^p#9-~bvogV# z781ES9UPH0bB@T{3)BDdra@wrb_V9Qdf^Kn&!X2=^YtUeCz^}W%DCz0=fU6eb0H%Z z{xxG>>9}g)ekl^PRq};bMr$m#&5|S1E#}_(fhuU~jTebON)xZpKzsk)I9MII7L=y& z_oklXrVCeH7UhJqZ$7Uf_SHm*<6pP>P7BjTfLBd@%g#rmpK*IP&>y@-T3J%>Hk-S% zcRJlncSdP~FGAUfDprejI|BwY7IV_l;uDFO*ZWRZh*`WWSNQLjU&HL{`ov!Hq#MhR z;vG|W8Ofg#iZ4uW5Vjhy=kE9a=No~R%A$!3LF6wPJ}HrraTe0+K|^Y2mN@8Nzu1Pb zHu=r;M>$^XpAgy|2|uIMTR};TJ0v9U zL-VS*s>-a}@lsuITi2~2-l+;R@G5^32Om~CX$!! zC$2gx&wbRRQCw}G`IbLW;33QZe-Hl<)AJ(pQ#Y1g-7#H#uMf7)}lb}t~8K^T;m@c%4(y0HB@xq)-SPHrFztL@blb9QW5Q0%X?W5hXhna5Iv*_EktXXAmZPJ## z>UvI{=ki%fPJh1Iw@4}S?I6C6$j-0=U5kPoL*MRYe6|KdKT?*j$hh#WSK;~}c3Hk2 zNBYfQnFjr@{Cs$2bsTO(as<4U^Q$7Jgo8q_i-%Hkfu4Yo_E+7pZ;lb^ZxCXZ?;c$* z6&zx1OHCZG@N|1?m5GH5@>+gY+_$dXvMQg66h_s3G(l69<0)DFZB<5+T%6UK4sr;Yijvz_Sr zfV)$Jkn#g(5w!$)@hNC-sz3Vt(PqX!!=z=VYpZixsy7Rsoe-AH*m{8WOF>RAhOJa} z;XQjR$+DT@oc`PJo^P~a*7V5l^8X$wU+}s0G?Cv*buH~B`3&+8e)UiJ`H9J>E%8XC zOwu=z1$4)@KRR-Z!m=RrYAc-u}T z+Df>&H+bX|bL;P=a@gqA?rn3V?I!p|EGA$j^#aMaxjC1ox$@oY#Y)fDtq+XU zKOVOj@v)fg_3h73{e7)9qo;Cu_F!XF)Ya|M7IZ0rZ+Segz&9wVAn<>To8i0lMDIvI z+hoB770K?E`m*hVVudFqB?n!V#q`Z&#c7)t&cDdydJs5g3_jX$$+YM}&}?uVVPU&^KI^CLYasZS{cA#>Eib%~{f+mG+P{IR#$yk8-*( zX7xG9Ox+Dd5Nw0`t4-Ig_Kfp#2pI9Y@;5BI;d5`Gv%6Bfe3Lgbs?CI{!a zUCh6>e^GFK@RM2eapl_R5B78Z_i{*z_Qm)W7dGFT^8!>a0o*1=ZF4GU8|MaHcF)A* z-Z$UoJ!HS%fqH#xe7w7Pj3eQ*6r{b1NjQ$lacfQeWza_N&(AV5IFWqMp zJ8OzE7W`Lm6wM%2wS0lQr0)FY_xgjZ(z6ltFX-N|Y@xgTEnC{Y8VoHuLW`IvVxtS@ zU8^l6(#JEu)M`4V+3i5nOkQVBVh+arDXss*osm2ohJW`zzj0U6KWTxi1hzEDRndf= z$YNPeu>V8<)XyobwwLU8?V|;MbKg;pb}*8L%#G%@Uv5*$<~q^E|J)kgM!I~4Gz|*7 z_F}O~S9rq-Hct4@ZV>*VXq-9MZVcP+v|@P3zJCXf4xIg7Qq zbxN%VpIrRcMWwK=87Ko!u47RVxTqfVW3Sru_Lr7f+Wr0HaVHmDb(#+#H}L&9=2p>T z`iOWtXD8o|PMm7&K7}6Gl^wL5XJ+2M>ff$65a_&{e_)HCS!Rvpi*gxfX?r7ZMh?@| z{jy_RER@65mhzpOb!h(rRW7#ws-m~r&nrDZeb?IlwM+*C$LrpJ|AZ#eeHq=@^Id(Y zbJY_vZ6R@7oHS_{bh;&!TgC`Et_xg$H&|8f#)k-t=l+o{_PT2HGZb#91^L zj^$22bFjX`@W{v8iA$q*CvFc6q;g3gXWDin@Ut;*an}{yjJ;#7ykWi48E->AOZS#5 zty){@sz7L%ZX)91Si<(=+-spuxx?imxqeXxN+7#iVs;aA@qT$=lnBODM>w6DJIAvzX%Zogi zd2s&l9!y$_uua4|Ux&5rValqTtU6;=w(w?GTpp52{*HWH2;4)=Ek!;)0D_-qAPbH@ z;l9VjZi7~q#;MSTx;s@nWu@@JC@%vwj=M_%AWjPw>%Nwos4qOLp;1(DZ=F%TJ43&J z{PpdjZZqRO%ciSq)E}m06zA4-Q@)3;%!{(Ng6i_V^Y8y*Jz#4P4APDat?P#_EP>lT z^nAJMu*GWrM9Y6DPv@-1`h$3uRxvdBp;qAA+V*j;d;N=VzsbotY_I^*3@a8Gs{B5D zhb@TEQCHu99bH2`bz*p=pow%?zpbqe=cLMVp{a6{=SBf%UAqv&fmj=GAC@u`)`v~YLpiYj2>JZV7P$p2 zo9116k5$O{*ybzWPuYDxrSK6uP@r+uNYA1hdMk!Ht4L0(1JI$^6(4o_)mW+i%vvNQ zKn!(crbUJ#eVb0l{VN#Z|4xSiCd7g#1qnyvenFFwUKbwsEfL&-x;)vL)e8*pjS05Nqu9i*B=m;n_HU!Xha_Ru4LOH}5 zE~^DYH%siKF}#Jl!*TXeE`Hw{B_d7aDaL!djnKDFG`X%pB(7@_0g& zZ8pp_Tsm#7dm!C;^p73RqvFIe_8VXmpt5+IU&L)UcHd*$$YCHHK|~7RYtZA>48v&W zS8&N>&p3XUj{B2gH9ndL!_0Qrx%U|Q@Xx_a-M%n%ASxKzDt1{5mm~!fIxXuhX|J_K zV1VMR*bd;7ZQb-OyO#ysuLxW}{EoWk!&~N4Tu-1=@Gv>Ix?3}G8xT*-?DCeK8H;}N zX1D2hU91~)a6#)J67U-Rsn0-aJ^Aub>9nWU>d&nigV85kMAVZu+==8}ESkzh+^edE z_yyqtleSpwLd^&?9Q_r1?#d=H-#h1j?A6UI0LCdpxNAR>fkB7=IvBp%qaNtE&#WRG zJCizZeO?*GxTAK^3}rMteaNostZB{Cc!w4AB(kbu$)&MwM~PTF5ZT{r2tsX2dsNugzWCd(cD^u?p$tcwkEy z7mG@O3H6&2Mn!1K>K-ccu0sMhXq1t?w_0Xw3pNM-fGPI-y6UgT0NRHY?+X)@JCtR{ zTRoPnyMdv~vTb#Qt;BO?x}%qz+b*LVsz&^H%TE{MhsDMb7s^9PkpnffjtcWsVAf-P zn6Qw1*~qU49dgww3-H}OE$$VXI_xMkc{F`zKKwUaayvdQ9y#VylPMn}Y*}&GF zN)T+r$7j}(e9h3SNY0tVAy}VBj1C$sDIrhiJX06q)K3!yd8%CdOsK{Jf zdD$ju_uZxW7hOp4TbjRJc?>W%!1#XLi#zknpthfAisqZgAvLQbXU<~jE$*Ufr=S-d zeh61`t|I4-KG08SD&0?W)7{l)V69o&YQ)}KoOZoQ`=wl$x%DR-N6`M4Ihmm3QgNEL zu!pzW*@~@nk9?h1DOM-j*AQ_c=!t?kA|GVQ3l7+oSej1_e=9WpfEv(d8)H9bw8&pE zKdLN>)wnnZm{YN6|Hl3@z;#L8K@i}EkO`|x4?q1({*@Xb6*z7G`pR0m#8w;{mr57E zJ7x1C7_f=tmg45(YpX63diF>=iu>`>{1or^b1tE#@M5tYYwz)$lsC2y=?k*QvA(8amn{PflP-|h^TUQ7fRzV#6O!4;v}nHdY*U#rc3(2F|-c9q6F&UnVl z!ft*#NLPFO_seS+#-sY1UY~5v-8j2JR^rOB?kxMX>*z&l7ti=!$Cr}JQV%R$(B!wY z1pf>EyRs&xbLBX!&8XqZc(vsDdZ;E>hVV{<)bKe<_?hcTcv*9#4czs7eQ9K6) zvd^|DpRaV(Mh)+==iwv$Snv&|ueY$x&p4{5#(pssdgRh;uN@HA$Vv?xIXX3#yw#Bk zJwt433Ep00eMVMi?4p%{G0CG`-@tuim3F%PfJ0K$TcR^sJ#G!$eaq?r>W;me+Qc{4 z&r6Qq)5OI0`yIHhnb_$#Hy^Bw6w-VMlW$wN-!D-gFon5IJ2)0aXvu&&NCl}vK#4rp z$CgE)M-xEz5E)~4pL-krgVb{z!3_Dcs)3)k6Wu$|1%WGBk=K`+Ym_L*&~!#(-C)3* zy`P|ONVRA|(<(!p0)vqRc`K_Pbqjxg|NhR`@ke_bbL<;u{WbLNty4a*6*f(4_M`@P z<&?n5D?UNMosEn{$V>vO{E|V6!@%-+h-_Kj9?!bm*0*5;t}}I`&<5uWxYyc0D4aatm6^eMW_? zI?Lffau&zs&nw^GyO0H(e!aJby1UOMSikO4)1PtX8>9OC*s)jIH1F5xz|RWzXs<=o zU6!MACS0q!bF*95x1=}O5WLdUBVad`CZJJ!BlGN%M$r|&y@491!^Ohfy!nCf7Z30) zD7`_&#+`XjzxM6BLe&PHqI|7n{pMy+A}{^sC~Tc&{{gnb)AlTQsP> zPW3~6e}KMr^}k@6!Fln*7R3%HT!z-kh-pA}y>EOzwBCNX%>7xXKhrn6=_$p_Qgxk{ zuG4RG3`aRK*S9wAyo&*>0b@Q#K1}>Zq^62;i?03!p40*8?zL|m#alyf?6aCan}*>% zd2Deu<2lH1h7FM76#SZS?wlEI5Br*CCsj=z!xw<-c14c;k*V3JRo(-MQ(QN(_AB?y ze`6N0%m!!^mEv4rAoz~{s zd>bO%ioZbfy+U`LBxi2lpk0k$#y*?kr`bJ04t@IwVj(Y4&+z%F$m^N%l`x>(MG;uE zlFe^0H*cyL-&a%{0C?$# z8Sla;`;0Ed;d8?uF5CEMPp&*SbI7g|LnEckEt7c(#`Iz`XeC2!*U+4ui-&rcS9?ox zx6fFeoigd~JO^U>f^ESywO5Muqs`RB%&W0W^T7#tLf9_u1Ki)C+T?R&)ybbC^ps) zj_h8TNKdRe^YhL(x4gdF0ziPplWGx$DFNVz>awsn2QAL*Eug%LGmhd~E{)D^&b@j$ zR&j%IZ>OK{Tl$#`D5YeSiMP7(_*Y_X^DRCM8G|!K4f5TCM|1#J<#Ujj0C(yt76tiW zFdmvcSHV3N%b=<5J(A+j)H3TFtxe-!AH!f_HV2NDtA5 zId@+RY3Gs87l9$!(KIPfEO#L!mI!LEfgqQ-6w7#;(w^*M0 zkp~X%gRhp@Xb&`aNR=GRm~WFiZmKN82=Drk>-plI4R?pBJ54|9bH?w{;^>Xl+4x(L zS18cqGVi)qmw8R|M(xy{t6$I(exS$#PPX>fwW&^Adxj=XX{XlY z4p0k})>2H4;Hzq#TT)s!3v$vB=9!{5?+c*MhZb&b*M6!2ZA zXY*u@udMyMldq1O2J(`civBs zIwn7(Y^@B5Gv$rKv2g3V&>Zk(7=n}H6lk_L$)SStotCM-aRE9BNsaN!QOY4~Ik_OZ z!61T=aoNV?KKm?DDl2W%>v?QownsagE6a-iK>_pIz|iCnr{Ke>6u0Nx+bvzwz;jpG zS_|I6qhZ%82#)bWp!G?n zW%uRR?O=BSy0dcgygL9fQuk{ZGJ0*~o#aG^Ozkxu?Vn3I@!jke$|@@nrRAJ%gZBK= z19O|FG&MIdC!Dpt3MxmlM+AuLjzykkW`0y`ELs;2`T*&l+jTmCW0Wn2Rw43x!@KHu zmq%gxqr4T6hEJ7$?H*_5wW3k6*cv)hc#W!F|wDNL}Y{fxbI=LF`l{dO?!mz#jbkHWukE&AXn8eaU~Je>IPa;kfCXn0Wbz?>%Lw-pa*=l+DcTb&tv^9LAnsYw%Etn z;7mfJbFWBdD$dJf3&8EWt?Qk1;cAEA>r- zy)lHm8|El^^Ja0b8@L^9MsilpN+H|ZelyiC!!W#K|44au`f!-G@Gc1za2n#6k@LC*i^60fk4HVGv&ybhcgLZ zB)Z;=4Lr`<46*iw@72|XIJbcAFfu^8l?T8F!#TS>F*d*?s1%p7?Hooas>jAHx20Y2 z$CzAAIqWHT$7C0lJPfI53eEs&EZ7+y2t$LWu;NMmw^4`K+T1`!-sh}5{7&0dWW}uYxQm9Kqsf`GXWMir0N~UD z`(ZI1x^i>|2t(5}w_souuDbbiy%4}LV&D$fk%t~rE{#%wZ5Jq{@!St$(Fzz59_82D zg_#q^Uo_nDbzz@0XPvP+@aifgm+fHQG%fliOs~KRW#&1WY-R(uaX(aYfhQxj)PeCo z;h(BjNl9WCLsZCqh}BSzw_p+hVRB&D|FOrILX#Nx)8Lu9b7NxQA!C{r6K-&L?4@6w z;m7PSZ`2egB+JBm(K(dsdNqH-KiyJXFK~vIxIPMr>rEgwQ-GJ{4dlshD~t2AYcGL? zDagOUgzWSWApe&d9e_NUFq+skYISWEj6s1c_-turZut5=k$dWd<~QZzLle_9O*lC; z<&J517+2h(2S6laNKOsqggVQwHXrhP1HRqZ#n0ai85kc(^=%!Yy3KB&*nLwHtD-(X zKPL9*SOE}oYVFr0x4vSa=9qOCDifo**cVbTNh^pba*k+y0C-SmK}R9$H4;~Q0^H9Y z#8dkLLv&pqam2AkwY_3@0wqlE?B3s`;!aaY2YK#`59uKW!`M^;n?_?u9eP(ipK0;_Nsfr1bM4F|3( zv#$0Y033m4Kq~NH*`>ZdiyYaIczfS?<9$Zfc+*z zC$#hge;sM2gJCqbzfHhR9EHyCF^19=FO3fwrEZsK6J)qHucGre+^@+fgHHuRo?xzo z8PZpt*tQnxAKc)AL8x+Bf&nVO`gQ=1R)DnTU6go% zOKo_AWCfPuZmQ{^Wt!uG+O*X>Xb;V^h!&s?TV~#VK zo<{Ce$ThrqqJkeJ{KbJM87BPmg)|WI-qhWt1j#`ZS0q^-p^jd__lN!T_F!{*wzf4+ynh>KQpZf07v!lS>X zs0jQlo{*8BC-HWv`bSo+a~GS(JobB-xcfr^CZFct9B0v+5r+>LUJJm1-H6BnI3BE| zOnCorU_Ah;4oZz1f!NstQH(01RKmt4D0!S}FBR_r)Kaop`9^qBxZn2oOPVA?E1a8GO0G}bp8WAndBQY`Y&4>JzOz(hH`FK4%62USR z!em?wfhf8kF*~8SqLbV~<~DwpzzO;5-Yst%{Lv2eN3#8Zj5}CCX+MBW1&-2=^?g{~ zB9=FX3={ z%fD$!uU#jNHxkMgfXGR@{uOZISTBTJQOA-aR-=5R299C8lz?bz8z!t+X&>uDuOq-c zwLp5w8yU?Uf!+0a`E=vLob7c_aigk7Y7AIO^4=wz|k{_{Rk zKMZ~rZpoXS%rgSc^N)^+@Hk@qkt3-geIC(q*osG9TD)P9)+|lza(?-hloB)>!q><8 z(t$I%1x8vu0ntv(I`j9-0}yy{2P#?%ugGru-gM{N4UKp`4v4Pxr|R;iwb2VX>cz%_ zl+-}X`}Tfw+S`N}(s}8_ zB;fePJ+Z6ZTpN0dOrSF?CDt)B0}=IM%x56D#z*8qN5o3Rx^aMi;N3we6gVur-SH)a z9T<;wq2?n6(dI@lW}a}icbl7=-yiowMbT+8WUReSGr+@G)8WxC^LeWXTK8RJ|2az91D7bXn^N70DpVR9ifbgB7V7VfG3&JuHAQZpz0T?ZhxZ2xD zmSRbGPyju#3*8NmmGcIJVe?X`wB_x5*mUB!&|O~J64GxzMm({SfPxDtd~mkKv8@0( z$&s-7l%8I0nP6Xl+AVhF#d?5;hUiXYVH*HWH}fcXKLCbu@kW5?HI&hXhY^=l|3*S) zfrhKTD`64K1YM4W+XzMVxvc?oNEN_zx&K7U@e&C#7b*?ot_zy>P&(r%;3i|&0V111 zMoAFzP3tvu?2Z5;!}24}ak!?UXWQ#8`L`9n;ne>d8y&j0`Q?b{cBlf>&aEtX_*W&5 zGT^be%g7TiB}lKBo_YwqT90D2vm^JVzgRKmk!Ycf8D| z5CIRP1zU3M9Wt>e$DumTzRq?JYJA!QwAs07^vH)TFCN7tuQ_P`Q zogutl9W$k@n6I+@IL&*1WAvWV^G|L0v58CWryryZYoj3dQv|hV1Xx2R?gA`RLd0i_ zZ3htfu4fKfe1j)KW{FN(wQ2)~^390$x|r*_;J?K$?&ZUSLaGHLS-no1Ypvm5-+x=+&FGsT1lLM#}uiGWjKD z*d>U@Pfq4yajFgktAFFM)Q39_2UE#1m6Zy3O(4n zXh=Q?8p+KT2D=6~yBIV7MrJ1CQyz{1d&)gLjd>c?}?#$N{z+ z^&Y0$&CJ*27_CL>Lz-CoZA8-hJDkY!}Ss(y+Er4S_ixdkPz67sV!;x28NH$CE6 zQc`007<;RGZq7Mva@qmAOJx{>PmoPs2N?7HUg$d1Z2tmw<^aT`7``LS=STdKXf)oO zONjW;B5O z6*V^&HjX}EWtN@#xf*r7h3FJJ^P>}y&8YVgb$p*;fd`VP*Mkv=J!4mQ`NK*vNVNTk zi^mp|A8p{xtv|zkx825B{gDarAFZ2w26~S)Q$Yhph?4EBKbH{SUT%XtJAjZjE67fq z%7*I3$GvygVv@HoZ>lt}0HHtx@}@3%jsS%9W3txp+*^Xby*w-|YFV8R*tT79IU}`( zk3sj!-HX{>ehJ7M=w1}~9fcQ5$$}*~QA}3V-(RU2Ve=BWd2Lsy*zy2fPR#)A^QkM> zN)uEAI93Ai$Vb;INQ~{KawKWr=Ru_Tb-iNSi@?SyA1V;8VZ%%(i(IT^pCE!$^_}s=_&u z3$jPx7*t$=jI-~9Au2+r1Owsl(VbVI>%|KoY-af!u!Cix|31d_j}j*0|Ko@+n;vg! z_v=_gC}WG69GEsHs}iVc7($3qH(WaX^DY-Bnq%x3>4z>11tle=>rh_9`gLJBz%3)P zd1{6NYzBsG@RtLpT!Z#o*QaB}DWMb|%qPB-$6ZV<5Wej^kxKaOftpmM_KF3{WG$Xt zO9BWnqR?QjqNZpisQ6HbC&s{q+l*!t^Cl1nvOpV8C6w}5B`%wh$QamafS8rw$eKCi zLBkB*1KpMJ>k?M)(Zyda)h9>3N%+cW)SL1D@$kvkHWoWWi0pdw9TS#^4@G|ajVP-C zbFwq$_3Jc?0rT8$K-P|R5I8{{%^l6T1{mW{T|Oh282YlLg$ga&Y_EtoWC$yb%IfKL zbVWCkVKZQ)mc_KET0#cV?&s}|qM6lsZnM}Pr=7tKF8%vTU#pA~W1-hYQNnJrDQm* zy(cd^0m5c8V6j?_>_el4IO3TOJx{9|(PvQ%65RvIxlIDueTRH~g21F>#dYR)*v!t? z({(Wbp1d32Grs<+1#v_;4y(5N@DWdV{^)GyFG-rccZTxv`AHLpcjrk7C)_2-(Bsk% zfP#Y{6KcEAW|lDqQQ#&tHGp)KIpehNP+on41jQ|F$u=?=~jFx^_%gyBwKvS!S~@H~bm8 zrGFr3G3BxcOt2$)uG3nV!$3Xk!afjFu0gb8;B@C~Xo&i5RiC~Oh#2aAZ6$CUu@CP^ zG!)mvhpw$QvJWY-UqVEET^PN9wk>9_?*~Thf$pX^ZA;1TcU2DH)(|_X0AJ-A#CTmy zd1VXj*caVeKD|&Ibpp8bA{jDJTSwA@flKk|OiqmUQd^z){qG<59}WW}mn5+e3DvPR1>d9ud@r8bbv6&57o?+AdCn#yeJF zQ$;B_n?VcR*q2X;impsgflmNkT|!VTuWfY#U%ACXe^N`Y*Aa?F3Xtf3s-qA1H=l#W zh2uweFZ_L30_|Y*t5-GVvDw*DfS@Ki>jk2)ze(do89MBL)yoaY#i<4zE)_N>V`6t$ z`@@raGq#~@#`4Zo*9iSn_kDj;_1H}bD79HQxPVK9wmG{o2^)916N*G9pIB8@ZBT;N zOFaNUJxakI9Lx^y(tuAar)@ZwFRQ2>aJ048Ton{a=10OYKhkxrJ@5jC$2R-N*qOC; z<01IM?4=zd8Dgs{X3ZeMdgSa`|E1x{G0+7OQ8NrR`1P&1MuiXV!HJD79xmc?%ic1& zCjiW(EcQPgrNF*~VZ5S6YL4niaCgNQ{^bQdA)mN=vb;Eo%yVslv}wfow>G7(@~%)Y zp^S#SaMOhXD7IoVQdQSKcd)ku64d%Zq(0Mq=qpb9xs@CLx^1Ve45s-L*EXn zqZXH~zP>nK8F})tdK~0-!iU7Ut?d2D90>}YdqDB}eJVlFUvg&Oa!5opl+LI*CW{Yt zl>0!^Sz_(I0`;F%C|W@}2191d@L>8=BX@x1r~U~rT-g=fPH+SxfK*^13SBP;_GTsd zfZ_@|-v5A57E_%v*~k_c8dubZ^OLM=<%_W$jvpAP=$pjJt zxs@rP=nJ7cp}vF#T!-YX(?4m%LJm6pbY^e@vjEPPHnN4yi@ot_-^ zft4Nw%z3S>-9KJ}RY<8B2IqX^&rwsV<lUUv@`bsKlY5sT?)J81-0BuB{&!CLIJ0$Yf1rzqB6lX}H@n5m*lBtVH`c6V^L5(k`GUc1Hdo=WZ|jaW`Z?exWcC~fm|HSOLU1sUFrb#Zog-Tren-rXzR{Gn$1&n zrDYg2LcgdPu3kY1XePcW9!_0Pgvz?P>HzGgR~%G?g?Sa9RFtszd*fnxm7bpIo5T*T z$}Z4Mo?t~1n?|FCfT|^~xNAmsQ1k=^*CHnY>ilFDC~Y-jXFw`+gLosl>Eo@tcU3v2rZRtAnu>r;x3J4X#BauKoR z7OTj=frtcN(Y^Yy@(!M$j9hR(5*(~r!hFh(aR2+LxOs+M>}*kOidD;Cfgf+Yn3=Lf zkMKHzL)TTtOX0XAq<6U=jTH%O1#Kx5_(08&?;>;(mBl@Noc3jWVO?f2BUy$ceUZrRcW(t>EXb7}n7lRB#s3Y8yLh?3Y|DCnE}-qs#T=|=z??D@ z#=^}Y06w2Lgc<9?r~{eJiCG2&mcgyM$WkAI1Pq_$JW~t3c z)R&5GGjy?POr=L$X6n@pP46+Y#=MoNKaWI4UV5`N<*wBw{`n)vqk?9yKq)r$1V>$_ z3dG3%5?Y4!>2_FP0t*kYf!GXBv+&MUJ2&;G+<5it-_QC>u30HHrqWN(37v$+ou=$> zX`LjX1-B>z95cov(^P1@gJL13uOOcu<>7y@B~`>REj9H@;Vc{?78aJ+(+Y9e$B)7K za|=i}Y3M-HdaU*uSXED>Oasr1{W1Pko&I4-aTXkb5Ch_s{IBH>;sR;a!`s(6B=5?b zsETiX`(c$QggX=1DT1}z0_?{JTtt4uD{nI(w_r-q-UTJ6Z&Od6f#4}Zr~ZAS_NtO15NHs%Ur{NJE8zm8L63iFgyYNiNM(OPHEEWH#=%-2F}VbxM%k{ z8NtAaF}IMXo|H%c2`@AXiz5K6FBl4zXR#<4mtsIGUwUpFSg`DzC% zqn}Vbfb$<3bYdd-_Q#76CloYm3O|{yvORL-$mQP9yz;>Se=D**#@8`dw&yX0y*1*^ z=Z@`!ghZHXx7?i-o7Q4sqy@=zOI0Kj|H_ z5+|@!DG5la)xT{zv7**VLon7Q4aDS4Y~ zfXp19aB_;+wp7vZ@IUEO-m}_eGqbDdPMzF1n0J|mix&Q(o3iLA>yKl%rdIHlB(J-fLW9}CC*zaKuhT?m2z?8D!M;T&a&q!7{)+}_ zE^3ev-vB1oiY&0oWu~KnW@7`#5YdO|6A{z%3BF$DxZT<204_+`4<2AY6mYRsU2K~Q z#P(#p@x+ z9J7fAcukF9d`c9TAeOlxE)J?5*tjO#z{VFL&X+(ESe1ALO6y4XxZC#dTP@U9^&7BM zgv)NXZR3k;e2!z)5|=bJTYl+EbCXU36Ke{C&0a3JlvAc-JMAH(4v^xEyGq`DLDwZZbIISP}EeW;os< zJhnSLOWp}-oZq?rYBqwmfD$gH_=JiWC=`~PK-@qU?gj`j&X6<({~-?@6H+utWmtEA z3jKV0;bXgq8WiY6qnrR~G-=^*`O0?L-S^iiQTN&3S|tZ5knpJ@G5$>Cy^g%t+Ka1J-NoG@%$x+CS=3pbgzGx^T&I~v3+Xl>W9?MZ6%t7K{(Sg z#0>m$JQ9?N{KYbZfOxH!<@cUYJQ-%yP#}!vE^HdB7Mmccw;1gDHhD0E1z#Fw~YoAacUMwL1&`xr@6E zo?BjcpPFjMH<+GYWyZH6vu*>^r$pw1l~9sPUO#2KN7ZwUwIDR7v2PJ|S(tOza%uf=Cua!Ct*{U_L0;@+#kfE7 z@64a+`^ihS?+7FRmuY`DIr3aRm_g79!K$lSe4)o>;UL1+_s?FBYadSgq5VRmzi@&! zAHu*JFiqSwvR}R0zy0u)ssV~t{K-ZBkViCYnY)+Ym@wz$krpc=JCGPn<#Fvdw6O5L znxbC_$5<9^PRlA6A+zkns3jR-9EM~Abk^P%72~GBo}(&YgYXlk)fbnE^l81>GPJ^hzk!#e~*f?85x;o zVB&)IYHlBd=n7?uKZNCk$7{7FD}f7)31Yno5A>_VlDd{Rh~qAo+LzyYD(qkj(<)Xt ztp{f3ukmp(^G_t~q!i9{FGim@8vZNrC;QU;G-OKE`f#dmWxGy1A`99;WuXOBWKjhc zBP7Sm-yf5>vpVIc@0Xk4@o!aZ^LfgmJ$ySNX7Y4Ho~N|N@xfc`Jl}r>}f;+?`lFS zvO(bRauC+9e|uFgb31(D_$!9sLLvCO`9{4isz9q_}r$RdKpjd>uo`z zQcR@Q+DmT~*eKT_sh8>b@!jT%C^U+w>I_P=^1Oo9-`1Z%AxiRSED5^1ArJK zV3^>nhSq}4)vpJdt!reD8B{#i@_q(y=>7ZmV|{|~YP>J9*9;KoTzCQo^W(8>@HPPA z!+*eZ9SU&x(Op3AifbMW_S)I2YItk#9h3%$*#o5J1=NE{`>!Yo1Xio8%>q*H5Y5x_ z-U%^^?LS}OTX>^=!%XWoeC^q~JCABK2ouv+R!>>gU>fZ$!%~v1D&6b-TvJ!-m@C^x<#%@>2KxB z?F1tZMlmI}J}+Z`PBKk3qQ0A7(A}oRybY9qu^MZ~%Ar#Y6K=nW#qe_>!h*g65+6kQ z?1gPnaRfD-Vq9y8>pKWfK*N*Am*q~eSpon`;$6-Cy?-YMQDTID`b%Xtm{qWAtj(hA zhW?2*G)k>lR>Xn+%CCI^rqShB?yNazYmJN-t$ghe=Lk8OK{Q71lE>@p{j*@|cBym<7l_@CWRtZ9EQuc!#=QOd@-(lsO>unSb& z+E-2hk0pL}omd+d^@iYCk+0DK4FH;kMi9q?O!{?hD=^hNq0s*rE*>p{>DX_B<~tjJ>{`V(o4T8>4;Z&YwzE*Gh|^f>UyOeZ(qPTU%mN878+M916QvUL25=|3 z7&INa8jxwcy4!cP>-uf6OK`gNvm19>220saU%!NP2Jk91r^TYnhMmVF2kyWURg7W4 zdcz06(fQtP_{I$1i;Y3CEwR$iIRIF7ke}1BR~PP=Ni~zXr2M6x7*F-c;PP>z>??DU zCIh`NC|{530~;(1Kf7_6g8}O)@t2gV>^?u-8Etosp~@O%!Pg{hh)htS z&ZM&1$qxBx*rf;CUhD!yEv5qX@&s80TQP&~HT&x}c)JS2?{CDtW`phWMhrtzX8RH9 zh<#9H_g!V1elSSNHkT+bD=Fl{S+N_X{qVg0IRta0qP@7(mW~>sHx;<}P`$W1~!19{(`VO_sCAKy59(Ct906WJmG$8=5g*{k0 zcN3MT0c-fY-MFVipp{;TC z!_O`z7aeh_^{r%cmUVb>DDSTWns1BtO+M-%|xK$*NW&kj#3)O>5Gc|@GfNtME zyBG3~%0kRLAp(rC48T7eQ#E2IrQ1<0d|)pNl6}g-s(8qCU14QrX)M zvl+n^SR*{xIty*`J+W{Pj*hb5jg6$XkXoru$I!s`Mg5&7jZe1GnAa#N5^wnk6e}Fk zG=W1uf~hd}D1?w%b8kCT2&X=7a^5To|4+0O-{jc7g6MoKGW&}j=k|}!4<+DCSMCSo z(ONkH$K#1ovQ2p3zm$ERwQDBKReAa-0VELt{Q|Vtr?0E*OQ4@?y5j;g0W1c840`0n zb$K*jfCcL1*I#Qr_7^!*OHdlV|hHqemrC;lP{_*5tiPk8k`U)?XBm=6Gx0w=2_>-W7ymnKefr0$FoM8O#Klr! z2d*F;+M5!@mQ{L`CZptO0>MM%ru)jaiP$5FUsXECUrrrMFe7>7FP%#Sd)CEfe*H!} zuPs-a{F?YJYA%v^a2laQk!%N41LJLQU6JOc-S3A#vZi+>3$5F>T!pmmGABo`BdJ?5 z5#BuJgzE^gTu82lJDU8d5Xj^j*+g=N3}MnV{@67K06 z>1^cnwE6g*@PfL!6b~F0B$fl!@kjDS^C2k#zrUsa4bsFezp?QLYmF@$(7zGxlJcFd zvBo7BF~q!5c(J@p10RhhG(WFo_rAg)gBMYHKp}a^%8RCDscroq0m`aOhPCU7D3<{z z5jg2beIPEqe0KuUd|ElDLZn*P5bS%!rH6^CdJ-QU2}8b=>bROmei@kH3X*mHq~m!G z$PZ)MlrMR57Ehdl<+-s(?=qAm398BRV@Qk8Wc>RG_KE`>W;}(`Rp;@hmi&#PRlj-1 z$KoZICL}4#=X3%&Tf-ef%m4f)Ns+^Df9A6dU)i#`Gye^y?!x*x1l_ln{H?^4Q-4}L z@>*t+1)qygd2d9Ue}3>HanXzlC+uwrQbgEnvnEihiA|H#kUm4o-^lcI`7e93FS6gc zmM-v}q2~nB&84@H60ERruZzGL)c)C}b9b2PeNWaS+%8a^jhS9NL0=EPh{F@fM$M`4 zB}6cNgPFbqJ&f)SpYa1)H!5_+R4F(?RZ12)e2c`tT`n z3QC8_`;d5;j8{=c!mT2IAn;5(G8-0#h8K8=C zxD_v7z3LPW$0rawo(9%Od3CrD%bN{Lln{@6cI{j1sCuJ1397ptl0#bgOhu)x6{-Y36ZV9cYpJJ_K_PwQirj^wy>hkv*flS z2W=2ER=4GaR5PD5_Bv?7!kUfg}FihHCEIDDytiXXg5qS%(aY8V>|3N zXuF4U!dOX6Xh=f)&O_e0^XWd)T(gOZZo#`V+ulHGg`akBT(?A%2wY_cg38cp279lW zIzks7546K+YHG6IKx@Ys?dgUrG3+95S;n1iZN_{|M;tlvz_VcnrtB~KU-%lVd#iSw zzJ0S{KYSOg6C^=udSjbfU<@JM6ob;+kOu1FTm&iag%=9FX9s8k?GgM~ba&iCge3RUG!bJ(&pDgGTxJO#;BEzV|`KOE*IM_raN zob!ih+E?>JsW}7GBOQ0w^SGggas-AIrPhsRn@@J+TyHmE@VV0Pr zCoH_XLDTRK==es!&`DShgcHg2L_ov%>?rNY_&`UVx&h~fsnRPMqoEliA2tHsrl}?`?LIWT+n;(3MDR$aHGY{~JYKSAdOeXTel`g z2&%0f8%+DzBA>VYQ0o=dXzFEL?Jo_qB71n%AS6aOmsxhg+jWHPm*9zD+BsGGT4Won zts%Y*%`we2F6nf$<_?2qpFbkw4%#2OJOaH^fw#+C=TlxI#c>g&3b^w6PC8Bd9$Qq!!NxISvBirtcYrK@;#e##F2ha)%Wd&Lozzkz?8?prf ze{^#*KbOCyOY@kKLl4WTTQ{DAu9fh5f?cM}RujLtU%kv#BfN5?aa5p8fe6CjObqYJ znx>nZU_eDHxEHoNC#0tGA7f29=P(+w9KS3r^Xe7<5?HZg#HA3-34UN~J|2HsE3xONG z6|Ig=15BP|SpBl`!yT){p56_A4S$JjM?xIYe-fyk9nc8c6T3#EMPY6pGE`gz6-Ot@;PtW&fAJePl(R+*JYWNr)&o_I%^Lsh^K8>9Kr+6YdXqKI!-!l=lMuUvb;QU>j6h92^`l4^48M9)-rocK|or zrv<4p8fxjFjUqs{*w+kR8g3KsA$^6^^d$^Cti(iQondlv4Dj3?016DL4f^bVBl!pT#Y#Q6v^uyEUJc@J;-mTdVR`{{DJkvxm1EX)ForApMi zyy|hX-o|Z5G{$YM8Qk?ye^yS#G8H)%1;3SZg2YRz=0Z`Pi?O}q^t~0c)(LuviJoyo z>MGHt#NCiwjStm*>?mJh)#Z8Bv{~aZW5e4+1E*+6h8rniF>j9Ipu-pOg6p$GO+8l4 z>0{%^m53*Xd%i1uxcRhsK~-|Nm6OAZUjV5@EK+Tx`ak(!5-N7pXj2=j{Lr+WS->QW zdQ|pZBpU=Jho@XqhTTRH(*zhjhT{QOq_axsn4Wk@?YA4MIVI>Gb=ykQ;n@-&CN^fz zt>o9cv*g1Wd0JJHuB-vWJl6*lJ6y4v8sm5t2`_R^Wlt~1ln3SZAQj2~R8Bw9%E@z5 ze=#{M1*eVJx}{)0dTZ#7j>Jvm*OfH^Lhgm54Ak3GQqC#3A-d=@Vp;uYO<}&{oqde> zCy_n?0TLq?I`Q2`^0{-Ph~?+zpv&Q}&i$b(NrKNtZ8xvbJ25it{n(?E{jr;RPrUp2 z#1G6z-fA&NDHg=03mg#9ei8W)*rvCrgDad9*NIySE-Q0u8gQWAN{;2WxWRjPs#n%c^9!ok1OQ~@0Me%L7pZRr+9O1Mt>?L zHk`)e3&wSI9VtFnga1xShT(sPJEAXuSA9TEB*;@f$HH1eXy9EzVvELMm56ip=|aQE2${wQ2)X-XX>WeARD@|IiuZBG5YG@=;l`3z8BRfE2l9*`?tvhi zlLEzvF{Sn%5O~2GXJE&`TS<8buBDQE6jL$=YKED`#~L!XJ-Tk`y2k>TBI*E5(5U*n zlEg}+U9c%=?dSCgQO@eVlSE5kK5*f2cE1myjRxNt7`Y9lSCF3ErDUOzPaZK@`-Uip z1kG8sYE)6jlf<>Zd|%Od;tfzn#Wh-WU3tBIfIJ^fW82cEacRHx%(s<9tjbED9@zR# zmvmG4XG)31^`@1=@N^Vk0COIOLrdq9g2nMm^F?O-=TjQ@75#Te9p#p$*c+A@plDsE zUB1oU)cSZw_wH%^a%vgc5X>p&CufK>o$A#ux%ZAt5br1y{En`_ud|Aax)1fsMz02V zg{EC+#Y)gUyb+~LNwF5`n$yGY?3djB_GU7~=$h<+ky*~qHQvLUTVhm-r5N6m)8;?F z?(@oPB+|F#^~|Ya!=A}Y@45^iR52J=r^Q>LWgQT%L)0BP0U|BTA8-3wRiT?3tlEE}Q{r?#eg@)0!**ziagL^2m3NHKp zmen^-qK>ru42cZE@#BZXWo?;L6b`Gr*-H6cS2xp7?MaByEzM`nTK(O9-OI3ARjAsy z89l|ZaA{ISBy?FVT}*8L3mdpWa`fR1Jzv5z5>s=#l1t2WZI`e`vCo`*3Z49f5rOj3 zBOcJGdM5JaplO&LgZnb5{^nq6Kbd{-ItJ^@HxElE_rKSagfzNQti}^wA`5kUbKjB= zrLFN_<&=K|Hg}VWbAO1;N&EkuTd9sb-_5?BO}es-%h>zIRDUYZyyvll@jr_nrnzxs zRAh((R5e$*$Ww+Z;#Trnza8g=p(3OBr6G&dPX-B9C+OhN!nP2!YS;xi37E=;W@esX ze<*HZVuD9M139=qHU7o_cp0!X(FWYd{TRV$^Uz!tanHmODB;mp~M5f*5l^z zR~d^7v+3&~E}bZkys|MS+sa0c9=+kfU;*eO7;R3Kfq)8)UiXLGyo)F$shrJ{bY*FG zV3PZ`S0&Y7c1nHr?1~%#N|jVJ4Pvhh_?k|X(m|@5H?Y1sP5ZI^`kA5Lpf?p(W7Y}W zm4BdOihS}8V2C^xo@m^UHe^#Ei`o4UiUu1s@nR9b#?%JXM3(VGAb&_`1xS2bn}6N| z_lLXHar0H+*w6|2ofp!9u;F$AybVSuegi%MwPXOe)rI%HG-*ro-d$HSAXJ$&$R{+J z1C?3J!fmPr*B|cQj`5nyY`TjFz~JtVJou1Zwd9w^{;DD&zxegfEIsU-h)4>~EP0NU z5zY}Hjp=E@8UW3qH?YWNl&PYDcgq83A@5=C-fXjLb`mVYb@l438CJ6hDgh(-FypZF1!GqZ9n!1xlvv1$zP$`bHPp2e>Tz3b&3zuQ}X$8E6Rm=O?YVv|@u9`284gsX$6mmt84{8E|s_oPe**pk5 zm~?nuhlyV4z;WD#24h&K1Q%r~o*)k#R+Ksd%@9ac9ms;jcGbk3hk|mJ*Wh4IfOHgc z;2a0k+uV_p``Bf^!Nn6ggJ))05J7fq>A^6P#@l5Q!j|u_gr>D|_pZ+(+1qsms1_l1 zh-!ESkHYv*d1SfL!3}GW4F$E%=Y-}NEjq&&#t1oN?cq6cD3l7o(9s+FPrD{hhP24sF+L}{6px|r%U9Cl7FS>q9b=3!oF4Q(!udI+~G2|%r*Vr;RpD$ z+tSr1opLokef)f0_#%-bBv>(O+&qJYea(+;X5gV*z3r(J$g)|mAP5AKLzVyr78S$j zp<6k3S=)6GXlgqG#lQ=d6hKkhjHObf3=BWJ-K@EJ3XRtBF;Wk+z$FdOK9g*$W=jRs zUO-)hinqRr(D<}R{~?~@5Q+-8RgiuKE^2cH=zvf7$fV2SB;lbCeWyE5gijMyZWX;i z0^x*R=#1)dpkX&HK=C*;KoCSemZ3TZV~5SibPCbY)fm1QjQuDsYCe(KzJEN-!GeP9EL8--Zts%ayT2Q@+S)G^3E$j zVh7m{T_j+<*i``CKQJ#xkyIlzWH;7SQAQ65bWSAHnQ+YA62JE-AI3vWHk133uvAFT z?&VpGhdpxnExi4#Bgr&FJsU1y!!4gHAo$EcqX~MfICP7$U8GZ5WQitHf9dimB?983%Zn! z_Sz=_I6)<5Di7i{uIoyAd<6!D+@rqqa4AsHkE*d`DGH(S2^8dQz&W`X?97wvi7F`F zMU1=X`78G?>>#pM_!cIKn7`E=r5v7OoV6S@-taY0l;RARafax!N{pI{EhMNokzs;) zc>0?|Y0Mm^)FXK27nCm-gi=V_spJVa&nJ%;YK2(%C*s}5(oi+XdUfr;9U1~W{Z{9jV;>rXi%>!ToWaMGV z|LmSNkeUH_Jdg zan6ecaD$~fpM5+mg`4BQ+}t+G7*bRDZN4&3PxCPFMZtqp+hr-fsRLpWhs9D2bj-oC z_D5NC@Ad8Xad^OoAQ*P{0Ue;cj({S8A31wySC1A~sXQ13xeEGJM*T%v4j}V_9yPsf zehxG;adAp+e|%bvk+ggFZsLeT)c&C8w3N8`&s&)%dn5kQfx|DA8>g}1x~8{q)3Ui< z*QpsctcfR>GGV=2IRZFoGu$-S`lb8iMG+ke|RC* z=Z&U3e%3e1IDQ=X@^U8qIzMCDo7I@t;U@yJeWoHxtcOIEC(XdU-U)mEusv$wQh5k` zl}jIr%z_X8-8c*nz!1w&)Af6>-BqEa21{O9VW4F+juZP0rZT$WP7^WL@8fkmqbR|V zIqkbVPW%CYr#rv%(zN>`Do_IJ=H0jOToTINlYrMZ1(CbSUs+>w%uei77P9faHn+T{Rlg z(8UC{=WN=Kcr7qb5r?>McDoLQqgZFLW>(oF;&{9N4=(-#FUr;0ZgH}c>=+J*<7|e{ zyykSV`ruPj_m67ZkF6%La>A>zMp`a#sF;y`JV=(CAFNg1k)gyj_N1I^2#zJS>Gjw}S zpWFz(peN^kf6h)bYyEI)JGa_^T7tU&W)`n7Dill@5#PsvM_cX$6j%vhj8b*FMb$eTQR8YG%_SUepXpT}XURg7mUDdz}^ zy`$Bw!p%X}oB!=uB^J&}2OYpgGt|+xCKC zJ*7i$qRaQ&K!g*&3K2M&F?hY1v-FdxQoen z?TGL%1}W8A97DfHLOg_=55te(qaae5TfaT=L&~v{fjw8U>}S{1J<@>cAZtmO z>-r}2!4(#HhGrF)B;5~ zO>!$ln(@&q(aLfJa{958)9E$n;0gRTZ!7>~8mgLw!HjFNWJ(oNADiZx?9WTdh5~(J zPKe`-g&N>&(O{79@7cgk5KJJs!V|l?zFx)01dlm19x&(om>wU`4Qq}84P5lf0t=Zf zK5QANpLdxUI$e>FmCLd?%j0L3EXI2H`uZoEX%C#aD}6V4{{@!$y(-@$S>vVYBFwh2 zG^$)$r}EwT{F%~pE@PimOU_h(zV=T+p__fh&YpE8{rzrLa^=^Y$=NlsUyqYBt%5Qq zPltOKpSG?zWmPd7CT`V}TRHGYYd89bAdrEn8>WpAg{wrtNeOuOIT@ai-l>f(RB-r> z2k+ZDbve?NP4pyJSfiIaKnUG5)fNtvb;5cWRczo36RTy1tWjud@>I~qSUC|l%__zy z$un!RKC+obFn;^3gtG-cW9On2|4jCm29uuO1^-c+K~H!vw0M%KmMxW zN+ZKMy)sE10uiKoD*C_BIwbX4S>*bfoR(2)?x?_+3i#`hOw-W^mP|tsuLV#I;>H}{ z;?{8nl+aMjsrGn}TB1#emEPMO@d!s#`;|n7;e{g)8KyJNy`WA-VTQ|_t+@>-CPY*x z0kNIOZPaB1L)C7Th?E{?@K9c2LHEir-AcfPQA;f(R1L$3*)4A$nhY|0zv}e*Q*K(N zJs#L@dq|E$Xw z&n)t(7r9pxDIIl4tA@J>u@3&F*nY`#aS6}Y=I=Jj0OU*Q-(R8UuOctw>k6BqnB+)2 zx|=P|`_q#MkPOCX(h7}9-fCv2wd#$TV305eVj_c_GW=$yr|_IXmF%+|2)@Tq!S@Iu zqrb8O=}A2GM|aSX#H^rOL=T~v1!+!4vFL)Otm;|gmB=^-Md>k&Ye2M+V26`QthCmI zt?zwlmv77OWx+!PkK&U>PmP^)op<>tLzh8=jYgKqXlZ2gIJ;9elTd*!MAZXeqb^`% zlG56RH>t3Kd#!5KkmP6Tn;=zfs=M`DnY};d7QDFw57y?x<_EnmSOM9@T^)o4@&&jA z(Tb^`ofZ`GM8Jh=5DlwxzUtQ2uq+4sW~E2oJ7#h;K5evL4*UD}(Vb}kw!gq4_~b?; zLy#=q?c#CssF;i7`7s+#DH0d^(fkI*&&l`g2USB!Z-5{B2P{il-M z_)z#w5VyRz5+#j4g2^-#xwj`+rZMj^R%uvIL6DWS_ji`j=GzFaHvn8jFjvq@1co`* zDj=W+5KL6YAuY)gZC;Ur0jZ683nsO$(i}T!nqkV6h-~_{RB@bn)3vhQURWip+0{vS?T1_7J+Q-UK0F#Ed#2MoDSD9a(iZ(kb(P+T!bx{1{*FibVhZ=04 z<>1E8tBVRWB?`32=@&!{LdA(;AieQt>UJ663Mv;*s+wg~mn?(INrVoBESV^<2D6iZ zjK1iQv|!SQuE{N1kQ9Q7HE37T*~zka+p+(0xH}3wz^h_lg310kP|&a+A$s710RzQt zs%GGkTRd%LNNzVsYKnnZza60!Gmq79`G{!W2iB0_F?d8}Ojk#ZrAUYmb(e=U z#IgP^4LH;ZMr&SZ?ugd0Apg}sJ4kqc5(NNbs-`#4Z$bM;EH-ok!OR0;#3YyiZoML7 z+1J%6G7WBSZo(uOiR};_#1CTTOA3~go~fkc9s!LPXRiH#-$>a(t)Ynw##Rmb*K_25 zM!Z?VH;2#u)^g%R&Ix?nnpV5|*=#vhmL@+puAp z8$5h68(27)&+X0wB{9@J0LAkLbp150b}Esh5aJu{fGjdlC?TFDm@#NA22wK@2nh^y z&7!!SGY7b)vil|pz!%wu5a^|I@!{4#b|E?}^e01U59}0aUOL`C+GL%EUBVv4I9M>w zdhhXh&r94m=^DLJNoMy}e$VwP(XdqTwtYdvX0gz1(UG{&pV)!mIr{U0HSBl2%^4|2 z&BO}^67%+)FsOJ8w_)C#21TI)@aNKj{O2(k1nPA*p!4RrhZ{X1Te6rd?Yc!Y7tOXE zEJ_4Az)e@={H^X`+*s{T6Us2>L#b&b52>_ zc)#l3^amGjeK%FEY}4W>EX;EfG@qK=tDHkU8hEq0!*^P!e7^_alabT~Ai#oLlg<#1 zcr-gJf{vtJQx$f(^a!S+J4X%c&4T*t?c7UDIRFS%-&Z6!TMo$f+SLpq!3$gpIM7_g z{a>D3M&Rh$ke;sFbA{=zaugm1YS?@(q6}u$SL0_^vM2AQzx16rDufBSEmeYLy;5ff23v4=$6Di@Ir>wdQpoYmgg>%04o`}h!ss}V`+cKPBl2~Fxd7_A` zQF>KoJU^y>oK-Ui><}86H;dzX)1K>K>_k5_lpkT6L8LpSUvH=55}vm!dp8`|(0Y8= zX`^qE1V<4D|Kr%NB`$!LTR1eivqaU*P!Yyg{(G+<2@)waF!^&yU*b#+mGd+6Qt9)y zrzbAu6~PVcE4r@}unx8_qb>-Y>M%Ghg6NtVQF`RyqHGYC`YQzvadB%VTCX?1j;ITV zx}etqR0d8VX&3S$okEJ};ZI4AaZQFrgAHXMT}3$SkCHUxr5cXPmEp;B3!pg-z$b`- zLTf={E5SM`(iicWvA<)v*B}=|Gh@hV=Rebq$lH#V58s0|0^ngOkE!7hc5&UmVB(@0 zM@b^^CshLXbp&S;Gw)TlzFvB9oXO?<*U z_ws~7(w=CHLLq#4-H07h!GUcAx&w&pLpCgC0YupsNy13%Bm{l1qzkZBFnAfFK?w)L zIutSfr{0Yv2b6Q7rI!x+5ugPl%#JHPs(;~A3*}rHcq}N>bovN%p@Sd5r%E7aCx6`r zg2KTMPWVhPGne&L*$nU-t_ziawFj5>fH`YML?3mPJNX1YH{tg?N_y^l4R)~rzj!-J zkS<(8nL*1yUayA^-9HKA8tH^wSIxH?Vv@)B++_>I#`1t%Xf1ScETmKAT>%> zcyLj(!B;Na@l*GmOu=zMPk9#{VOA{qk0WUo4gvR9V;k>g&JZnY=sa zGwTrREuHV1f%3{FK|0BXhET&qI5=~}v)(yT1w<5tMwa*n?Z~LEK-tF6?{`2riZ2OU zS$3d#6!_fdwnpJE@!r2^Hu`2RQEingUkl~&BP@(h^`(UYx%5*s!R>&k?fF)0m*+C| z(1kEohp0wr_!j>C%r>+71&hhS2em&1ci;CvEI}PyWnUOv%5syYF8Jri!4FJ_2*I#A z2Z-Ah%6BjY(&VS6{&D-5)cN~wWjW>J%&@W`meU>QN0D@V4H zT<^hMMT4Xo?&>0YiY3!;^c+U|K3bk&oLTsi^B~@ga7nEdXP-aQX;#L?o-xj(wu;XV zr){Sq9OuIGo^IW*zUDyIh3tQ45$0v`m>4OAkZzWm3c_~C`g^pi3@W@kiO>@E+^ap( z_|C4G=-Tbro_DIJYHDW8sq-HPugBLzE>4@3=;_RPeeQVsdBVNTY4FQae%o2#%VYs9 zZ0S`WfrBQ#C#(F?ihRzsc+j1i4%_r%C%QQyKz8gmbCS(px4{h6s;3B`sZL}T;|YYK z_{wj1?bw9K>LvxXTi;I({Lblo`+3q!CyBv?ynf4;V@Jb19eJ|rlBC`^*_)eNlECs*R|;SeH=>e`3Yik1c&1PnSf_PM6Bgq(2kn zX?YH!+LPRVJ`|y&|4v}|Ye2v<0_vB7*Px9lXJ52sT_;?=RZR&Q^D7#Q?T186VuVhFpFeE1^Ec34utDE zAn*(YvIlu0f5oN(0HZs>nA-#5sQN!_cu!+jrME}OMLF_ZuYuwg{sivRPmzxK-Lo5m z`R>xEX|Cvk0uQGDBR4n9FvGw&KI5ma47mDi3AyjQUkAeL2WEuxA8?gNyur2?@zWWG zP4G<$Yo5K)J@`xuR#8UIvKnygyxQG_%zJ&Egt`~exeFLsgLOC`zCUa){`1c?WO>X7 z7cb0l{`H}cw;h3XY%zn56oi4Ytg0!7I<7 zU<55lHxE6-%kO@KoRtuQplSsR;VAN=%nPN9MbO;ii9G1aKgW`(H+>MqrUw0u8AO{} zV|o(1&)+N76ydgto{^oHbeZyJU+oom`G@s4whz{xZEDc@bZ_klkhzj85{Vb~e#et{ z1Fh!ErA8^WTQC`Z=+ayxk#Hamzq;V*j;cF!4S?{d&6MePGkNgtSx4l$FFaD!9M3EaD{eDTSm+AXy=Wwh9elsm?{up#sqwm13j;Qv);e-JW zHJhCuc40w7S^^mbi~g9fBe>&593D44Py_H7y{phVrsdaWRFc6CjdQkKdUO3Gtc#+9 zq>JYi3-mR{kwOw>nWXo1Z7E_vH=& za}D$v9CswDj5&dvx_k!4M@FDdZHHq4;&QS>rANb%{Wx?~F9V}rwq1ZC>HS5zY>5gm zyfM7MN$|oGSnVWm&w2mLnzbLx0=YdZorbI|tIn(`1kk^Kng~A(w@zy$M>|NI`AiME zO9P_EZLRcHx^hdxAa8}cE(hHl13}LM%WZGy_z+!FWnn;k8Yae`YS>7!_v z%pXUy_8=*p(Sunu1t$l5e5Gpckxh4YKBVlCtfY%|ve1}`(AJ>v9qLEDHk+sNpgnm1 zRU|ryrTeDeig}1oUPP3l_;Nx}syINp8SNEHz6IRi^FTbkM>@)P0vg5PB1Pya2~ts0 zJ}JE#RwBkzIx7|I{3Xw`Ym16;}D2u`o?W*e$)&E3|9ffxt#XbImvbh$lz}f_kJE zm{FG30@O*0*n73|?J?j%i_#8qOnq1fKY~x`rMH%G@nJyb+G(_bU{~+c9;P)k#|R5! zd_XrCfv(_*=Qe8A0qY|FI=S~6{Aom(&I0C<1b@=%8l{fbra_W9J!wcgl;&c>4d@8}ttz#!$ z+-CuYo&K3Ny2W|$JZSB2O!$-wt>RRR@wdgayUKdA(is)UmQ)c+3h}Tgt-g1gvQO8o zKVMm~f>h-|n{N$gg>vX>Cv7k^i1!*at4bFT#rR8MlSr(g7I)@P*-6{w8#tW0k<@UR zC*%X;v*=kU=C?t#+YIDdggmIv0fmQ_{zl`KPT8{VZZ-IJdBUf)WC<-~uN5phf*=N|Nr;&XGScUy*BC@kSs11AKzmfXk zoI430eETyIvZhvjz+`V&IRYB_ap~;kkO&@)pFU2TU&yp3667YPcz>;}xpir|tDXG9kllC;^5pVQx%3C+ zkYP93Ph^fyl&*qn^?yb?m^PscT(v!5)~%&!XXxX4tL_<-3(hMoJ4RbJPqo0&<+lxT zbdth;&i*s6tc+NWIo73CJPYx|EYRQ?BXEEEbro>> zbW+q1q+k`91Xww%me=>LR3Ku?*9F7*Ix^~>Ixm z{rf(489`xM@F)wURcfh!7!PY~AU(0C{7s~myM0v*l$*CEX0=?x*^eLBTmFjmj>5Ki zyW?!lFBiO_ zPmcb_(nF6k`tW0D#VV|HZ6Qh-(BnL@yClSP$6XAb|p0zuquN={aF?l%kz$dqTL4s4RG{X$CsY9 z-WSU!|Jkr!6w$OV7((*=xaE4IK3Plqd*IaRAvgj{F5uBd5~KenU}ipj53Gi9%<#kE z@gg-8yuQ4-c#PF)Ns(dHq1o#v)fy2cqLy4Dvf6BN>FDr}y3$z}bfS8P6B&+UgjFcw z5V3xv5dQQ)jb!gL%jwXl|2-8UWffB6U)M;kwN%wzu$oBF+h?tpek)Le4F7ZbsaBa6 zq14000Oi?p)IJRGdq2SV=q2TD0BL-6WngW7iB+nN5BL7eOI7JBNs_{pXLw^n9~^94 z!agvQZg)kRneterdsCV+H9m#uiSPbY3o(NbWimZch(4p@(=80alju9I|9ty__f0Vx zJ7tM9c43!X-)Y~4vF{^ah}PxDYy*%DZVAHwKe=^=3s=d3^Cn-r-of6 zqt8jl6nG>sC_OsiwQ$S7zdvp~Er? z$RY8uwn?t5RFaGFJvR+WQ645ge6||57gt8FEzP$V^($Oq0>=pi3D8`r+)82{q%0@a7Z;57{RyMV{OO_<4HFwb zVz;8}ZF%6-A&QaL@JA6bY?yRZUplPvf{4VSI&OYEF0>3JxV$U=v$@0=Z0YX~Jfh3D z9JR4#Dtd+_KKmJ;pCu)@DkH*&4mP=Idq$E1H<~R#6Z9hJi^PDy9~u)-t+7xCPz3#p zb;0amoCnTW*9)~`vN!grl>!-L8F%yLS{H9islpA*;|LNfF1Qpxza3brBH(ZA=>)b0 zqm3Foj95!{{H4p{(djKJvJsjVFsZ1ypm*HsFncZ}-(s6#tTsZSZs#GDx7ggX02Nbk z)FaOq64}ex12d`3d6uA*qX9Q$?>VhR&SuXRjy@p7$M}qXstKgV*$`yl9Ou1{#Xmx( z0Zo7$=1+iRVabh!-X_vl2$$^8J_T`nwz!znh=|5|_^le`Q+oZQPxg*6F+0J&U- zoAW=9gB&6n8X-n%jUH?x&GWq|rK8MlpeCZSXMI79q79ZJMk)>`{ zTm7yMs`0~q_cDx)B-Z~7I8s=pAi4}6Ajas_U6N-sN>1gDr3+tQuaF57w5%4Fy6+ZH&}uW zVQaYB?B{?K`IJ13I@f?^VTh5$Z8z71et~n-;fr@PZ0eMc0m>Gu@hTX~5+APQIXlTF zeuoM^GVAe42(<`!`EuX2%JVVECm@$MewgVDmo zLmqteut<;9$Sqs=LWan@KWf{Lf?vqn*dJ|lK!Ctb*ysU*eVyX$;4aoLF1dYnKL# z>2}*}D6BoX4BOVvwcR6 z{64d*Ecjn6PHOz&-%9h!JWv?t0>3}8&(Nyt1unt`K!K0f$E!0&DH_F9S>(9%Z9N-( z2<>{Y(+gxft%HE7dwL)Ugx;m`6J}5oUGjf<4rNhGFi?PXb^?w4G{X{sbcROu=*)`Z zpvuHoqF7)=B<>g_{3pAg>gpusO!SW!2nq`701!iTGlG4irE>&pR*ukH?{VAwkeyFi z7uO{K6~yv<)`n~I`og}9C*q!qls&~Y(pdO?nvZ?@_j_hCHDJ{*x$u*jZV(lOkjZn` zCunA0odWY9v$-ZkcE6ZDM(Zwc_0&HMT_MN-g>*kf&b%PqqHXtnmTAe;Grg}Y;Rm)3 z%_zLXCV>_*gXuUwh=#v#$7*x^s(J25pj~Xvy2T6PfQq8b5gjiH?gdO*hq-6ye8ZDB zH<}v=v|$CCajngs{iQ)$NDF-|;ofcBj>1~nnYrr-*#JD5)mAm=xcVby^uF5b7#dQq z9b_9n0bce(ya$Tv{1428*3a8+`_jUDKx6Po<2R(6Kp)qkiKkf4LF(WRK*C>IS)`Qn zTLMg3xJKmn-{#)4=*N*X>;_P3fi0A=^bs4v zR1juCRpI=Y_stdT9UMP~nu{S9?4(o!DHgr!7paR4e0nK~$G+)(^PCGsa?3?hy znSiC`9_|9%PGSVmnz{1ypNm1o@fw*FTcg(?{Bm!ATUIzCvd8E!_xI6;Gl#+3#pzen z)719ysqybMIt^xJv%jcW%r`MSu0S3qKu-h*mpgz|=>euvSv60F1Ia`)M67~6IkyoV zqu9ct*9G8Rptd$!xEsf@#g-f|-|!v#Qb0RJ`>o9TNs65g|i zX~mz+bxNx!Z>0S7m0HI^Y5pJ5l%VcWz*dxZ0*M4UDv11{KMOVq9{I7!<;ql$^AGF` zeD+0E*8*10P?hMeVFK$p30%=^GV>HT3SiQFcGrjthTiONTTlGG#04mdedr>9>AMd6 zcFUd=;4R#S)7(UH6U=Px9i-+fYFwMaMd!-zrqYbbzOHSj7%BJ2`%10Hg*nD9#G3XU zY~Un7RepmE3%k(m?~tc9chc{i1e0jJufcqWuuDt2;0p{AusyuF_cV0*C4cGSI&tS< zc%_{XbXxCtz-;cOlXS&rfX@S+<%IWGwK+{H6BYGdahZf$EdNwE&PBP068RU1L6@qmio0hM`Y+}ZdN*4g)f?-#OXZ8BXT?m;cB@>npM_(Jp8 zcV+X5A4c7e4s1vLHn!_XFUI;mUo51ktf$Osx&srhk*2B{TU#^Up!x|u?@r~sPtZF- zJwqYcy15QJY==1IT^|J<#v^PqiOg?7<<-Kl(UP-T7Qx^DG)O#Ds!hDWjUGiAwhkBN zZKA3{i(Egr0L^C;E?^F-q|JU^H*kiD&-&ViFRIy+?E)*2 z4>_c)ryx}4XASpUabZ(p<8*hBYA7>>us24<6{B2r1jS<_@4p_YWz{^jsHUy=M3^Z zjHo)Es>+!YNOtH6&2~9D1>X8GrK!wy!F(oJEu!F^&ZLZ~g1XS3Dq-EyJ!F-i&@7WW zf)K!;i(7jl)g}PcRA+*jh+O<~#FfLgSx!J$iLqpR@)hFg*1-j1`FGgtIJ;#Ltl^c$ zXFR*X0J-0GF^#O!z1IXbSYwX+MMf!QV8$|kxmDF?^Y0I;tubQfsTXp*7!MJl5vehr z$aC8nc7QtNHL;5_snV994IOzN_-3*F;|Jx#ng^X}+RMio8ez8Pn4m?j7#(jF*SEP6 z9`Xh+^@?DowuQwB?@hl>9e=R#YmiNt-tb$Gbd_}F3n zemK}{$N>k6CWd$FX3$H`X?N`3t?J;UdHC$ zr=Sgtu@Y)#ths~A3wG8N;s3;wuDEYAA$K;-G8U)iIq+29>CPFIbG+UBhD(_M)*vp9 zsi${kHX7{KfZ2)T9b-UybKON~oF^SRw=Wf3n*^0sllq&)B<_1S8*oKqq18j0vN=AdT)E%+ixzV=fL0#(p@MxM9l;98(wPa)5vK`&Gb zRZ<_IDhgPm*}~DU1w&e31$039e0buiqsae}^&W6J{@?%jRaw~?MX9KiqL7w0qM<>P z3L)B4MDzBxDjF)GotCyVwb2mLQfa5qQc2qDf6jFmpYQK~Jsv$C)O}y$b)DCl&+|O& zSo-xuZlmX(%A8jp_CA{3pi1L1Tp@h2%6d8Vx)o1|7Gca7LM2vgC-z_Oy83%n5e^N9 zmnG%cpOghV3b0LqpQ~%HI>e_nhQQ=Dtft#LeuT}BJxTHwE8!Xx!2wb6Mx!;XCF+T0 zdo|;j$qNw1$`F3@KemoAS+xP)REj;#XLL0?A?&=59x+E-kUFAD5J8DoO$AL=_v-MM zmb--sXW}jq6OVMx_S(7z(iK4@qK4rIyi%m!1Exze&6ATDq)eb89PI~Y#_ZYw1f{_i z%Ia%~oj(nvf{&YLLjd{ndfKy1FDIS9dYE-!VDP-(joE0gVwo$I&f{fOjJ4r3dEF3V zR!pxU!khBiiRZx$0VyfHqxg8&jck%*8um1prR?lKo^m?(Q{fSn;^{T-tLxfXh?*m? zY3uliTbZzTEb%t+tU)yMTSH(>+3^3-ON+G_Z}^m zG8bgEc6$ClHADqwfg@)g+j8_`Js#y?0eeH!a2`U;$=7<6WP%oA@s}T z)*w_=9Uc?1A$5Zx!dLBaASCkEd)~}nqd~!uNLVH9(`PkLPD+~Iocw#TDe+ttDFRzF zz%|5?AP}_=jb$S*33M3lt$WS~ue>Knf9owLiJWsx3x-->Y&31Vgz}mvP)Ol%|DVo}T{*r(JWHNqqG8rJ0p_ zRW^&FyUDD@k^f>ydyZn0@1EX^5c!81YQF~}crK*Y1Jbq9q6|u zm=(t9B?3$D?=8r#%S=el;loxxWP<1LD>q+FlL9T*By9xt7DG7fg}gM#NdZU_N5sLx zjH!1>U7*s}2F{Y1E$dVmw9nb)7HZRU0Nse?__(G~S~j>0oqOjx_c{cBbOO?RBqmjl zjOQ}~_Z$;NTC?K!nf7`C@w-)qR8R#@!j5-wo(co93HzzS1alD;LTiU$+?nZ!3mv(A3BK;KN~tZwKZ1mF z+g>kMa~~flu&79GU|N^tD&Bdg+hLxrG12v2pc_2t5wUFq)EOJs_YL$uSyM~#o7tw> zglfLEy>YKh-7hfL*MQ(toTU|P%vSd4FJ%`-`|4WR#&523+72S${@Gky3~Xrhqc`2` zCeZFv5U!;cac%eGg%k{Dk71FC)>Toigu-$ozdGGreYk%@2x||!(GL{?H0>&d?SiZI zcOM37g2vfD!2or1%uxlc^%7H@^3uN_BC&0*lqJAdZQx&`&Ram?8)$ge9*)Uc2C1>Q zOeUwh3od04pTpX`;{dw-j??VHxf4{pl`*=aQ>2DZc}8YzP)hd`G_%bb2}n5da7l!( zUwxSNjsn+VjuUq-B#N}@Ce}s9b~kW5j=q2D*9m2YB!T8Bv-=5J0{m_w7ml32(PNS^ zD%(f9(x29o_V8htEOhs{+`c6~T;E=%b=%Grv5u>b4cvJ0)aY_(gIQ9(Hjd;NdAfDZ zpwhmr-F_r*EF*<=d=8N+JFmdxo=Yv$Jb`H%Qjjzx32^};Qz~T%!;LVnWp{NwJSD|R zp_Y(5RlQjHd0Rg3mGtBV1ToLF6Ji|za@V?JGOLNu?EsM2w(+@}H*dz=qnrZ`{{0Jx{CZh_39#xWz5sI4$n1@AuUq#kQmc(F`v3bq1 z4mY>>5_5v0UrPiZXu8_F2`HPM{(6G#w{z1&?de-#qNLE*{eDl={3O9-k`DnvU73_6 z^xcv1H3l8e%0bgK-S<9~qXrzvWc3YxL2QYrqv=rfjVaI4O^{cMqkjvx!XQL+E99RY zdcqDw8B@0ha!{#h7(MBk!KRhjvF4Px1L-xOl(t~v7wM3?*z6JM0*a9l#uymh=Z1$c zmJU0%Z>JXBi+K_P3$l_OxHEnKBlRVerQihpR-v<2#R-U~y$N?#Xe7Zd%Lg~+vFl>! zMx|rmwOPP7o3~7RLq<2|Om1DKdE*w zqG_|6|M>eA#@=EE2L}&>+uDy0Z5B7~%?t)Y--kd|{7#srBN*X2X>2qb^j;VoYJpMU z7u#U^@Kns%d7SM&J_i|eq0y)nvF=~G z?yZ(^y;s~5jwF4on!U^T)^18?{15^QmzL><#M8B(`=LSCp=BBq2BL8G7a#)@t?jd| z6W~r69v8vq)U3bSBsynFu;zlw@voqCS2d(6)b&9jYXLsk%-6C^xK+6ty6oG$9i zlcypL8cK7(&%02ceQ3(x=KN}XNZNHhW$3yKf>bSem41ka9uyQ5>>qLkw&gAmJFE8@ zU~t-ild0^<`1t5(38brG(0kUKjt+wvxS|U(wREvH)YfjCAG4Zg9CB#L)fL(b3QBuV z;Eyx$%R2s=ywyA@;+g6mAu+;ybi}tHVqaC})YMcb)C0DTKLKoKG;c!zL^Ngju5j;N zcm0}AXXtujzR(g{m2A8b>sblJL^i;QL6w6~)dw9F4xIkJDc8d6@001a5-p1AKNS<9 zz_Go13FT(y*r0u(W6Ly7Sj*>an1xoA1B0`q=-IYjPH5;KPW5))Q!qPVCHhJ_}`yc&81#SG@E(E%rM63lm6T%dRD2chyxW$32lOIGMpsPxzS87Rl;O13kFl z;4J#7U_?d#1d=2JkU{8TtBrg81^cX$foa#qn|ISnoW;Tk7_f9k70{(VQbF7s8LBmu z#s-KrMJUh&vClW7A=Lz)3+N0C!jo8mb;_njk;l{VBRDnHRc6@m)79qso;Mbnv$nx6 zGT%Vleqr+W_l<1!NQVYV^kGJ2ND5TF5;tKo;ZBJS{@JBYV?dsr*b-N_rYI!p$%Tkl zx+4y>#5VwLRgEEml&9l-oz6K{oHKVMc@+Af)xP*R)}J;K{-&Gs=gwZI9Y{)V`KC(% z=2=gCR}CL+m*Lg)}Qzo@N~BeGz;p*n|MDnW&YS zt-Y(?kF?=Gn=;HkPQ$>|4y*vM*d}RD;t0X)o@e*DB?rldDd6Kaek}*r87K?nWnj<% znt6MjnZG-RKG7>F3WpNh#y8&3(7*(QO>^00`jD$f?u2ozGu@c%LkwUS+en<6GoOQ_ ze97CXTy#-4E6K|Lbs^I++#J58`eD{8=nR8Go zZ`1krmS%>&ctUc6QKN>Ge11Gk{ zV2#ekyD`&3FRxo_$Q=O1^9pu@5NAlY!L++l1f~z#fcY~~2Ap&CtF+%K^HVA44#_+J zx9;R8@P+Bm>A;GP)hXV8r@R0yAc#D15N~^5b>5@ImwpuO?}^KaCyCxp-#CZwLC=E? z*sdq4MNHPro(oh z1}jXMDQ2klZE>-8VSN$V(4hEPDj9P&r3|MuAp=?7WQCPi`-EpZB+|t=u!X2O)8alf z0&zeW>1LQ37V=rR8=>~U*3DNvkFB!92H4lHU(`3^ z)gmu*+9+i69mN^%Ik`iP<)N{yD~JPuSZ77k3?%&1$ep5+`{|@S>t@kbI}ONw$C@{(9Xw53x3Bx3l`U;jo$_!BT-FgN0;Mozpre<>*blYjD3z z!gQV;EAPB{F5@Y#mOEQyNVX-_s)&|=Dv&|^EVJz=?3ER6(BFtidHnmDgFJBh*0OG< z);ON89@7T6)Z{^~3aNs%V1@{)VAf|R*StENHDx*%y_KBa2JTT8Qc_~+H0~1_Ekf2| ztD5An9F|(vghE>v`xAF6f=jsDND7+Se?m&b23NJv>K5gEd$q&&X1KRhk2QC+5v11X+JB(Rzobwh?;Q)+pqQXC2 zK%thvORP&D0jn>YrNl-AY+Hzbzv{9QgIv5TDUpks+4|ltA!D;=$3m7jHL|q*x_kXC zOPkLqu7m8or|PO>jg6Mg7F6${XvOdNi@P`bxjsIJ!qN^yXk;S;4+k}hAy~GmyzlFk zjWt5#)Ky$XFlKX~9CnDuZcp%k_VG9!_!|ZEMAj?VD9@4rdkR;O^SF9iT(*<2KKg%F z{v>>spvTVwtTwam2A(ZkZ|7QKdJL2$9uKy^5YM#rAgrVNMwbxp(hS>4YAuSTVTJ#q zs3aY2Wm|qc(x6FQAZ8AQ-WX6WS{kZZc4M@ z%DA}&+;f#s;f38%;lM@pW8l+1jseQ4u^%rHw>A`1oj+ z@XS6Zc4!jzk)i6p$FJIF)ZbRbU&6zT7@pK_R@|Lc^4~H809-GCpWNJdzYDD?qJEVi z)<@7>=ZK@~e^g2EMM_J8o*OrZ1E6l;e{lE&TxuA8q%K70pqMRuirAo(DsX(c0t5r6 z7L#^v=FAiclYvZ4CFw-%OCWp;z$`bn&`qlbbA=az23ffk394KwbT7Uu{Qb=K@jXX2 zGVI?8zujz4y)1A51xBaYY}SYpy-j-J)c3bRsbKGckZ}3Mx2gVtJF)3tLRRmB5mR1x zh%^&H1_r51iw=XralL^FC6eK3VJRrLSMpxF95XxW?^~F1OKa62^|I?39v;=s@C&d6 z1ViVIMZ1W9+s+Z=FSPg!x>wf}ZRF!Ir%85D`MW5TmNY{pIl0q+?@dEnBK5+Xl^uah zn@P=w?*8@&!{aaQJm7uVU$ZayZ^1&y$$b_yP8dkfXjZRTW&n3hAsux1_;}yeJ#w`! zF=#&VpnQJ0g0K%%e*+G7!=`_yjZ}@SfpghFUz@%3lZw$f){-{5H60I3tQY zQTj_`LV(NsbA>MNdE(T<=D|&~Abz|%=WUAyF*Mn={u@LXF|bBw8GkD)_a};;(7`3eV>`#Q&_hIat%#Ls z8_^PV2y%1_P)>td!^4Y9cy`UDjE%dw^?g6b|F6hLRGCaG9M~!q{cWg!Fn;Nx$gI~6 zd7%C#<43&aLQDYH@o~Jmxu|&eYv6zQpF4DO(_MDlC?wPVO6rq+#2!fOqYB3R@;PxY zX@{Sz8gHX~%&o;eu%3aL!oz7pXI*EulJHp^Ct0Yen%y-P{`c}LXgbPwkxnnP0N}Z7 zD+76t#Q6I;8|LVt!ofpMPLBW9)rP}dt3F@mHzBeEO75>DWSgnTKoH81jJwLTQqhL& zPuFTM>h3$iK{u4d*#FTSN+ej@yo|1v#B$IZ?iTz(KYqii+Exa7r!PECHE5L*N zH*HYoDoK8nAmv;5e5lA3MHWiNLM(%S;?i_mt9SHrjjsqXg!+X%;LNq!5)tZeifv2o z7Q>mfKRFPAR!D6Pc$AYv{X;|E&?k{`odZ5j8Bdvg8> z-{TKJHsZu_3*B~@G!EOBKYN|_o@}ZCk-fbP-T}1iI#Rc#*m4o8wrzJ#nwlVXL=0+3 zf=>_$9-jZjEpP`cf&Jg$%gycir5C@%-#2_~)_pVU7RgOsxxAp_n0!-#^R!$0y(S71 zzpj6Y7+$$5Glpw5p=0`2LLS1r%vyg~JyPajmdjf3T(5p^hQ5pDPEsj{=kK&2*b@Kg z%N3LD?wdDiFYXff1`MkH+-&smNj3EwO@2Ey?)o1uXKY!Xu$U~^j_Y~&jjToe22tX; z7VIy)7M8R7B4@l^qt(j|AQ?nZJ~fztW8CI{dreX9zdgs{U#GeUmi5QcrDT#}n;76z zR%K9^9G6Y9cBiHE)O)i`)77QAP;1j-dc6t{}RL_Lprt&^N#$Vs1Rlg-g+T zXx?hPkC(^Met81pLOz<@-KR2Y>n)GpxlLoRAeF&%#{>2>c4s=|vtij}SuK8Dc3P>0 z(EppZf@V{-mUz$)greLbO|9cb8~M1+39_I@K4~z-Jo_QJBvr`d^2)3VTxVni{%DL@ ze#*5A)&4rlU^m+a^cF;TJp)6=YA{SHkfXwA9&-iVvd}P!IWAbTLm9vbvYML~zTRU_ z-(c9g-JONLzLpJ=*6+-x}WiFN8}pc_R8>q=B%p$ss2Y=v}b zdua3B!$ny7z~pnP^Yqwio+a?bcXx#~?*55dL9`dRT+z4v5NT8D;n?Ns+%-5+ex*5Z zA7o7MNEZd8csyrY9A+=@)IYGt7>To?f|A;u8L|GC$L8H+k0Ok3zbv)`z9T!`pMECl zX&z8qejU8gSu*jf!F9civyJ>M@|B<WfE-+fHg6K1}XbW z_R~jpbUP`0|z|uHfV0`y15|5KKAxQlLZ+m6o%*AIArY*7_Kw|b3BAj1&{f4p-a$M)mW|dw-oqLeg-cR_!3(da=}bjV|Lymnlu-P@(Guf9oPATsp*D`e3QVJ)>oLTFYMeX$MZem}t2Vg^BGw4dyb%Crq(H0#P ze99g4^-#yxER)wLLpe{?q_@=QS?UuLWtEm@UtZxNfe^M{8V(szykQbXhy zo61dq6<$w#dYH;gk)J+dHgv2*d!rco6-`g0>jtm>>Ax)WQ@_%px$eakJTtuK+=MuI zje*?lrb%p4(cG({v#WU{@#$&Q>n7!E=ihI)Cig1?!#%cr!fS)2cZRy&7*CLHh)JSb zLuza|hxo0Tp<*Rq#1;Oo3${q>Bh@o`7dWbZ7p5zTjeL8{Vw=o#md#Bmqu%H5g+FjT zZ#v(q5xwcs>CNS^iCZ?nWdWEpCWAL-QE9a0%s{aHwymqyHP35>#cF$BKR=ydwPC?a zQZ?xM?!LK}8gzUMAgsMU_m6r_;!{x){g0PqPbHr7Zr8JWN8W5M^S%WbKzgC+vUa+? zcBhtFA3O?n481Tt$VP+*=#ImgX?@@+qU^``gRn6 zI90yN9cB~M-{e+a@c##5V^)|Rh7>~D3T-_^y3wTkNS#Xz{oikoss0?-XD~2A$6U`HoO1AWj+zQyv=_D< zw`Q!$cwAj*zEM91slte-iMKY25Dk3{d(GQh z|9#f*p$31{iqDtho;)LS8`}%1-r4pDRXw>F8+Si8WT7MqAk0>(~}P2g5PGF z!p5llH2CxZUtvOC&b%onf!>e$Sy{(8dP42Fe+HTKC?6 z)}*SJtFn`4(31^Uzv<1*GdJ(*iRI`TN13R6aosr8B*_TOJAtK5F zv|PFojg{<0R?It+$FXRd>laLDi}bFoEzLZ0>*StI7YffZtS2av!>+Cmda=R>ZkKRYI=?OgUg0TZ$Sb#%{sM6fF(PZRi4U#~QS5^sEbgsbm&*-L$4F(o9 z-iwxAmhF^%$f;BxNn&Q$Y_NG`=+@;wr9o?Zz32NI*4-b^H@U_sPe+8Wp(hT!LEaf; zXu^(OWI+1)DnImBN-AW$t|JFM0Il4iJ}kh&f!sq_H|fGboDF$Dgx7>15f)9-=mYV0Y*K5C3BhJLl6f=RdG-hXh>d194vWs0rS6YR zi9J*cU3-=ur`O3kVuShxoD>V!E;9lIKHfy+*_5G4_v_z3cq+PZTqr&WIAInf?#C8h zfxKUDaBf7J(|cTNpZAGd^WD8*Q!Y5kltG;&(2fdmH|f2Gq$bQ~h91e7w$MX&8#EUc zBT)$SzS=-hqs)s{qIC7lu?MUFc#R)u>&mifXTu~ZlJLzzHg8+vjQFfs5d(kaJtXZK*FdB2zM_?il}kwkPCLlfUh=uH}3g+$xL0 z|Mhk3ISk^noZ2IqAzrH&w6K6ip&Iqr*O}(T{F^*9GeH-xB%Cm4YeNhN&TWA|Ls(w2MRN*q5_x02kC|PdI^J|^S;sa9$Y^&$d$}VJeOby)*rx}ye@)6ia?EU; zHEHMd^s+(ckO+|us10(p0Wn-zrR&_tWho0-I7(@6qDqv>i#A){>fuF4yhr0Trgi_0`WW0)`|FCOla2gaTvW#@sDskc(G3G)dLM8p@8g(|XgOt31mj?^p&MIZ z=H})Wx%0q{G;hrj&a`Z0*2^?^M=q>k*i^@ov{}Z39q&=t0q`?Xbx(Q|fZgR`0%`QH z8VUPk4$tCgEbyS)yr{43!luI<_7~W6cQvl9J|84n=rSK?QrvKVC+O69smeVQ?+4UkgcE5lF`AHDv#G&xASJ3?Mvd9K?d|FN-34BogSn50K|hX ziE$Z=B;km|5$mlEb_&~!a0W47`xGw8|Euc{x#~Yn|Tln_YE3g;RbHmVryP9I}D-2sQB;76wwS0pTt=?G&L+NXZ>GQOxt~)SkgtrEPbU=QC2A`Jpj| zJ#UH!y^AWY3&E51dICFLJ`O4+{nfnJ>dl>a`x!3yr$lGvSI&;HTr^etEnJrRxnCFj zu$)I=^7Wxg?s&M+@t*5FOGlV7!n}z3LZ17(XB>fcgM^F&{-Hn&5Zq(*H0!{VNGOSg zSv+^okj*&Eye4$ka>cUIO^Z3Y?GoNrZK0zpSbKlbjo+W2y}9%xpNK$y;?gZdxCBHg z#W=(Sc}wzRFWJAV8X9$wB1cS*0~iVBv~CO(!Iwog3Lt9=yYLdpKhyAWR!H|c*8YGe zCboQ1-=+9x3=%Jkac+3->iWc+(WBFaE~jQ(yF)jOoD+@Q(Vc+h)gC3Pg960=&Xz1I z=NVVtnfU#XR z?6WI%Or|C4?e~z7jmThVrnB&ZqBFzFI3!LK%AvzM0Ot*+^S~54&EyJ!6t6E_Y zuk#0r(pactc-{ULN;`F(WLm?(DgXO7_Jl#^&x=0I`15qd&U7D+Ji8LcDS~WWoDH?3x{A}pANE6LJ6oXc4;;kx&xTD zl$GdtqY|YUo)zmqvHyQmkT)dFYyCBrP&R|NXvag-v26l-nAFlN<%$6hCHUmBonxh- z&=Bz32a(AX*-u|qKjl&vCf4aLpyh+wNY+M>-=_Yne_d&@e0@B(6B45~YJoNxzUAkF_gOD#wwsl@Mr zMc?PR$TsPH`>LpE7Fcen=wk1!&ozVg(c=jT!Z1>IvzSGIx`)4fu8<%&+ovF0+NYg; z4P=sf?HXX=B)?9Pe7Q+!!{Um*%T-E}sxMqw{=v5S?EVtJ`1&LVSOxMPfSCMP{w$~j zllwedo5}pcz{LuzHu*#!w)@H_=oi38NPb~EN5NZwjdQF@tXVSpf(P+p96X`jpc0CJ zJ2X=Iy_Ylwfy-(iSPq@O`y&Keq8K5jLt%9I@c(-f4(leNXh`~l$WW4T84JhE3Pn1{ zK?#FK!Ga>JYo&4gxyICs@`<_`d@CJiBh+_o8heTaFyUK|HA}83tMljFbkrVX~`OCVfe&oSn&*z*KM^4%O`vo8mL4=|`i z0q?a-DfO%1nJ6Gv}ef;ga# z#yKYp!wDTjKG>2872$w7nCstO9NoB%_jF;(G5*CM+=yQbEp3UFin!<*>2y3usTF zX6&hwdVLAcZp@SaT^${$MLFtWV>Swk^?yc_eTKFXdL|+8#7P-;Va<2%QEsNVuX{4vs;CDpUV#S6ssFl*t zbvL83xMAM$h~!wy2To?!RZD~Rh-$p@caqAvd~gH2cN54hq&R)w?Kmejb3Fd-t!&`5 z9PdJa4+2rx9C{+a>H?;V>@5YQQo4G6ZJ5PGBCchXC2Rt@vUQsADuEao!@+C@&py|q zH(oY5KSY;0*xh{Wwkzjt*B~;kIs(SV5MVpVkSZ0?{PiyFD+Y!-Q(=;U8xfq<&yEg1 zN^#nWzClSCSaMNnnKk}}dVuNj!rg+d% z_VI~6;oHa0V@|N8e@7z)N66QgdhDJ-?2Z1TTl{=Eb~leHmB2pL&IgNe@?bxWaT1yz z^eK?WR9@&8`295NTIYaNXwZaKVAD#3f|g);8<}^(o$P^hJnU+8A<>_Q?n@kshZI^z z!IQK}j=1vRsvg)tq5jSx-63l)S_5#QzjYDP!aB4(N5pOR!fuJkZ}AZ9-tx zs0UJ!2WtVIf|J_-)-Hzlll@1E-rmYNGTzWXdi_ted>3qRmT~4t;nnM`W>|Nxcfwml z3k}S!T7Bzr~(wH2B0~oDA`tO6R zOT66n-^%TpeK7tdKScwicHCuXyc6Ds7XUp(`+ITmWRHyQG$-1GpD(5~#>PjIa$mCT z7+2!G7L`o(s$khfAZ3lTlsMlE@`Ey#>%};@&F5ODjjSA(y8?srJkDWs8qaO_gctck z`ZS!IVsmQcPExPn&D%v*7c5sb!=T^5jo4=cT@l4Vi`0cX5KwPYG;PC8&OCxm7w>(N zfQbJT3?{>ASEv%Wr4Qigekc^QC}s8XgEPEt5yDwDC!VAra`d!i^KoijxhjNY0YoH2 zJF;JCs7Y-`?sXObI{tj_SrEC@v25kap;@RGFqYt$Ld0F_+m`Rd2CPey&@T%PSOys> z(LIW9t-=3;esc^oOw&<*XiCbFD!Q5Z+hEQpnOz0a&n<{*XtDjkZv*g`5m;_5ae&DEd`Hg*^&hAK z;cp6Qk7H;~S+kJt^nn<}(gX;cVaB-?Zf>R-%!m?`glqvx!-&yNL-H90hH8*-aL+se zvA7TE3$WwZU#VR81fEs==#CPv4|b2+LJesk(SB2j9}rdS3kkX;^`RHrO+=GhVxZ8; zl|?#!`~0+_j|9ikLwq9Ce-cl^9M8shL@_2S*l8s9=4(^sq0xtX@b{21I__sa=D{lx zMHW2lc3$0xzx6pGI>@0SnE%~wG0v;{1P`a9T21JWmclOCNj0C8+YXM4HNzh1ka|L2 zp*o;>&;vZakkL#UVxJ;4ZT9W#y`=NC%l?19f{<56?N7wMk{G2Nb<{xxfCelBlXfgW z1quZ~-T0a6ql)V>S#qcx&i}q?P0?Q@tFaYaw8c}2moX}#O?1KC!0ChdY9rh1VZ0qR z(e}!S-#-eF97F$HT*v-&f^_+m3z%%6fD2v|nrdL`KJr<9@<^h-KpA#|P)jwGPxTFc zU>u+Q-FDh(QIB3}QlSlJ&TxYJ=yrf}dO{Ck7zORA%7-YyO zy;9Xc5?~#>>$sIk4G&##wI*hAP|JDGjSY!M_Zk8_=&Wx>u57uM?i58(h zLKV=CZKqxumP=>V^^aylXQ|*5%&&)!>})ZADxfK_IWpL~+Bsa^0%U?bsFWMPMCS5Qnh~3_(H;j!N!c4U4f>ZhsV1SYJLcm*?H-WSgPeoo7W505P;y#rEct zd*=EE!1kU5djQaD?}{K%BQY$1$#(O~F{N-FFma}5p)BXiY^4?u!t<}H6WKwJpfc>( z4xtHzf~p^bME7D-o3kz@%c7YP^ic&_za)C}%l{Q0jjcQkn~&^2UlZBqNk=ulwm2UW zfbyB$;}MJ~Hg=rfG+2-v9Qg0#m2)gdbn+)w7&CY+N;HKbhCXTxpp(S5p zSN0k*ZQlJ6*nOFheFCuO7b`8G6o-5+$WcZ-1AoSO}kY1+iVP*&L} zBQRB!I$YW~yC!I%-0Zu7!-5?er8oClfd2j5GNs-0{={?pp|EPNtt)BQSuOq4iPkEd zb@O4p-5_mcFCDs$+cb#|xkE|@5wJ)-_ zdP|pmQ7ZWT0}R#To9Y`^)s!MJK#@{SODsCVStq5 zx2$76EZ@;PEg^oWbY7}k`7-y@k6bNpchawX$A5I?saKkE>Gd9u9pav4$e3@|iEo)9#&H@R;67;^i490(qniP-K_ z{;|<$Od7UC+fc*qlz>LZdfl|~Cm$0tr2ALl?I|8CeBjp8ujuM98Ym$W)y9p#gi!5S ztzgvAWC<<`b$F#|7h*XosV^GtO|>p^GEg}S?6KQ~i@6w0yZ zL@>MiZo(1ZOn115mZNjwdiYiV)a5(ep#; z&E6ygbDdD2EjrT)WHu(_>+uu6Kj`jK`QrLq=F`+8x-NXcromS4pKcoiqS*zgs*Up0 zPM64j$49@L3hP=K*D^@Dd$O^-k31ZGh013}ty0`(mrtu(jD)I4s9P*lx|w$z31t6% z+pGrnLkSmE@m59UFLUTx4%Z!(wOQr`a;F(KgXG|0 zEVZ>}MnM;>pvhNQ4rUJO_31ZHY&Qwi1ZSEWDl~s0nwn! z;YZ-a{dRHjx@*+C>ak?ip~)^-Ss z$;U_!i9Yetu6XWNT-J@o@j>s@a?`$rd#TFb^svHPX(uTCfNEKI6}$2201yN0PPwxO zp}XxO5aO7Q|017G_2xQXZo1`rL)k~VwbU)HJk!0e$Mz-AGzk9+0a2D}0-mDyM6TQB@pg>G4Syy__}rVA(bV9v{b-0bjo4|q%rt*^yyONgz)bIY7J6+R z=b5Ci z85^g5BX6OWPhR_J4B#_x)I@riyKp5D+lEKRbuyoRxa`OU zBvJD|4)`#|Db-7bZO_l+*UomW{rfJe?WQYCyg`0AIpR?}Z2}Ab7>D{q>d$@ecgb5x zc9aK+T3L3z!%K>*mB*DE8ptkIe?|JzXN=?A`Cf%QtC1tJxr^W?#84X}jS_H~59Eft z7ZMcQVCC4{+$4lRH=@I4)wJJoO2`|`9>cThnuY`r0xy&{e!Yyhk@-x6edm{U02Zf9BjW-2ir_3+57{fcWB3R?@g>BrZLkdl zg@iU?rw?RXC5KbXjuc_T$$D_#EgyJ!W!l`vYllR*zYRFAO-G`OI4^2!eLxx?f?}ze zVy{h`{q93%#S%&a>)0Ha9cbl!d~h(ktCJiBymqZLc~(rKZG#dgPO@J(YgGuN2m`^! z%CsmBtb9bb{Hv$L3#Jv+)#o%!h+JESfVjZlvRF zHuk6cCGy5xrY(|K43QNSD{@RMHA#S-99R3vWAYB*f`$HW$6l9&lmcgCrh)&e6dgu%9x*9WRdr(Znl(pX1zX&8f->vVOtgAc5565w z+LwE0wmjBMzVz=M$d@gptje?2Gr17tl2O~nP7rA@;%oz?qIx#cwD(HB+VHEZj?zEs zpscD|itRC&`t5=NTo!fKVOu_Y_FwY=PA)sP=a%nsIu%WVO=~eA_J8O7L;jWf$|7MD zh?OW1pIIh6f0iHW;BifSScxuH52H$A#+$@tK`V%%1!_`a`%Y5XJMfh=MJLb}fhz*@ zosN!a(p=B69;)3Q6%UYJ>cv>R7)_eSmS2o_6%=DP`|$tHu{esF^)QibhO~eKY-lB9 zEf21Ens@3;nE88c{3{+c>RHx-EU+)MQ0<1==2A0AAu;cG6l>3}nqCwT<8?GOGselZ z*30OiMxM0rYugLkO^EB%RtIS|Cs?p$!DrZ-7 zuO__X|1PB_@yYu#AMpXkh;8y-0CQ=7ON%mz1sx{8cxeT9)a-!@4x0J01m(>_W5GLj z5aHcK1OGRwlkf8%8ezW8;~hV2H=ff=sy{shWv0f(tBaen2GQz0c|i;Lxm2^4fz`&; z=kMYE9XVO8p~^P;eBr&2@0s+$ngE~-u5sBH&1GcS5@e#;PIqYshZ)B_ix!+d+?sli z+xOh|U8k~?0(*$+s65GaxVKc{zLVvZ=-`rd65omq{z>)8{ue8Yj%r&j$bwk8z2Bkt(8sXWH9?WJt+N`R zr}drqt{c@L{8t3>dEcu^&^Q^-<%x}jM~HoYI$a#3CLuKCz-O|CiVURu7k};4(nfBN zZ`U5cTd;2el6!+|(Es&KZSI>|%8ln z9H_rz->oW7Z+OE^TjW>gASZcszw5}m>n$%XU%?-Jn~_^E?ueDWZ10)inqAbj*~PJ( zr&~T66ap?t32f>^bG>16yh^n{1!XOZ)l?l%$Q6 zn}1;LZsL~A#4XKfha8^q-Rtp%e>=_VPjIuWnofKA(%G&|E^j_wqEqJ64OQ-i(^gH2 zr%=po8Z3emh~U?<;4vn^UXithwHWOfs)b|{&s@51$6h!W(Q5uWPsvbt)V{S({=#*0 z!5~OH;n8!Q?;Wbbqi;=BXu(M_hOV*`yAQuiTCo-H{o9=*zS=~W->6BGTnGL0 zK$|3p~v}oRw#DcBN(BvsbxXzgPfDigDAl^bb;S_$kvK41Gga;X5ZO-hA}l0XYEW>C%x8|TK3r(=#4^!JJn zjI+Lr8u+?@QPn;cIah~a?9?^6MUO=4 z`DrnTWOyf2KQBlN^(v17PnqB0a{2Cabhv#;TuSxE59zo}i99pDx-shW@A6Xp;LUiW zF;g8A{o9|#wo=8z!2aH##QLy<@DPT$>(#dvqO^9^@78K(--4Z^h1705EQI?l=KIRp|{4R;`bA5t4#27~$Yi zn`R!k_YrKC4SAdJj2^KIVJT4+95HvpeNbo7MoPt9Jw-|16n$;o4vp`&FH=(Z;3X_- z41(3v*hTHxw0vodW*$`<40Kro=K1qNf#qCvl{Mrv7U;5bLNA>V*Q!}r1bC-ws+tFw z*HG^yB=N`gM*TQ{2*c7;QRFek!NY(V ztdDOxt+fg~#iD704Y4fRZw=h9-TW_szoHnjvS?CWQJ2L0{xv)ix0mxDiMb2!l?~$_ zJSZmMa2-Ervebaa^6xo`9)nx6<$Q$qgMYUPJ)Ey_?nxvq}qiO~6>O_xW2*^ziBp-6p zNewJDz(!mdzr{YY-NE6d^P|&a!}xDMGNcb@SzVzfVkIj1chA7}XkQ+c$$I7cYgOX4 zrd3M_18p!#@pJcUZ(xrLj6}0(y!7}|%{6W3kDpQ9$|lsk&07*;whQDmwOm(Ox$aq3 zY;d*P!tKbJ40VU<@Rn?qA7pRW&)}`QmV5NzSKG5m0Tp7P#n~nDR)(KVi5-jG?9A26 z1Yg?jz0$=;i1qRdnaP9Robe07_)Exy(PtpZzw1bfJ_96O{Le<7iBVTQMf0V=iCkp? zih7)XQ<(Ojhf(L?EEMe*Yn6Cd0>ct%A)E2*e_RN^I`vaxc&7BXp3dign6PWFl4A;UH200^`# zeV3QG^}Zik!JDax_Nsxva&MQZq)O+``Ez*&XC?b7vB^?#o9ptF-WWYTMqz>2alwV^ zF*t%Q)O=;Dcj&wBs-s|qminoGR0ISoZ258I}#nd zhelEh!{c4dmsrJ5#A)*VVJ9CsZ8bcyIR`Ogm>}v^oFFjiqVHIC*Z3El`J<3)bP#A4nJS89+zGztWjK35jHJkmBcn&u-nSpXz!VA%lSjY z-aIELmj||ldF*YSI?*y&HFhe^go`^NBUb-h=JQQZNX_V&p#cHQ*>VUVHZg|<@QxT0Z`HiM`{NYNgw5NF8pA1~iJt4`$2>Hf z=m_8GHdvPFLl17pWI*mc{D|zSDDHENW3i$Yj z%5%eV3JcirKZ5yN`2gsxljI1=2G0c#-q15J@8IYQXALtmyJvyAdXS`Znd--FhVtG!iXgb?jWk=Fklxm+WiDTPA;v zeJSXV+ic5N5yrH8t?s5u=O1mud7NWrwJT`e9q9k^tvYO`H0?rzoUrud+v)C2rtBdn z;8}E&0_}`09V5N5s#f1+3L6=ptDLERY_Xf3DW-y9G2p4v67haew!F~R2xaR)oBi9s zis8Kt@-y`wJBK55lHF#PP3sCBCYoLg?mD_JMcu2=p(J(KqidaqT5Gm|wv^;H*lApr zM%~%)GOJ8Ac+Ec^k0gzLj$RFKjIW>H0WDsh-8A|K3zxfBsjy*@io=?Dj)HswbxB&xX7P zjr=kreD5R;w*&@C;dRuv{qB}70DgjM^Ovq;dd#ADN=8xmD?}pO=kd>!auZb(vwtq~aiCo$RI4r7)|wNq(tptm*in`l{!1 zH@@$B#Nlh$Vy}v7DJkICbsg&C`aZAkOSSx9{Bx${>x<*#x<1*oFRs>_YoR&sA!qr> z>YPfmG5lna*d~VAd^>+g3ex3ErC!V%J~7loeM!BL1Bj+NO&){w%QH*cot>|?6u3-p z{Mvq5Sd&KVt&er}NSUW(J5NFbCm20{t~4;a?=l^Zp#v@Z!d#zK7ayW+$9a%uh} zIT{0S62eDoR*;c2Jb#e4^F@`J52NF9D{D_OFg$!A%TGTlG)zgzaQLH{w}qfQ+m%JG zRMNgjZ{8ne4zi)ywd_N*o$t*8!){rxPs366#P(N0KlrJBiUIez+>1x_?anxSZFgI? zn}}^_9kgJ|tFeGAn04zMH$mYbElSQ|;X5iXOw3D{ZVyYmscr~5$$hZ>X}In_!p95F zwoM=RT~R1Fjiu*YdOv+`=64{nTKQD8Vg16zd>;WwmgqSF>!Yo>oO14kkIM3`J(x%O zEdb7s$QWvlefiC7EsWlts!?s0oRgZz6DksfhJUsFa%VsKT`^2s;8Ew+>9xfkx0p&m zg>0D?_<0c+Ye~)?T;j@eA5tx5+JIqWS$qBdHjrCVOu+3z}rL{IIjC zPAmBi-m2PovenrvVd;6l(cyXL{^W_G4_@v%vwg4QMWK4_M$MK~t%N(ye8@=jNP?Xi z+D2{=bm-uCnQn7^kKeTqYoZvG?s)fJj`jT=*_?SraPHd`8PCer8H1cP!1}rsojgji z&#~(b$8-rcBlkenm*JwPmv)@Q7yI3m_v68+>Sc{nI+!Ond&j z#O}vR!yjjtT_|~dztcV}caN%mfjx^nBK#=pCqP$Rdrvuw@%*8aX~5R6&$_*Ld-|WUeDlfO)M@a?@~-^C z8=4qO`>@d%guf^)D|L4i6VBI1i#N`B|*N(XJ6b35|^!E(=aIgSfEx#qLk^o|eRhpj%5_V~+fbe%q)(Z1LA zIEm*{yzkdWYti;X;arH@6~L;U*o8DYPQAy^dBBB5ut&MBFLZZ3l<3F-2`~!SB=7g5 zln1~y`RWd5#bZeJmLNP82a0L3>1fUQtfkU*ZQx5O)$hzy|?_A@)k<{D_{@qM98X!>cO2zJ0@URI6JoW zZ6OIR#eb7*Qiu`7kr*~WdzNloJoy4h{>T|MI0Yc9U^L05PD`hPdCt@AI!w6lj891R z$jbZ9Prfo3L&^jVQdY0s;Au>P4NW=uW%u(E%GEoepuw8;#1%lEWrRBUcfluIL z#bYbS?A|q*84krdmX2brG`O|T#06A8GtQ+eir#gNn0!vR{D7HbL-EJyL>l7VauA!y zBmhSsC6pL67)Nof~cYa z1~o5WW7a9T5;_t*0d#qOrnv}C!4)2cNv-?qu8mxn9vc{b`8a>i+#j`hA)q~asGExo zB;!CuHteC3#{uxKP~BXJgiTl8(?nxr_iU*%=J+kgY;%utoJzD6Q4FP_-hsZg1eZcHokSS%f9NCsq zZd90IZ%KL7?6t%NO9UgZ9ia5J6^OMb;y`NE<6%uGL!)!B?0I=cfzVb*ZKmG#8-Ar#O3l9Jm}Txa_)+S=Nd zPU9@72}IXl|GMg2c5?<9bO_SjUDDm%T%=RFzd88+f8SZl^}YyRX3os) z+41b>p;d~z1?CfiWY2=Vd@EJ5)xBy6u-c|S^m2uTNrvrHI}K*s6M zK_!6l-nAq`eRTtqtAO{T?F=jf1;jX*(2fl=&dMnIpzw^`OV?!OEB(4Y6bLk=vl`;) z%u^Mvx}?m$SN`J+y@G;oV{uvNP5Jh-PlDl9uN@ZPq&Nr1z^A2j-=qzkCXL4j-bE)! zkfrFkEh13{05K%Xc2~`#RH8dA5Qw1kwRr>BRbh}?kmmKKN(X?6H+F!Z+iN(>ZM?{Z zn5%yn^*ZlE5=0QS1M%L*&Q9on$4Tiyj!J#bPtMb6(?W=6aT)MDhC?)IYA(-CPk4sS7pIvJgiR~FFOn> z05&x9`BBGeB%&h#7)VVt=`B-e-CfkIGj z=JD-QY_G5)aAF`5c*D9iNGlBL&VX72M9p6SygbzTf7hLy5pOXKcc;8P>wp7!mr%$y z%3toB0G)C!U@uRd>Vbq4ByVALcG{&0ZZmOk0Z-KL+Pl^nf(E1m=;s7MA&}OBGDY#d z=`j=}3Nc^pjj?j_*ouWUHzb|)M3a*j@);Yy##{WA8TYCjKgtdk)U~jSKX+vS@=>{v zhyATRLF|ijFu&ARqV(A25F_|Ia370sq-CdxXFT7IFbTbJ?wYt~IJ1QUx`dwztsn6)}@6GOwf(926_{r9Y?Vj8y6RZ?Y{n6rhI`pS2;fjS~0fy z!=%$XT4^cDaaxFS zY)$sKIUx)QqkWr+SR`o)^XMnxNYod>3%-VS=hiO*+^pk{sYK6BUIZGDb)#8#+F_ z2T4%(?*W(RA=g2OA-|ridwDm2sdK}B^+7E>EtEI=376-9G8Gqq9f))RSbapZaANBY z&hB}$=GkBU!mI9lG<>|RQbp+7*A?nk$SHu?PBbD~}d8V}m6D$|E2_~sA7&ep&rsz85lX1!*<^4ZYU&$OD}98Va((1t>2D{ZktoJ^S66REr)%8^ftbeZHi_Rq!}lt_=e91HpsSgiEB( zVBpxg9Zjz?CfpYGSSB7^TscQMExZj2xn2AII&HSojE7AMEN$NpnArCror$lENbUlx zf*eEp*IO0aAwn0UOr`UuTmE~bp64ZL@T_OAZHXyhcI9QOq`m4ZawdD@KkdLoo5;pq zs^Ker<`RP9C%OzMOkjxwFn=I|a2|46cR9BgCiU$6MgGXf#zt&0lputf_p`=^d5Q(z zLTX0R(%a5@d(D8l*%FWxDs1gRjnTl_)eoPb1!fnJxVxELBdj#%V73(7Qq@WhevBMD z%gt43Lslv5%?r2qCWWj`YK(A(j4@>whg`qWo5(+Ry6eo|U$gFNJ+~`2R}{SgWpIxF)sh`KTJ;ti@xOvX;4FV>!g`-R+5Nda!tuciGSFoHHop;YDsuzL zja7CUFIn4;*E8zF1GJu1%ngpGX-pfro#0(*%WW?0IR;sRX7bVs5UeKL#;U`2WvC&) zLku|d*3Ok+h{Brs_D&if5V^Q6;<+C>nGH8XH#w+otxN;PT>u(WSAp{2Ty!g&-A+(Mx2b=!oL3AIJ7X_KuZ# zg{e6iR^PM1y(^pv!bKV6#g0(f_i&+`wFc=+5J1OCWlNcUpW|JlsNW4m`;x(-P=`d6v$ARW|_<%cG5Eb z0;Hy=pY)(Nh1afzVX_)T0{XNcno+8UgwB!Uwf1yS-z1AldB`f!J*z`K&2;>zFVAB0 zcMxDJ$zUsZVxG6C&dACVyK8aXXK;R>X5V`3W$F{|yPytd4~IpR3UKYY+0k zAUQJPy>p-vl_0rb9J4c(2&80UkKI9gRKJtJzyRjs>@Gsf9J2VbAxmbE1<6z@NA~Jp z1J#*6VXYHrKpqu3RnM+r!V$kz5GL!y=6?}%6YfIp;VMIJb=ntXLq)^6lWefp`S2$_ z*kN8*rhNr3yl9|i5jIUB(Bb}a=N2e+1_3ONOZWsNMehXk&XP7B#j&!o;(*tcaFFyo zc@Btvu)~jm>?0cuEv+6P#g7d|NKsPz=&YxZ9?m1Fm$p*F#0Mw#wC+V z({wsQIJk)XAznSlND69(Mq^Eu*A}4$B;cuvLTgCdVO&O_{H93jtuU-GHUVKTgRCWu*Wj_Ij}mHmN#!N5TL9NbHNbbe_cb50{`fk@}}44WZz|=yHx;rQTrn z$D2qU%Fi=_k+7(IAg7oRMp%@dP|lwb9J~5r>Rk(E6K#OJZfCyz)_9-OHPCV$D7&4S zZUjn@FLxS0l!h{HflW?%_v>ZKYY?r1FB#*Mm6|`4>u?KtB(^ZacmwmO=Co5PLHZrk zVwZoK*QyN@!SH?2o7y;HhuxB#MZhoDE+|pMV*(%nMzFIHo9=eDmZ^g~!qYM!KQ~!! zy4shDN^bWqLysGXXBpNtfaV;C{Z<#iE(h$$B?PZ?=J#p8CcVNh?k5 zqji;$+6VeSJ(U7vd(Hk;L` zHDyObLs!)npD6$hcKSEpBtc~ofD~?CPp(|^3?2bN;^gemMLr+g)X^+}kCG(pvNA-x zo?>W1F^oF;L3=6o2eLx$n-t=XxA0-~Pw_-hA!juwP9Cx9CwkMkvN{dOprcaG5Zuo2 zd-U{v5=hqwa+=xj|HQ!#d)xsAuL1G&8rBA!H)+%kfa+s@Qo|v!uSu5)$%ElFNSK) z*2{DC)>?O?1T3I*-gO%4@8>E5mLrcjGNEI0odrFTZI@VAILx7p8Q{2$AP^*{!dm|yCK1~Vh%k}R&!e98^uwp3E zurm4V;CI?z`+Z^%=>w

@asXK&atrJWH;0=w&`naEEw@-qw06o@d2goLl#?=WVhp z97#))#~k?Q;}#U5Tvy<%mSVPKhvdemD8TGQd}$ z;L@26X-2efy?*_giMRux1%c?8UigF|sUhFW(p2BL1Vu8bFk6N~&f<`hC+9_MZF zDaX(_TTcz!mp9)kh&L0^K{O@QK4m`h6{>pmT2@ zY9ET$u#sH72HbQG)8XM^VeP;KMLXZF46LsojfuF+*@cD1x2sPt>^K&L{LD91n>LJ) zuHgQ92~VCS(c3cniagyjKpIM%EY&dSJ|J+~YCmRA9D-89s+22X$)lUvOc{8=fTOpy z8?Z&e(AE%jus??d+c;Z{-VLa)SRfaWn24J*4_i232>di)zf2>V~3QRpTQqJdK7bT zVFowz=jX4Lb+rJP-!MQbQl5XSmQP4cO>MrFe03l&#M4gOgELg4h$rC~+SVDs(A1YT zM!m^&b8M(@rxJ4HtR*aX?hMav&&83<>;hR^J^iOzjWbPVVN9_` z zHz0aDcSfQMGReoq*@)gsd=&3Kulu~^ywGH9VMI+#QW z)zW$u1uo zkEOlDxPyHNGyi$gI{ik-`9aC*($v2p=Fd-086zyNmOq1SFA8{tEhVegw584mRFZuN zmYe?=7SXlg`GY(`CHycfyFGPY%VRqQ`9=j1W=xVRc-(l%@4M(#TAiJ7WFu5xf$NBU zTT(2wu_lzpq^=tN2ZP!{R?Ka;!DhDN(yMq)vw+$z_P8AGx zofEjJGi1BwjBDjGF2k)%wR~{A$p7wd^BzHySTrtZ)^m1 zb#)17TDFyLwL+Fw85JN}Ej0O(5>Js~D`W30Tep%v1TSPugh-1YsZgy(ow~hp$;LlO zxHdT$LsheVObWyQSgsjFYgv7D?zt9u=X_Y5Ztjer`kd;QD1&;dVxVJwmN-x20@Ttk z++7lv`R+59*2z{lx046}32d~1l8Y~N4nggLP18~d=9KZ+ymcF#K@j;=pnCD`R0C#H z4~Rcse|`XJEq8Nss|=6s`SXa3thdhduc4it-E_{}9~&MN6qIQes&6^b?Nqggtd0|G zg)dN0$x{bIE}R6Y+JU`FuM|Q-z3xUXi%#Yu8DWdMS_o_qyk%B=@EUX8aeV2xN^iy~ zkMsv3qE~fJ@0NS_z&C+I8tPPzEsDS>S6!>3!nw3{Re^9BvDRKwnw=uhyWyaWvfT7p ze@VxP_J3yRqkzMw;a%_ZLp>|2)z|uK*oIsZ0ObO{5}`47%n{;kAS9aQrckWCEftqw zoHCtF@BVaH1)J-)uzMVBko%C2m38QwwVm2m4l2rlf{~;ds7wIFv^7_+A;3D6)SVLq z^fwOy@rl9eb)*m!U4k;t_KEcZULxGm;!+l{Trh1}Zv1@>?_~=&``{^7V(j#MnQy_u zIJqa;S~bDBU59B0Z*k+QZYTzXZvk5k5$m=|_N_S9tA|OkLjjMIWx1W7_g5cfsMcGb zHmU#$HFBr@C)TU69iSaSh~)M|tNUq%wWup+krfM2JD8Xe2nn+vaGVg&`!KhwBW*hW zS)x6bmdX5-B}M0dHmh!{AT(w*#iyG0W~!qtR)UfRE}(AV!J_+TC;OBfhn2mI4t!Rb z^z^R&TdW0qPme!4#h=PJF7vxIt2O?zNk-c|!i0r+!)%O!nme0jvPB68MoUWz_&@W6 zov;3e6M+MmDa2!Hrn$*7%1Y{{St$hZSIX z-E|1ZmUR^;bL>oA&kqO%olFdTWnLQ7AYEcuH=hIBH@oiT?01+1Uqdtqu66T4{|zl4 z%SjgPJ7@m1U*8Wr#d#v(%+9?ZZk@?VQatl^fB!m-boD@q?t(6p@4quJ*B!Xr*8C<} zOY|zkUyx}$GUUGv8OOe_wta+A7~V$>$6OFPE^`iYAk!G9JCwH_*+jY*Y2^e3uXfRD z0`cHGhORSno=H0#gQS#B=d3sfht3WBl*$uKd6_U+ALtmcF-~?ri9NUggn()vJHFy+d9!tD*S}rs^U+QJHv* z52%S83=yi!KqS%ci1uNJZJO|RO*IH)M)PnC2 z-8&#p2Ws8=EWh1)PHQF%jD7^R59kvN z>N6v(E2ho#Ojfqya;GjJwvSakn31mmr*OYmE+ZC^Bp;_b!05j-OXqx{4@$O_hmim4 zqBLm|w&wQji)dy}`C0hh91-Q^>c?90ka0!kHs=@I{Qa)YOGAM1$l1PxAJvOC<1Zfs zE`I#6{DGV(GgpzBi7^3?rJfMT&275m)9uIT0d!Ql zFB)Q+*f~v`|4F^!(P|++NlH~ z?zh<9IG)JaQA z&NH{W*U=Yc`ztf^vK~`ZRB!31EAGbNAZ59TE-1@rw_Qc-n9g+D`{VCOtm{Am(B6Ib zbZX6F!jdU+%FnG4Gb(4%V7Df4ovVY=-#C||c@8)OW_*5^^V8V!zZ(k+C7nftlwmYf zcTXJm6_2GK1}z>Ac+QC!VR#Yx>6w{n+1Xu7CqT(b2ZZV#e78U$EWsk$B*4DRA@s!c z{8f>lgQ)0kNr-jU(ablRx~fuq3DX&!is>i!5r@<4IwjFtrecTg%O_vBSXKr*nV+KZ zm+m}Lt7Sr}BppT1B???{+Pgv7z_rTVmL8U4v_zgiU`v?T7FAAFMDV7 zn2^~vs;v#SwRT?aWT^Eg>(acdu*J1Hs>(zps8R+4T^XD3h?MaG>~8cpI5K268sSWX z;1h+R>7^coA!t*5%S%Wg+XhE(=_ECksxhgts%moM1pHlN(t=`Id2VqrPG4VNKuE|@ z&p9b6>Co`-vK?ji-TX+l(3{G4#Q7UG)&pj~{VqRiAz-ua|NiI^6K9^g^NW)o9N063 zE&6Sd>On>4ZJe@>jnfeR&8M{BiAg?-umDYwO0#l%}>y&-amR^b% zftyWw$O#ZIdsdHPq4m3{uI-%OaF_b5TGgvm;3s-}^C_^W}ul2zf}(K zPVNgw(~iYJ)Bc>63%x8+ig@m4jRAD)fHGlVy_(u| z){>^DphKE~g}l7{8_C#5c&-6PK#f@Jjq#19k}39hLmd(2s?t(mpBS~DCn}%Dn4g4T zKV{lDa?)5EV0o(WkmG3(8uD&YGUt9jOH}|+kym0O`=afq#=7@lX1i1`&OfE)$^6f_?-qf1Qjr0NNJT!TwD{DYZN<^3Ldio z0kb+0>#e=0H@2`BdknV53)m+rOSQu^LX~ewei4>&sBJsx+TtYHrtxAypAH_$$XC1b z&pSqZqCcxu^%6K(A9+O0{w1troZDqEKFatY@_LxSD}Q)<;px8vLbXtOSsecAp+**L zyW=a%VF&cq+2>hd(xTtWwVM%**h&0n`1ts)3H9e{9beSc){*qYfz&%aS(_D`?0CtlUYfqw}7@b78e-sChm&o zjSTc#n#KMYATN&O{+2RdDj5k?My@IvKi+J-{wrJIGM$h@^~ZEe%HHt5VUkc@O-Vd~ zHv#=Lu(4QNx4VIryTbx#-HkPU$f!ua3peu;)HH}ZcuoQNRicGfja~MLl}$>%YVq%l z6TsQ^+l=$_s!lu&XTj|-bi^GLEfABFqXXz3wgWE3J^i;S@hmjIc&CP$5%>NmqtpEuK%yK2#ix1cq@aKqcVgilo~X>S2+Nbw3wTU5`de${#I19#hNT0+F%#-E4%J| zWeJ4nQJcR%UH>A}jpC(0eG=#V@juf^^PrY;E&W~%A`8Yt$c_v-b--9~B&PwXYJ$Z= zqo+_%P>`ET|J9WnnV{R`h9IOGE;q1YitY=E-8<9__+gT|dCY^Ay91d;iXWJ%H8X zHW9=OKZ9P>-$&4CFeWA@=HALHP1rpIn39X51kcNvg#-(r!HzaOGUDzc>j{ZMCR%_L z-KqS?k2|G@O7Gt;^pzA|qMB6uSyX@uid9U5hI~ z-Lv0S4LU}jJPH-}pMftgTY>LitZ3ZO0I?L%63ace286#}%gaYhtTE8hHGziK7nzs* zAP@Sr=Z|J`aDceV*tE~(LVruDkXg%YM?+JHf8`?TfLkb$;}0ppd&JVe_?^T3A}>V8 z+Obf;m5eBfpMK3F0|HuKVPbV1`3`C%c*N_3I@HKJLBG2_z2vB zT_Z;95SLxz?jd-ykkEo=;u=Uxw}CwdRv(O2IA7V-J_(OjR`}t)%v%8<(WaT0wvgyJ z9|#a@{xeL37(h@HC8p0Hd_d=AEU0;Lap&KV5)%gk62dvS?Zb#I!QR~8-I)%HX-H#P z##8Qw8T0I!xL4nkZh+ z8U_<$5wycUJe#F$)8_g&ouO8pLp_+P6{st9DBm3|{&sMVkbO}poM746*|MkA8yWFM zj(eKnVU30Z6tmE7I+c`>A?FBq&H*4RKzA)`#QkJv#vjPvAUj~wJeo4&goM~SdwOhZ z7J#HI3XrosISA|&I3F`VTR6o^?J={h8ffn3zb9Qp>u}Z<(uG{{UUYAql|x&cw^d zm$-WhAUYzsV>NCX*^nyt{&Mh(WuO6#bvjj~g9NPD{$_3=6+8QAI=rI1Tn7-^oB_s) z#9c1e6SFG-HF3!86I~IM$3GZx#Hx88^D zc9b@i(=HBa?jBVtn#^=EE;Qq(_EOcZrpzF z6;|LhrltTi8wn(|DSK*cYT5!Zp#xD$3SVDe*;6KPb^tERXDnAGt-gM4qXFcSqKIDLQ;jtq9 zETs*3T~)#;Qd8J>4u_?T=+otaWTIMkEqVOn@)WGMH)Z5&*XNA0wNJ3Q>g$LOJu3+S z&n9+ve9hJ1axv{6Q`6!=kNlh0(2T(|taECLtR0r{&o{vX22uW=@4Ti1@c@{;d!48Asz;~yiqq1Mxresg2cWvq_YTa7RYo+3>mPYsv zu0k=2%%plBRrXf?@-S!O#9=_b4EXQXZ0GarkB_J>;!F}^`@KE&80?vU?lw9DILjcu zY#vU3YyEenOa64Ar{}e%W>Ux6TN#-)(BzUbu_Ykr_kI>IYh`6+HCck&O#al|+`J8J zi(+fIc=*66Xt7==+5Uo0fyPWpD=?Ce2YU650Y1Lmsrc3p?ix{+$^Y6L^vS4QANbVnP6|}0J zKMWz{^SJ02F>}_YPd#d$@uxo)yT`;?D?yO=-xTSpiV*MKmi#{Cu6WCum@t44+7BeG zm(C909(-~J1~h<0F9c-$8WZ*M1OOBfwy1D_k`&+#SOD*|PGgc!fFFb9ro*LRg6cYX z{Kx6Y)7j#S>W|d(7DS)d9DnFaSR)D68A`tM_e%GuXNYqx+T2K_v)uHP!GA(@PdW@u zL{^t>SCyCegSDS9S42R7Y{zFa=y-0X9X%E{CLUF3_Na;AaERNlH1F77|HOtkhaWEK zF3%g>iqs9w8aykcH`}RJ&tSa~N_Pi)0JId60NX$gWull{SCp)f6$ZB`j}ONZ(N40ZU?=awsS)OCqi)ueTx&rZ zJKGmNE}DVA8sp|;L&47Ld?lrCrAbPas@-O-f47jC-(BA!O!8JCvRrPE(HHCqXLh02 z^K$!_r&H`U9FMtE&r|5VgBSN0Xpe5x7L;8L^;4~s}l3J<+FAnufoTUvA&_!{%Y(tryAR+L#r z9Nj00ZpX%tyA8_mdKFXF3+m2J?x$$ayFw@`1f&YZ!HF)xd-YSkyQAT=sHg&0gAfhm zT6GS5r|7j|SC?}~D-S>Pz_64wdedfJ@p$jGn~otp*84KuWDE?XhBJHm{&!r?g~pogo-X@S(ScVB?*!ni1d(ovjRW zgRBJzQ|?PuUlMpRaRL&q`_Dzx5S)tYKlL&1&;~VO@P)Gh`*Qa@6>$(MC|Xtf=Q{@Q z|G6<@hyHmeMjmXN9D~*Xg!U zDx2~!@#db^kHsxLOyE0hc!IDMdEwyhU6F#Rls@PipSS#(N>{R=i{CsQP9H?|ydu!v zd?r-+JEsFO6z1MNb|nAh&CoUP{6g>nh&}{f^?Hfgk*D5sqPZ2zL8MyKTXwE7%7Gy< z4>bf|5Uad+S$hR|knah$VjAXUb?JWntuTlb#V4T?v6<>E8uCFVbhP zIii`|gL{g5bnU=Mc;pMsWz?}>>K%W!K>7D#a4?q_VEgNrR{BwQ6R`c~yUM(4=Czh( zcHf>ZQ!L%L9&<(JYjVMDFFaWi zBi{seuBjd+K%Z8(Bng|Go~UdU>k&7606O-^(WX5++rB~H1JAFHi7k){`<%wHW319AngxT0khfm>;g#RMYi+%% z|IdE>>Rs(1i1?lE{qRC`6hs7OJi&7cRC{+w2qR z3btC?>lpH4lS4X~<3BH4S2pRKRch4^1@TSnwfLVt|16vCMHkdrXwh*K$z-(7QvI<_ zG5_lm0h)WI-+o7saMb-SrVDx~CcJ%1>{Y*4F~3ufr!H2!chWF3=vb@#%wO$^W1&1e zhAxQv-B3`z#Flm`5=tl{xW%-^6=JmdCv?hEQmauPv!lO9nrkp|F(k45)rec!v zzx-jSb3FUB^HUo3dWF6EyP;u$ZF{l;MJiT}tzlMZfddemL5-16ea~?%Q0>_`xdrQa|U!0dp&jY{AJ;M5+0(@+_^*FR=~ttRxG;hWKHD zl8%@I+3K$^s5Qnb=^3(kf-kaKcHuIEbe{t5%P;+{mW&~!Bw5dhhz=nnZD25IYVKBE zzigNFWMR|kJfjbN;UIL=OtJo7*as)SReaa0cH8#`3&$`Y$KNaQZ$Pusg=q#}zT&7uJm- zjP8|f>I)wE`Y=N*x+^F{wzP%7f!a>$%hr2}WW}7IE#4vvcV;P4f6X=8N_-t-Wp?WxhoHh4L)0HUxX``L$ zd7e=ldEwq`_l|7A#CBOW@D_@XjmVY%w8E#hR(Y>O2*q$ZNNe8BkNPH!%-7<-L|{eX z_(p9vnBzhO+uobPy{9uc;C}1RlD8Qv{V?S_#)G_??DCnA%LPF%5X84s^vR-iSTe_k zokxmeJCQPRj+T@9hx+FbylnL~sVdTg*~R5Kou#>%@oKQGa1f<_gZq`zEbZE|eMCnL zP7U~B(NnairWQr!QvMr0kub-+{KlR%$b|3R)G(4fK7xpsNWSoQP2@zAb@m>*dUVC* z2lq!_*433(A)H!FhC8I$ckX!JmfU+=ntE{AV@UPP=8US&Cona@PZn=;My7?(ek_;Z z&4Y=*_N1`FJ;Bcl9ttdGc}M5u>8i2h{EoME4LPo-l~6f4`!5 z%6hZyZ3BQD1BO0}6KT-Bf`d!}@`&JpdtcU<(J<2LI_sq>@84HeCM}E}ttPqInHV;2 zRuOBVg*msFm8Vq|jAVA;i>2h0qYmuRwH@+FeQeNj%R*U`32qxumKFJ~xii9v{2QFk zs>5UVb(Rkjvp2`Z;u^Pmd;9Y>Z2{OL4`!KzsCcE7uRguS(VY3XdqgH+&iTHQ_+aON zCVJ-2j;L#}Oe?Ch(%Iv}?mw3xXjNWqU7Cp2r+y;6HFhpAW`QC_YQ|jwKl>U~-%m$? zSfYy=6M@e=Xi+*ARy*HI&U(c+N$M&~#i8KOH_!zeyo{T)%R)&e%W41F%^BUlpjW(P z6=ixEMu0_qcd-hAi`CMf&~$HsdRvd=V-d4Hw|vW7`{Q~|c0msNIIGL8%dd_lU>z^J z)%S-!o8-k%1UG7N4d|r2!57;Wod4oz%V=Hq6OSp=mlXdcvF-yC>0qwMPoyz&`@(9l zsN;D1kb)=BURhGU+5@T`snbGS7$Hb)%-RG$GyPA zqjF@xzYo;4)~{cm^(d91dee#rV>;8STc>7YXc3ITg~b>*r>|@262$3WmuX^#DhL*- ze!N|_caRsoolYl7e?ZLYlEA}*K9L;DtMl3-ifOLuAibW>l+3wq5g3~BhB6|{IcGwH zXW01+3_(;ieVlF|-iKG7B(;Kd!+Oo^Jvf6}xZ{~1=gNdtvoX3w@Cf%Wg>hrV$zGu* z{|gRq3AGE;NBNSd&IfQg20Mvl6x)mH98T2Y1GWCe36=D^O-74XH}-1Be>_n14lo?&8Lmba93&--frDVd)jbLlW{o%d;CMx=7l3cjuc zXOAKn^N&mzQI_56cCXRZLfZ(dz!SSg=XE25$%j#hHdANS1+aY&i)S7;H&6T*+#3bQ z1L8I3gB>TBNM6p53Ee1;n6$<(M8QGkKQs6XI^siuRPoyut~0aOlor;lGk;zp{8W4P zfTXRd;^#ob{F<1AKMsS4-&1lHuIVs#_dOhS87iqw^6)3^zBxLBA%!ewl!APlc4mi% z-n{Jf71)-u4y#SN#KLe_wq(U>i+rWY%m`o3_LgVVeBWJ~t!!==*C zqMvAFlHK3HZYa3M=m=VOZT-UpuXR_N>ygB zzTZPBO<6IgTME~=<YTld2H=E~!@L4&#` z2?$)wabM`IQMf!_Bf3!TtrpBTzP(7^3lmIs(@AizyYmz!vHm;sUbJ|~eF*`72zu`2 zFXH5RJOBPeSrCH;;~pCQqwMwFTiv`C$8tv?5bTY6fXfJr)VfjChvb7b3gq{MJgV24 z)-9g;SWxja8m&dSxpHzF+Ot?Kjn@q7E>^qAjja-=38CW_Y=V!4Pd?&l&>FpnG$6z zd#cE`b)e>cOu|3Dl<`$<%p?P`fd}dn=>D0tC`QecVEYsXyR%eGi*X$+Y~`Y^cRyXCc54`$@|4 zg0~|P^27=Q^CZT6(lwP>!gN}GZW{jgI`!B@I+ROWUL60`rMHsjw8r}I@2CBisZOshonv3von1(k9so?*RL zRw4UvF^9C54w>BY5-;xxUXZRpWx)DCCPqPx*1&PKPpKC-~e? z#7!p8Zp&!lm{cF%{(DRymSXVWG7%gZ?)}oo53spIpK4^bc5idfR`O$@>5%xp6=BqG zmj86|^AtN22pw)~ec>Ll3Nv_O)Sk4gJQ83|jt?jg9!4ZQ0sDh{elYNN9F~7FWu{^$vVQ9qZK(vE z$LrI>pW3M@*TOHjWQ_HQn6EFH>)h8qWSMgCfclKDYgBhA{VlQOiQmLCSk@a!N2MKkCK6)zDE+n%~0UQ=0}ZQn0g%K_MN4 zefup_fmtRyB0VX>)zUPN`%{{~_0m1>3p&`^>Y)US{g**a{@q*{2!oj2C174)RY!1N zS&OT+7BS3%#EH{pu&$fKF9Yr75U?Thdc#`uh5Be=i^Hc8kI%YaLD&4#4`c|C%SM7K z&8)mfYD4K~S@%1rr1_a@?#9){H#0C&`^5!A>7dr|h0Z@Ki)fu6qDH~dIQZSKpy6r2 z;9)DtiBBQTFZ59{6YchFliLBGDq$LmU``vCXq9J(BB~SJRaAlcA(Gex3Ll{0@!b@{w99Xaa)GPNVm_w!bLM3 zsdH2Bo1N`GZ4eyylI23(VT}8jj4uq$0AHFP4W>>EbBIktw^T5UPr3G|LGk)Hu7zn= zG{0GtdE;QY$-dNoT;0iJNqq1KoTZ}tB8tYdMHa95rWlQfUqP+I7!9RYCa~%E(HnM$ zxOWp4Hjkd--+Mfs(%idJgv0nEj6)uOXxf}ufxL9?d8+9bvj8JPow7+k-z?3mn$dLM zo(h6->aAPB7Nx_;;=;O5qx(PKySdh(El^n6YzcztXxNHx3Lm$OY`nLT4ja-lP?-EG zBN5GBWjW&%YhYAZ5Y zHtJR81HrtCMY0^a2IdI}y7s{-dj@>{Die>F1qsR9DRz&J{|^f=bgCeM zrBb0IVJ#4}$vdQD$CN;eckh?@=GVlBL2nIcg)I1SJ?meaZSN#gnK1pCssu!(*LyAomat2p^Q1Mr%cW!uC|1?>7>bDe@9$8FB z-A%i;`|`smOV)$a=IokJ3|2)Vpn)b0>UJ@k;i8KcD5Q-rdTB#tIvOeoLKHTr@IM=J;6_8Bs zV}^3WPVSC81s`KJ?Y=UxY6Nefp*)Wx6Id2)0O5AkW#9F>ou2(}GYPNska?JEddbR!S9V(@RAgQnOlQ6>s$-72{E7qMouWjG*ax3;@^QL3LbsEMym?2F zi6Ph-zpR-0fo5jU8qE^X9;LX5Ol?ocULn@(=%@CEzl3$ghDYcX)E~YP`~KRG@c9Db z@<^)JMPPSiDoKdRxBj?NtGnt$Bg;3J=m@|F4?QA#`Km&XZ8-IHk(}ohI+eEraXN)&4=sDbICo=scw% z|BOqS$Edp<1CNCeANgrv%<^&hoTjS3E7wZ3hJfAEIRjG7>yvweJgTAFt?vq_+2qTQ zRllmwdjl9zUCGwH@r8zm#VDaF9cCLZ;Sq9w4?sLo7H)OL3KY--Z3wccw^6rN?{ z;O>ux$~d!cVeza$^J~b0mf%S4Vk`(g3%G2HpEdTw^&QDmEP z{Vb@bn8Da8Ht=|PWB2EI;d~^YjB=ib1rZ3T>rJA&Ogh+R!j>XmkCDyTF1}IX3ws}W zGw0TJ#LaJG%n2fD&BVeH{Wi?o8!S`?HBg58cn^YhjScMljyvz-UT-V@RZuYZCAxvW zuYo%XP7#Eaa~{#vdBGoemgmAGy8?eUqWX$N$ zQTPsjSfs$*va?PJ@LSxnIV zsk#WkhtX48+>T*q=&49jYpt!khrp5bLwx53AejfQ+XhBcEUVnk36ol%t?L&tR$uQB zj2F(sD!SxZu-?Ww3A{4Eje>VLEqLq;-%JJGGq`AxZVut4e)ovHW9fpCdzPnEia zkKqy3gjtxJT9l@(v5gCUz{$&w2y4MK@g>_Bs#o%P5gWzw%Uj3Os%>O{Zvy~loeud1 z7$`@qzP%*=AH3Fik#FFI5O>H4POe?# zdu|NFXby*;AjFA3G{qrE{heGG7kXAS?@Q*f0WTsxSN@Q8sBK{Un#h5WYtc6`y~+)o z1c#;fbbk;*S$aRS&sT3$>Tj!&UJa<|LiujKO9qg&N5{^OL-EyUQW3*EJ9?OF_I7MM zt-ycxMN*WPR$iRn_lCXE`0&wXxX-+jF7564jwgo3v>ZJV3&*_InC-WRdhd{6yPlU` zLh*zTpZ_Zxt$6;cXCU)Lww0n;fue@Rb9<0Lo~gh!dy&_2;8&1>5pm(uWg@{M+lP^1 z!b=1)N5x}o4>J^9+(LR)1t@NGusq5Sim=ti;l#O&|H?_uvdnmo@mv_+)pY+xZ(`O% zUOY(8?g>e*vxkxHeRxp*+uHuOHsp_7!E@oCEySD3?bHW{=T_~K>uKW-lHCcM7KKpv zgM%}4hF0icO`s;=X6Lo!caTz4f#e(i5&MCn6-a~q=g`~-mz4oCKW_oMeXMm)?gDBJ z@d_&GVNMZiA;VzbW1+JXCp>0X3zd|35y6vIi`-9F+YfSzR7+W0&3J@G960 zg`9m(E@$8YSu@oH9N#JWB|)AWd&3Nn=l8jF-+Ksd{+0@V6MR)cCPHw;VP4BMSRggJ z6={oyBXf^LXNw zniuZ8mivkViaPBIvbsho@pth8ZmJC*Y!;M$KxIsNd~rMT>$10#Qi zRcc`W7<$u9FB(RH@{>FKJG#REZ8kZi*d%4Fr27;L@0<1uk($*ICJmy;4?m`T51p#U zw;}#v(57vy+?#dD41#%AN2cG&mH10NsVJ2LQ4cekdw;R~67$#IKkNP+nSWN0H?;!? z@Jc0+#XZXUD$L~rS*E9=0N0+Xa?0fXoFrME*=tF6THF@)m_*z#j>E`^M+L{$Z+(1# z2NCQIFbJ{15~`)aj`@;Uq7-sT*YN=!v#sF*sp;y{&MpteFUVmRg9s2B zZnk;yHtu1N$pw#I-x#Z+^2R^#D%t;5UU)Sk$06@(OZI)m(SunB5JZ5g6clYj2|w#T zVtTv+q>5i4y*l>;8n<^PVo@0l-1r$8Y&ROrYU345E-%(sNpA0GW{YwB|FLx);9PzG z|Js$1RAiPiA|!h&iR`4v%$B|P`1CDgDH>*Q084mPyI!p&v8u>LeN2D+<3gq~0IqLj zF6`Z}O~y^a#<*}z^uiuyy_-l>hJE?g;@NJz-3Prda-HR9vG0kRJK-~_m3ACkhc{t= z5udxma{bc4*-s#1i&-Lr=wbbw+x4bSZawGM7*h!)aQyUYyhIZ|RGZ_Oem+yi_}!co zeE6{Xqllqcp@s~0RPgD=<4c@#x)vvA5JX%A|gDu#}}=8Rb7{e!V)5&7zqnT9@!jQ&0Bh z0R}?|vivKu2$cAMdV?ys;1tGZ^nNoWW4OR%&vQOsZ6X4pVG_&D|9mc6rkYdjvVYP< z365euG7fp!bMFGQRZy%zaAbApI(%#&EAg%0rLC!kYDR|IDoXYGdPROjrSRof8SquMk6CdOt4mb~ zz&y73c4^qM_sjLCg&+`8+FXHu*(lVyN`_W5`YJ(4kJlo|Ap`bJV&#BDuajILO}l51 zK}~!;?bYFSc+ptVG0TdRKwZ=Zz!=g2$gipF#f}D;Q)172w~ig&8JgOc=O$Bn?3R;J z(a*o#Pno(a=m=hy%jx!=B^VtyNqF*OWIwRs95M^P7iVrSo1L%MtnhxKLO|st8Dr`) zGFzm%KK3j9Ti55EjPGyctK7MT8OkEWm^Lr!y{e>j--G6H%Coc3h5cBC&u89Vz>C$= z8RgDhrg?olQpE--aoRM0AEmE<^Fmwo=Cd~0`@j*QMI^~_z^td8|6O=icD#F2;82yY zYDBLf0q|VmkvKaZizWjJLU%I;*jySvEvx%}Tq(KE<`;qcT21ep0!j)Rf1*qTR`wP~ zoxaQq%oZMbY%jABmQIe%ywrf{D}Xhr2Cr%lN&~zy_enXpz0zeEDz}xJavmdyn5r1x7S# z7dziO_dQ>VjKx0Mbm^h2THDLfZ27}OuHrKH6)k-b)u(OO&Ha=)bT_A18l<{wJutwn zl&QuxyuzX=KlT(W1LvEpF)?RC?|Yf&5dajeFltV|x;*jDOIxn$(SzmTuwHZg+uZv| z6OG;?Nz)ZR*Z(1#8f+JauZw>S@8Ht&SRbcUV%dkS^4!Y#3{-jBctu{9j+Ip@06Yep zG>-S*@9@!M{~%5?xixk7&CA2%Jw@iJVk3k9r1x7NovjaQmHakZNK+klqX0ze3F3L; z1w9n86>04*U|$23b$HCGhXba`;IpLu1Ek`c6z4KukdxruZe+v5>_JHe5ni=dOL^vV zE7uu@iiU;{@dOppgPSbZ-`gHo+S9_t6+kLEw>-;061!RQe0BLF;DhS= z|8~8CZ>a5!$IN=cCHz<@aRMrO!A)^?5Ef!LA628Zl~OUKzli<9-59$yhWxdk zAsua9yqBiX_wH0)=Ac#e9ODf-1IWR>J0;58437OfD9fE%ZR~S9g7uCndAq6@}CBuv{e+E<5Tax!GFY0 z0$}fFe?}0)uYTWb1OiS0jZTx*oNtK)df3Y6Nt<%hzo7FVx^^*Ge$vdB@7{d#@(#x> zkZ9X`wW8y0C&2ylX#j9CALna&?uO7>-m@3%OtAYHN+~?C)21@8Gr;Yt+~GM$jd9q8 ztA}|ZL0P+Tc;ULAAWi1WdXXxA>i96JsA~{#ZB;%Hd)g$|Tw~$KexAFB@W%nUVwPPy z@Tt;uDGG@r%BReFXZki-QHp&_NB4V4WQ*l|JYT-!buhjS!g@gKd^a5Rh$}H*-HI`) zTLyLeM%{ZG8(=3@-r6d6Q;Oo8=nVx&~LJO#_Rc~g43Dk51FDSiE zB#6P%6(hdRBojyoV#;@Bm68V^gGvv$5*8#B+|8njSYsm)Gg)ywE6Wx^JQH3X9y7M% zlFFt|W0WbE#YCbmTZ1}>g3;`70b3@VC9QX!b~ADhfe!}Cr(P8JxoLB7f&CWS^Tvn= z*1)ics@ki90k2Yi1HbRqbrNjOZ5C5fqvMkGj8}cFnc42kA&Bjf8G~zg^=2oC!Jah| zt44G2o#PL+O#%^k>x@X^pr;%Y8iU6_>E=M#yl!t~npb52H>B1}vf>=TJCZ)L8j@>6 zld`}+8B2fODz`*+1C%sfNqM;JgVG&-AOkzZyUn z(ZRZWT+eK%bGT$}+MIqLME^|ffqQz{fZp@Ea0btpqh3_Vk#SZNwJH~Zazv~xV2^0SKXAKu9(&`qbEZ=P6NX7N5b3SWvn0;MFs;la{tg8WbVpo0Z~W)&gB@n7oRIUy#UyTI0*miq$S9=*A`G2@oWXkd#7BM4CvNYb!Aj~ zUCGlA!r4cam~G}FUXfj>$xC;&2UmNfqZwM?KmsH3-Qzv5xC;x#%&?|eq8HL;qAm6R=e#dPc5RM-EY*dPMMyDJ6G$Sg(L8}?16UI<9u6} z!p_a;50(e!o998i(W5o9*#}hUG}eKV-qJ(28%haClOophX)A1K9mXExyvYYoNCSIq&kNRpRe_SI z8gkBHqO?~1JU^H@K!DUL=c`$KX+}G#@P{Vs{7sdc#FoWO(ik0sYVQ`KRIeJll*b7j zWmEjb>7jiAqKP+4R9bAU{i)e9G!Q?+%%{SN;z2czLcqm{TxXEK6umxAP;xNsM_XQ5 zHXPSt&&V$Gy8c-knf1_wzmecUHKpKzRi#Az`Nxf`duE0@#^w2#`U#Jjr#{AB@SQvR zDPf5sQ+cwZ$zaToRIV1dLizSl#DEu#585lM>qS_Qep=zXc>{#ErZG`fChP`u-bBNN zi^)xvbE8$OX|4_J`SEKQ3^$YR5W*DF9mD`XO!ovUY zY+=)%aRr|>AM8XoilsSLdi2q%?|*loX8Uk4>&ZlgonQSX?<;ls7cB>Rpdw(wGL9xL zZ2-8*cD6wx_{izdHN&NP9h?(eGq<`_S_?jbmKc3bJ9QTW z6s&|_p$conR(CL9%2EyX2RY&ooVFn6bPeRSQ&+uS;UKM>qH?zqD`wBNJ50j`0fl*8 zct;gR)|WsK4+!J;NnL}QH)B=XETJ`I?jJM*#GUK?L_o%DMT9wdf?>vRT;VB2nyNEy z9Y=M()EDvjJAA4l8T_CK6WGT1(jHLi#et2X(5R0tgwt1Oz%JjAjZh9s;5l!MbF`Ph zcL5t?uH$;}*)t7>l>)9x(8)*2(J#<7%#01Y0>N{)UvN`D(xwghkc*jPVf10?DGn{U zO#1uDQJ$Dra0;Me`z8pkSV=qM(ruSg-V9rYHSt>391|p+M2!|~v?h<7DT;>ZG z=N(e$XX3-L2$P=^$;*_ME(kR`05?s3%6weOX3kH0Lh?%8Zu7rO;8P}TX?GSmPJ4og zVs$MoB0qg2UKLj8);N=Tp)G4`qwiJj6`}r2!(`pvd=cXbI^l|j>Urz=Yuv7W%) zQ!RC7K-PO2$6w8VtNmP;)O=^#0i?TE7f3h$lY!tMglVXEM@NU+E3-$@1Z<>@mc_N} z?!5rl=iVJENQ?e<8^oWd&cswN25CmV28AddyPx~#r4UPRiF(H3c$#Ufa?7KxB!fzu z8XE4)p9@Dee|*k+@_ltSk?&*3Md7{HNyNQ`8i4b>hdef4&$XwA?(B!xQ@YdN()%vz z*kqKudmFjYOwvLcN>V~(7Di#wS4_Z;0300FG%AD(?WnjPbtFp}qVRCpyAsbUW$I%H zdEm>{PYN3vuc`f781QXD{hIfF8x3`q7S|2xsw!7{>f?Om;`Y(iN1q(0e|p}#e6;xi zMB@Q!X$ECA4g$DhP;pFT$XP5l1ojKE&8Xc&6wEE*YdDG7`|r)y;2OP?@2J~-;Mn5sMcylKjkBBpI7K>jd7kM0a6C@67}6)2i5WFN<*&*&u-v(r%X9oEne&PJsl?N^KI+i{9q&YSlw*_O-5{~ z!I5P@IC;%B;_B5U-a&uv-UZ9$wcF}~%*5FXOx5FQ+}%Y{!Q`pcz<)n@VetKJ=o+ju zK|Vf+=-G{`QnxoZf@~FCxj>iAlXC%BUs&6oVQmNm`FRd+&og*srg9g-KdZCe(_aGT z@+Fx~UCUAL9rBI{Ap_O261XFVo+5w^_LcR)ziVSzHXJ$j9XCM= zLBh_&f~$!ybsT2eiTxyymH8Y`=&_S=K|df%XzNf9)3WKkEgTw}r7CC85@g2kyZd>i zEn6xlyBr4q#o1hcK~2-ybWV?>4VB@1#+JGLg9kT4&K6HbHx^rU+=Q`1Vau6_^T1KN z*hoA`EK)^X!HG8%*gLr$Mm!0mOi_7&J30v&HBUIu1d8^vmGPdV9V0;myXAC}$Y zxC#NH?D_I#tm85Y%X>PL=P=`+y;qfd{GLv_aN2Ejf;Vun#wYozp+xyUxwTsi$#~IxA;VWc3fqXhA4N9g{#i1)v<(2 zS8uyQ#S4AapiiSf@@>$)BTJ3qj<0bggry~(guzSUZuKyE*mc0joPf;5``2pIvH&?T zDK13Hb{A62etJMPtAi4OAQi1n?{PsMl@TMu5uI>jPPY8Ht*2!s4dq5NkHx#^aK|L% zW0q$Rr4!$7qd190wp-_QM-eiD ztL=>gyju%D?;RZq;7+X6SeE}nW|3uC44>ia*9wSptG8RtTP|k3qTI_m$fTP7LASmz zQehhxG#eeZ9WWa1o`^X9R`GhZjHZO8l_jg@218r@+(3XBs!izT#xJ2Ewn5eX?{FF$Ab7C0a@<+^*gcS-Z*p>Ux}rkqut&;u zcB^SptVj#hx#?Z!H4#GNChod8WH{N%5F1c07dN``?fCU!D6gO}Wszns2ci6V3rDk5 zCEp^N0a6Q*uWaN22GPP*wjFp%i{uMK8>2g!3twY~CTPlMBtQ4LF0gn{=vweyT5n3X z`ZcVWVYVi;7HH;{Yx5e2#A0<;5&S!!Pl{yd7o=Pp+Zy+^$_b z#D3cJ&X2Y#zNDG(Ngs~&wzzCLf5Mti6=FW$gT<{ZmtRm0?{_}z-|RLC-I+DX@(mic z(x-H>zfKLPogNTyZ0>))dm=LT6WQR+2V_>-h=VP+o}Ch!@*9yY2GKEUftyE9S!zAM zIh)z-&SpQ;v9^ux8oDM1_5kHJ=~ymMXHykqGqpvL)n{#@#2PBa&c{DC`i3y&*$*ot zQ%1tfE^a9Y=1{3zhZJfTZ{K4i+53{iv>2=Xrvf$=5+&-sx!PI+F*%vpT^ijed@KeyOL^_(mzqkFkmo_2f34p$_Qa(-5m)%n%zVzeYv!&g&tk)DO~DyIE%N zPss@Auv?q;?P$0c4|L=#GCu&k9X#V)Yh$DT$=MkqTHqtR}TI+<+GS#o3s!gxgB`9!4Cjw;` zkB^BIHv-#@(1d#-w@-%+U4T$h)yC^hBRn$wawGk`8a4L@ozcz0Am>M&(8?NUPhb+T zBw#Z4##}ID4P~AcLV#p832>Zfb~T?5BG|5{IcQO?t9<8-?iwFoM9^nqwb-waT$KCC zI(>JP(&jsD0|af98YlBW5Hj((YKurtX?gG4%3r;X_RZ0_V+3}(LsG;Pi20}BXiac9 zCtZQm*T>a8%Yv5KZ;4o$KPQGR;dhxQdNU<)^?mbZ7q&8BU9a-kROQP;36YJutv@(u zPtSU5=2piJo-XEGE_o?Py+@Q6gQ^pM2`}|vH-H4}ok{)5(3EMSAkmjpq3?!38>uSc5D`2&rr4YAX>1fdoD90y;}z= z{*p|3Drt*n^jICVXE`!U5|=3GO&JJ~11Wu+5ZEG7wnyZU<`qcp3o`|RVx(xszU)I@ ze@SAG<4TRGp#7e!v`5f0iWbL(?p?>7DN|S~@Z@h=$nzH)-T}%{o$-LX_&gZqXzToD zy~rU2ThQ`xvd2|F96_2}-)(X}T)=|b=izg}ONSLH2H6UqK`K})4@>hfiXC0xF42HT z6w_};ajI*ST~JZK44FR?Xcf&XECf_&KCoUxPi3ctP4HsXeq7~9Zl`3WTRE26T-JK01}PFAR6AV2L6}TGuYK zBNU_0UbPd7_Hkx;&J3TSu3-9z0-?+aF(}q}MUkpLH+hh-JF#tTUb5fXF~~9(*O6z_ zv?^4!J`MAqoIq)DlfCJ>0xmMhhEpnnLw9V~n9^=kdW7idv-7pNF!!BRfpF zxuBwyw*<)J(MiL}IJY@9tK(Ih)$RdLIg4cG7PbNuG;G8mMyoOlDY27LS41y8_Q z3(Uq5=)KK;0VR*4Dz>Z)J5EU5xB!E9RAZ`?ADrnJiPk1)js#ge1~T5EG+$oR-TQvb zCTvbL@-3`(Mm+QBVbVToufSLco%!^eG@Rqk&^I$VPaCVnWM5`Rd?^zH9EU7SLbIPx zHW9Jj6oZm#LifLn-&T5pi|8Y-JzIEXpi_#y^~;izGyl;lDb3;rxAVjIcz4|oSM&Im z^lb3ZLZTo#ZGG!U;#)Z(-K-wSGWJ{!uu%<9*G3;;K?;m!FCk6lI)n!5CkdyV=~HoI z$op|w|@k3=#j~leVxJ0}#z#eDMrQeK$X=)5s_?R3a;JC1S*Su!U>1fu%FhG7I;Grco|IW>?hi4_!l@0%<(G6T*wOr6z(S_@A4c z1440z013F2Jujzo&TJ#Pz`mSVZ0BId(B5GovWOW@$$6+H3aB` zAex2Nbt+~5m8d0S6tByI<^{P>0CNo4Uek}PMYk9fkaj3I*Z2pNgFDuHXsX>qpsy3>S$U_-M2{L%cD`nvqfmPbL%a5wEe$UZm7sP@dGOa zeW8ObYVBZ;YwlA_0AMxBBM$XFM0jC1D<7plmr&iy$%?(a+o1) za}#^EIJHbep_SpUkR`Kkd$ILbX)NTlVof^X!qNtO^eDoAGtnGEkZ zM2sEB@3>DqUX55f4;}YY5Y_+?9)p6rhy>@Va+v{R0_L$ITKZ%L8?kO#8Hzjh z#_-i-!e%~v1V19Hs}XnXJz5)~(G;nP@&y}Ujev^PNv*~T4|tfzjK?}^xfr|CAC*0K zvI0t_C+AhOvbb;%YD#bLI%6UiTk$$Cj~rNUVT}0@FIItfn^FPEoPa{FU?FwBgQ;j1 zbb&S^*D3&gu-U`$@4VCs3uHqTrl*sbl!XGY6e7)FPX`CKFgi zOWRXVU}8K58+5N}y5M03;PNjTGw~FBTtjX|U*>Ubq$#S30MA?5oAY%b> z`)QL^OTWSbI4`2T6}%c@KbKA)XAe{oP`VvD-faoAv~n>dP;0dT0rJrh&|P&BXc^D3 zQ(}&hMi%Z}b0uoV0~itJ@^eeA46St@&QmgijuYz5tXXwg-zs_Y9qynUnvM!_*o$P~ z?UCjmfn3+rtuT>^ot_w@V!C1g9H(@lTO{y*iTwOh-!AiNI%pK0*$xet{S4DOKyj0| zIQ|;goe>+|78HtclqEpIG^cynn)p@m$^w9>;0RdI`?`B>AaSR*ZJ5-?;>1k(tFc z(Hsp~Qva;7p?BGS(zWW-CPd~S#7DK>6nHAnI~kKH{f5QPXH9zua!QrcjSn4G#;K|Ic9!kd{3ithB#dSt(Ffg%oY3)W`O)xdIp;3meE_fN z13xE=vvDEs%wtni(_&P|&l})QqoPa{r0(0g47hhqPn8Oa7maLr>#^A`1>SHm#=PIi zdtG|aLk*a--j4k^Mg=U(%-8adVeRFc&?ffXy04Mr$CEsAL|N^QWJMR;_X$y$7AD}p z+GD(>A_-t_XBVsqF|zk-NGA^tbU4XFN!?tXOD+-D;t!!Vr}C`ovt6%m&g1PdS&i&i zmLK?1t-j7K7Tik@4Oh2m>*`vqcMzr`q7)&`^GmlHsr*ztiCl6#&fFhb`|@K~A7kv< zq2KX=qwB9MU9*xt;CN8Rk_9@9+@W@$9Ht@`$A>7E;K|aakxSTYdui-{@;^SJ>Z>z-H5hryLm#9cGu8UF7B%$x*etp*4j08m__d8V+&!As5~i*?5R#be zHnpObtgoYgc%mT+l=yke6ph)TXcM{qS>WUg$!UPYr_DAq4S!B}AMf@}Hgc>J6R-Nk zm9QO+rORvD@~%bI8-V}H&aNFOnI7KS=$~6(-9B1$E6J4SK8h;~to1$)%C>i=VCzhV zWdM4MUmeIbgDo^ORg$=qJ6gqYv~Uy>gF46JJpHun#M&991M}#x&qLkd4l0|sfC>?r%jY8T6Q|C+w>~EU1DP!U1bXcD}8BF!2<|<79^k6+N@PFxHt-KO?O;rYbXVc5Dq}v9_yHESBR_Fo>fI=H3|Q`o?V2SA7A_)tz~~$lf@)$N>Oji|gk#k-EieIEWqj@$ zLd34^nQYZ8yY7TBI#_LtZ2?{&^&`Y=+E(m3Q@GPYG;;d@OaY=u`7lI-H=7(79O*tRp8b@RcfPkUa@tEvmcGojt1lRf(9$fB= zuX!G3e%*EYRwG$KAn^GK%GoiaOKsK|fFn4vDZCz%?bBff@E?#2=#nb4;p69#lvHm$ zj@}JTw5zZWddM!p1W7}$A>UYAAA}h*>KY0cFk@b>RcRf}@zk^(N4ZQekMg^8m=FdL z)x)abc1A{R+tI4fDiAVO?eH&llSl7%v?`B(?zkLpp>{fNw5e~Din-uTlF$^h|439k zXr>vZB8n6A=rGZ8F>*La*rp0-vNvziZ343rB`pJLZ>Kw`ivOs!s#JhlkbVDsTh;bY zpB+yJ4I16*O(X88)d3gz8aDTzN4!?%tDj9OkHZdER~@uy;woL3+&4!>$ncp><~5aB z!Y3F|ws+ijdX#G|JjUPch*TXcDj902myYgKMom0%pz@P<-TL%VLsertQmW+A@yL8u zAdO4)tDVu~iQJvhqY1U#UX^14iiPYtP`Ni3#<8}GHlI#3)L6n{an~s@n-?Bm&-@3AxFl#y z2E}8cJerOi_xhDGGBV1iY(N`p&~oR-#CMEE5M`(zUwsEmLDok#P0%>r;V!j+n{aG| zM(ONcsP!!XHT)~8Nxi-RI=OVr1MJKgO500L>=vrn%$6-8+V2a3szE@_#_Vlo@^V)M zzl4h4S)Q{VwG_%4tPnaHt8&vH-UYU4IX41?R(4f1OazZ--1V$^&C9F}yP2lnzTN2x zs^G3X+8HRe_@(Z;zcK8$^!!%%#2D%u5W0&+8YMRXZm8>{smfXE-uUjfG@`{^zd2cL zH92KOIU;hgK8bV!4({#;w$uO(Yqu@XuIw|vMNnS|K3~q}o;aGE(OIGu^RC7!fQ1-D zR!Tg39A~FYGcvd@9`1hG1beM+OSY!CFpMHqUP4hHuT_-@Rjy9ut+pf^PK-a9(bX>? zp6>Ll(vo11nCNA8c;Hb0N_XOR8~bWvf5F_>Lp+ywWCClNK*Z+# zs0`R5h}23?=ce!>Nw!Z}tSk4DvoSxMPyhjq$)v*stLmwS^}bLL=AP+TbzJ0fnGg}# zlM%FZ<&Jf?7p7%B|CAaSVL1K+RwVJD#>1^XbhR~Mf1Db2WovbrpOVIX`m$ADNLyV+eQWK)gkRfr2lHjW8zDDV*T8){l0r*D_N+^M z+-O7~&CDiDL{3BXmV(}Eax2}w4oG|D7T6MxU+RL+zYfH)(nCN-0c0$0&`zZ0t*_QZ z?Am3!EV&v0_YIJ=n!#|gyTmWf#o(o}!S%|6*@)&os+6ZXDVlzu{DpZ^L!y2X2sOnv zO`Ow_M_&Wdb9+9l$)RSt4A4zveQSO~tVn~}LD*_s-O^zE`#u-9dJqM@_vEzllB@8A zeK@u?=tJ{V}*7njTXGWdee$M~=b_Ss96I6`lzIn(~7k9kN!CofE=wOt> zhT2Gq>UA4YsJKE?Z09ktU%|7=+_}3k@?urvE?2(P=`!(K8V|{{ z+V0|r$S$+l_k8va^tpud80Hl^>)Yv7sy+gQOM&30)fEoiA$!}ES?ZayP?xido%@pd z2)C3c%_O#JhXO%rV-WbNXs!dCC!1YiyuDQnes)l5+@s4Khc~Qjj~jlH)_I0a3J}^J zmozF@+0lnXE5P|7J(xLi+zyyrU83OesA3%|VS#@tXY@m&G+i8Zil;d`hq4E+7HJji zMyNcfp~xDcuqd{-knV$n0<{Xa!a20^qOH;jFDaG+Fz{?^bQKHWm__$*mTHt#b3I&)Z5$}F@Fw#FN9bsoEHcv9r?-%ugZDN2+H~xgb5+Og9a_oH4c}-JHz&- z&g@;Ak?(F}EVv5L2&|ohEMU|EP(b3E^T%;>qAzF^lJXve`l44Oom$ndPGdsxeXx@i z95G^c1~MFhhGmAK=()w+Kn*9*$f{imwyUDsSFff_cLsL_awx)6ndxTY!$xpub`}Gy zb7Daa*2p7WK235w$3u{CLjvzxJ<;e28cc=L50uo@;q{T=QHb=(Ekhc-6eCG6%WY&u`wX@#}D74XS}U&gk=ttI)_^N)y9j+ z5nJSl?3&TTfe5h_7#<@~xy;_)R|_XGe89h;w$u-Kar!@;g@63rj-;)8ZKRnoe;MxB z!y5yegkRR#m9hnGQWhM`WS?hOBR^q3q{9eV3i4+SBE7h=at4)k>)$|qHsC}Y4Fv2zC~B|mCkPykB})y z#BihsOE&n9owGiBphpGu7Q@dWAAS`UF|Ho~I}9Q5dzc35F_<(suRZl$8ej$td>w{> zN%p4mew5U=cWJxUnc0i-BO6uE;v;YnHeb*#3Bo?DkBPlotHo3Z;{_NdegsHh>;KZ6 z36N*S*_di&Zg0SQ?RokKos_D`0XPK(Z6w{MG5Dw-1+%RvbK3O6 zBm|-gr<6B$ponDsdJbZsJC2Hr8Tv{QJe->;uL9y-5JGmubs(_0*LgrcAtDn8{HER4 zm~Mafqf{>eQrin~awnQ)Y@Qbys5j@%)ynifQh_M-KXncRf{gUZhM54*0BSGO^k|8d z=`C@0<=rCe<9H6^^7yAcl!MM?sZgArX?CwOU^70S8%szweVVE~WEkNdW)r6+_7V8jSuyX*7`)25BAVnR=Fzm;P znxN@4!b#I3t_A{9N-z^Q3@?4+#zq)kN$8OLh|-Yg#C>rYxw{ty4o`kh^fMckCxo&- zM455}Q3A1Mih*Z-BD+3)bwtDNPM`Z00mQ000zUh)N8fm~JuCz{xq{>f=8NF33S>QU zz{NqJ@?3J*wq0QC);w&zP*Rg))p^E>(C}wDGM#8CFwSxE+s>kh2WQXxe){wdgNUQF z>HK;Enk<>{`?PjZ39FM9f)};{KJu1}4od7Pu*)7PsbC9~@vi}RRdOjRRP!#;3M313n=g{uW+8_9L5+>$aI&HCHtvG>LlTdpvmY#GEq(Qcd4fA zvgx&s9f?sFPJsBLCzrrz(5(KxgQ?%4Kw+(b`Rs-q{44HoX)Mb+j4{FW8iNvW2RcKh zXFju42~hM!0~3;{NX@q(bfVcw{%Bi;RjYH+=w6As?{eAVSI7DB+#S$K-e*6#wRSb4 z)-F3UOd13g(GCD}_TXjx%PsIL;LDV_htexz?O%ZcfJUHj6An43FWZkrGJSbvy$J$jh)+u+DYK5!rUpBZkax%0Mo(bbszvzy^7x^$Vta zlM1;nfyzO}ok`=Nzy zScRi6#<#|GuQbpvpoCTL)MtR5Mt4_O*cH;Joa0D1{K7Z(l1{V_{6M_)Qzl^DIm{u# zzm~3quh@a{Xfvpi2?*wteNgJ0G(N<05f@SY3dCeiE`&-ow&~zI;DLTB3|OrZY&8 ze0P7~{MNbgcVNp%k;>rQ(rvreJ4R{@7eM^JN|k_e49&p%(hR@F7$)(hA2ki4pXZa4 z*m5z7BW`1;zyEvtxzCYSP_d~nkjisnFpRk$K`BcO$&pXEefq*?SN_lB6Qj*;UYnf$ z{9&>t^f~MA3KGckuCS`S?cwm6YP6b)tXtKW4sBSwpIoAkyP06iAFm99Jq1P*V4ZHz z0?tz$&3>1IS-jv1>v{CW_*SY8OZIs-gFKv7JGng-6WKL~g*>}nHU5tX_yPtRfw9Zy zOn_aOPFAQF1&B?7h#`lu8~UmZw$rt!Yr3Tl6r1!l*w%jX59%hV`q{ss^J|~Z46>*F zXK`RtZ(f@hwThMUg4G2`C%|+AE``{p@#j8uDJ)CH69@y3jrg4M>}!l6lfEEL=q507 zIiWBQDDZ|PVEJT;2!{wm!;&f(3%q~D7R))IVx${pBeWNT_#Poi2E|5d%D82}+12`o zV%mCC{Vn{*Q8W3WkN*;xgB>QakBwh$X|JSRb`1fNFaWk~@P+s|ypI+KS4YbRi^-nqQ2`HyCWqgjm0#Hnv3m17KEmGgR?$1-A_mu9Q zhoS<2)1m`f;zIGk^bbRD5kqiD|M#VE={YwPZX-$Ba0v*sGkWhkYi41YG3dlWgwP{| zrZ4`v88kPhE0YwhHN6Bl#1}U8o*y_NL7}RPpf=5Cxyy)N8WNa1l}BINF5EFnuY?n! z|2?#%(5gvN5-CX)y*7rWo}(t=pTR93F+Imc5J&*g{eGbC8rFe(@==PyFb9#_3RIN@yyp%WBFB}H=0EaHrh4L;HEU>((u=?T$P7o96 zr1%q{4Kx&t4+aH06IaG2Ie;KifO*GUJrzcr$C-LO?MjWGsJ@k-I&a#tpeRLNmVpT3 ziGpvJJiWa(Sl_762qv%}n!sG_@9#i@d1L`^LMweJ5Fr|;1PhKb_QDubCr8*s7hhBX zyNh-!6;wcu_CX)p36N>(V=y}oIFtOBCA5`(42Wa?;A?((6`10abR%PiPlp}>l9(8T z3sft)Wsi8gz0vR=O~x;Z>0klfW_gb_3IS-5l!0~S_edFHAjEPPAh~kq2aUO~e}KLe zE`*+cQuaIx2ZGemmhl|3EY=D@sA1V=Nhy$h-9MU#tNK-vb)zM`Sf7){3M){c>fa1(xK&HXtOm204^{>Wz1iF2S}J~7!FElGZRfHZe2tM`v0?l zFn9rv1Ft3E|IzVAAqkC`fanZ{VXCF9;utyqSpGX+zk2TfLqjuKacHN1+@O~k z4gyvoc7RHzXt6VTNsdq>f|89OxdT9qlM8WhFako+J!^@w+!d>XLaU`>WgLSYT91pt z|DTvFBNyELglCWJ&j@mb7-Ctj_5FDknws`%e76%(q!qQdx$iZyZ^oPgqx($ zmX|qPI@jV$>?{}XLs>NXB;P@-4nx;Z^>+I@T%H?TleSFfrYtUW-rid-(~?x`w`f2(O@7>e&?J#`Yle6#>Mx9T!c*>e^kg8IpstHUI) zZK?}WfB%=?jGk+9C_g;)Dr`MLpzuMTyzIu#MTo8RzJ_nN2~c4)YV~($_iIxeO-?KBRya^M6?eZu#%VInohKB zpS&_=z#)s3Q~&VPpU6-9k_MYzw54N~0SZ>)fs8Dh>CP@E0kZY;>1h1&5kT9XXppSn zd<iBOw}Qi4bj2D~5y?rUJO{2E?-@YZ%&7s$ zmjfkfzwt)jM>1J*2=xWP2Unt4ayV-A=bD1cdJ$P5;|)|=YD54Q63DIeMdY9VhccU9 zPW`xfsw=bDBY+(_G1a7pt{hHBeVgf##s;J*mf=uIY?%N>>vB%zDVx)^Cb9FwDM$lfx@28n$lY=3*F5V;v(U+#}pGlB!6F-%+s89`eCPrzmG9g z%0~^s1B(BWB%$zsXbB!T;retLgR797mB(K_far}VIb9CZH%%c;O|zN^kn|CO_0&I0Yv<=s280ZRO_>JWO9(L5PV@It8hIc?YyAMD zo?gFsCbaPq##ri{9}eOPC)9NOmy>U2cY3}z*9I^z8azCLaE)bvWJ9PBL9AlLJ z%P#*cQLi5wZvPAIg44?%W}z+AJesIXpt|1PY*~6Ea*|^n5AkHmBVpk$Rs!QRz_p%` z2E$8y*k0R-#DWiBs%Ai2@!!|RwHxsI(7;c_5KIX$-kcvNlw9o4sLlE3F46kGG46Id zAh2<<8onSJ67E_a@foA|HpVF{wBIH9OE1H_+AzVUnmeV1!)TA^@0@xN@XX*EGk9iL zmJe!j=RCt*Z_9!Ts8iJ?Ixof7qWm*?0T_6WbBZz06LPB`3DD+^4cg3+*oH52O z;UHnDL|@3`Hq;^B^QWk7tm9!D3b z?sKqh9V8pgFm`+SGCqVYQ($kD z4JObvUX>c)%i5UJgp8=;L4W0T5w7-Ti=7w_-xpWHl!Dxu?lNaG}0%3Hb z{~v9gir%{pLLo<6+kn<>)iP}pj|Z2cq1(qmK2NSYrp{R){6~gn8`aEbO+q+3$Mg^> z8OFlhf7PNS8UqCO34Ahwijml3!GC=eGFCAlx4(zbw2)WM+N3Dls&8*s_;eN-@s~Xj z#L6MJf$unhp0Hzu&@R{r>S59-hlM~l984tZKiigl1wAcLdM%(V z99maT!B4PXAwUqn_oiP6@2A!uR%c z8~zcLFXuJEhUviTPkDpZjux{+m-nr45hmlbr__$8nuSr#uiv-Dx?+qe7ZKGU$585V ztKuJiZyW^e8kPOgM=5V^@nHe~j$(h$CX@8<)-*gCh1s7L4k*!0#elr!s^Vyt`aH*3 zK-ZHCQK-<>29!`O%qt3KLtFsA{;XvYu*r1LI5nTaL6xU;kou_j0&^uS#>G052c13p zGZN!#Sha@Uu^PU|UK-0A&-|Cmf~8qH#&FgF3Qs{h>P*+0jM-n_SMKB(CjD29>!Wq% zU7+FQNrOA*CB_SaRnYDTvBow8Pp;RiO z%rlj#WXe?LkeNI4%)6hrxwW?MdAIM6_uIDj`(1ymEbjZf&f%Dk{Wwk++i_y9dfG61 zR9kI*+5Vi7ioQK2x3!ph;UsB0ekJATk7i81f3X68{&&0ampV`i7l z=@4bamiUOWKat!Wkj)pTb0TO!8HFYzPsq#(#PUt#smPDg$#gxu6UQ+0zNj%3hA-Pp zr61;t_Rh6WsK%ycqXVvdbn2~(R@vGjsNbUbFz39F9V29wJkcB(&P*JvYpOdK7OsDH zY}{0-qA@A?qW$oGL53a9<3yx2hd=x5=q}*P2UsZMiKGz;VIuqW)%`8h${QXcCdu0} zcQU&R=-$yS3fpUKZGD$ba7(fy2S*MrXsvV**|N{Rb<=$BJDf7LcTRDi)q2%o{x3&a zC+NNK=FOWGA7*mgT_^35h^sSCE%!)=3q;2Pu;3z0$EPzs2lA;WCvNb4vhdOA%Lh(d z_53nu{mk`9LDw7rw1Kj#_@BzxzMgluyezin2dZ-5&R^TOxVYMe20KynPDy!rc``Z9 zBcANXeGl6^9}yEeEcEL^clk{5rBW+QtM(6ZQ!zf-9h)84%N9eMhFj3w*v6Ie*da?u zv9Yt?4Yca;Yw5Bc>UytN5_QH}udBJ_{e`?Y3ZWNH7UPn0KJ(7Th{4{5%D?Aq*{{%) zTKMkFp3SOpJ6Blz{-6+NVH)%M;~W|Bwq!Paa%uMhvVpkCH4*jdt1HqGZ(6qPY-x-s zxf=A0ns?Ko<^urupB^VD(80RYeNhOS%LSZX=Idd6s=tL}$ROZ1O{6E=(P|Nk%GERd zo%%z@xC#2{-o*|vp*jW0ssnkdNqwbVagVoZ9JJ`KJ^Ai3gO9Vg691k)r^1%YbHA|)Xl3*12;NdmC|NhW z#HEqlX6MW2v#DslF;2%S4Sxv!Ovpo_va@sJT<)P-_}bO5=~B6V13}go z$T`P%+r?{{?uc>)87AS%Z{|nJ#)=nGF{>R%i4?i)jcI7jw&s{2FeDPvQ6n}nz zGMnSh*8Rn%H6AUvnVr8_Q%!AU^;cJBKlwn1x*Xr|TG}(wj?T_xLh32(hKCM$2=n7A zY8FM8ByzR6yP&=UA(k%>H>s`DRG&nOs zrjP2j+P`>We(&xdqzzf+82NfxnQcB5vi`70Q%Ja|NdNComHxpQcY-s7Hw8pDM=8Wy zH8^eF6iV({ZZwJKRtifjjx-;cm}y^HTKdwf zjz)7dr^O2DMb*6|43X18R^}HFwK1;EgBJ4aoXzPV$pa-P`lgJY2mb93k_^tKPBj$j z1logZZ|dOUT$W98{#R3e)0FZqggzEA(d)0`61OeuwlC9)FwT2(^8KZsA5V9L`3&DB zYhck8U1l%iE|3%+*YUO+7uSpV|JIizd{1OW%Xf80av{3<$N$Wd5f8rFQh~*_TyvRs zPf1joId}1R3@LR(cKHoAhY?kvWiI__i#;wHj{fPE#uL9YuEkzI@iCwJ}l<{I%KQ$l~-qHNx-o3p2tOG1;3JSSX6DMd?%Nwi&dXXkfy#)4wwB3*;jRkzr) zgb2-8)F1b{5OF^H*aWb^Ho$`o3c zsj8}~MVous#m|ZxWS;Eci|Y&xOnR{4_(36kFs(t|i$?;dgU=@2xe6&E{d(rg)z3UH zPI)&jzOlBIK>K*>c64+kFV~nS#XZI)Z{!ce`27A1QA~kAGe(vvS za}O}BeR}KQt7+vjiqEKtK`60N^TJ!#k`UarYu5(E#Oq)AR6MiWa-q)Et2>d4RZKPV zvc}H7#$ayI;Mt`^gIy^`Uog@k0YHo{H14%^AWC{x@|X{34y+Fx*aE82c-VcZ_OMQ_4qt z4J~xuzTT3xhl&5R;pcUa)(S=ch-2FMTf)guq~!SlXI3#)s&Q!$Z%yWF&gZt5wsY@h)Lz;YEHo-KN4-3*~H31b>t5`q$G2L zx9?J(5C*e27OL#J8Kx+4cy+bGuZ&(^R=srwS-WPg6Y9IWE#tOXY+PB5eoV{0{&rt+ znajppMUjS@pK6qqmDin|GXMU%*%OU?9N~jq)KV>J2ot^Ten?IkV`CE&lP6azY#9su z6@xi{^mx=Kv8Z0`?#CRtv9#M}&%6UB1Q5k~1BP7}Z*I}S?n*|lcqlAsvq7j^RxuXJ zD*F7>CKxRN&ks_o>uouyg5q(N8#29Q#Nf|zfpt;#yC-mE_K$uES53D!OzQ6ws-o3`f!4(XsCB)8iIBX{rwLDyA=fx|z0BKRm&h;C^hn zQOTY$`xcWU7HnY#WHy@^kGfOir3@{(n&=PET9x{P)%vUfLXGb}RX~eue!bd8FfUk= zL5+EWIzEtR^a9l-^pHYf29#Xs?;gk+rs5_DpVNiMS z&0pm*pE;@MaoWc;4)R`jK8L#M2TirzLS-Ly6#_ClFK_X{z(AjJn;sKoJE`1oCS0BArFv{{(f}mD9%7F42xW@(HHr*c;J)?u7Co(1H91zsP^o2JecKGwRA^<7 z&XuJH#@1W2QNnk+7%A_$r9yDZWAp)cGcBX`>*$n8I9YmG)z>|Kr=jc=`!p{`Up8@Y zu$cPY3~XYE$G)dUsQ+gYi+CWM?6AD(oy&P6xgVgIWd)}VWgsStFH1vvJd(}6W(rYO zS?BAu;(c3JQxQv1xIV}GHf{02L+lYA(QA&y)X$qYFS)ZRS}Bf)dXU~XgOZ&=V@JfL zRB(7gA<5;Xn^y<9(2B~+IEuoVLM>F+J9ja%{s`wumtd!ar5ehfG0e+qF0sFU(r4ep zwvy@T8QOB1Cv{JmT3RyZz!vi+}Uv|o?}K->w!GDlGI7APgKZq zhVsr(6Iv=3`5v@>e~Wse{jzN@f3^ipNq|YO-5sOoakAB3 z-(n3hk6tze#C8^T=lY7B+`acLzd=Rfj+R7bXRo%#;LPNNgoGk1PYuPp9O7a)>rOZa*h9k_0~u9*84eo8Gbv!m6UTtd?3urak+>< zhEUBDLh3F&sw+Tf)Oz}Cy}nw8jW0*Pnf-+5 z$UJRA;yR1J+%8ZOUt9Ow`S2aX!>-?2Emuvau`OD~KF=obZ>lf@9Lp+Z?K@QIygS&? zEl+VeQAHMw>Kt~l=3N4(yOiQPlnnZs!lmBIZF;@cCb?eGtxU=a-4jNhs^fDkiS$H- zILmmRNaMSknQ4DfwBpEM?b=X950B<-DGqx_i>ftzyu4YLN+N4K+3Z+&9FF?TeK@mF zO7y6#{CKz-Lz3tP#u4xTeKWJKx7VqF_sKT5ydR(C0#%lC4F0~Q4*q8>h#eZBIl}Z4 znI~N9?X+>~QqRqK)6~i&$0J74Z$8Z7XI_qY#12>&O))j1H0^GSoR>16b-qU!sORvX zWTeD9a*rE)n9h=z|5k}Dz+K4jeE;uT;&^|_2p-Mh5@2q}EXPI9d?-=Zcz7ey)h^}ImW;y)CFZjl4 zHQ44QXkqo0FJ-N$^;)_e3G&$P@y?>ZB_$jXpXE&w&RKWeyJoxJBRM;e|F}2ge@@Wn0988 z<#2&D5F%nec9h%W%C`fIUV+Nd0(Ctwr=jo^Ej`X*gXzPyWr~+wQr6ekC%*Md8F#s3 z8q`eAv}4n3CPZJxqe+F|5Fdbn>Bg_) zr!Vc=iGyb>SZ-GPv?XCGQ=)lUUnz)4%iiqoqLQ!n;}NSZVDaLTf3ty%1?z9XKkxD1&Ew(59 z%mWcAdUA&ZB zU=~NTf0M3+ZK53!;ODo=WwYW!O%EeEGMc5B0^9Xn^#axhw5Ae{c_A zNElYD}!S;=ulbrv)$MzM}iVSF-o6J2~UtVbKpwdexI6ZR@XLhr@z4+iePr z3Hs@#q!+o)xViX;Q`=yh_|P_&Ey{(L(rE*ww9qR5t&EI}Nhjr%7b7Y%RCq}_R>e`@ zvO$S>Fhm-hQq1pt7tqZ!x&(=Fll85#VLCrCo}0RQq!FFG^ z0K~G6SH!esh?EC^>EyC*5en2*ax!HzTshR|IMnU*$~(Niw7mNEw&3cPFXMS zQl1}C%{dlF$Aaj`&`AP(@Ef%v&VRbeNDodSP-56LK;}%wT*}T~Omo|uRQ7 zuoF=e7?fv^mrAZ2!=+@pQUeI)LHu-DnTZ!csr2ZP1?f*UTc8Kr2<4R-!E7-o(hX1gcwTcd`2 z#)e|z2Y+&VUUb+Ky5h`RrQq{2{n;D?M=LH^iceglNvy&jG(?DQM>lYFRs}!Y~9&s9ASTA*FQoLbA)-2a94AFjn z`PY|-o@#gX{_Ym;A8j}%dyf9{nFb(f5;T(ToTgRG_F}q`$epKr?R;H(x zxQ}P)*_7vIE^1TW(Z*8@co&J>A`PW6D^6hRu9xF>!nb2GRKPNB{B1Y~b>IMeIG(Zi z#rQY#oDWeGu#u@gOSF3fu8izGwAwMeb48m#fjr}r+mx_~;as#+{VY9u<$p<~IUO1gA1*bG8VPog5tF8=367`1ba#uhi~>B? zCuHo-~r9Q~eCNWg>`-HM6(xpxvIqH|(W^?)MGyMN6b zVOOAh$7Yy!a?CtKBK5&}w0RC6voc>Hm^PY=CZroN0nvdG9!St>`VH6BoQaWZuDs%j zdDjinm!fqhF$wW*K@YDzL&f~v$90O$!EGkk*kOE-Q$48m*0{TFW9&U@BH-M&PU5fR zO_=2F;ko$kZ-}}zM(UX4s0avMGzl)zx91*D&_s;fc&s){*~u=wu!f5Z;sW z=&wD?jRhx(>1jq|Tk_g-?c0V)mexpW`O8FkV-PBNon=%vl1+x@4W0IMl4Bb_ytZS9 z8u-V-1S>fVacU#m|60y3bmu#zITNH+lLS4-Mu*`9)pH-781kE#%hu4~K8$edpHWH5 zJLr@+gTlD0y3+BAt~@=CDnMrjztRf#$|W_nW0D1DQF@<_Zg?1KhATD3^;+r+7d;{p zPLS4K)Wehd29xE$O8Jp^Hzlj6=%;^GdFj|}s-88CVH&Ust0G-f?@2mkIsIrAJC@8e z#szhw^lM&pmG<)U)dNHa~3Zuy`cf);K{AX)%oj zEg%gx=>R36pE>$UDl(N0>!XWtxdyIDJ38DVKm+@7soHP-_%ulbcbul_3w$^sr6xt! zDRf|#MxK&|;l**OBw?PFF$#;ru2tW}tm%)?=?`vnMSwt8Oi{yTrH$LLn5FmPSqNjl@_)ufHH;tH46ZzLdCoa70F3@0 zz7vKov6u-CFBXPreOoC!>s%>fH)-VEnP+3Uka6^nva?HvRaOFsPfqCr$M5rE@i0sq$QW`3{=6pEJxmT-;2F({+JWyz5PGKl8C(S!lo-zE}a=K%Uvq4 zH3w(wy@kFfesbmVJA22!iWh1vqR%8xt~@7Tf}XrCU(SAO$U=3`aF~ruHcw71)cr;8 zqOlj_+vQ$=(U0QPwd{a#J5TL*j2Yx+#{y!GDc(3tZD~9_ynOt3?!%|^=z^0>cjM(L zm)<5k9^*;1i23z^*9e~jR@YW=fMD@J5 zQ?2>qWZRF$3_ohW=fX9x=^Z6X4)%hbLSs{WaMK?&_r@7PK#Un$Ay$!YaeB7SUOpz)bg_eSJE zH=|?kxa0Ccx}*6aodAW0MM2fHa{mdOfN!pJ9Hv|SOU7^ zN_46pRM1;1(kGRWReJ{la(G~)s>k;YDxUM*DAvhnUo$6?X?Wfgm2hcwE?P1SFF0gf z+u^0Hq7JOvRxf#Cc9Fq%jCAqwrH{!(4k~r>Y&+XLYma-WdEU?tZcayzlUcT-qfs{< zPfWE5K4*e1xR>V>PStMG4ekCJA1jj4!{a=2z&yp_qMhGRjdn{}&0**W z`?vPkG&io@_8MnUzY1rdrjQ!6dC;giq+346V(b&AJOjw_`|*=kjXe_lb>J^=u_IZhl3?!uX@L z;p5p6?Kl3*wf8p=SAwqf$A0Vm;@lT}^pB%md;f;)DC3NMlydsl=wS6ea=N0Ei9`A`-O70~Y3=)0=MbxzZi9`_9jCK;GNag@ zn`$Go>JVF?q(v#7}>+{{0KY2!T&I z`Fvf2Ah+PRk0~;I^}xAR|Kuqfm(@_@fVC$~c#Q<>K?F5k*-aYsUtdmLI!~Y~bTu|% z0Lo?|QTgM~fphc&n!M{0(w}!LfPX?K@sG{gbFi_7t=;hf{)Gvow@=xTX9+^uJbCg9 z71tB;qPqbT2l#`pAfAbH_}|4dFWH8FNUfK{MH2}V-XOuc`+slS*0C}?sgJ`VmrSBL z4E4`B(nb4Z6%w-O4D1oQEjIpkrz}F&bSrr5mlDzoh=id#H)FqCX}j5(7|fHI1%Lhr zT|+t3Ibbqz{L3e28IrinWPbL3@t55{)Wzk`-7lePZ9Yt*=jho@8w3AElY{rH1YXkJ^0f`{t>sE;S*fNYIA1tPOd%br@^P$o4Be( z{j(z1qAT!!wU+PcV_k0JR2Xk5J_x@@3H141cMCF%~>S3aJT6Kl40vK9-1~~ z?1d5+Hf4&e6EjL1vMnwBFjU&*dF4uf+UJx-*6SfJggV${XT`?GwnUc=Y-x_|DvcN# z>{Cy3;m&q%oAn{}{u%(NGH&m+TS73^l_5EYb;`#LU`nm~ae={=%>xN{BYs&A^?6&B zJ!tW%5V5O~bkVRqj3fJXlC1saGhbgWl7A%`(aj3)RuXJHL80jNvn@dONpT2VTrQQw6W1O0 zSjhBrg)>4HLU27p{G~W7w-a~=uutvxXrVwpekZjVDlt3sB7WX{ETDUefy>{8QEqSbs+$XO5(%osxbmzbA?sfM~ySeI`?~Utk<7DPYkFh~zw<=_y)n zIgfqEd})`>w#ZDrx5){Ax#!lrq`fT4i$q05(@9sX@h9OOoTO790jy_N?f%FzBSsHp zFD<~trc7npIiHlVeDxF+;RG_Zsi}!i8@mfobtMWw9L0xvG7V}xOp<{Dzf42iE--02 z%W2+=Q@;Z~Dz?J9zvVo~BnhUb0Mmi{Cjoi{1Oyc8AbX#g2+UAL3C*g@rYkLIGr_JP z6V7!OP>IL_%tQ!?Ex}i9avuO&S}K3qV6T@B@}*k8ak>+pn@kM6vSy@4i9p4=+>-2A zQV3Fijg$j>ZYGs&m}GEXgY08g$+5g#ETHk_K{p^2E7t70TifM^rF4H_vXU*p`7bvq zUVv%P40V5fd1z3m?aSXSIbog@^$D)v`cOjK>W-o==IQo=rAwJP4=w#BMqr*i);(#F z1;rL^>F+f&Jy$j5%r_Iv+XIK|pl(xPXk-Hc002Jw?p`cG zjxH6qvWRa0ikqa;7X`_?z6Apai-`1{RsuKNT_GCvfooh2Va%l}pfqhGBO~-3?<*?S zAvG3@!peYDSjM7!icBWN+O`$J-*PSXQ_N|zyaDv37fiWW0#uO+PD+!(9&;qT%Ooaw$JM~*nfy8kTyaNQt#FH6$TPq)f~@=Hrs z5KQq;XO~I4ROB_{ z_ML91t-VdqTYpf11Q~*3s5_;&1E^Hdxs zSS>bAoB;*u*`WI)Xr0MGmGhCqQA5C;7#7SFR^3G49hH!?mR>qU9^IJ3BJc-GNJ2I) zEPSsng?hN5)YxhdnuX@KZF8>-0WPzyL_8F*_jPeN=FUg~zxjcC?j~_n6ey-EmqDWwq^IbfjqyM}RW?V{nhkXa`+MGB{1G(6Yb*;%w!&s;KX&l2 zrlw|dF9f2K*UzR#zAT}%S3urviEaNTR!~?}ROzCmcVLD5B&m4s$gk-SGRjb*Qrt0% znRBi9r=lO~-i9vO1@VI&-?1-VI;sQp@|Ep5NA&-gdADX$x)_xp4#0K62h|>F+8}Ga8MQwm!ePrPUHtg(aLjh6JCnoVH z7S>-hArc1$i_2zF-hX)l$G-3PR|e{NwJ8A`w-K;$4P$+FSs5Eem$|~G*}9UX7K`<= z1I(UkPYq1`07^pW*dcTCzSHq_FWp%?YfkNh*uA6aWf`X3$03G}wT(Y=LIyT)SaSg? zzf+&0?90))XY3WgU1zdY30ZVs3U;I;trDYERsSJspIKH%W%3b1pYSsOT zW8d5J^DQJ3t3Jb4MsZGDCJwnW;o4OF9@DpSb|~ZGD)VY3kbke^nL44T?k*Pzn*}}a zCK)H2^_M59qabJT+O!nCmfB)=iN?^FYzT8)<7|k7HOMF=xXRwW?w^K_L*!bobVKUb!!JZr8=GA0fDPuF6irZJTiM~)3z)j_qxs^eaD#`7Vk1c z3G6Bk>?-(&B#BXms<=X6w#6O$rX}=s(Hvp-{8Axb*C+^3CU7&W0#fZ%Hf@pwkv&Vk z$SLFYAi6X!?_vL3eND$}89z3Y64oom#+{L!wnr>hlXB8Onf?Quv=@dzYF7o&P*c#e zEKI*ltejtCt_=;QNCdE;eW%@l|0Wd~e+XQ)cZKejRQZrQEbsQtPJzCqGF=WPF>6eK zK~r@E1A~v(IC-3@$?zDKOW8hBTt)FK%)6THrME;rFYAEWCk*o`KVh=|m1SbKx%RED zwsz@nHv(aEl&TppP4^NP*Nbin``B6E*vS6djaa270}!xwa7q>% zt(~YKY`&0<+77rW0p-UxWQq@2e7o9ygGD7(*$V^{6nh-DKO1XY4a&!!L=O^!YO)8L zb?a0x6P5J{)$ZF&27n?z7&S!Kc!L2ZvFJcB@om&xRUGJp8MAG?U`?Jg2PRS!2jgjO zKglN~9jKwV2;w_c*&68Sv)Jncou%+bn$4u7qz-wBiGBv1PI%z{AFNAcK62M}n`UQp zDO4jd;hkbW9!96@Y1_DTp$dWCm6>2^AD&hbM!BiDM0L<8#DbaNmw$rzv zrxS)lBl(q(W~VrMvu>U3ZLb>$fKX0xv}*U+-E}(JShu+s=4=Zoh<<85Nr)v_6FbRI z&M%2Tjf-JuDKdkRc+SO(_y1&ij{=9sNw(0R!+il@!@~(+2|^HK!qX0y`9a}}M=Gp7 z`|RsY1|X$vVc|#bDfNZ)29Wu_dHOQVCksfK$E}#j-$f(HsV@Xj*V_$1r@MJNvF2bJ z?5rn` z(-$n;Wng?2BfFUpg?z6V)H?^IQ6|lVJuAmsjQ~OJ~itog#rzeWE2? z6IM;7J5EoxD%*(})>sxlbdNtNDTxnfvwq{o3t1(T zM!7d@PJ%@6CGc$u_V~U+8w$BnND&)pxd6fveBYTTuWAork^(d3EUh%wHk2sCxg26K zA4DfvCK8;denm6b^se8q!4{I2_vXCitkAYX=Sl_#`YKh2I#eq&L}+)99~N4NGP6KQ zQ&ZCroq{dkv=t8@K5XeL8xq^NX;VW-Gm0se0W5#~_`pQC0OFEdWUkpLC#Bs`PxNPg%71%vY<8wFA0uvssR}~h5RMz}GH|N@-NLvzx+`+vW z@6LR}jerBX4<0_$=vY4C{WjEA%EMyasT*tE27zmY0)T0^#7;Rx&ZNM@j73m|-%BJ}4@| zOJP#@4`%S9_mkx|MQu1cjx-zIqGO4Z@D=#w^V`$aCTt&m+`nK>!sOrFTfO9uY~0Gd zoBxcF-ua&iP29ErvpaPESs@+^K?aI@m+xVZvnb(H?KUk6)Adn}w=%80Z9%Hbb8~Yo ze%3&MWk20>Yv+||)FM{mSj;&;k6Kyu6=qVWRVkc{S8v{Y z*&{_&xq(tr?}O*A4>BRkGxof4ggQ)yiP;Le6_R~In?${!O!5DBl)2vzB8KALtEfoY znKaE2*Dr}OI&tDe)zdYty6JBGN0pTaZg_?3776rrG(5WHfQoK)7!8*{z;Qa~4#z1~ zfUHlqnsMuUgUaOZ;reAPRw{CGF1Pfk)R`diduz~7B*SFR^RI~3u)v`2{g~O;(ZI4v zKHw`BEb){NHhH94HAMxb$4na2mPo(JPd^0KO^OJG79zg4L019Qg zQAHB>yN$=PPTI5tg;rKl$V#%(9noMDd*9XCrQlv4hop0Ae5h>$iL+mkF^l$ubgQD#Pn!A>_B{g z?Ix`RvbvI)sM*WsS}KxSK%U9^R&DMIXr_YrU-`Yzb?ep{6dR-@5!asHx9P$0!=KOi zl0)cOhX(&>9}fW+rx0sq6ob$oak;Oyr3+RferreS-yowa5MQ)+a&ppwOMa!Pkl$fv zYiccO-k)6hIExSMvX=6lm3;H){4X}@p7jke$i5qaufoE@1j=Mk^%it%h1q(m-W;!F z#P7GpRg!9VWKIOO#C2D2HqNEAw%oaMr?q!5I8%%b;s38XOjN?ty!`xRR2-j0V;54b zOH4mfu8bmEgH&t7+@n%S5Z#6a=R`jrrB-^l<;1L#Vz6m{^ZK>zue3)ghMA%)c1yVL z!20GxQK@T-Wm8eO<58b|N$9?!UL0YN{pO_bAg6=HRI1fiwwkeL2K9RxFeTdvHE=LDoa`rXpWGLIPfaO+{j>(t@kwKVBliyS<7FsOB(aus%t zv497&vKD~7H2#gwV#Wlk&;O3fccw@_Gg2c zszrS`cvee&wHRXZwTn8VrQ0MqCs`YOinD<_BM%V9zxS9Qk~~t%mli5o>H6bLrMS* zKqx67j*_)$JG58h2>Lg*6aDGP<#}~ADQu19qnOtaPNSULN*fh1siU=?l6+jU`7SqUJ%p#Cebi!%{$|7heSgIFRy5cw0e( zE*R$2%hMTTnEZ`p;DbeXNFTh#@~4jmG8yf=yL1653tWzr&uuZwUP;18Z{BRAXG`Iv z?CdVTPWogdid@jqsl2l(;5PCJ0yi1i@=wGQGejaEltoMs`D4cxlCpNvu__ykvICW? zJ_u5ge9!kNBOPMctDwyKDjG2~Sk|B`lDK4FXA?PL#X7|}1}a_J@CkJOoeRMOq3SS8 z5=dR*@A40%30`6p!_*mx^qN+5lQ>>Ok7-w;<;z_dQfu=&nu>_?y#U^Vo@^#1(RTF2 zi7TnW2n(hlZ+9=R3+5Ud`tY5TE2F4+dKi=hAq0D3rIs6=@K=qG`%HVwBs80PF8wr} z?eZdO|1IKplafiU{JHEqcuCViw3)LFwD`3tJI=CCn1(h3$NT%@hs;SiW|&^dDNReb zKs$S?ocX|eW?d>AgkIuD>7^g0iw!3)#t;_IT_$w-+*d@HqOQ~(3lx#EXI)IXfW`Ov z#os9#Xg0a!Pcm8k=rQKtHPEQZSicNcZeb(sX%;miJ$i^G+dg~ttQHac_QoIER8X#O z5pF1pS!`1`o zeH^HWG)_x=bJFjbzyIc(uy_faMcv8uZOKo;W!@Sa=&n(E2|iHaAkw_wUkIHCD&ME9 z@awuI?6qOjCObmIH<>s*6$Ih8UqxRq)+@wz%j)l_%i*H8G()zVmB^VRVm)i&H&?!N z*ZX3kGZRwPrrI}>P`GdhtxOyZ%L1+r4RlqK7GnF-c31~s*#=!DCZq=6=lS!s?~O@w z2E0L_K31Ho41L`ZySWyC9wuY>oV^lOZIr0G~{!yKyL&s$dG+qCbe0s5X@ym zLYa8s%R|l&4Gz#*G7v3$?$YC6-vZ?WRfvq)J`p!Zj~~xjOCuYx zeKD94@0KCFd;0R{b+-ISbI{lxPN$P*S`wUw-=;*VZ*503J_#Y?d8R6-PO)0I30mho z*FTJQ8--!I=BaH=V%;lAqL9;)L^HhKR{@6tfr-@SmKF<$q4&UQ+@(E&O8$Y|5G9sL zcIYOlT~BO7BM@<6#ODz`N4k!)@{`QRTa@-nK^xjYdc5%DpHk&&Po#E%uR z-zCy#E@?wzTl4GJucIm|o)5$O+UuARkvrtC2%AB!l*n?e^~1~A1f%NUP9ARV^ja07 z@?9^2MX8zUP(mxGB494PlSBB5mRy-QScN(B5s#{8UKcs8dTIKKs&=0|dD5b{&exV- zIodeARu5y$zh6SOM2)^BYUuH3Tf_C_(r%0aI%m$bd`H4B&u@UPv8y*0Z<3QlzVob1 zyw$+gI1yW-!fsw9q&qW*uEMrUA?9OSGj+z?)cQW7>5}M7b6BoyCiP7l4F4XSNMiA% zrwq|PTJUN~^zO@-FT_N|@>c*@kY?hCq73L_>f3%y`$i23yzfNQA47P+=dOg~owrk) zWA4ww>=%gUhrO{MBcZ`SVU_`c|FpgmYf66S=wJXbyo z3rh-L3Oh4e#$F~z2g$*V{Ceima7sdYEqU*5@?O7}FF7Hc+!YJ~s@Q8_V6d+%jYJ7D z**exi!nq_7N}Q?-zz9;k9twsCh@TI=r4nnl&XZOcx+(19kJZl^Y?i12+rs!J5Qbfz zpL`1G0(oubirWUmk4WL*pC-Rlgkb9euqdd3^(s*%^rlT+9{k#?RhSrw7)2LT?5jwaC6Ict8nChVN9=%!AdLl5r?-85I zgCKPPY1!|Oc3mK-mtbfJ<&Tu2%PGkx1umqhXw7d4*9?K zI|3sQQCY<&AbCF1)~fGlPZL+fK+U!Rovc4W1dt;-Wo;@2tR&IRmYHiGSZQmNDg@3s z^U_onoZNFSLi;m%VNo(?LKZ%87OOY&4G?3X=KU%)r`eMTFA@RHG&#!VJaHBl34;f! z3Si)n>p&^mllv*(TETmv|I$N(_`6 zA4bYrNVY=!!i5WGzdb(yhvlJyAlf+876hs$(})oJ^(8On{tOrk`+enl^dOode*|kD zsW631GW;fWYu@sOnGN;Kl-A&21<&B>!@_mXcc8mqCD!BE+S*zRY!}S_b?|tYIjs8) zNDo+0#6r@Z3IY06Bt1rUEw*{63~h{;!t#hg=NtpH(a`J($4=hIPVS$Bi7xUay-~VQ7m|MqT`vEScLUL;)mk8Z< z#Gi&hJir=jNa&WNFS0x=k37ZO+6~~ww5~Eqg^w-1n+}yfvRHsu~t00~w z;;?hx??eaMb6PT?H*NX%?%mtsr#i5a$l_PwJGAzYjJi98|aoc?DV4AF7o2mDznn=op|xEJH&WG-Wz-1M2M>fS!tm<*!FP* z3zaTd#vW_daUn>=&dyF9$JB!6qsd35mY>udKwHTQSY%p3T?{rZyFhzYZa9tEML-cQ zs!VZogfGUG&&VdQnWQ2)O^<`DxuwOb?K7Pr)V)Z^FH6G6(x)CN3y_L3Ew@Igkg};> zh}y5qLf# zLiMw$_0xzL$fDDJXLAV~fMB-)7~p>&0F6K(cm)lCg?W$Ya@`_>Es_(GuKE+5yz)Bi zUn3Emet<*lJDBJja0->T#QV>jmBF*~cfwSm`oBiTpHH0HaGXyC0p1}?vNk_duY~kn zc#v#zuj}FpE9Ei34 zXBkmN`thO!MCaeJ3LF0Mp^NDnFC6eaJz_$!)&j_IWM^PNKt}H^5m+Vm=$^-!->o*2 zN=@|Mb^RGm#g-o#t&F3Bl!PG{G}vrc5NuEltP^|dUSDg>9+o{FtLYa@gd6V*?b1{( zA}-zO;u6`WSHac5<9xlq)DamkW;umo|9WrLo`so^hhFacAcK#L%HZv>NJJ+C>(t;M z4aoSwl$#(^oRvB`d#Oq!;6+|Ml z(;DI}h-m$SJPu023248yboDFcftN^-Id8>jZucPBFP!v3P>ih+fm|V_{p*#VxDy!a z%>K5R`$veV=b@Vuq+{B`%rdLKCjU59MMc-ED)QE-cp=fNt8s`lu^VAnIu)jZ3bVGu z8DJ^v%@2PDi{X7U>8M69p$H0H&i%oG{qXLQ?wj<2rLfW}fLuun?j1x-X<_EAxyzhj zs@Z%D!&xS_0fPDK6*HRQflqCAbHW=-HiykriEdN&u+i7%TQ=#a+6fs}OBxt74+REd z>U1A-coBgv{10KG-;WaeuK51!UXNWzUv|>UI7mY8tUZ%4Wt03Jvc19-$77f~i<13| z2=!IY2>eu%gx{8^+GoN;Z;Ao2s(5;9#T~h~r+&Q(9+Jk!r^_3<3bq~?KLTPxJ#cYZ z(MnpUwm=%J+N2*3qIeIBdynTM7nkG%TpkY|hC`12v_{9yg_-6Z^$&dxV^u3h$#iR1 ze_Lh>U>QsE^73qrV22x%=33eC8Q6_F_mZ`FB0e^HKvT{iE5(T2yV3zhWYzu z;Mwg`IIMTlhWeDrVviWQk4TU6gx>a`(XU=b4*{(`G^xq-^13R9CUO2TbEuHH@S)$d zx$7U<@$)})5jC4gklRE=xuUH+K`)ZTl&ujIpPjF#*+$_jwfB57oanTn70|X%3{1JQ zgl>b^lCV`p56Gedcw)V8g7S!f5!>}_`hR9IyS2-}^#=nUt}sPsM0HrcLiLE^FCt={ zh+XfW#OPXz9#wQh-v}{)v*c8TVPg4Y)YIkpQ=v?@o|VK)A9nkIut-ANc_#(ZSBujU zGStgn$!s>J&zVh8F~srTPQaVJLYx;`U` z#6pRWaa6No4PMl))7-W%fQW_xx@haUN6Chfi#8h{`M&DflmhOK0=-d zlkD3v;e8s9l$XH97q9Apq9X>ROlv-nzbrrp300Xot`H@fN{9aHny@0hVV#A5fe;Du zvKx_%Avx0Zgx`4q;N1lXzEBHhy)K^wQrqX{(dfq-d18<3q?^+JLFzD~ z{*B*49n$fi+ymfK>I$7soN8Ns2s=B(s0HemBWggZ6rxRN8K0G4ED-}YAR`KG-nJqp z<#e4S`iO%Pv=@6(*8xy-5{fd^;WXJAK_@tXLbrTLOEb(>JWsTT*p039fb4a;NwS~3 z2SSN%kS9Z}x?~R!a}@nJx$yX;twBaK2fgMPcX<-AwgOX;{?Fj!#dGHf!^_vf(B2YM&c8wm3iL3$`q zp+~CrFo~WBG~u{fer-nA9O^k{nKQ5VX&P}b(Hhhaj37cn$F+b~#L|dSO*&4)!p`&7 z_wWL+4*nSVD;(>;`1GF=H%~P0X};!ZRjOP)`+-wyDjX8s%U$j9c^E?Rrb_) z={rRe;-+T^;E!K#DNCg&ndg}Md!XWXz%3y?S&i~}kZwV1W6u`z#ful?Pg6MR5m%5? zQetBh)blTByl;yFj~ys3u)-fG8RBEo?R>2ZP&q3L2=}%ws)@#BV7reUJ-UE|Ng*gT zIy_+3(-SlpR?%`MrR9noNChHmw&*oEbQ>$LiC#{5OAz8CTF%CW*er{t5NnI>oO0&J zTMv;xv#93FW}BwS7Uc9QZPL|rp} zL<2Se)j{HJ62x}1Nrpu<5>m1wB{(EHiYsH*IN&mgyUk0tYsr%EB#He;^tYzDN9>_i zzNLRI-`|!vR)`3zw^n^77r#h?klY*X$$k;}fnJz&6M9-`1b$byg}6_OG=>><1tcBOij_bw7nU%Ku5A@In` zGF^~r5MoO7L?G!FtBzPx3&8ZrFwNL#IP{AEXd-a4oa8BCBWOW7!jjqdXp8bQgr>3~ zgO~2Oq{fbtB2v|`4-<~FUQXHUArU=$l6ItEjTK%^j!9xQ<4d{^WJ>85UTJx z?76L+l3nOtd+n@S$u|y$a`L~Naq-{<1DytkIe%^Zn80hZSy=DYgFC737|Z9j#b`AS z^*j>N40&Sc<^Hqnz*WP5ZC$hq2U@Znhs2$w|Gw>Zy$25-NCuxz z@9f!zxYzE2wCJufYjHSgkIpVCOUE3`mG zdi0<4V2A+f4K_O27mjBN4)VDn#o(z83`#&nG10idSYsLj$=t%mF6i5^pr7B9H9) z842WHJR5k`5^S^(#=UM$E{wt+y++tJIrsH(wy!hhu`eYi%18Uzfv_7|VC(sRxCk9V zZc+OW+lXAeac&gaDXT`pV$gW!zY;fVT2WP*he_!&;Mnwd`v5L+z2x3bGOHxZ_o0!f zW8ebE$2mJb4k~FKqoShjnjUAR^pX4~H-60sMsOkp<*E-Z`LvVdB(XFZ&m&(#S6M&z z4KGOI=@?%x`i>B9aJ7s!wG(k;oT<|FAE=_>z$WdFI2v^teY>;aYs?6KecU%0KP=Q6 zssC8?_b53?T+?8qx)6ztGH!BHbMOCwG)6J-(v0WfI@u#^&Z)Hi2L8rMOgpx(VlZ2~ z2WZw_m(~o=#(VzUQT;J{a}gD>p=8iJQ?%<`%m-s~K>!@+|FFHtL4WV9=Sk7xvw(mt zA4ZV46061+l7$R(1>&J!9}7NY_>KDF;8K-7G%)7?HvR5j`YGOP;L-I3h@JAtLXCT z;Pjp#Ts}+iU_8<+$b-z;T21=P|E)Vbh|Tk5qvCpzY#76(;}HXbtIxtSTNX^rCbDnS zir9AmTj0e9%tXprg#2fPjS!^Mi4(OW{6)?50~x*Y_s7QFVE7GGL?uc!GasuWz&k6f zXUGy)C$*r2CwI+xT%!fZ! zM86q{_+tb{qcsBjU%6~X!tgq%=|S)#FyiOOOe=Qo_#n_jD(1-zF4qx>hXGE zZlgQD{b+hU_2YyfiTEJ3J1g`g^G zYDV6ABQJ*BuSCbGx-|;OYKWlx&l@uOCpghw&&vut{L(vXMy#PLl(wHZG#DvxM^;m-6q^Gqx z3&7{T`-2oNV2R^Isy04ZNV_BbU*WTIT2))W!LmrATV3pORVoq88JQ($8}S4#2uZX* z5s#J)VzkjgQVdzk@!@30XWVEwI0XL2_LYVE)Pt^(nh=SgF=5uKg#Z{Iw$)Nh71dJ7UK>!tg4l`_OoUcN z?m+ZjaN^HQp}I4z2MvMh=2kBaRE?+KU;4`Df3qAPixyjZ%~ENzYFBLy zp*aybmFBecqH|ik%4n!8#Zr^;a(X$()kc=|A`WSL*^{D~Hod5!)gU74RHTEv%xqmE zCgQ?4zk8m?j4$Ww`IHYemzw|cJpbqZ-!H%Wci(r?^SlVkf`jNooiS+g1ZCy6fGIM( zUnE4P?)V-KqHc4**K5}4rcB3Q$Pr_X9`j>;6hyvso|Wsqw+3#S#InVl#Wa2^|5vk$ zfzzwpde*|;*8Hn z_3_bqq{Vkh^Fk3D=8qPStoRnH z9|AzMIFlRYcReS@L#xS@*kQiAqW~ahO`%x1wcDkyYV^WC=r4>@VmxVDM&$2eo8S)T z=aPx>l*4w)yL72+;I!Z?=(JzW7R?cM8u>F94&Gqa(exQ{Dez+*50vi&&k9+91KvHY z7z|dHPQ)lx5D0631eySQg~7X?$Z8Z*JuUq51*Z^L zN-ot<;QKhjG9}IRr2-!SYg?+S3lxnTgWRFsP7i{72lV1<$^p)`>Lw{!B_;E1sC)3hU*g2Qh zI(*yUrq{7)dmc<)FZsEv3N$@Rm{GxM3kr`D&xGCM6XkAsX~p4x*F~?4*vl-_e3_?v z<1qGbDXA5b;*Pcxericl#zpTlQ!ucy@}wpftt$wc3%%R>lwbrPUObQurcefu@)4vT z3nPdB1ydtcVs4+<)0@3fiKFfcWf+y*39Ywm+^{ zO{W+rCTzwk8gR1)#3(W)G((suoz?}z$er$#D)FvNoLI-BN9S(Y%m7yiZj%EiG$i49 zU2;O9AwFxQ9c(+>D@R!{bymp{M~oOPWUjklvQZIx z2PS1vP^Y!G4f-*!wK6>poU!sxb}U7godDLfBqY?`*&9Zkg@`}04@@p0?DRF{4CnRc z0wyh?Sw5gkJzV(=95gTF$UI~$+OYUx;>B6pF3t*{Q>j90gE>T|v$vZO4_%P&`HK&#LOH@bc4xqLCn= zpQ68&j)vAY)fD@{Bjlf_5=(n_FaVjx0wa=m?_WDqJW$HWVf&Z_C{r zIB$G+wt926wV^+)3AUgsj^=ky3qh1MaT53lU4FZYH+|Ob)?PeipjOCh)$k&Py|15e z)gi)N%-5QWbTM*rP?&r;N|6h>u0hy|yAhTon8W2d&YK73Pri4kQ&a=Z42;;{NQ0zt zYPsq#Fu?e3lbFS3yBhj4pW8;|v+UyqV{Q)l?Q|#ka9@Mv&Xiodzu$oZC|nyJ-PrmB z28By0mkdcyc{f(}0`IZvpTma{u9Z-oIfc9ZnKUyS79l)J1h*JI(ig&5m}*tW9Ohy+ zZu(~kL2kxRjVQNd9vT%EGupK2X$3Te)yvuj~ zJO{$a!*oq8O$}Zl(#l;E$5x?ZBJK#DuxbL)+YM%F`WTHz@lK{~+; zf(rm@L0Cn-CwP!ff~8B=QP51BKuA<6h2mKwLqRkjn5J7=IfwMGRT0}9+0oWh!le2p z`9nEkv}KsF=RjU+60CcB2P=6tZbv@a%xO?GY3qX-9a z3QBP#Fu##%} zGO}2x@uz?2&3P4O+V(dzX(;dA)D<*!g$oDX$ICq!3msTV`AR7MDi{lG0RWAo6#OR+ zu52RF>`&pa{E3H6&B#zgUzB13TPu$75lnuY+qkba5oFB4ST`9^POY31Ux2ug*YOr- zZMItL>uZUK;2Nw#j1+XAQZyc!4A8TxVKlhWtGwg{s0}+fg3tV;z#OJoZ|d++c$Z|i zsThVpMS_Kp7quj}oib6>z<}^g?AbDbfYPlz3YZC-Ask^uv=`9e_o6=t*TH zoAC8b8>-1#x}TNQ!#Y>VBY+%NIEkhrxIwV#Cje^l!RHpDz|K@eO|i(U(Sd3k)Sj&2 zZ7eqcz0H;?@+YlzG)GAN!!;}P5sLufcAruMzlBk7WRv3 z6vhXqnXwz+sfJteNC;e@23gNPTxZ28ML8N7aV#PmzAJF*7h{JgvuIKvAOfvXsodNg z?8NyR1{R4wm|!&ucCG-j)!Kp%5A`ZF!BmvegGkwXT)uxB@db^a#J|7|egG(^1v=v^ z4}0d0vp?2(s2(lU(x!`XbYd3g zUAdBolCV#**KDIko~B80Gc}RE((ZZ8g{>v}8!o11_zat-ZL%$c)VdH~r==bBp iZs_;o|129nj*M5@ZCh9P*?VntELi5V^s1--f&T)W_VBj= diff --git a/tuning logs/2025-02-25_02-59-27/plots/error_x.png b/tuning logs/2025-02-25_02-59-27/plots/error_x.png deleted file mode 100644 index dd60d61b8923eff7cfff37fe51d8beb6832a3032..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 221104 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_uc_H?*ISz)sUGaw1>S_XwYXTIFCE!QYD=Ls=_mVE(L1j9XN=akcjJy&l;* zYFx2zPn_1?xJYL_Gh?)5`Enyb#rDU(E2CNw%m4_vm**^f)cK}QC-Qq4fZ2*NV3SVZ zCzPzWo@XL|2AFcKh=D;+PW*vg@_UJeg@qqbW4@JtsqsNsdHe56fbzJbJc>dhBkT+( zd8%;0MqIsl^JaHME~3C~sH16+fQMv=BGG|UcO5iQD|8997z@aDDlGqj)Mv=c*`a=B zW6Wy+P-~pJ*pbpW9q}d!c7qTNzL36A$M#wrIAK7$ya8$uBs4S(1XoG49{=ahpAm1V z2bz$|>h5k|_p4eL4$WLoz}}JCE5Jh`)&RGA_K1%E(!z~vyQ;?%JRg7AFFkq{enuTY z0hisq+}-~GoJ7Km85Bs_AalHh2yR8C!$M+MH`pgK6Q`4|cgszJ>aUgkQ| zVnCpdRhy7^+DbO^S7Fc+iTVSfPTRYO+3;(?W47%;v@S1WJNNDrIGHmooro6JZ!4JA zE1AcJL`T%Jx^V^N0*7oSkKM^Wzp$%7|L^?RD5+$ z;Djx~PrD!+zc){~U~maG*XCrSva_&B`0`aG`cWIIUc1r}k z23}AJiSG;6poKb9wp+o+>_h03l+;vnm(&Fh>C7CK?lV!zInaZOqCep=EPFZ*fLb>4 zTGIB7J@mmlvJR2%dw60NDb)wwOT0Mol^v3H*+{l}p-!Y+Rte@6 zq09w9Mv#5mmD+HQL;ig?TQ&53gf@Ezwt%Oxvu{TqH>M_vBfW?;3Xhb904(l#!chWX zqY|(Z$2JKSKQU2do8?^=nSYQj9!)W25eSqQ`*ufMg-YYAc*k~D!Y zcMG<>jeO2E$jC=s=8E0<8oJ~(d*)YKNN#=9{R zUc4Lr&ePp2R*}MHH!QvzgfFOeWt1XCrl%_)5+Y%Ca+e>N1pvt8%qEFblsY_>3HC%b zXND1yhxZ)?3G|mFjWCYZrbQ1p$vzH&yY?j&UD3K-c0;%vtC3vMS)ryqqD5o>+2-4k znVlU9qD*X-EQ9kLcN}>`IKeLeDh&!iN zx&H;r`x(4|_D8yQ0x#e67eMGcb8>;Kf*+cV5xz6{6i{YGA0at{bR^IjI3d>@s(_QS zMowQq)@}~u@&%-ufI&XDfR02WF|h~vNRXbnN8DUCbKVLXaBR0x0Rtm_&d0~c>Vg}o zqylF^uis3nzr&U8fvV$=-Q`FPDoZI{B9S-MAQSLdhN3t7B5;0y)802c4)`7Z&>_gD#V* zEIy6=#-$^bn;>O`)mB}|0EtsgJzEVYI2b+%J2yaE&z6o(O4>|>kx(wfP%X#C+=oxM z5EA)-YWdsc=RU{?OQI+~=v36yh$isIo;>jB0g}Vk@MCk3bq)hf6}!u9kf{>;nuR>_ z5%>^bk$HCR-H?aD@Suq2aXRRxx=~7 z-$t}wFc_9_&0$s+e;SJM%$A?A8G7v}*Ng z_2?)J0ckb*sbU|@^12~W;y689c#pDtG=J^zRV^5L55y_5E}b3*0;f)58OwHNave{6 zR&I&Dd;kN?Rw4C)fdN9q3(KxpULt=Px^}z0{lFICGuAJrFDFb^>$P`e<_KQ7uX3~G zfwQ+{-XM^bI@ztat__ZK1xa7!=_EFZOcIpFOXu2tY)PV zn(O&o)ZX4awY=NeBjm@ZAUXUtP$quY5OL(d4ao(L^(2n{k3#_ZZOK7-w8%S|juhBls{;oPY=b); zioNfMhYyLJhQBu0U)ABljTH0A?mXrC`ufi1hcQaPuZQ(2Yv}3e=~_LX(h0^`ff89* z01uS9Z^M^h#*svVkqg45rmoI~x(^>{m*uddB;>Xz7;c)iOP?^`<{FHyUuz?=MDWjt zBVeQxB9al-2Nhrdx`btGCAK*^ojZjrDrkeF)rPM5`DJ4e$OiuLhfC*2b(VRX%5}&b zZ%p)CKt;#I_`tB=FS^nD=Tsrn1C15BO*QGR$l3K?t_!lOy@YbeJy%QZAD? zW%(Zv48sX7UH3s!i-m$#>L4%>X=J0r zfLQ9hE9$(mxw-iW+Smzhy=+vR1?~Sj@M5N@C(6w-;Uhnp>w61C%U4|+P%}S|aGN6% z-9-M4gk&euxlZ3*%*@Qx1566;?CN}IFtW<5V^e4kD{ZlM2bS1qY_@!nNNwGt_oZpQ zPe~t;dk{fvD+vF^4JF*F@^lm)N(4E5e{I(qn={*fr1$++jw~Y|xsnqu4FO#pf{W!{ zXxU(SGD4O8Cav_lF7%xe)UZ8-n6T6Dfc=oS7sc8o=(H^8a4ghS)pm7Wh^o7ogsV@j z*bZIt%C<1L2P&D)Iw;pp}6f2*;rZ0*OjzIJdAcHbjYssKG*vx zsvt5Znh;g2zc|13jKPw=H*en5X7gKmcDVE=dPc7q!On68>%nkHvbp zgFf1E*m?Qhtfl_Cr(RLtAWrLrsCGC?x@W6wtx@Y@a?%UF)3KB7q}uVa(faxFV3ek@ zyw10U>Z7Q*Sw!+6&GjkD8K97;BV_vsdK%(p&yKRJNh4ovKYaL1uzDG?S0HGfdIYPK z*We*|q(IfoN$)YBUn|*rXP50;@tjQOzAEm4fxJ4+d`P}ZbA%+Se&b3DeD_%=oqOf= zq1?M|M7w2ZnR7d4$2Z$cSRw7BZZ6ocHlgdYHxWeD%Cn{BJE0+KF+7zHjN)lZ2eRKSTx@i6(sdi+Eb0aLBZDo=9}@##>C8 zGKFz81!yL3J(ajPi+3)@MRnVCU(q+YxgHzdNiQZ6WtrM@uo6{Tgp|7>DN^*?$l?u1 zZVJIiKJC<^Q}f1lWz>GN%~%};CWyj1^XbF+E4@-tz*vW~74odMb86~ZZ@*>rV){ja zc)%nRV6iu7D`Q^>pq%;;Be*C=04DNAEnY;-Fln!^i^2OtENru0m2HjCcWAl`q-EWf z9H*g*ns=|tF-7k$Hw@_Ne86qK)mx_Fx=}z@dT{Wy6Na0LXTJ(hXb3Png1sc`YWv2!=I;(5xwEjXlxvs5 zSv0i9lLS=oD3lsRAzw1>35#)D!qqO3)9};kq|ygebZzn^ct9?Nw zb_hc@NFA%mgQOy$hO)s=DF}mK{9HUo`;B$rjK<)X@c@|gm&B)C+s|Ev0**}NMguNH z$d8_c+vitM2H=J`iaB0-mUMB@zj0g~-fK&YS=`?vyOovefX{Ll9{w~{O;`8UGkfGU zu0KnZ@7U)mWo&G0javr&tWnoQ@cJC-g+!53K$l4wZXt{rIN33tB|IXf!`Dq zEAh%33!6~b*CIKkGE|8%vnHnvAO^E>x%CB}a}9l@CI|kBkiyW%{7|q!X=$CMv%ib4 zI-`Sh+e*M&1i*1@4fM-8BeUM7!sUQn+#qH}*kA9AmQ$0m!J9Jei(#Rmi@Y~AT=&f} ziO|tS-Xd)C5#Wv&sRjCJ7sifgMfErrZbTYt&+$s+wCDD81-b*Pb?@|s4w&8}fS4ZF z=}V~d_Q3XhHnL^pj2vFNBmYLzeZ#|z3O>k2WU@e4PCdGgSKg9o!w?q0A! z`xVw9IUWbKR&~iWBNo~XdoE(%D*@2(y2QpH<)OU#3l}bk+kgM^ATrXk!>Lh5$k2B& zjNn>PQPI)1n$fi&b^9pYbmwY;yeoY9x**5)OECQP!?)SC3D_2?F%D`;rw^qQI1|Z# zd&1jZ2v`Xp7D~RYy;s59G*?~gtofZ-%iA$e!#S?Q(A?sS%mjBsWAT%50#~&>Q0~zi z9RG+rU$G^^M2XG_(_74DV!k^uKVNAGOawGY}P zJVIhn{_AyU)$KTkMyaJN2E~jn{V#>H5m?kFwL~i`mno<-eTs;PASQ42<_4VOU}pW< z0djIBMyzxS5t#R<;HziBxCkScrIG~}Ov}<% zhiIDg%i=o*WKMDB$Z<$>(`BQxZROW`d-9=?knwaOTc_e@+bfaWvLIaKv2Y(=2E+qa zMNWt!ewGnHe_AaE{lD0lz?o+V2NsKbI|keis0$JfsRWonT*a|tLDnAIDixn6?>4U{ zaSI7CasOiCg)gHA2A?k2MPjUk=7@*02fqD7j)eeb2UAsM<{8RzCeAKy0)MB1H4 z-pLNIjCB}F9>~Pr+>|>8%F@y5^}~hIglP~f?q1O*F!FsM0u-rmU^P~gMPj|5uaJd3 zjwZ^&;ta)}81F+96bV|xwUz7-w8IFJ(N4grDjN>IY_tVGvdeItaE^~lcNl=c+fg5~ z1RI$>ulp*oMWH~{q;GWAhMwe6?3Cuf*7H{e1qTb0bGVdBh);O#b;a2PdKWv9Z7&oc zrs33?s^wC40L6)8zcvpTI!7E#vjb5u9IqY7CL__a(i;W?;hiQqc&k&&wM)txwSj$``I9g{h83t?OX`)C?c=;`>KR`<^ia_T;pyDpy5{HxV zC4KC>9>G^XgzS9^a>ubK>LCZ=7?B!l4UPH5#l<8B+m1Li6!;W1Of-VL{v~UQKydgK z?jANH70d*i0v-+y4wAE67{eHOh!e0HPav{npb|pw-CMSM_ip0a0Iumzq=MLWxK8tl zMSJn0p)ax-6P-=wer;|x|%@R*O7 zA|r>9RiS8^6$tN8)3%OyTv*zSR-Ek^y;G5o84v_8KDU{n3hC zk(f4+XG!XO_$uY$y`4LAfGm9No?rR!A>7n zr}y7F5R_eT#ci)v3i=;EQS<`~Kr&b3SI87C06EC>`I1x;0JtKurk8a3^(o`mj{qc< zZcnH~y04d3fsJk>fDp+Dnk25r?ft&9Gk!b<7VWQFXUdP0c$F<)69;1?Gex)93 z+*AzVr!@{gnoeg%lWjJSpGZV*R-E|+s|?$g282CfYGpODH^^;Bg<>6QMX!mkb_HOS zWOGP%vVvG~@N5x%x<-?XrR%P#hU770m+9fO;d;>=RX$S@I?MPGlM$wls5yANZB^jfAcy+4P=LUiTIOGvS2BAmTh|K=3gaVDypEqM_z zGct&exv`40qG#dGw4J}b|4-sNk{(+*Leo{EBM^r8G#uL`#WU*VmVo1p81u1nmf&x5 zAcJJ!5uo{|R{BA$61@&skV#@hE2){qAr33}l57W2WJlbxV~MNqV$9#2XyZH zw@&RoS7iw|wi2WhYJLyjL=&$QXdA~2b7YW+NhgE(M0Y+Ov2o9j^Xl*)#x-||!kByV z;{*H+{#9tn=QLK%U&Q!-pZsq$hzyKflgY-)x5yT~*Crl3oE2};6n!v!BdPvs3rJrK zUy^1~k464J6W{Sh&znDgySaHAx4!7Qb>4_J8$%YIGKUf%=^N1$;sRj@HWwXHRIYPi zprnU4$8~OY7|YWM#h~S z(Kmb5qEZskJ&1@He9?kllT1)U$RaA_u5~KThdXCBn-VG1wWO#U4dhiDOZhi$hb88) zquXQS@6=W>%+8F|d+4W)O#O|hS9XKt{qr~O>J z#sRC45g2&I-~7>#8$;?E=6jM%v{KTC!gT$aDMh|7jlVZ;c0PNT=1fEtaU#FJF0U+E zxF}QoTE!{iEgWC+tG7?R_lzowlPg_{SmfBm+x|X#wmyj!C#?VO9Eb2e{HPw>GMA!u zZWv4Xj(3iBEb`u7v^(VP?|z_Z_KCjMJlp9w7X8Mro;o7cgF4I6oc9I4+u@ByPaT_W z^kBb_AH4p%88=M|P&z}k@7vGwQnfkY_KE%!a34q^AW!?|fDEs%zrXP5n!koq_FS7n zEx9$}Z6#&1GjfEr7MxYxymo8xH+!6$u;+kAvCHQkgvB@qT7D|^DdYE`lA=^JlkZy# z(v)X_ZHv0{ZvOb;>Wn^<4wNR$&dAz6g*O5x*`J=+alQ(sghNve5yabM{pzZ{_aweZ zoNRR2uYwT}Tb?wirJmd5W4;Waxs^;7L1B#OF1 zhX3b&8Tv^x_Tu%|7&hTpNb-Kbi$6|G66?x_p9&My$kKo<`KR zQ&#ijj|Y;!c?a5r$QWvej&I)o_%h>pYWzdVlC;zfXAYE(WVPhh4BLb?u3A^53NN&2 zEJ^d@w{x5CN{tFA9D1}&@?^!eXPZ1c$oCVbMdZ)XnhpH5y;-hq&O-$BZ!;Ft=f7X35bd$R>Qar+5o@H|fUyOl45il2^|-PSo}& zw7q*(d11g_Z3V{hvfb}vHTP&wLm=BF^LEM5E_dr?ORO z_)Qmb?JaLyvXJSN`15JI1Kh53G6&KsPk)>HsFoI@sPlnWEqDL!!;fZgRw%OQeNP|fk9Lfmj!rv&K*N>!Q{iZDhO`>m{7Cc1vCv}!zvPZEc9NW` z-uCCH*Axx$vrzB3S&YaQ*UxJ-vQ>>q_Hc+BUCc4PKR@T)rF5C^#UD;QbvR`}QG=?# z55?sObp>klxvR6zo*Vs*d+wNS7mzj&<~hloD$7SvVcRDBdKuHVg&Xb zE?<89ob}V0g;)=-F8%jm@q5S@?i0SS9Wp3HChhy;-*O*2cYX}lq~cZRQ>a(o6YkK+ zR8~$uAMLS;;UPx>T} zisYr@XHJ3gx0u+E%{|PYUQG6^MR>E~guXqF;Kp;%{{KGbBVCCh1^=14`}$0i4!AMq zw9Su9k<`Q~3ZhQ3;vHuuwl%_`W%Ax_VoHc21NEPm=TQl!(L9*2`kyZvuq2i7>;H(_o236kI2))>D`reOuO}8{ znA=XnWXRV3I#f&U5b5;rBb`i~D7fvchU8f;6Xy>yl00eWANR6;k{5&nBtCH+e+=iP zR%7fRPyFKkF{;vH(y7%dzD2E>L>f2)_bxxto31tw;zp~SuyQ_x^U{^J#W9xK1S#S) zKF3@};hu@wN9`axvmsej69n~=sTd_)PTn$ceX2>Wm~?%HMh38E%$TfM$HkZu%qLk4 zmrU0)9U@aK{JS<;^oEU#rn7dEsk~(Rp01=rZV{Y#ON0wk<-v;-bu?$O&@XbVxCpIU z%Qea9Z@ce8=Qk%Wnb`Fe{PQv}t&$tKZQ zLxEz<`$UP@c8)3I!#W~z6Xh}VHS4Emo8jWf2zCC_J!-C+Bo9;N38D!mu9QWa*_l5* zgC&?~KeqX5jFiSrrUEamcsR&KV<&B%psyi#Bh;h{iqrTil`z?gaC;mfOpRI3iPFf< zM%^SWUN~VE1NKlBj4%E(y=;po7rGPcnG*I*qKn+vMq)_Uw?c$}UbJn#frC@5K1^ox z+#;S&Gh~@WMQ$rLgoD+wI4)e~Rx0RE8}f;AE4 z-@Cc3sMU4M&P}{yg$(g8MX-K;UOSaEY*-o2k^RK3NBpq)SAO@`IE^(doyUZ9=kMK^ zMl_ilS#3YBC1Dn0?%>t`JZ0RtP8@L=BxZhkMtqI`G>W((GmYV(_{laf{W6A2LL>Oc6y?&1LlvP_oFe|_qysnkBtt40mS>_EYgA2V_!VpZvug^a{lA15|g@qXbYOlce$>xmN=62Wk|7%OIikWVL01O$L4JE7J4Y@4TMtR4BU zPMdBzcT5NW=Pi+ZtQnI@6zc(E#~I=21O>vRasN51;bbpaaTCuX0m}sGB+sJ8qrnLh zO@k>VVtZqPq=mE=iH--<6U2%}OeuML(C_+X`U4pFb@L{X+K`iCW3J%x-vynScmz); zlk<@0nB&PLOz~p~WwClIMLqr^&hd*Ji!iAmN+gzaq9DBwuc6O?tga_f^3Q80<4N3P z5+|CBeFuA3J~7PC1Oa2-%sy^nCoC1ktJB9L#fby&3!}_WY~RF3@pY%G5x4R`U%(56 zulqNA-PcCH`MS(+;3hHL{|Re|iQ!L)PS6S=B#km=t|zuui>#iE;NKnEx$m1cPNQ90 zh=uU|`qZBTMO~&n-a=JMPGTxqeKpYW$%gPfT%j?gd)zRRgHm)5a%_!dAUA=oBZWq$ z@fERPfy_d&q!EyRq%1L3e$mgj9=%UoVxnkao(*H30^dXMwY5N$yAc3ZX9f#LCistd z30NF3v@BA)bMD-^Sd^(|uGa5#m;RQ)QiqZhFVsWJ5{$H6u1@vbwlj{Abe>(L2CB}n zW=OyCOoe&pli-mxI0vQNb_Av1Mkp;|fM$oP`_jr#4W!g`=V!An$2@*M?NjL2ms==` z$A+{_9OnuGmuOjO-xx^1i3#BEAO&c82I_vsC=-$+IA`#9*;WGlPIoZ}F0&I)mXiPe zk548j)WalZrw^cdSi}1DQvXa+Q2FxZ%jA(Hh0#tQ>zC|O1jRH5)hKSj^~lKgCFWD=E%$<9`o%1((1^#^f_90!QP2P6=i2#TEC8lT!`P7qmHs(`j~*46xT z5=R?EgYJspuYr~Hc0=V#_>TK~Yp_dDH`Ad14*{H?W8R`+EE0;4{@3LaxJ|1XoxK1YS+px4sxToM~=dqGghmgCPKZc1M0YFkC;by6wl| zbWlXtcMbN&rwanF++x-}w4VTfLH^?gV2SO4KEbu94fPK5k>3o$nh)`E(aG&e1SEA5 z9I%#-KOP2rgm*;5E~@h4If@c%fFg1=hJ0ENHr>wwEK;UqM^ku?kmDKxtW=fl+*Z>E z{Bd$E4t(usI)C`*Q(o!)8${gwGgh8b6h$%oLV~umLzS@bMS)X039cB26AOU)i2zLr z280L%sn%>Q8HtE+CsPxPqPy&=3jNRJgVX4LU%ZI=jdyM+@IRgT6c{*f4&XJd3wABf zx>+;afQoUYSsWZWU~Dh~kl#9YZ9J(5lC3>oBRukThxO+R+}WDxgT?wI;y)WIVrD$P zV4)@dOf5la9xo|^Tmw9}x9s;*yyanZ(kf8SBUeA?GbAHzBCyQVA5Dct8YJr*+>I zO3v{+S`&@NaFzzyyxSzcabsLXdt81lLcog@_z;qb8qEXSUp2$l23G4ADk zqi;>*xd?tXDOwA1po==9ryaj+cx`g*zj3?&og7C_qs5?#Q~%9$HxAb>ZtH=zhbL<8 z?;AG_m*c{`H?JaSLsC{^1U#X*v~*eFkSl7XJwY33m1#>#AWGdNHGoETBn2HENeypS z$9SR|^;xG7x31Ne6x@vuNu?4B+$5`i2|P~4K8&nwIUD7D*0ra--!fi)j?~Brz2WZX zCbjoD_3?>#_0trxqb-wC*n_BcilxCk&C)n{dsR1H(2~1jjJpv7I^pJ_)W09?GIvc*rwqG?FWp^4}j%=W{UfYs3nq08ys20am) zr2eADmO#xz*W}7o|DscR59Vq{`S80A98&GjV&vY4N3iG!s2e(?&!*xr{~ReV!eP&G zEj>h~?1jDxYCB7?&Zw%eAFU=LID~dmKTHf~cc2j!W5#GO(bIWV_DV=u*q% zwr4<^H4gpM+ltLXAI0X$oayO(6312kcn(F=wJ%_?dkzb@L-z@Q^=i_ugObs!Bz*;d zf=QW-TumPq@L8y~&&Dy9fck?T=3|#L)4z=ru}$@MUA$=a%~XT@j_KII$9#!i2WhRF z89@1xGnRj36fc&x5DdFPZy@S#1y>)WTmDn>ppvWm(yjX+-tQT`hwY#()U0oR zk-C{o3DAM@UAWqs2u_aEsiP?NdTQwiYOYSb7@yOU|2BhqrS`F@yW8a|n}>8u!X~-Y z<=DD|y+|>{;4F^50otz>w~pqc7G09q=4i8q{NS4S5g(w-qf0xIJJQnHep!s+5e@>B ztILO!>oR6FLDgK?0*BwEk0WT`L=z_LS}@TG-7VbMhf3?DmY&j-1_@{O8$Qte(WT(m z=ZAmNTrv8yahF3QnpLP2`kg-$zIS-L`3TXaAHC|}D2>g14 ztbFtle}{F3on+a%+Ty~#OH*v_<)m?qI4mHI&VI7@z6+%rr#~ztOHp;_YQ$LTszI|v zTn%WwYcWp7w?IV@b~;q93zQtEQ{_=qlNNmVj-1lw#hz2?{pV_OtUg|H>s8hj^gh&+ z;o&m)JdDFT-C(2Wy}d%MLj!ons5T-<9hVV1-QJfPokf0vM$Q5vo0925Q$01+m&Mhk z3&<>g=i1j|RGXnZqQID{FVRT5G4`l3>=2V=r;?H>j9YlL86kf#jqmg3s6(mN?Uo*v z+0r2$COpS|{&_boCC<1{p6~2v?qEVsWqkI-d+i%aapc_Z}Fj0oPXGXT^DZkY7f|==~0jkx{8` z?8wzYrSO!(rgIW{lTr!dIKnKN`0kBsM6pO&&mh!lP2UF3xSX9PtoqgJI%hKNbK5

>R43BkQ=AVmZyY>|I5B0tESlsxQ=Yl#zU5p%* zSV8mf@1MH`?VrjdCT79T&dw-{G1fYxcNWxc1lGT!>44)gl$OTA`HwbZ%@BQtn#+Ei zk6hj7j0*3rD+=gDHq3yjwaUo zKmM+n?rx&V&+|CGD`g9pXkQIGRd?|OD^I+9Pq->Ma0xaXjN`YUNQfLs?FU?eR6V8z z8-XxEFQ((&rX7V~q7qCehWaEuB7#)d89h@lx+}<;mwv5dDo2~=fO>out*@J+vB{oe zwryRp*rlr|Xhe{WGL7cqjE}0CzhUZ`%)f4={loH!-Y7Sl3aOE`q~4q5E7Z6vIJ;Q& znLE0yc-9|j_)OOFy^4m0kuximeLY9fP%e zJc6yJQ?p+~kjfzWKOErOpQGT7vQJC+8~P5%Q&83{aDl4_n*!PX^pSlsehSr>{;XBC zNzjf`pg*Z{mo^OED|XL$zh^8BE)XNzeaQC+b;GF~F&#r!1I)wH>iUE%a%zO6 z#gFY-rQ~c$8J?U4+A|Fe(Lr$I5jRX+n)8vA!?DKRIegFQMjh>8OIEiyexOI3u`PaI zEXT58mS`yRxlbZ1u2k}bxrLll`lI{Rl&cA*Zsp1fVGS<}8Rc>me!v9!a05tHn<&=bQ&s% ztY|ttBY4M0<_yAUK*E;`HI3)F_PSMAB%8+v$5*u3!QN{2kMN52#5l=2q<*jnagE^b zG;Db#-DsQR-JM2dG$(>czzC6k@<`=|6_1uHr&bwAo^?ED*PkRB`Qju+liSq&=w+R4 zjLh+;_nE{_l}J;xQ2T1i@IX*P)2LfV)s^l*&D3U-+E?t%p~j8&=VZ^nWST>PbbKD65<^t+NIQeDSCf-^f?=pAQkJK9}N zel;=}eRj3Bn_GBp?XG=-j@or@{r=}DgRX$m$QPc5J#D&&ka3__&Wq=;my0g#lUhU8 zi0?-cRVrZ}l2-dPFu~jSX0cg=UnYk{5ymmOkJpUWijFQKggBgek#;!O`H&=^a{iOc&fvvJN9#Qd-n& zywlSgJO9Y8aVjg9eo(dM=t)D_w&PxPO~EmJ9W1L(;3>gFPt|K9Vruw>>B+*GFJ%_| zy*_#jTIj126FeHYhhP|u0e|FbBD5E(@a}W<)gKl!V$)lW?TL#6icJMjvq}nd+k3je zx03K}lWh0V*rgW>4Kz_$w}W zvQx%|ubMm4Q+ux`eDV!5YN_k$%($w$y>Am!b)QRvBl%BT*Yy#BHW4z08U3%wjB|@| zQq*o#rDVTCg|m@iUA9Z|mn+J(s`PGE&6IX%7%LLE@jUlbYPlflba=Q9Og#DuHP6g- zKHD5>5+b$EpKWOCE36ddTzcZTvxHsiqi_3Ey|!_}YsA##`>N_W+RKH(VnRE#;o5vj zdCFI9@xz>ZUK?VM*S)m}&WqmVs8_M}(|bkID#O#KrqCpy{SNp&F{EAkPBLTba0bNu zn4u9+BqSit+aVVAL8kdZnBU0oMTOzRW350=1g&_S+~1Rvy;>?tcrZaZbxZe<xA|#*dd+}(=j!_wyQ^6f z=B~}4sC{}I<_2zenQyWf5cKh`{iUNxv-^m5B#G~#924zu0t(*iQb7yj zUOG}@IdU)s|K!ID^QSMr^{BOx(7ViHJNICI9FG+g)|w&vhsEwj-ka`Sc6@o~hJ|FU zoQaTdV`}Y%P7Vb-Sqn$29j$gJRt}!q(mj=4(A$}>5a7|F5V!bvWtN3P$sXe=dBETC znAmt!{gI>4Fo(&I+W8M3^{$ZEBZ~6$aq*T&ODdP5Xm3#Yx4XlAb+nuEy2PVdEiP@P zE^Fn#{mJ2JsPwP}i^*F%YQeeZLEO_&TFlv3X`_00VI`7`_8;?+8q2&6!t*cHV&UGK z69jh%R#w-U1ot;^)W*}BOYU@T)?+7Qq|p_qf4eSyC$hR%j$XQGI|K6$1DM#;_c;CR zCO+ioBXYIG6vLfKvdLpzl4(}UI*`Nkhbat(alSR}0r}iI6s*RzN)XPu!+i$FTaf`y zeB`)wzQmL6oWv}PSpHEaiqsq500B_PdZW8w~>cqjcYq>V$KL}al>+& z&14u7Cl9Kg>?z#3k4o=V+)o{8v-BZk3Mb}o9%)7*L#wxo5aC^@8v2{x;!tnbwFb63 z$5rksygQDa1X^=|!J2l(kW!&|@sj8ps~E3gMmN#XwVS@DtKDAvo}y$gQeyjd2M@e8 zsr7eh@(-;skk35xZc}4s@W{vD?Wy`vu2nb{!}w!<4DuC!w1XX}gb=6rr5?MR$aFkF z%WpVvuPWL7jEH!^_DOqfZD7piq|32PhF6wOrFFH=W+m^-RtnlWx_&x#GTuZSTr~Uo zv{HRX^I@pOBd3#dEf2}HL_VnnQJnXh9n#UQpnZFMvaS;ayMkEq^o`v^`XFt|b#WnN zd7L{0#Jh+7xF*3*28`w`6@O?C)h|`kUn^Z-c5WswKeY^pu8?;=@N@CrI@(M+d~GQ; z%l8e=vJ)oUS*JG#!e}9LSxd4?;o;$&c_&jys?7S$%KK{^^FZAq*F8ii7Ib^NkRUtz zweNg{S^YFhl!$|(ao$;nt%8UTE-u9ynpuSL zFNbNWfSB))GvTzcbZ*hf)wcoR4ST(Q#)geVC|B<1r?otFAWCQ&wIaS~Y1*ECZYrdp^)2)6&xAIL5JWaK zH29^qlV}sFWmsj8s;ZCavAPy>OGh1~43|2N)U=|?-OI=6%VKLpJ{zgJCJ#}JilcC5+A#)C}wKCN)}jKZkMkQ)@mIli(^ z3|=yG3O6GwYXOs?VPq9@pk$wC{?-Ul=O*PkWrM-}sPMPgwjs9zw0b9sPCPZHcag&N z6@5uCKu16{854~3XkBM+`f%=$t&cM=VPfd?i%&65Z)a)!7!WSY^eHY|l%fnzy|pc1 z&S*Op#%KYjSLUF1(HWqH@l{IqRestO2yX;RI(T#lj{;$_!6r~jt1Wnn$Fj+A3E(Nn zl9abyX>#?`RteC$xy~naYc^gA3JStRDC*LN+I4!9I9$G+Q+q-&T`)b?WUed7&}3RR z9>=FLLk-Z56sxmjjE_N)!=;M8$C(n_C~6rB8^rvCu!};N>rNu^^s$9(LiNAVOq+}S zfLCzjr*l11oEXaLMZDs~&0pT@qX>W9~2+o;Ou#q3r z5Lh%HFEKpw7AFp$<)7iWxnV_>lAD?QkjoM{| zUDGiv07*9VBP*;BseF$PZ z8>G@VJx+~tx4_<3bW(E!!+>5|9(1U;nlN8Lfu2fl;8-K7NgaY8L>)MIg5}$u+_~$i zdEx(zm8U9RyTdkS^lw(_WE>iV(T}f{IQLwH(3x_+ZQ$*&%aPg5O?kU9B)7vp-;rUV zdy_~Gop2aR!&j=qHjEFrCd5l(41_`2PPS4QjA&AoR$JGsSrciOzb3bqaDLU{0o9L2 zc`}6JPO;LsiFAZKF5sv2IVti`Vgj~gN+H!N!I9F&5^8| zV!t3BrV!tt+4VuLqXQSJO-`Ix#n=WUVagvJEW;j3sSCne7{A@8XX9~+J!37}w(pL^ z2`XW{Y{Xb{r|cKetNqZx8-31E^RF0dIdz8#dnpXRRPcnhz3t=rYT?C9|McN{n9iAh z%S%2o!Mq1tTJ02Aw3ro2{nGmmjwAY*8qfLT9bcR3QqC6)y-qv9MX@~yA^9jmDkF`Z zxQpxcQ}ule2Cf-gB7;wuB5!+6Z%sb9xa}Vc>y_p&72x&p2EFM_R!oK+ptkQer`nfU zj2kB9=DEQHQ27)Sf1rpkv7kKKnIyN#x?alX)ywGDkx3)edH4)mlJKHHJbcOR={h>A+6>OrE6b z;nHZgDKH<hgdMGzvL=E%Ds2#cH`;aLi9L}J-Z~cRguYFV1R8P((c8$v3D%yEDJ&6p~ z-Mi^(Y?NW-M&cJ!Lx$^AS*&t-uRspgASDgD-a@h)()>ZQ`J3sFH9 z##7$1Qg+&YMjhjYSH7CfgZc-#(as0!88?|p&gG{i6YUw|-mtmpA`?TSLX{0|AFISs zym5D3M=@Ejt5h%pAzuQ#;*{3mUh2WU#7wqN4r`C(`7&1ALFJm1QsMEtwC+ZacezT3 zqL!ADL7`gD4d9M5PdJ|n++IQ%)<~Rct!_CnHiHGb*{Q}&+pr7rdLe$h?^IqU^(_?r zr4H*FpvH#y>pWBmns*`h)JbeaF#MtK%}d*>av6S@#<8i~WPvEO!4V2=C??0cm8%-tsc(9Q%LAmp( zc4AdB?lkodc1|@&Sv*?d)wje_pzP|I-0$MlJTfb|BJKt!r1>+XEI<&!^iu!juPT~) zXOir~qkz%=!Q{F(F;yGlI?GjZbEtiBNe73D5r~J2r|;f8s)@f zc$2hgzwFZ@kIZu~`gSGXV0Ya|ebVCV5n#{QKAZ(Bj-lFiWK`<00K@AdPAFtcqCl$t zERiiZ2Wxw0@SfGi3+AoMZ%7Tgi^MLx)F}NU%!h!(Vkl+GS9kRe#>%Glcq4#XSjXs0 z{Y*-yf)TwwZsvfib%Wsh?-J|ntGi(bWv51_eOb2d{p-{>MD`avXHv3TfAj>(j*+T4 zK0YU8LKLqNzh1bjZ0oTj&dHm)t(j;hxm;BHzw1x#Q%sN%I|{qT7hqJl0F$A_LKqkE zGizt3Gxc-3G*8(o%te*y`Gut}e!7sAbcRRx+!wY_e=S4Qzmlwd-&0b$&O`4Jv6a!W6v;2ZT;3CV@ZGg zpkgOQE&j)(D~LQA;}_$i@RX^{QHG+eGK=g*Gs+a~nHer1!!KpYNI%=FTvwqJ>?tGs zkvDZzM1S-zmb&h|iz2|@BytLwok5S zzjJna#Mm8Xdcs8Q|8fFZV#bm$z?78qojS?EN*VrT$B;Vk;YPXl6y8QqjqI z6fO3$ag*!v`xbK;qny3t2$NM&OLYqqb$~Q4gLNm2Jkf5nOR;9+QA`O{C+2PBqC_+> zMnpN2Q6f?{idd+e2;(wEoabCQf2?^myUZBYA&-^Xd9A)I)jw&=n4=^dK6SYMrxq4t zx-#a<8y;!Z-ZPWR#~W#}|E#7e$93O&zAw_1F$`11kTot52`Z(mZ9bYp85T9j9MA77 zRDlB_w(fh}zqWd}Io<2kSvL`iy1EroY{(qPcbvbUnA(gl*U8x2)rcuwB*9XdAG?du ztV7QBe!X9S5@yVhA@dzc>a4@~kZnHB^r`6{hQ#x#Qtj-tA6dZtu9wrEY5JqPV|sM@ z`?m!`Eere^>vI2F(cUZ3mhq4OItC!SnrbA~Ue8eQ6cw3<5ND0`2(d$p&=fHy#@exM z)81o7Sr9)z_DVTb*)r}%^Y#oPYx1vkL|68+WayCzxXxOoudskCxZ}PKS}L};Ih@IG z+}YcW+{Eh^2nLDMDBASPmDCy{9bAW9!u^K>ZyY=bJw;2w(08@YWlaA;Jq7p^OkA+i z8^J6 ziRs_?B#yG$mbrS}(3|v;zOALtYK`+1#MZft#9G&Kw*0+G0zFc+@kssB0R@v`x66Wh z_fs%t_bJOMlG(ZvG!H7bH4gqvuvvw7RzmwT^G-j7f#m*A+#POzs+@<*Hlxd)k9Jdw zX#?u?c2{MT7LPUQuCIxXekwzXjfq%sg-A%;%E6BR9O1Oj?FkL{hAx7ro7%Sq6S&Xi z7w7k`zBjAYvQ8!#PNAt-V;P@YX7e=LbqpbN{U>ndRzWNSp0va)SU83d?B|yqcl0*( z*szWVV2tH#_pz&#-8N-luV|WepV5yS_c~B^N!R9!VPVH8-Ge#96(N#ePQ1A>~ zt@*)iuXvlo$4!kOCt253Pf`}~d{dxPUP0B|GPx>3ZhkcQU7%evW*5Y7TyqWdZ1DDY zSrX0r=1}s2g1=ZPD&s4bmpM_cH0!H;WBv{WdqQOP@@}Fc{(2k7*BSiI<@hY4JWI_Z zS1}S|4qbt9jlE3=556a>1?%pIUx-=xSNM~rVu9HVHf*hRHc4IL()c94tyG$L6^61W zgALqugv*8chD|Nv)t|@9%Li{P*^_$(s^n&5(3xXT#;whL3>-l(N90+E;$hwIG=)ii z)w|DibjZ5#nO$(0lL5?EC zyixmR+n4kbK{!AHf{gQ<+p;cZnt508^vQ4LK5J3I+d&`hs~cS&RNmOZ!N!Tu>n+lo zR(=?%py5v+5~Uke(>Z@w8KZ4kHQu>NP^(>0cCDHIFd?OVeV<*F}9%ZtOD> z_3kq#%VNIx&9El3(!Ur&R&HY9B4Ux~>bTH|XvNN}#f6gJY;EGslMYf3Me{$pg#XlW z?$=+(esH}{MwBPfvbyWgVWaq)T8E8TsDYzBahlJ5ojSPz6mgR5TDX`>Q75jEQv0QWyDzfkYcp78@bgoz zmOo{ZR#j#U|D!?dc$kqMjRjepPol!VbhK)(S!ai)w|;cGpYZ>OnVEM>Wwxa3$Osu3k+^SJm5?nv%E;cE-*H~IUhmKMcmMHz zd_J#S*L9x9cplH=ILC3<&D3Ff@pCy1Hu-gDSIc@?M|x&yunWgnN-lKZ8d4&;WyonM zvw@$dVahMAsbbM33#!A!Wq|MhBaPN5Af^&P`8BcBkbk2>CMy@gY*pF6j zh2n0D;yUHsyC~f>`~D+heIdvX^iHKbQO7e!> z9E&X&dDRMHBOUxXa-Tnjttlx;jM?RuS{O#GH7rO#W-~lBBa1>7;Z5J32UFXk8m%T` z1H~r3X$K-sxd~G*O46mb7Kn%D44#P-Qz^6JmMoT-o3ajh}NH_!^ZaN z%)`I7NCK=XPSf$0y{)kIY^rH}r;_^Wo3Hp$!0kYRqZHZ!1JK#~do$LI8-5r0Rr z&v-1i9YHX|9g;{j|Kq24=B0%5WLUaA2Lz|Oe&+`C_0%HMppq3lVLh9YjtCzMM9GVo zTk~g~_Oo7PCbqan6T;InNmt_0B{wLFt2Bk3z&v77)8v9Yt8D1Oh}H$aS_&e z@~*Ic>iCXUV1@Z+_EB};W+tHT9gg%4+L*Bce28L(kADK9DkBGDiO*L?K|maW0OLZ~ z3G~;*#>N_ljQ@%^SkmKH;*Ti7URVdT8RI@_-93Z=5R@`FeRCsmh!3PsF`*OJbl8Zp z9RqFZV4B>(O7YsnxAn_#lDTT${}1c+PD3J0*daoC&Y=YFnml8JMSZiZwKnM6L==UD zw7ar?7e!uaa##0BSL5uog_Q===E|~4cuLB0y!4g`1!K%ZG!)XRxZL|e zSOTy>wTBQq6mn&~o3P;t~Ts zA&b}e2ztm1A3G#{m%8K`pX@UhASb2y)3hTGapYI4wo_ zHMU9E8`Ve|6BwE+%8rRoUa5JmM%kiV>3yZ;y3+ua*-4(+hvN>Ojcqk7xW>02E4$|f zzRaG%3rL9<^j!W6i^copAz0yr4=+4$iCNXP6}t%HRmq9j+(wS+3( zqeSGNZODxf3Yc+s((BuUYB`ONCsfz|r->nVJb2)_#fgi70#H9uC7YlD6RvX`T-itYR)-yQq7nSy3A0*;w3TF!p%#k+gHb2>)di z?*|WY42SlQDN4pIp4?%97S%yF#Q!?9U&@-8?B`^$llqnM z<)*a`ph6T%<@I#sD_Sr9RXL7^K$wXa9QtD@3whf67TC?DEmEU+U1mYHYw;IT!OF0& ztoJTPMqYUzljY8}<@Zvn<2g(6l90Yan^a6&1B}h%Ut|hza7KX%`^#?zhinf@kN$Y| zI>@zhrL8xDzlag45VlFZkOMbS?p;V-TT}F0Vq+g~mZ=U4C z`>}BKM+Mk(@=LStwRj#7AKLhjnFFcG*=O}%rr;-Sc~W-orig8Bm0nuqAI3ax4xn$I z2ZN)O`dH%Sj&dLi0GL)-DfJGNdq9h7qUe2m2|try55UNY^3?|(oI+QiMwE1CAqXrv z=>X^-eo4Njmm$lL=Y;x60K(@@>>dNwT)myM-9abHH$k@j(g?Dkw8jHX>V`d=i0`ey zba`!ef#gwyfQpL%io~~E9zd4*Lv6d6(U&~O$ZRse$9MoBC@TDgg|1@SF1I8mkcnd$ zadMD1ZK$!34$7#w6>gP53u>aamgcPZQ~iU3*KmS&?pq@+9e60dUd^}(H%vVo95=Ch z*~^;d-&pxk5eWl?j^YEZbuLtg1AQ@*dZ(aD)NpC2sWjSbynbR-%SY0-bMd!! zd4!rZe3Z!7ra;=|YTd>fX{&hP07qxh*}|AiRKww`pm zTf%~*(dzkM=2J`JO-_gq;GbCc)rINB8_kq3i_531(K2WLCliBzwERRyhr$xdhZwr- z=M;j)y9SjJaeW5K3qew?(0h68Lf1YRMw@myO2nU`yHnwpdVZkgZ@vXB|>^a_~7k3`N&W)w=}!eDf5#Ie-S8u zea!nGv#3L6^v3}1ZyXm!7h ziBQe2+v|xqHp{0KLqN+i*l=I1iT_DX$6j@-0rL%5+&bM%evKfr(!p*2I-wvIT7JN> zSr|47an>!ojcaD`f>PJCWzNMn*ND2|CqQ^W5JD*#J_VhJ8=b^p4I>R-j;LuIoOvMA zN!P4ZagHtFfea6p;jUwZXNG{f3vUF68vjFGkY6<;7G*Y!5<*z(j_0C5OXP}D{a4R9 z_DEvt0T2buC>lG9qx+n~4zSxgCU!7f6~sDK@!8oLP<6vP*V@GQ-rht>8j2EVnT)X>t22kGo} zsTk4W$;T%`IY&Ud7-ryAxX#3oE?ZLc<2Yt6p8DqfIbSn94``**8CWIdEV9*Do>;qi z^VF$S6S3Xl61nDlDSJf3F~T-jpQ80(Yayq&NbM|iBh;9su$3F0nRl47JEPHrvWUyt)~J;kvgdV!l@9M zREr5L=_g z+VgR}fZ*&xc|c4AuRmihSq&Oicxr2T=KI=uv32KJ0W9bvA`#!R{9#g8H6*j%4D};V zA=}D;*z8LxJ+Y*nXl{_{ESD#`_r^&RDOYAuLk8i@JwRz+eCd#we+)&qTouqjl+Vo>n>q#G+sgr zu)ac31nCGY1gt*3f|3~`j+nM)q%jpC@fNjG$g!IniP0`)7uKY07k~AhjKB|kXy5a` zyvaV7bI2E*k_LsP7l0Y!m|{+Yn!?*1zzKfpNXldF)&?Ip5&6E>W6RmA`+F3Pab6ozJL+x7lbrn`xr&K2AOfMNsKpLq>|Qs6>o$kJzcp0E8O!<4ABo6 zOk6Ft?UdXBu?nckv(^+!ee2)!A?yV`1X_f%$mjJsLWOXe8klN)V+(BGUK`+dE!*TX z`_9d6>GO_jxb<%{5)z^M6ph;))$jpoj9^$_HBHlv=MUI;wq_datX7oSxr$+wy#NcC z_MvbFBiZK;MK_nY9XikZaMG!5A3*Gj=uppjkcM~&w2u=h;?*1@oIv`ZsHK0ij;@K` zCe_3H*dCJW$jC`Hd}V?q$onR~tf18RQ<(-Mzi)j9pT~)3cb9;3z3FdN(5F)4r-^$d zJud@CUI)6)C|U=WrJYHaYH1At<(L)a#FDR6=`n|r zM*f^^`_Vi&+q=XtvhSM#dY)`QO><)lVG|j{a0E$p;a6L&ZjW_=&5v%aIzgB{qKkUf zXN07L6;@Kx{mdC&v3_%NRlrN3kPEztHlT{Y?bp;j67ItcsjG&CI7%3ddcljyH6kPA zb6=p_9#B&_^nAYVU0aU_gKaSX+H6$2`B4}4I()eaUetm?r$h+&a=1k_IftXWE}FuMvY7?9WjcJv-(##9UOb(Mck z&JQ?_2aM%#O-XrAv5;G@7_d{2`}V9Y=l42#N!D;3#2**gSqaCo4p787cw;;8==jDY zRsD2jp{J!Rn+@pgY8$h~%4+<#lL0JYKFb!d|K|;9UuyM$9XTyoF3kZnT`>?O!ks>a?Ok$AbY{Cw1GVFM9pz`|ZA2^HMhj>^wy^(2u>>KQCI zQqUwdsbjAu^?2}-on$9d@UQ{PVjf7q_Ql6RkkN+)jO_S^W5@gFy*qZIhhta@VG#?# zXbbWIzl87-8}MY7Z3l|Hx}KfngiNSh1HO9%pr%_IQnUWMIMD#nu-)BP347W9J=t3I zOA=E(gCAI>^j>12*hWkV21DGv@?C_j=SR-F*THQgZTFzS{@dtp z0uAwK+XmP>#-qUfM&T}c3@byKKH986))a-$9fKShw)zRd7G8uZNq44c2$i`Qc~mEw zQ78I1dV<(9?Pwjc&bcG607H7F8ze8KfNDM;sS|u9u1VG;gQ-4O=bh+ggGmsy65eN5 zc{g>Ur(p+#V`?*6oBm-i0+yo9VJ8oLvA+3Bl&g}w?L6mJd3%E%xRzg@d&To4UsIB1 z%h2aP}91_y)T{x&t)K=DF#uq42{wWnE zd@RttwfE`=JEj9b?}VhW2$oT(`d;EwYa9OX8=c8PR)O}F;!EYXT<~WkxF8)ImFdXt zH^rw7GNaIN^85h908;l5FXU+(E$AusOSyLh`*Cnkh1=ftkl zisM^Cbk06ac+9i^X7K6C_)JHxpvY2}%lm?Rzt2A{Z4T(lnp0RI=51`7DyngZquR65 zq%KKlsBOp@+H`TPUrVGm=0xIsu>7Nl`9I&$!HohFn9YpHm3_^P#jlANX3Zh=72dMmAeUx;`^wIzzcswpx5pXTJ0Nu3SM+MjBjx>TI?oPeHgg> zEBuyy#&#@&z3&$d!NLyy9?KA1jKDIWPD*Y1)c+yaYN^;2-#q}}=0LH|OIeJ@+20e(BP}VxaJ5_^xg? z(>_lzJM~E#EXvZfVs3No@q=jaWGP=RZk(49@FhiUbtY@BK^mlW>mp@g{9oK;q&+tF zQ|8JcI!XF<0>X!cR@UE5FnQ@#0^K7Tz`ESxSTy}vAsJ7h_~*zH^KK2DX5#Kl@qOsc=+m3vMyi1w33k7N|3yyt7p*m+}tGmzuy91@D2q-tpF%FesS*mP|pL5y-g|aobam#{eHCR^=KCmK29a*fU@m3pai52_Uix z0(bfl?RIRXzH9z^X7^Y$dPXT^BVf?6;+Q)S(=Z8>P?2e5-s4U;XE&SJVNia6m^auE ztEIRY&dJZQs&OR#BWjA%;$jLer>(AAmK$0k8h@M)Jc&&p(K+2_A0V98Zgza!G~?*A z$g9`_a_-VJ`r$2-8;;m1-HSOO}T6EDBtOQglEF)fv*I{?>hYe3eA{{%M8{mDzVU+J0muO-u`f^wcQ^LEsj zuzVF<1_vU$E_!EcBr{m21nQoo{Y|ca*v6jnMe`$um~oYkd*hU#`r5AHD_VP)CpKi$7lYXuyD;5dQ|^ZxH`U6rgV;C~Q(svbYVR-f4A^O<-Ix2G>;sRePI z70R1$ce-vGdJ&FWu$}lf`kcq$CB-*sI=_d{6WB4rRE~4`cwzNAoU198); zGrV?l3Ve;}?Ni_lFM0YIV{!8=oxH*0DI^0zP-2}5kpKLTA84qoN;Zm>fRVSzA_?uP z*Jq_Cb3ix{z7*}zojGmgjurnu>@r8`|+55`Q~0?L4?Rdm;_CyXTAJj*Gjd`U_+14U2#|W zakq~{w=3!k>|~#;*7B#HZZ`8iwp_4*4EyB1%6JS#LK_>}~8}l+E z=7c2fz1i(I$4cT>i{O3Z>aE>a(Lar9AdOx_V83}ieh{e7oW<25AMGU|G60D_`CZ$DN;-i9^t4h{2c4J?t@>q zVBxed>w6>I2$4f@gYUYX%Q5mH?wvPAcG)6{&21o~_Y1%9en|2PM-`&|WGfu8w(vWl ze^XblR$etls0HDWe;D~HSl#~-Y4a5n3om5tl8+vy2}XMbU%=%DF`j)s9>BHi!x+t=NI^=H{XE&D^y?#nNzsh zSRLuwXp8_8M|O7buaC$LV&~hmgCL<6*>prjlDBYZyWB-{PPp1mLr?|EE9O7C+r^zi zEQDVua8nt-{ojP^Ao!CL*c=~L83VdV1>R!v*f+3l4r0GI5>24izJss?*9@L>&ZaUz z%4Mn#X2ERlz6KIfaICobHg5kg(`#SyBpc97?;(d!zRyOar3mI6zFtDC-yB`YT7>7X zabNQ#U|}BH{~4FMB@X)5XwNa>e4obfunk_*gLm@ucV?h9hjsN>CKD*z|C#CoS+FQ% ztBH(u*gD{wv%Z+{D0wxc1Xqk&bAmzgt!~DtX}#z*>T$ydm>&{WyuC3EXG>c$yQT1|1mF>4SD|qve+=bmJ_0v z-2lJKg|A`r@n)`_*Gcr4dY2q*9vXO%{rxT2D*Rl;uS680Tww=Vj#D~klX3sbYsBXs z4f;CFW^^q)RjU&ZMf@_#kZl_#6xzF82t7!&k$?vqLx7rK9%!XS>D(`x?oR4cNWB3& zsxspq)RETGto+slu?)jls_y4H7o~jgxt;rM%%+dlWH;mfmc#=L@;3V75q4~~DAXj( zd#r*a%`R_cI_*kDtg5G}>C`!ULu4Cw>P9r;FZq&s=zFIql*};p=s}Y)ssk8SFS4yN z^-QPYykz=(*qXu*{lWV+(vpP(El-^O-0y#GxDU&ifB-8?A$P*Qe?(mzq{8Emp)!FI z5w{HSV#fO>_-^FEfxDseN8+c2R!67mf(!fdxl@4>Nf=TQ)*ts9=AGnx|Rm!cc#JUpb?^d&)LA7O;PP zFa)|Yn)uM;Yc~IA*gyu^*f5bgI|d_3c#LIPyiVD|dmR1^+to-@LhtYW>P7KgZ74y8 zM9>r_xWIg$i!f~OQaci_jLZ{$<`0WJ#3W(1hjID)NnnZ3n`42Hr3hacHqn4&;p`2^ z4dlZ0IC^rr11{|b)1XY?Pj>j9>?EM>d{@M=f-kh#)*D&Xo$JWR5_{nR4K27U9@Wm- zgw&ttVLSjPxg)YC^68mQOi5aro-7-={^}CY)pxgxv>5qC7Wi6B60ki=fPUPFMP#bd zV339UFQS)aY@-|>+JTPR0vc3vmmWuWSO2&k8%A~(U&SIYnclVfb^5kew0dQ?`6)Ev z?r9j-=>Lo;7aa=#X1xWI3^6yrVgho%wq02M;j?sl@d+dh7pG|^ka(4jc;!*Ky}1u0 zDD#sXaM>g%#pAk*W$StUs#QY)(>`4gTzp_Gf8@&IPuI?bEx65YeH4|02Q1vkV_Rjs zPv?JuWRfB>i(#nLM`>37Y%`k)=Pcsw07h|N9{~c^cGTVVx;+5NIf^>3WIslLL*To) zfy{FY=y^k+hG*6NF0T^z9aCYMUwk5#f@hjQj14FP50ZS2pbM6^Zcp z+|I7uV`E+3KCc_mQ)Cw-!8m#{_fY_wz^foYfIAf|uaYvx-@_(WFw2;jxCgCXUTX_N z@=u~#2DiS$8GG&pCpUYv5b)1=ljoVU5O9!BZ3E4+p1cXGpkLJlWk05m0lgcQTQFGv z=B%G7do^;3e$vw@8_q98z2iOBaYBXzM*=v>m`7V}wC!{6Svb zucVu3=2_xAXlPNB<rCjvfw>n32>oqt;IUY98gkR2-oQHDZp)%k;7 ziWAAxkwWv7k5oaOq?!gi91I9aXOujF3OmaY}O zoNuRgA;L$0ppBNZ?Tq4TUvT1_&)+K-1tY6)`wJTQdGSvt>@wYttj^C;w0sv@$szD9 zauvD03j{}1ahfNDum0js-|RD2t<@g7I+5;kaAh3+C(`q`-okwxC47hOmfY=NgV09t zN{!uJmt6{9z+@A+pvY-)dON06IwhnKu`;rx=;gCWOIrNpWLdjsT^vONjla|pTCRgk z!^FvNf^o{gNACMjG#Iqgywal8kKM?8%QS6t# zfc-c;Jak`GFd{~`4A#SEk7h#(hUzJ`7Iq;XCqaKW=S}{49jo4gyWj8Zo&uf{YLaqZp)7CSb-!= zONA0R_~NMY<}yH8Hy+XuQw-0Fft`?9$HVp*Ki__AsbJMaDiK)-QJ$`geeb^i;Pk3E zWo}e4bMsvv9Hk5c`9RBkd6dLxmY@e~QB# z$*&-LOpps$3O?--wY9w{1MlhqR*Q1 zpsUYt_~$Me%KQrHOxY8@b#VQ&m*xhDz!XsbK@TJC-N}g=Jh2L9-@?GXUY#iPm&Agz zcR;?5PR3wm;^(cyS?Q6+lBbIcQ-CTHLR!0HitZoxLc++fn1Jup(z69c4=KsKSkRyxw;cz zKL$AZHtTaRZ@@BM#gYORY?ByL@fn=Z!D_9v2X%Cz=AX-m2 z+sc!>$MB!J+3vVLzmgp=`6-j|ZimST0&zm40s28E`_4;M^+Xu4(blWU}XCZ=%`Z5x-11Tv-PH zdBxLp}9v60WCJKJD zX~EkWqVi?`c})*gSu^mG)s2C>AZPUQ`?2)o>Ou6^1iKfNSGV^0)T6TLItE%n+zL~M zBJM*$%8|HKo#_ZoyfIukmTM~_LtJjp(EhJfoop&M)pZHJ zsX2|&1`k1`M<1AMC44!a1>)4LoyqiHMs98J`a0IKZb=$W_V#CwRG}zBp&t$!?6OG# zzK3C;=NHk|PGNSN@d(>m>2*I~5xq8uPn9C^FhbVpP{+M682%j{1rj0L1|aoy+9U;W z1&AP~6F3o@B1SovjFDMhu&Ux4l-E62mzIqfCvFKIbij+Vt)K~c|JIyZ$B*5nxQ*mC z0_~Ffd;-34eccBT+_tEj*t-Q%yimqPvzei?fvpLDpx`f5wSE8Ndk(cU-Ird~bzcJK zXW9|@+aw>(&gmcCi)kK-zkiA1yD1Sg-9Nu0co4xq5jvA$KaOB?29*(CKFvqkgS7HM ze||W85{sqyIPdQtGiWRZK3?`+e-VVl=LU@_Gp}391qkbD+y8~#Jf1j1v`$7mf{u=; zpJ`iP77&>(_9%I-6IRvE4#5yDDJwZhb3G`-2RxL{pgEZaUnB0e6r-6Laaw=1BX*4_M z4^XD2>TW%%fMuM3!P4EOEO%c38iSvfKW-WgMP_4tYJ1_+05TRA!IqyQndh_yILfU5 zwW}J^cr}LW-AXi!;+F=F(z>4zWh2~gI1jdKgQHV?ZA=6AI0@65GzV2j6?r zWTZ)P`j9@>yQWk07cq>o7hsWjy-+ZG4cH?GQls@T{9Bdq|H=tKnYhrIm8!cOpM{Mk z))Ir~TrKCT$NwLtHaFmQBZtG`<<`{yCh-3kW-CO^mXZ?~)?^H00@Y`n1>wm4)9Oi; z4N|>^faFHiIKqLOECmQ}f-Lilw1+;LaY&!WvJ5Uj@c*=$E%^E(g=zG(24LfOK~_8z zwi~11!2i4+TVLoeFhcc6dm8kgwT*SlKD>&2a35-5`CKVfE#P(;GKO~-|H)lax~2o! z;X{glhDAKMUx@$p2e9UVI(evA_pydQVgIMplQ0<+p#B+wn?Vab9!)wI1LP_3>}K^K zGjafM#uP4dH~d&>>?Z|kEG93(k5kVDH+Dx5hO~z{EbX=;ID%jKV+ZG#maY%}k)j9` zNhHqM`ANcgNgMVqe}VPrZ9-oeQBcANA&jhoubAZV^j^B884eT)goj5#GG9&zC87%Z z{=bl7CCb6r4jqLIz5qdlfJ~}gqN64SQ&>UE@le9u z{2rx*c@Zzfst$l+3R3Ys6NIup4XAQaq~VhFeGA6M@sCWE<$%19P*d{-;r!P|wmBHK ze^et1Oh6_^ZwA$FV}R_M0?2AwgE&Pzk&@~f3-EFRw0JZXTk0!&x zAD_0by+9b%*rzcbvCd2WU)WKp#WR*WowHAR2Q4}sj28dKuK6ntJ-GUDsJJ4_JAKQj zKb)cW|95+ zG#Xv`c9>)|W^M-Cm+?hOp!Rn80ldU2R0H~kAn#oElH5DbdfHKeY*^1~>ELW%=spY| z1hXMq=4gQJeR(U0zDPWZYQcD^6ctCvhiB`t2%WQIOATMA$C><3q)=hR`lS|mGmby5 zI7?u*#YWfZhwWm3d3NhKVLfAFQJ%i^%dDBca{6{ngaAsaqzdCKs#F)yWnSdus=L7c zq=i5gFwe^0$FOjAa6r7;7MC~qIcsi(ZLDbK6iVUAqd`%P%xhIY1>%v<8D!d1%2j~X zmMlI0kD44huByV5oF98{PtQLyxebL1@?fOo3F?elGmOA~ikb{-uL`{r00j`0o<(qH zUqmiJ(ecE)nu5b7PV?j<@7}Mrr_oDJ@Nd9~7B0WF7ib7fpQwn=KO`pPA2Gum(R937 zwXgz(jq6ZwZl83D#@e8V*{89tTd>}|H5FN&S!$n5Wqbyp*sfW&s=NsY3sF$W)}uYYd<6tIK5`h{~GIZ z9@?X7up3r=;%)C?IN@i{cJ|bI|F8&O0VE#H3Xs6mY~jF7u>@G1*x#IHIo{=}B?V_u zXAU4s!m*bEXz-$~LE$YX(#}o?W*n>&8)?V(&?8KR>&}3+G~`rNYrvA~RoR%4lQiO%%QD%i*8wWMBC*Ui^t+`{SSNC3XM} zwu-4@Ir|TpHTm~qY5XW`mLgf%mlsY?PStJd-?!PzvFC~I;M&UIN$z)W?88Q~JcAW| zPv&L+vGpTuy;YH%v9hA={nk}SanRgSm&NE@(}=4)`H63X!47onM5`niz{ zx>i|p!=PUc3CV_~dC&eDceN`VoX4jcK2yus;SmFY(ty_H86!6OZ7dKyN_aL6$@Du! zs3~&#ZY`lEc`X}Tt3EmxUlBE|VgNI1v%I%~0HY!tMP@tsjO47gSB2#<@&GLSfV-zY z?g1#FCWe43Rn*C~oR}=t1ioS$ZkHIc!xsIO&6`{U5j~}8{f>lhsIbUxk8j zNuJ?kuPyY?>UVbkbH0Di3cSv^*(^%(p!TjPz+m#|4iDGCZc^cNyRS9|9^Nx{0+?F6(3W#{51tf_VPo`^{A z-Ume@E97)A&`NU4*tDMPafR~XvqbMCHdmQDx08MZC3RIj;=FfYtvsH zm_f<<4^4k4&i#B)e|}HYv$T)n5l(}*Eb=pGF`i$^{?*%krZ!PV?dI3*`Ae@r3j*L> zdT53-Y8iDxd3naUoYH*J=f|x5fKt(+AabUby??R>*5HmDow`8uDSlU5g=wAqI zTQG8K{)BJk=dR^q3r_V4(sU{QFq=~?W-lxSJ3h7p&lXgeBMhMZnfT)hdoc+D5*Ti+ zkK|y&^+FUH3NCpkQQX5*;WiSU*w=QlTa%s$9ekUH!tiJH9E8V(5{ug<-B} zxNh8aZHjv?A&nEqif}>L_K%>L$@y#T$=4*b90I>6J{dyG47^zy2Uaz^ykGCfC3!id zLlm4UsBs_FkQBJPXWAC#{0K_VoL=wMf+H>lP^!u=69!f;k9afw8+Lp;se5?Zk3V|% z>gdt+C}54Y>yUGy{;LbORd(JoS{z;p4$Q!P{AGfI8%ZiW-wb4qm@+YEraaUPP~vWM zzGBDPm$$f6B<%IQx^?@2W(b`-+)EV1F3+;s_d#*?{`3fG*{4pZa4jgio}N2(E1FQk zA$O8N0eT-rheKl~jt(+6ljyzb87il9gF9tW=xsUWHSMAhuZMC49zH1d!!ErQ(UrQT zF?GeIY9qRID0soUEH-zF=s$)1?pHDbAG=ZyL{be`0P{%YFJm!A=UL%B_M<9Em z&CStb33i1aQ1160VHgw4!u9hqi2ysBkV#M?*E?9!ajbU^WvBO<>kA)cMPb%DcED-$ zxsD}z%a%4fy77u&AL*luuYXVw%suv`uZa-2H`?1u%$X|>VD6slbP@F$oQR}|msJ#Y zt1x|prwe`$6nlC3Sc<%U&?32jl?6}W8%=@@GW+TzMOS-KEs`O z^yL{8-9XkDxx<0IOiK|`aP1;Zlxkie972*5)~Mwwq1gs}j4}w<+1or`aC0~czB~fpvUNBQ1ZLUiN1g8wZyd%-T_kWQ1@aJ6W%mlrgLa$>8NZh!vgl zlWuh5fZb;9zZ)*!+YM)vj@-nrJ|ezdTBNJiBrTM{J}?e{hK_#=>#&wtW`K5oP_Xvv zd|K!}HQKNi=GlhJr^n`>QSz|x7zWLL&B2yCMtRtd2m*0GK3EET+!&k z{!LHXf3g4bpW~{33xu$+T=mY(?O?~^{Rb40?B~bi96==3L3gL-b22HcrpA7vwX?g?05QrmE9|CQ4Z@9aO&hB>h9 zI)3UlE6pgG{SrY*b>b!?<2aw#W_MLqy&VsO$eX|P#9VUNFWG&^dgqq2#Qj&e)DoX{ zCjVV6KFIUfsXt=+?ccOT&nVs+^9yU$(suoi+!sIfFL`i^AvzE!2AG!QTC#PabWYOB zoifuTvol5kt^OGH2JK)WKYm*Ir>B%v_K?D8HLq!4V@DyY9)t*Ov>Yhr)3<5lK zHWJX|EdphFD`nf@e11$H;ip23_dVUQ_#G+mP|8P95@ZRDPb@dscgCH^ zVsf)lS4sH6MnFwQ{P4{FO?GeLgu$CgVe`cA>9w6d*%;(L9G)5ijkCXX8JNAY8%q+Y zIzvrHExq7BChBY=!p;vk*U&ExaO<00!V~Q8V59NMtiQNRsCpUjM^7~jvoFTw$EvV? zUxb9J-|XdG$O_l3=iTea!M$^w(F@M2d3oGZR_J?WyJVdtk-3Q{9J++LIe(xy+02nD zni6!=!n)PYWv;k>Ti)y6S|Cb-EWGiYK*&zcXU(r^F-vtv^Y@s&tKE@C{~$C^;f4@h zYvEL+H~eytZMO;nYy*L;EDsxyEYwFl{4W-Uv9ASNqd^ zE1tK^@KzPM-T#C}^7R(nq)803?+J($llRHrmwDy9YeF-I#mFG#zyOur-8dsfC3WEP ze5{Ip(x=^>}*_ShyD`M$pp3rR2(D`a`0nW4pb?%~fhZeiUi_ds4Yt+9G z!)B6cO@Lgs%@o!%9T#l5z>b|Nxg0z;CWFT-zp&TqIrs>Tq>{EgfI2~}uMcuPeYk_yr zD~`C~(-gU3Y&1-&O!{6;N-7k~a)hFSyfVEzM$}^>UZ7m$qW$3Pk)7oK@I*;N`jU!^ zF44>kwP92`%J<@_7W8~|03N;RE-F12>w@|eTb@ha zLf$(Ku6u?FGwncoHZkXzYc1$LIc)QDU9BM z!N%_Am0zjJi~o>Psp_Xi#S@2tD0AB7Pip$k%16pZAvN7*djnd&)__a%XkdBu6u11V zEuxG`+2LM|Y+3tR(R{I2?AuEOJ68|2KW^sEbHpenxFTMyHAd*S$`CvjIa|#l7JEafW@+(THGUOBW3$m&4j6Zmc;J1{ zV+TLg7}ozMVT7Sd_wny%ZI6(W8I|tuo^P8QW@f6$RXJ5Ue(8RTV_Rf89WbWc;J$U z$bkb}-2*5#u+1+icpO2!J1awlfT8QjCoHs;=3fSS;qJAAP1D+lql&B{33E0XsvY-e=u=eDQ-^SKTM zm1FrKAgbMGc(H!*ek$VL5T^~}VNp6NA!t10?(^zTFbTw~j=fXSk@}jP^^U%tY z1NE7dcI-Rl>gpO@vCF?~V0btH^?HPMm%YCpaGK5)KH*j^r-gn9Qh%Q7qD#AjjprTTKM5@R4ton2Wlir9w?tw2zBdeQ|wsP^IRzr#4?GV;j|MMp+YTAhIBhIXnXe%wI<=lsQPNF6uE51HU zS(nTF@&*&ad*IURfVaAd<-y+5aa75BiLVbt*Oay7{?;XqEsmr(R4}Dq(}v1PqxRXB z7)eAI&VzJZXV(M1Pn|ke%_czw;00g5TL-P*@N4@~t4#fO7ef|iP+zk7mI?)CP=jx{+_(vAb;q#kk%THX;Zb?Ha`EG zCoW%R&=BQ$6F~B=R_1d7%vcyn?OfFsB(_~*$s3U^B@gjx7479+X=|t2vZiwC_Y4aJ zJ?P0D!?TS|LLfmiaxWN`>M->36R~VaVo~sPb8>Pjt&3Od4Y^?Y2>QK9F$)-E820mr zoOM9=vp;0y?&;-Rb1QG8*4EIiuw$33@jB9&Y3JlrF@LUvHV>FQ-_aXb-f>3`7|YQu z)Z~-`kAGvaIOkzuJl&f}I~{QgVH=9REbkMvqB+DYssm8NO7wq2Q>mf3mx{~37#v1& zno*0=Jt_L{{<^N*NQ`8D#;X+soucgapXJa~3FctGVC)trk;53)F4Ua~0+XOYCZ>7}2?`P&U z@^k8*%lEc0^(3dH`PF!hI!;LXOi4OGlcL%DqLdVVbQd|^6E-j~@J1!abCm!V#>8lE z_nb;B>7&gD%b;L&HqH+#iy@^IMVV;fA%+=Iqw$2kdsN-k|6oCBMs8wql1kCycrb8E zpf8Vf-tMZAn^KoUy$Ilr`HDN6=z7Zbm<4R2V=jGvwNheeAAB&gUQ@PAuwZy6xQdl} zgp>%9@zNN{$2zM@f^}_U!(EW4kl?5B&+}hY6-4(RZ-*AwrO<$i(QI`xw0A0c%`@66 z+H>;je6?#4lSS06K4!B$#Nxp^hB5Z6Xb<@phuU){=<#rO;%$We2767UdX1xjUpJ6D z%5^F4ybmv2l+Oq) z!hRAoq<^UecXV`2Kx?8>&eib;AH3|KPwXRBv1_GV5BBY>*cUCM9*<#^y#S8t(C+h+ z|KG%-VbaC z2yeQSdEW74>hN&KuzBaez_$$Kbn!3YfCw-h?G#@IHCD{l_InIo$4Ls(`F!c(%1`sQ z-0Np1&@qgSM5~s+jVZlNMs|U0cArEzpofF=ul5hVPD@)a*p43T&gpMy$Zt}tnW|Cb zM6HCa((-xAgV@=4Bb{_2zz{^BvrW}U=9yohnADb>oB775{e%C?ToaxRq{2x_pIEdj713 zKl4$)l=LE*Yu{foE)8dCEklP6wd@ZcEGFkRc)gOaxro}kc%=8zF#QCarJx#BP;v{+BFrmRB)jYR*+RKXI>bPc|oLjV^*hEUm zL~lg}G+^H&R5XA2nvYqA2x_6Sw7d!pX7f+Jvg3>*hUDDdmZ1~9_4 z`M55gR%1K^q{+G+hIvj>$yPLScG*1}`w4YgpN+%^d84Cn4{Mm!Wz<74GuTU@@B6DP z!`EFoi*%E-;y)$7E=V|6&jcGT70%Ai<}LnB0W#tm+#9T@;0+CCt}ME4wqn2eh0DvE zWFSzkCRC{R+7ix`*MbwIAgXG4T;vip39;mcq`q<|s%}Mr(T97OUANgo@&!55ExV%r zsO7vz=0@f{ElpBxbuZ^R$0AuitOir}s&Pi`gz$aHKr4rr*3h&mj}~xSz7JvI3fwx>Wz;#}0%G-8Ik{`SP#N_cI{^ z2b!9jGu@G7<}h9JD7!3zcV+-M>qWh_QOg?C;L>~b+WtZS?6fX%pl<0(hfrMDLWZoi zw$Ugc!PiL$Ru6=w4o2czZ5onaJg4e@_)xV^=n>@O+X(AZ+hX*9k

^iAO2yEAZ-u zO#m^YTQG*>$a7H}3RAaV_vsS`(i$%e%)PtR#qQF=H4CkaT3oxl%>OpL&4hk^Wzcz< zMRqvj*_NTXrvH7qJ>}4bWG9Z|5K1PXdsR8=?J_XBI(6@phQ=oEp}8h+m!Wqb z%11tQaYQfw=I!nA7YZ_Q`FY5}=0|j1-nUF7j*!T`n*U|R*=(Q=I@^qh-A%(l7 z@U1I-H}hZ0I9sBIU;cB@0nFjYaoRG8HfymM@u0opd@6x^cO&=O2mPFf6oi=l@#sU% zAh&}-VV;0G>awZpbTrgtdhf^sLju}~103LqqQcrjjjEbjC9z4%%c#)ZnPe3f9?q}5 z1#1*_KQ*~$AB65Q7w(lcR8F}Da7GSy>AdC^z$zl}BK7a6&xDbH?bx>%06bu*sd`j| zm6Ndia{!auC}8?YN@40%O=+NHXP&K&txs`RPIOLAP8o^2X!hw7pHO_Zk*LW zyz4S3Ma21UgA_Cfivw3iVFz^O+75s-(bl!<($QMvoqIEXpNWZy1Bw}_rOZ6))relk zw^X8?WqRvRhH&q6Ee6+n<{b-K8Q9&30xQo~e|K zI44H$thc&Cq7PI7BqkdLiA5&R)hZJ@9piF}*ST?be9VaVPZ~Y#2N?a4#E6}!(Hfeb zZP7v>9;1`)_~#o70t+JL4aEBQKvQFl@6n2iX`d#)y@cTXG1`3OV~%2*5y=|{-aFqL z91M+$NCA6H-Cl<&ZWr%qCapS0ciCOP{xH(DGyg;*rcEDb^h^uSJ6RTyr>_o+sgAMQ zXndV}f|5}vD=@za!&1Fq&?@Q}$8Ts17U6umdFC$3>TZS=3HskabE4fA5e_O5_Mf+i zc+QU}H%62rN_2-#@FAUG-hP~(LnG|nAKGuK378eh9f+-oUa?SIGHmyps+u6JHm@aL zTxsxyuGR%LV`KUKQMD~C2Cpso?7-D0z~;+gt(}>jo&B6(Xk2{!A;h7OF9mQaDnPcS zJ0eOYD$b{jxefB682&o#WyT}4fwtlOM4WF$2xo_6^~e0NK;14&AfYNy5e8)c^M(!^ z;)MD;Jykc?fe)QRn}!~kJpi_s80m5`0{AZKHEJ0m8Iz#?YA0${<~fsM7Ko_GM3tSl z7zZ@;e%LZTMnzKxeeIX%F%tO7J8kh0giHusdsm^od%k0TIUv@e{I%hhOcAfeX{q_{ zyXFAQ6MK9n_UumD6?0P^g&?g$v~Eb8VVAwSB;`4oH^1QMFR}FUYKli}!G~QXdnZ}- z@o4#zFXSmFz86&A$?QQ4SZJI|pdad#l}RYRgV5iSXStxLudfd!fR{(x^BvY!<|-gJ z z1sk^3h8)MUMs4Xq9?U`;7H;lgJ-+^^*?l7jbd%vW5O=PN7fZCp`Paq91`aEklnT9)?sK*CzA@ z+M}DO`OZap+ofQ|RX1bj#`9ijKd*(`^bBX!q-iUkY(rrLnOZOO?lR3$qdI+ba3jRE zIb&&A!IiIBwY81m$CY96>gdEqf~*@g=1g8M8J!DT(398!TV(j@5j<6eOA5I_&pFFb zk?ZWv4d)yh&Z(AtzE788vh}1k5FXTO%I|V!OaDh8498T0_8GoT_ALS;B8A!-L9@N! z8kj<(phcD^ba#7b2TTLXv-kIywhZ)xJBvUk^Y7_3-SxG#nO|#G!jqy#XGcpbo_}L( zUTfy;UF|AjiT1J3J;p5eV-vyNof@Eo1%id$MHZ_QctZN}e{?U9-iKI5&{* zMvRa3{RHZsVzS}n59ln{RR&zFxjzgk@s&lC;cGuWi|;Q*@E8aky_j?p)E|MXh~;*= z4?D@X(XYIYPwRMcAL$go2R(`Kc=ob9?SmwUs5!TG!;>_C`q!CQIsN)k+P$*cOmQ6 z(^DZUg+ioKMo8Ja$Et)Rdq(yyd)>ctu3O*N&mYg~ao^YV8E3rT?{kipm(i_1qmRHp z`cF+&G9|2N2n1WS(_%!77^n)jD!eN6AStQR)J8?<82f*V4DJVla|70@j;{2)ojs9E zol72H9HkUgi6|>8<9yuH(WItgoJS0WRlY<>4JXSX2=^G4v=JN75a@4LnSgTY8rX}tVou{bU;p9j}!yq~ylU-ydo^n)YUSl=lc9-HV z8`1DdFQwxLe&%cNhPD-3L}loaFzB{tv+`pr&k>_O36^TCMS!0Oezz^TEMGa>4mvr4 zQXovW^;XAi#?G3kr5go<`3v2GWo@pbdbfSv3&R+Cama(aZZmRu!E{Ga7^5Xv0{_xr zGLs?5xZ{Ru3q;-Hju7Hdc?ihrvUKWs6e00L^Nv&e1%qY z{QE!X9hP7$tQ3pX#5X#r(NwdVPOXADO*fbqI_NZ9E?B^6u+X`cabk|Ryj_T(>sXa= zym}SEuBiBMXelx90w~DuR9q|y${Wc%@-Y<*6x0d(23d1)vaQJhqxNnV38gU;w14z0 z;?J9|F~#mt3em{<_ohB&aZn%OyEEN2+jpUELO$nUAc9 zYvj+jj!tDw4H{5gA|S>{ff)JvMb<*uZOswaS<9HyT&vlDAUjiASY@`khUzO182IHdr@}`;&{22sPVqJA@ z?PPk@pIJA!XxBX48KV6C{r3ke+RPu1s#1XLU^71tk5RFgy=6_yW}6$YS#Q2QBqFb) zQ$t)_Mf7L3doE3ed||78+V>=+=e4PY(vy31u~$YUo;&(&tKOIr>-3@CDb#-ae$r1N z5BWo<#d>-6tzlwXKg~hN*0tDxEZ~bSA5Ys-l8J$~cG$~A<)e4SM1L`tgCCqDmr^A?Z+WyOyAA`%6C4DX zk`G;AtSc9exsK*J9fyClna_o7VS%s)Eut`3MpGLbN^|d$vPS#3Ucmz!sfGJL%BDqA zi?7_@aZI(FkTo9>dro;KRpJ%Z8rt`yb)T|t5zDj37fum!0j?~udh6~BdP!2pZoDwg zUkV@b@?vlN&R%xDQCiyd>o4|3qd%Jr%QM@-=k$2cd#3f|)p3pY6?ywVJ$6lzQ}o)r zFaL{+ne987f7%k3tLT2DqD{v@dTYVVsi;A1ZSBsaoDrY?nm1ap@0*U8eSakmF!{Xh z2M9x)7sksDXs{KA%--jn_R33d=bs#ZptYx&4#b)Rw;Wd39$~)qXb6~|!;bRm1IAi! z`@Js*p(fRbN6Jzc6V)y@|Pj zd(weTYcba^ODW^RudTPv8Qvm%{cE2?1%T50;EzI@&BA|<7YVcYCUeP%)Q&5iqhlc0 zH+)~|iForsNhaNDXpwjDQueX@r9Zulzo5l5C^BO<&9?9F!)TNZ2LA4ScC+p>+T*FL zy`kkLIJ35lo8opiKHmL4my2msJ7pxRmtTE#A@RA_VZ6G(t80+EU2r@F_#hL6(dh-0 zL2JoP#BQY*qH|8X?@{1fSc&N$ahdNmMDk?%L9-$VsoIBGy=*ANkOLe7wP`dPf^AV8 zEx1-gLk95ey58xn2QRJfwwJKyx;V9Osx;f>o~}z zI!#%RXZ7T@aUGC!HA?6yrHdtb-uD+2#}8%H8NXtJ$7wY5Z3ORsh`JK3%KfL+~X6V2x@=H3GUJ~g{2Vo_HN?)C*BvPV|YF$JdZ z2B{pooQtrj;r=rp?l_%*#_h4Z%>kDFQnfC__um|zCPnPN%87%27;&rvXYBFF~7=w`N2`y$-APk z7+~@3?MqV`T`&dJ7cA@B`P}W%24@BlYldl*vF$e@ue+k_HeLeHBhAbq`nFvJfuz`# zhK7EYX1=8-54re+Qz)s$xLNTBLd)%%led;`9d+4z(UGO)v;!h^lfT|MS#pSdy?l6Q z@4&#>@u}VTC>pAKC6dS`6IV|Wnf?_|h49&4jL#!E-_Ji0zaBN*+4jbuxzpk1ByF(B;Y=9pwskk|otIecfU1g$ zN(9WPACH{Q-3R&9MmU{tQ-9fKWh`E{7!FfhxV;-)Txp|8RO@JV4a`VL%AXs66Wy-w znn(?$Kni)`wj#mM_9T7jO+>PdT@FeiYA3i0E)Lc8*uzcQdUnGcqfjP6kgFC6L&wF*1f%KH`o7W zdfsMYW7Lei+n`Q+e3Sg3%Mr*iqzhzRCi+ax&Er*}62fB0>ne3V?J5?8!idW)N_L<1 zs;)aO{e#xZB;DNFmpkgFs_xN0JA~2&79BijWCr^XoR`r`3$z@;_sqA-cE7#+Vej?I zh;86pP34OjqT4ezJihvFK7cwCF!SS$^yV0~c0nI<7Ax{tzi-X&(D<(<%K<=0Fl85` z$rXW|r39~x=AVTZnkh!gD%X3l-POPaxn10E3QSH$EJdzK0V>{OZo*>xu4Lrd8~#an zs$pf=TNL^3ncSM@B0OP->mNciEye{%5wpj~OEL@dbq2@JEnRz;J>BNo1y|0ut*uSE zK99OM8lYpHwP)?!lXv+OY+}^-MgR$rt{;NG0w!wM;dfTN@fEcAfE}oA>7(8U$a^?W z>*7_HC6pjPuS619Zi+p8CbN?3?{j?5J!yby9lS?3Nw3 zK!J?k6?D7ON@;8O(GJ->95`vlRDAYwr+Gb8e{_|4%+Q}#w zGH*}}XFPx?;SC;y*CcN6)|;G~a320xwE<4Mor^~|v;?&M}Vrd%Q3dwZmN zLbBF%3OY6&BiBaBrj(9MI$wnoEvV0cpF6r?7mYtM{0CQS_iXxCCJET8`etbzj-?8C zt*=65#d54tyBErzPa-pKu+(i(3e4!7t{AWph*Urb$hJA&*UM}6PjA^}lV{*Pge%2g zuBauhnhbgU+UQAL3{5W9D{vQ~Jpx}BsNd;v*rz@as=4>laElA*eB+7+{<-01%5mR(I?EbxCLa~I&W)Sn*6ciBthUmV zmnYx0tY#cV6-l5(%fBi`mJaSjuKeA}_l^!)$ut=8j!rfdgWd&q0axtqtv@|h>*xHu zZq`te!Ni%GD{j4h`z=5eO7N5lP{{#jHT(0UePvZ1Qy~{)Q>|3tsALJGv%Z@@AW1; zUHm-#n}DY@TBgto&(xTIC2=)8-D9AeFl(jg%d9@`IMjf|SHgu26N7N=9srKRqYuNY zVGSXl^Z?|fEYq%wU!(Dx>cK5tFl+jJZr6@cucyK$rO33vU8J`kfewTs2tPiNaJXLZ z=qWD`$)|z$X8hGe)IP52HM(Ju?WZ2;oHcs3A3XkBBOkr2N2cEj83~xW_xd!=IK&FX zY+BRdcAg6L#+FAla)|f!06=`Kw|GNETcsJldd}(BLxocCYVEyYpgu(Ms|8Hi=6HUi z0I4Z2ITndmM)l2V;B+7oi_8Q7*XY-$ha@_JxeunCL+}UT?va(1l}{v{tXrJB{OoF! z#jG5kIK$X_KO}z4${E>jl%_I2sK4mAS9&C?zKK*IDt~rafrqm&JZ$?~?>eW+FhDX1 z5Qbb-Olf?#4BgxAFf}s+)8v!v&p@3rKvSGS%9Ci!Rui!qHu2R1T zV2UMybAMJ6K(D&l)jCJ>c%JRG&aT`B=q`NuGNUKQ+G8^W!N#|jn5HTF3Ohnx*P7B_ zAyF+|Mz|kY)x;QR4Rr3Bdwv9A$YvoRA7E`pJfmC}X2!=MuRl7~WRXlKBPJ`dBfGaD zbGSZvw{%iY{R2pQgRg?6kiACxY}rJyIh1>o-Mzmgz$UPL#o3d}j1!WsRBt2dG9mG>KEdT~Uzh~W!iiwqt{VXy@$Qb#!z2_s?5xhfSZ=%2ErRtgV z1Q}TYGs`pi0q0dxHu(Kj;pEAA$tH#75|)BAf`q(D1PulMCu=$dJYxnJlhb zzaD0|FHI&>q^z_1U-N6M)F^^{cst50K-j_ld%N07X&0ZgoUBzupp zuRZ>7Oka^cR<*Y%{t6J6M+g2m>7l6O~%L}%Ut!(~97G$;e` zK3-!pU|BVRDjpoI7I>pduDXw2gMTOt4>}Juw#$*hAwA*}X&o_!L*W)&q}u(|X~8{N z)TL8h5LEl2VFo2Z!euUyZ&yDt>I^5B?$PW@Lmfbr;Z~^|qtCLj(@Q4ntQcOZ`IKqR zLGXqNMP&qlpyMjk2^EfiJpmQ^`b<)c<@i{kGicS~b$5ZetG{%{g9BxgsuFo-*}vD| zUCoWliVie&kBeB$BLxnY-bOyXS_}jPQ+Qc#K%!=KbmhVib(Ip|ZNi<%mXm_iK zfG1QKDWLTCjg0sUy7w!k{Hc^I+b1*o8My&t;Hfl|wh)H4W(Rju49S)4zPgR5?B@B6 zcM(_PzcoPQ>*Ym0!Z`V`bBvitlPsPobU^XF|86|*g$oU!^R|MS62ZE=xGFbp-YgNw zXxV_gnY{cEu$V#~3p4Cs8Q^yEhlPb5Nfx9b1R!4qS-YYb9qk>zhl6tO1avwyeAcsR zqbE9Q2+qHLw-h~yB49irE#L>b;IjF^iwHtQwX_E!KZX+>X&4(oBw=1Mpe+e=$k_pY zglqg^T{PNFwR?0Oxg%0U;W0Bfc_1~5h1(6tO6lC_HyeN5Lv?u+RzM&?g<9DPG4yy^ zvbzA@mQUUGgC18d%dF15_}$<-L6~dG?V6=;CesFfQ~`T_F*QFUM3-6SaD@E8q)T8C=Y8Z0EIs`xS>RHIIkI(hJw1cyMI_1)k z@XUdsb;P%fqjVkCNDKP(3tV#=jk(PVu&*-n-QuzvlP>3x4+OEOVrHW)EpR?VWS+m_ zh6(tdL zfLOL*P^vkwl3?fGu6B+X`E1VwcsR$W!&DA+r>0{$kKn_Ez^96R!3qunHvhn$bHvu) zn66$`ATn7niX9(FNIrciRA=jwp3F>hOA9B0-kq2~iIl@9AGsIvlo&!s?ep1w#aPZh z|H`2jU<;MijbRO>N|^ZZvUuLUa8A4r@g#DeZ==-bPI5gfb<5hjGoMvFHlWmWGe217 zu z7Y~I(wt!3%A510;R5ji;E7#oSdvZTPsVu~-Ss8lTs6e6msH}3cYlvyxBYv4 z;}dA1nVu55j40C_DJh;bQ2pBb2jy>C2?q(!T?s-_3niu2kCY)_zP?k;z|8t<86V@w zcB<_!uIiRc?C<`p0C^Vp8fE5Ld3AS5seNP!v|cH@(N-T{oCyy2Z3qmk#wMHk3rKM@ z@YtI1YYD@?FTD;IKJ{*p8X6Y3mBL0mS5sUQ{u|V(o3>W8Slp=sk=(iMVmy2Ocd)I} zbA{4>5OdQ?SUf)-?AI@nz)<{CAYr=$M9eLHy^Nf;vUj1zId+HN-K%sRk)4Ig(NL#g z13F;JjG&`0>$%olNT8bQs2lHk@d1$geQVa?EZN0RbR(qtO0xigOf@w%iO$Vp zG65CGvcsld_vHkS@VSr=8D#lmLo^?>-`@j)iqyWrzYgy$DCpkSg2EvLBc)FddBx^t zFX~un{)7;~T)~*Uy@tW5e5fi2)K{0=RgIMr@b&CpH;jmI&PM3-0v3d6G~x=6#eRS9 z0^UDfm6?#WGCjk-p}${w<|%mRv8Q*%THO zym2fpeBKxJ)^-m_-JwPbB%0M|Y!&y1K*qVTtrn{#a=FsVrR-o+JGqe`y;;5TIGNwW%iE>9=qmqQy|ln(+J)#7G(wxRzszP1exv z2K+MG+i!3O_eHtcKQ8B35>&dU~V zvd(E_{?V8Sc!e{?!`Gk9lu;JS_HSBhaWjxyH4~(C$QwXmjg%vRMaQKC9^Cz1?;Mvr z9kDa(D4ij0(RVCAgX^pvl-h3k;R@Wp-GuJGy~<&mdZQ>y&5paZGi|T9^(z^~lMkc? zsX!hsh=x4W4xtWoXWHv~S2ud*&@M8RWc~j)1DRQ9@nb&qI`=%swPTyLblKWxE1hU- zRD-L%{Br9E*K=!$z>827ihG!_Iq{iC!cd$Zfn1 zsTDfS1~9HK7TOCU03zKFObY6`6{LSZy!8I++291QiVLuLd6>IHBn0s3Ix@GxSb4$37ArbR@=l}?sHUQtgTFnr0)4^ww>vt9TW%t)LOScD4>KkRN0 z(Wf^8zJ|XqeD+RS?dr~p2X24?D?W^2#fdmEGX-g$wX3RLLT!V&In+Y@EgfQrQ~S@u zxGiTCEXn>^$FE>!kM3^CN_lf>)(@`jz=i*<>5DA1C-7sg!1t37phv47w5IT8=?y(_ zq16q6LnWncL2-Lw+XEqp`d$Img)<)jZ2Nnk0>M(C6(+sxL;L?)y&x<}g);*adrU^# zUj8~b=vGaQk5336`I1O~Vx#qj?#LS(4(Xg&zisS4OOqQK4W2Jwe2p!#J*{f;Yevq7Rlp1#vg2$w74FOxO9#F6svM6Ok@EQ=($ z%MTOwRB~W!{pk@gwtGA{+3i|t23*1D$HM>0&m~NnTGAyUjb5w+;K=5O% zIgm*zkPo>T^hAf#u>)pw9TifvmN4w$LG*=KPxtH7zGi$Zd%nd| zE2^vu`zk1Csx7|lCNKY4PmS+iiwgwPFw-`uHyn-O>->#;|d!3U_HRV4gTAB*NLcx5{NBT{P5}s#YM?}+rZHfp!=<9^kkQXB39*ukP#i489b8{nl z+i1f&h{iltdX{A(NKQhlp`h!D-M1tpRGkO~I+Zfi1(cZ?HNL<0G7rYq1o4@`#6=Gl zIGwPe%;e*#?w2=-iI|9}kiwUM?sZaeQH@S@a3^kUAh;M&i8TYj*m_jcptdPBLwFz( zc*V@2_vM|KlLI2^KjjEd&96j1=1IQ2Cd@~>ds4ny1144!ACuI6L=HcKbA0KsOPlRy zTmep4fsKte0d?DkYRrl0X_f4DD1CNJy-FL2 z{YeMbxefw&aC#_-k;Vm)T;+Ad8>*D=UhG}5Zu9xUJyhXk_g9*4D8 ze!jO9Cj}WJy-^n}PKU2T<0XO~LV&-sO}eylD-ngU<`v(F7Ok7k5FWRwG5$XP3kuhL zD`DQA6XiV3vRS@=tiBDJcEJJeuroS5mTj@#xgtztJet*gKWbDme}6e(JULMNGPk_6 ze{k>tD3FRlOEh;0gDGG+eQw{ry>*cbtelbroDf;^9D`{X5vC)K7Jv0mCC26i^6bju zdyOXlG(T!DLVGI9^}glx5gPzsR0Lk;(djoqU}ZEvHJr1G;>27~H#phw?uwi)WQb%S z05s2Ll(2Rs+PGV!roU!xEc-_@;bMsl^^Z&$sGKJoQq9!m7e;o+xZm{{oOC%CE}CfO zx)O*0Q@)t?%wY_1K0U)7t$x@91m5^Q1J}bmJjb+^#>`%G;FL|iQJ+#Ei5 znI--}7_JB}bD?ny2t2vAf)3!p$#*$RIdIDI^aEV-xKOQ)>Hr}?p-FjmPq>XgkenBq zskXRLN!bJOPsD8WQL(*6P@fY-QvZFkX!Eby7W7l*69WLe^75jVV_@2W0}#gMx5w$Mw$5=~ko;3v>m!Ped#(l3WXA?hVBUme8-s zVp}SteKR9Y1sqsphg$y>)9M#w)ktl;rr_Gek-0D)qrP_F4zSk5a{o?d;+tiO(XK23 zY;Y{Qq}Fb~S@{{LL?jWHv+&HdPgHU>6GE!nh$4rcrzWM4 zTy$m+COyC+9#J5o>aVx_cZed(Bwbfivk?)n7W;AmsKdZ|1cb>@s0{$wDJ?B6&KuuO zWDVsM6v*I>L+%?(P{~jl2#|YI7u&m%U*!!`s_JKY#0n&&r?aY%$qX-#1o3i$F8^+K zcJz)rDYZWsI*R2WMrp`-x+9VKa_^FXwGVal;pBMbBNnSqF8J_=b!(Z{bddenCBTR% zKxGo@hV3vF!07bBRzZKO=Ja9V)wvmmt>laEF>|0k6bZxVG8XBX4phCMT!2O5S73B9 zvdwVNU*zSv_a#7GjQxDKQ%I`pI~1E+I^b0GH^}qllj3`L1IJ zy6+`UJ~FVRbzynlk3I=y9^grwIm4jxgB10$Qf7+A`&B5%F#BkLQWO0^rN$j zUS7a=9Re|!|Gg21s;HDfkExrjZ70i-CDV1EtQ~(XmKPU256DQIy^@eo?^rU9P6#ac zL32!{PcECCL+5u##oD?-o3^5pOx&aViV&IvzU(x$@f<=Zm}DX>>XZDSO6JHhNlAkr zgzo-LFZ7c~r_y?-r*F2NDVUmc;4zA-AD+v@lmj@RbSTDR{Fg%KDHNxxm~%@Kd${d% zf~zyFD}Ww=S?I&}Ft-9r15s-g@tf%5iS4_U=-<)brv-5<$9{(v97kDq8P1{t zv+rdHl*&s2=r zfc4@iU`j!QQyt*3DWla znRUeT#xF6&3?1dovgAp}$3Vo;I`MEA16LE_7(=%VLV7@w8XnK%2z3=X&U9 z3db}yn)tD?{XO;@o(dVCj-V{f+AYoYD#(+vE0Czz90v*gc*h;qQsV%rEsKkbf?1`8 zvd-elAF&Ysk&3hg(yUkpOjaoZwdA*O7h(*y?&5c6DEByuVK>h1_#*j`gLt08BJ+-S zX|c$pc+x4+JBBs+!Od`2;l!G}4^17<$Y)YYxE4!T-=NzH4M!CT=MCX96c6+hOA{*8 zqdYuwb90>_3-JORiT|4o#CqE5zXXb3PdF@b#nG!kl&$c2T)a+x>{BQXA? z4&Z?PxQ}?J7jLI#vWsT!&^1AhZmrcsVDc}94mv!vw;=xH_ymbV3thLG?)bfzT|Q!* zJ9J#g_W|u{`*h%JgtlCH{H1V%nI_GYL4xOB*8l)976I75D^=Q6tO*o zjxKSSrT9vyHz|Iu!uC@T8+@oeqCsrMKq!!xjF4kRgy4H>(X@!+3mB^?SSbB=$ezbM zf*?$jm{t{DAQeEgkpF@b-*Asr0iKhQcyIMtY#iy?qS)R9PIN$ z6hEyc48m(dHs}Z0(b;oBQ(NhCRe#&%iYxozTZnfymsb>)0zthTh%2&^osK_+!}k<6 z)Tr^F)=_E#*(rP~K^)Z)C@RZYiy{1{hZrnu}GapA1CCHAu9-CpI;0w_bZI zZBnIY&zJ868S{a$fE?^)2pslaj}O9*EHfQEU_!ogc((GaB24co>hSfu{QaH~fUjKCD{l)gj?&QXrWDSs}h9|1-WXlbDgcc z{HAq4u@k?@9O4Ln=y#ho>y~`srDPlF4NE zgCQg4Zp%BhM~;5%Ib}9rUst+9lvRf{L3m-a`@q=LpDov!x1wT4}g zaFQu6u`L)T-oo_xuU6E?=g+|N#)dT!mOSu%o78Cs>2N6o5~ouPmxE$lpx>*DcvNf# zyx$n~nSH~r@}e2UN5`~lRuoD}(qidvx@j(uDgD9kA~Wi3!8)gx9Ot6nh=~}&&N6L3 zb37!6OuRS2F+5xEM9Vv$e>UI7@9Br9{}H)^H)g*2Lwxh!R6Yab^#H2K-NJ(fyBH%v zI88IlOUZSu#h1Gpyo<_l3ct`EKbF|`%-OlutG=NHzy8~qIOakDhTjCC{1Cdo*77<| z)Y~^PA@ z!?)ITPH&~|c9~Cj8d;E~gOOakiRfgpX1mTdnc0$ieaWv`e>&kvrRNgIHek-1?Zi@i zLcPhpVfk70;CBe)b9Sj>@aSEQ4;eK(=VYXXt}9neohYVdVSFBA4ar>^V9Oxa!S*lb0ARxa;bg44F*Vn2)*;`%%hrsa~>mP_Pi2$$uF8K z*(`KBg(x@~q;ae4Spu6voRvSJam6Bp3EXhli(26QT~gMP=XAw6w5YryEB;8`E;$JvadOorUu+knm0R zS#aH}L9ywHYuR@2YmGn5CujNx{FuqP?y?RyQeQKAx;mmq1`_C&`8MfNa%>NInV;W2 zhH%4Tt;>z+*_}{ivGlgJp>=Eu@O`yvSuW!Fw)aPgzvs@|e47ua;)ZQ-AwM-MgME7r zp{keHGM;2;)R^gRa%eD}#C}dG=Mnu`1l4nLW2B)=;A$_;TdR_eS4p$JzrC~8TZwemYS#< zFcN$H%>|+u4EF&vb5tcpAcZbd1#uO)$8pzJ6CAWm*br9z-P7RIEz5A%)V^ezQ|O6H z-Afx(1YSh`^68*e_`b{EWqDdbqTdB=!eY67)0FLFJken=u|D%na#+oI_!6R{WB`vB zyD|RJ^N+_Q;cDf~J2XMV(&7u{ader#O?L$vnBUw?A;m@U|G8l-pU z=0ykr@nfbAl)rNqS0uxr>oo6Kcq!!C?#s3va5tBaz#tp}J!G@qQEIa>2_8@S9#8w^ zl!VADd*k5s|M$s`uSAH^zT{KMq8ka%Pz`*d5_veEW&nH5GniK!BzC95#(@FX6Obb^ zuc9^fr@agOAG|zE6BZCd4QBMbtw0(;8u_Al<7NEU-R?Bj$m6Z>(k~ZR0wx_P7q@@juXA_NH5}?0)g&w zXa{?^{p|-{DR6%m5^KAnMzlAIEnKy_;{;}7sr%*`AGiXtf6mzm!hKM}`v5-`7pm41 zhtB>l(lCAZmagMO)O_{E@nVPO?eM0a-qB$yWEbP--bYq>y3X4-kou9_OKBlX5ijs# zB+R!BGapW$oR}!COVoLplOvg(lY`Bi=H};Ls>NZK84dp6SPgzVNLc)*F47UDzLkn| zjN6=QwGvATWacb67vIM*Lm&6T87bQ?qE{{I+Lm^Axke0(Tzg{hHuj#(2 z&@`^|;hT)3=mR&F$)2a{2r&{0y-7znr)=8+n5-*qE8GKr7b7C`lGpw-v}NizYua1+ zj7+#Ob0jsnfXh`kH|I2q#8Gl5CMQe6L@bPko6-d5+Sn90+1^ChE9Q>eOn!h8@t(?O zk}nn^Ec8^G;TXfEC2r}5I?<3NsIQKvgCePP@5A;Q47GfPPfFNDR zS)vWFHh1fbEaSF*!3G^G|+})e0_MV*`uf>`Fn8@dv0>BYRW* z1&2_Sk1}}9x+-`{)=F{nIglJF>uL(Sz(91kdLGa!45;`vTC<1s& zedWPQHN*ngm>ZYz#B-#8y5wBt+O|>9wXwX@ebm(eYaTBo)Iz=tG)BP5=y%Op@=WeF zRmne_>i;m-H~cYS@fd}wp8!xum0_y^6o3P_O7R8oqWiZi9bx+V!BY88A=f#&r%~-< zs$}3+TJYn_ylt@JYY0^;jsm4|V=;tlIqXvq7+397BOze7HH6A~06;?y>21euM-gx& z$Ng;Fc;OaIZ=c(dy9Ddw%HVi^J}o&fPh+R^*f?T$pj53EN8u(f_w1SDkXU6c=0kv1 zciGI3I{n|N3zh8q`w>id7oNM_Q-=v4-Y|0)1#QCFB6<1lK0Fq5Fdp54$%?`*T>}FH zT=DTQTKPv1FP>?v@(_LdZS?u#s#^x}jbhjG+!M0~9T*BS;GHk!I@@t#ku#Jcl>j~y zG&s7R*eUoX*Xa7fyg>xpK5nQaZdo!HxDTOR6`}iMD6$Q8-QfY zakpy86sk)$;DUEJnsvARvi*|~mHGodzfwkNy`QAKQ@G7dVFBmPoT4T}rc0XPqN zsV^#Gz0eV7*DuE9&;52`@?DgeYJx)I#ef&5j}e{_3FF9{C+lDDWAMzFz)%7F6=xjy z>&p;aN^B&!?vvtHsK43_hqN*Al+!n*yB^a_^OaEklbxOY0vcL@*kru|*R89Z&@2WY z9tvJQyEfdK zq5p05C#;Hx4pEn}@>*~k^wjOkP~BgQU9sMNsPw_|Ykg2Lm41CH%#mFNs%-3?2h#bH z@b-nC=(2=bbJROy+pbbQr`FA6%_n-Cce^$vv+AVsgDPSmW`hRc?FpL8MwHvrr^c41GMK5Vq$bsrGC~S`KKfb5YV#WJ@3HR_1dc$xAWjNK^Cn z&15OYjT&WyJ^Zt{IZn*ry1TB$we&TAVA!foi}%1CX)s5 z3dXuRIyz(p99EN-fw~?RhyJvylJS2pPCe+v7eHDG+mlqcu@HqGX(146;f-KAD`n*> zj=;lFgDeeSMGL-u37zG5=pSvP6`6g7S0HDqJJQ6_5hDc+3G8Nm-VXo*^sQL_xZgM) zBQWYRO*#-wo$V$q#lufABo}I^@wLy?ZzR9%ia|llGHJUI!=*^V#4xZr!0x|-B8N}A z?)y${Aqagn2|0S(c2Dqmh0l*yo_<=VZ@usWa6_$u`FDx5Ox5(C34-j~J4@z#drd3W zlX`(MNj$lI$8MZ1s)y$J)a$#!7c9Gim2uql_S(x`4@APQgAHU)Wn z$VhIQ30y}MI%_71Eag>GZk;lreGIx3twnQ-g|_zg&1`JI1opPE7*U1iNDnA z2|pHsTg+8^Aw!+TrY{UonkrwQ5^X7IToz)Etc$L|C3a0|R+Uh*O_bdhT8z6|fyrCj zbP>OqJzCqGXprKA9okDA_eQBKbgko_Zl_Sc8Dk62T&OMJE&+h}9Lv)cg_`6o_hTYd zYy``CD-G5s3itz0%FbK^^zS?*ynfW)oC7aoF8MytAGQV17P!vWVd6m~%Wfn6Q`8$w zUu^xLoB?LwA%rbrYlVU4cScO|#%DrHhPiL)al*UE)j>1F)`_Xom7a|51ML?}o0yw9 zviIWWJyIDk8G1lwGUw>WcB{_}^MNuC;kg*SBpX>UdWNb30IgBoM^f0>F7R*Z4F2%C zc#XsBl8-ekrW19bm^=D1FD-g-xG%Y6I)uu9NT#>%UeY@F=)zxWfcGk4@Q(5GYyD)_ zyAar$M%KYqUDUjv4r{AuMM!tW-s!w!l7Hk)E2IY-gpX}+hD^$?y-Atb0CO$R&oLnl z^{N`E=&k&&z8W%<_n`Q=ZbQ*T{|69-;TtQsqk6(k9NffG$)D!!`LtJ48i+0?-wcPv zf!)+NC~wYi3jVpnN$vjdo*JOsg$8FNYJx_ChpVQZ(fjGG$L~A)CX$m7eMB=yzS+r8 zlbB-r^S?~!BhuWs7{-1+9UcR{ex<}rnPRK(klCRomEe z&Y~|&a?V1i!-Fg(;8j&BryhF@j-+J`Aw0mqz<@PMMubnx>wrZKseH2&8|`28J=Irc*F|N*(%AnJ(~*_ zfOw=NWw+OCH!}AtJ-4Z^z5CCjK*DoPg07-#REX53TSVF#I|8S4#CSavpUN}u%a9sZL1% z4ule%!a%^>0R0~uPTtGKw}v=;n~cqM5%MF?D^MbO z1LxF88voHd&a#2YIn`K*X>`mq5=_}sBb zAhhzN_2V?cvRNTKiUBeMzk)reiO@Y_#YnK%zX!N=n8pL|%qd>5*;KI`aP6lI9cv72 zD)R5_>TuT+o*9J$tCL~v2dbETSnU`+s>L6SI**7O-_P0sCq?22&@QOO+CuaTFlFiW zWpBZ z-KpNt=F4_h{Q~#-sTm-lx61$_d!Ne!h%M-d%Czbqm1F&{u;b554gPEHYXD{7aDoP` z`bA%02cOnMGo1(8>KvYo=$je#^iZCqGZTj^!5YM-rWa5BtGb*l@;-FgpYjmy!7a>u zph06MG_v0JLOXF}Y9=zV;Ep~&lWubT{l(nK$jD4AS%-c@J6zr-CJI0*bnoOxX!&A< z!JD@By=h9Kiu-_i3Ow-sO>5;`x48-6io63G%r5xFo2IZT_$#L~4Fj@*a`YdCdHbPKNY*w^5wRjLkRFw*t0#FZl2I z=i!O>zB9ENm>Jr;@efPQQ6n=w>)EvW8y9-~CTfyi5W z`*Yzd7#;`>t#ijq#d{+hf~Hp!hq+QizPCM?)U>#eT;IAMrbOk1A$Wb(>Ba4F0(LOP(pb$?xwUQSg{`w3_!WA|~@ z)?%nt@5lBgZ8~5ZMZhGnvC*fwJl=Sx2wqG1_5Ti}1sq82gff6AIaLpJrvh>U{K0#3 zqZQ&sWgiKkvtipvfgdD$#&9oE09(@aK;!`-$Hv5uPN=?WfF{SNB7^oZ{?No_7XV|% za})ij93zb@C=-Fcw{HY5ehJQvM_Go=^AJ8zP8@#t!@R$W4=E+~X@0BzuAyN`($c}3 zzY3uZn#bT^pLZ2y>5m*W&vCd3Ey+Qh^n+MYt4kR{fB|YG{nS;YMCzmHVOg)P`8}m2 z{0f9md!PJxl+MeecpZIo+hZoWj*(~dcHbVSbCR0iLU}DEPNgkqSwB667d=WV; z=3cBewSk#6YJ4VUWD%a1Ii7Gu(&p#A#RCW~?UaDsp{LQTE1+1>xg0=qZ0g7g$CGFI#$eznBF zZbbPr=o)c6Bb;qtwX&d9%f1<$jB?N(kUWz8p0Cj|Yj!ICHqiRgLZVO4BO8`DeySP) z+DL-D%CP3U$gzMsSp(W_FQ3U;!X)zpY~jZr;O5CF&oww*?Y9FhiTv~;K_Pu@0ZD^`a&$LcT7quF+K9nt#^z=noX<)$|9)_Wh=E6vSHy3^wt z)j}wLz8QXvo!=^^Z*bd^)caw$`XdauJl=*DDwMaanNp5BeCU1Okv+cM8DIT${MP0WQ_XCEH>R4|5T&1Jv&K`X7b2Im5^IY<^t4+ z(r58~nN|?tMhCGI`uWyM3$sD@d3jzWYWN!KON(T)JY!3iw!gl~eJAE4hTr4r2gloO zJW_xDY+sGL54(B1R1doBjz0`=+uhXMtl)aUxDLS{r~%bo_{qKW6Hjf&o?u+*dB*QW zXvCC3KT!ih^u70f5M!mo?&FJ_tMdEC)qASi08wsy9Z$dD=qn(WY*Rc5KG*Fh&|KbdWTGWs_5I)tKr)?yq0 zg6$cHhkdhAoChuc-;4kJcO&W!$rR&?h1FTge5(v%XsYG5ha<1RK`mA_Q??*H_?m&k zFSFL>N@HUD3hzW5mQK8sA(D~y07H5bNJn`q;`7aIQ|V}(u${%DB(@o7iFyrNPS|0) z4D3?|BB@6sP5>I(bYmikH|M6dj;szuzOjCqa@|ngeMD+3gVe5g0*P zA}<8U-$nt_$i;~E)9bLG>$mLf@d1NOY5~MCpZC5pK%6La@Z%tnPhsb`4kVm%v1fZD6Xoy7ffQ1FLZG^84NTpie7< zW~f~{?Q<8In3!_=reW5 zDW@^rXJ#!+5scc-s3N&DG!1S@ATh=+291YXo2;Ff3!&5$5QLN~MfWnHGe*}FV}Ebd zIRf%O>f3y=gJevghD-ccpj;=y>Chou#@i)tDd=N6_|BTw${crFR}im&K>EDP5N|PC z?XuW^<9`S(4@q;oST9$O8<0FNY z;Wmh=kz693CbU~1+XRQ(GKQ~g&H@kWpf+5!|hvsDCgkCB;DB;vO{ev-ebIJ zLz!%HQzoCk0LJ&Lc9*zc%#ic#{`1Maf99}e~Qky zWl`N%`$Eieh%WV)BdgLjt+VU=3CvAK7se{{yL(~HZ+(kpBfV_x{Xdn)PU08pi;_zb?w`OQr z!R}bm+*4MhV&!jO)mj}mNfTS0j>5BDN+V{h%O1 z3^m=*;`BJi<9KL|$2&_f0CH!zJ-y|%pBGB_p;hQnAO??3G+=B7cnWDgAbveEAp+a@ zTRK<6i3 z?8GL%I8mc80g8Wi3mudO!Sw2t)XKK(noXX<5c-PFyRsLrH*R_4`D z?)fSOJLP$nH;rz_i(azx>q`@mHY`!5MvgapkI&~=v|)A6R;l{_iF4U^P{*$ud#0F*iv@aWWUpUjTU0s`v^UM#~3vG%#w~vbYjQMPMeB$wz z>}`)TPQB);>>qKMvZWq=Q`361)g-a4sMQzASsD$hSyrtY$Zd;L}@n_5vw zZ~F0{RpaPXmSzH|;<&h^61V}XoE<@!UBygqGvCh3L$>Gw9lgsjDAh48A3xqcpT1RF z8hgSbQjfkzY6mwVEA!R-)v61mgHJuOqRa3xM^yv(y0(RH~LRqYJHx%A8 zJ-h6e%9lxAV#m^wn|M6pd2fz{I(#H=?wx&axXVQ$(7y%^y5&zRD0Hz>$5^|txfOcC zaet>=Uihz0>#7B6gnJr2{aijh)P3O)2Ji~5rwuB)08&NyUp zXVW%1m_G!4QBC(&F535m;wv&mo^0K36B9Ym3gqM4>rHMJ?}rbAJQe1@hG#+5I`8D~t+>Syl?FPn=_Xgzz>tR|=$#md z>H{q0F?n|LqP#rWz5#kt%Z%jysU!0&!0cryUIrd-J!W(TV^tRgwD=#E1%>{p}w$3oVapNd16(-Ec zAtNq?4GhRpFokrCpV;9j`oDaAV$^DhKcfjof?i!~L#WmFvucs`IWr@f`mE zSax27*!_t|8Y4N+BMhqvLfBMukJZ03$uZ(vMIhSvR9*RxDTWxaj|wHHUxI00x%Va< zvDUb}%~)}yu!?+Fj`+`G`046(EKri|F#WxXGE|OR{3<-HyS~!Y9baZR>Hs=rij{`o z-2!);cy=sBec<%&&i5gjg?hd+8u_MhNlx$_B6Jf@)}juA6Y|rk{GHo5cs+lne<3OC=E_p{_i!Ge&xgJ6 zBy3OWI#i!rJ=4%D)lB z1RROGY4f*{c(0gq>Fw4vUPZ`Nd5cU$cMOQ98vXV+mgdAooVGHxKoE!XXRgz|lh%M| zP|logHSxwqMY+s>2(2$D@OY<{RaB;2cwzi`^5yo*uS-xO?Y1N2L|-$AsMGC)^`t3u z#+8TOj(|siz1?AaV8L0;1l?94GK}C!wMzrOemE7X z0@F+vGp}EbI7LsW@y`oz`dGA0Km1jd*ou=ovC%4>bw8LA!eRTqD>H)M{=vQ<>S=Id zym9m1o5&CKdS$y!WE<_K2=B z>&Af9uwe=+9GanhR-qO_1O0yBJuU6%Ya+Megh$?U*9SHMQ>ac`%Ao4sh z0=<&(&8Dz^7iQGN$oK)E+8fgkDagNp#{+5ac0ru|H7G6K-80caZL8XbqX|j!555%gM#%i`5cryfQ8> zfsg96S)Q`#ioCu4Aws=jV8O}-idb1k$VBt|e1o;=Hq-{!m6%LKs1l|^XWP#$j2{Dc zQ?lcSDAnd`eTi5ojVMG$3{w%dP05QJM?ra#J~i-Ex)&EuA~YH~C<=~0_8~S)0VM3@ zbX$=`nwvOu8Ts<4=TC2{Aevn%U#4b2?ip0Fsa0x2V7L`9!i>m55-{9UP*I0vSN-U7 z=tLqd%(dTrbai(8_ZZG=RRW$mj>f@#hYWB?2_!%VnWM!Bn_AeI^BVodt~JrnJn@=Z z=6)v~=4}+8l`;rY@_?|V4+Ag^#AYml4EY|T`CT2>>Fge}K_0BwOyaV%2pC_gow$Xe z*UR?XfqTAYiIxZq+(EQa?`W;ht&njrY<|MaUnLeut7=%9Nmr>!br^KdVVwYH7n6ZT z=49c-eadpT&C)*TnVGh7che#n{GfS8@DcRK%wT6Cx-JEI8ttuKBVYtz3PZ%dEzhwl z3M%<(ig81h5=^#m9&aHdi3gLmr{_)J*L$S4?N}=b^@1)yS@gQS{-|m8u^(|8M{#U= zrWI-c&qB*BLZOtSw@_rTaB>Gk2xG4W-S#&RO=%|P{g+3`UEtpV34w4+Cu5BSjc=f) z%M!ve9M0pUY-~X2ijK)2{d$QOD*}w0;uN`*R6ql4Zu`Gl+yOn{QwuTsNCL*Jl_lbdYziEB!v>&<)b`C^| z5iS0tpccO))?drisK6X1|7j#%o8D27OQ?NTBQF=z296uOv$nG$IgKwntL z{bVFBl{$EV)X5VTcL}HbCW}?%zBgH3xw02Ke6Xu0yR~DucG(S?eh}0QU)WuR@V#SC z({s4>CxROak?X0T!$#h6(mAEcn}jgL0CA?%%eeaGN#RLA82nTBS)$@s6@GerY#2)= znld$hAMX>-`KhYrgkaC+BRW1HHHyxilo!xt)&iu_`8+obamMJUsWaVZmJc{B zlzuQDq*;2Z0GKav_R4tI8C3gE7Hryd!v$CIfDmfAfrIn_A-M@-5BWm-5=e*cXz|B{Bne$kM$IUDLb$xZ#rgua1fW&gHqz(B)6?<8&Bmoh*-3Y=i22}E z?*{P14fEF!DH zck>X)mtK}hD3CQKP)o392*Y*NPg7ih+uPT-1b{+0u_qLatKU=UHpOl!N;9ZVwK0WC3C-XbbT+ z0ro3WUW7<#`t|FIE>KgAz1*J5D+4I4CD7vj65>;6k37&JdG%{U^zqMdAB&5NI|DRS zJfSbnu(%is6|ry|vi(hl6yT|bqlwPf4;JrhhSyzIC10m~shRb@Ea{jY1ewpYfTk4i zPWFN0goz$n+6`Uvg|MGOw2%FitsWy#-x=t8s_wrXcy5D`KfU9!U21+{@ znIBc2abC{yN&F8Ki;#W&HrF^$xcU_HQnRaO*bo2?g>x%7Drs7w^aQcEo6togrO4Z6-THg5$&l2z72@quHF?ZLe*VQHJp6w}Yjhh& znkm)W3T60v+rAB4Sw*oI2%!Vt2K<#;aDP}JY`4rAva%s*KKIXLBUC}>Lp~Cf7BQ=J zQfX9kP5OH3RMf3!gRIpt2%)rWZ4FeO@LxX zZBAj#b>vwT7GPhoS>4#Om9}sou|;-6k<42wP1sJ`EM!iEPpk;AHH^hKid&zqte9wlRg@y5mplxzTjZ1S|I{ z_;2h;Er1l02=P~!f)}?09U>MEj@E^yI1`n{AJ*w4w?5QFb8udIfwSO8C7>V;9K z10D0OpW49{vbkBn-U)4zc9{80hWvue$OPa`|3PAJBQPEz5nGaP{FBi#R9qr6l|1w9 zzRdX!n3}+g7cEYxW=;oLbZUTNxc>?&e5{F%$yOFjXxak5e`%bwUa@V?Vcy(3N!xD>Y(s0>N2&XR&!y2*fy|6U0?Eayp zxt}1ID@!+kJK_4#F6W^i_%|W4(DQ;N=$o&*^kz zUT6gc)RkbcXioA*VdEFD1arCH{NX&1i1Rwu)@*I#E-}aR0ls#5E0nKwi~+16ceV(2 zv=*$Wo_jGzLU{kD(-6R_ATlY1v+ViuHfbJ^FCudJy1>6!5G4I4^OlYg@H@MZ)e1W~ zurYV!d&&k#=+1zLxE*pvtp`>~P3mdv>OjT@q?5+}XaP59DA=iUB+CNp)W9Us#OV#S zkM0jg!;VMTpxV*~wS`{`v6rC9nlE|<)S!^wigkg5mDLk@8ObCuIOxV#u0-*)Cqs)% z3BsLWXAQVDACXKIr^OfgwetE)A&41ImV`4-b95Fmy41`96R=Fa5GBO`P z`^(@g1pj5$>9_XSHHNQq>|3eko_n$fvfUyW%S`8od((|39+(pV;v1q0tR`2Zt%ItjhNbylArpXlmCXYwSR4#X8@1 zErk_fQ#&^-b!^LhfW+2oUxNcS)8~g6Ye9goCHum8e zqCx$pbe8IMS)Kx~7qd8!OzC(y156eyNL7mNwcG3xJTYSaM^9(f@~XkBL>-x&_f0PaDS_y`p76yeO`Ej?SMX_2q4<` zbY|`XQ+FUl^80D$<(VrjQfnb~Fq8)0PB_PeCl65bf`&7{b!kmjoVsY6w(+Owg%~(r zgjOo~1*d;Nh4-t|<+oZFMn5gv3@FbZj^a)KgNh@eL&*$R(VG|g|6~0>b)Y@^XQtBg zIH08DBL5E!VnBO867iQ6mZ=sn+)EHerZ*nu=0sU*ktQEZ)n856>Mgpnr-_<8n;V8o zCtej%Fj;x-z~LLYm7J(7=Fz4Hd5>hdD^9eK84b7zaT@t5pX}9fHFJVD)_jphk@q2l zUfcG*xKFYuAg+7;StU>jd%*=Jy&bvcq5tUeHKid*%QLx|g?i}Y1-6YXa;_!h+RHi2_IW6PYGm1)s1oz7C+40k_#v)w_W5a4zx10@`SLw0 z6lw+H+4tuFnuJ7Zb^sJarqkRG9rbG?axTBWkPnjj@SH;<=F=mc*-{G$+x|XkE>VTY z&ftA`M)4|wIJt$04p2}~=!9y)&@_D4oRPHxnFA6!tvzH^z%14cIscgOn`@N&f39RA z`!`cFk+^{PhQ&M{LhUS^d;U8Mbekee)O#o=|7SzQt(Z>Z4DqL4*l-|ozpNl(h3>y z?78>AA_#5~aZy5wx*o@B8bdP4uhPHcU9SYG4;F)-E&F6SfUV^=ehAPD+#*N$_=zv{ zecS{=?FGoW{PMy#xHis7y^sus6Oj8|yQSsQ-y9SGk@T}+4vOqeKf{|zbMrU`21m4q zNCgB*{MgW63>~#|R3}QMpWBv9cTWu-oFLhuGttN;yU-AXZeCAX&HtR=x2LCw>( zS)@wdl`$aieemRm#J?#)Y?h=PBiop`1K5Z*A#5;V*>Mt71ui`tI(;1;=KAC2QZ}D% zefk0Js$3KG`9Av?C_F8#&kklNZXhDH9$EvJBIE(2K`g2=e%K1 z;L!t?h;OuTL+*hxV1L^U38PTwPB@ak%2B10+cwSuf_OE+<%RqEq8e|!7`~M5W!*4b z`K$}7aOD-L$!I+GI3>BYX!qDp{e)|Br@OMujIiD&1PRJEzAT!I{je))5=>NuWeEk_ z4C<}5+q@p)bkpI})D*7}%R@$;a(1)Ab=%7Y2BFV1Ktnn?ocsR^;+ohOD|!lVI~&UF zGaTYzIFX>I+t@j}$lQdxwsYl0d?2}Gy=>(!Iz>HSV8yE*X?o-6UFmrbj#PuoRiGYn z*nA2}cmRwW8x(cv;<@z?L+J%H5h+$7HH1|40W<};DNzUhJz|S_kDAI2>QkDCR zyk4KGRdi{u|Ac#f)jxv?gt7e2IozzrWoxuW*u|Qm%Raf*@#)hQoj(9+KtA}iNK2H( z$U6$blcxLL^7^W#tp(>#ZbUg+KZWCo6cqX*o%=n94u%yLMBow`!)rw&YXN1R;0-2) z>b&{7Q3iYw@dYkTEx$1>@y;5QG5%BT)0@HP6H}=K^`lsEmXYwlc)@?D z@PY-Dy6VrgUiE!&tw2SRAS9pu#VQs0gGyScHyE%Df2Tk}6niYli9Voo%|jB<-B>Ne z2>^%_d-pBv3P^zIe2kFyv_pwQ!Twb6rsVy7!dh($6B(nE_qPe}gy_IDwWi@|@Y`lc z#PF#1cn`5QPk_xLB0X>$SR82c<>d>J2LgG>$xh>9l2HIVq|30d8;6= zYI+V6oLn_%w;61iMkiF^U`RLRl^ z1WL%StQGF|4*L^F8b-RkxilG({}P1UJ_sd9l6vfUc0BR1<)b5Z@JY6fJtA3Nv3233 z7jwk|eE9?CT;_<`+@K;pflP_n6exqPV*yl(w-#4L2=Sp0bi}(Y686Q8=Ja@i1Rb|1 zF=%8&x@{S|1@acg!|r*g%FO;EQ#$b6-mfe${`gjUd!=WdTg#I%p7t5L?>+T4mfJ*j z6BNCg$~A;|Kl-+m%j!v2S5bt!qw%?nj~sc17E`@R83&Af`X7MTjh$v#@F~dCVeqg> z)h3g1kc@v9QLu{WxV0mvWZ_rUn|6^)=p#C|Ug;NbA(Ndw*PAbq9z10K5xng^km%V2=@DN0W|Ejo9AI@u_33auVxDSLMVP^W|zLMu?IuOkDuL1qlU|4 zP~wpwETNP^xgIy|LTnv@X_ChNp16G&XCm7@re@DryDJbk7x#eyj11LgrRliD#1387 zgBL4*mWO^NT{e~-abIPJq3x2Cr4Hzia&23l((;(p5@jYe} z4e=OZM-~d14e@i{jI&X!@Gclj3>}PP0)3B}uG&P!7C+L_v88u7+G2B|2|`zsn_%*O z1q-!09k)H7^sy~LqZk5sZi|~65U)M^3CiO!p9GPE zXq~(auoJmS=>J=8VSAnMSuDw-CMw z)=f{=mjLQOsz>1^sQ#C#djJuwZb1U?$tSxJ!TQ3J4XqrqI=OFoszT~88Za!mzTPBF zazzbal7uD*#Iukq&3F|}t3UNV2yS0pf>zZiT-YyxFhHRXj^{TX@x?1QLT58uoSBz= zur8Bd`FlsDvK2@t_y@L7_B^e()Rbns4#FB>-l0WcN6Sh3L`^Tqjit9aTSO?p>BiH0 z0(32HJ|V{?mFceG`e)9?r7f!djZQHnj!Lcz`25WVYfCugWd@;ov%CJ57U!ZGAvGU9 zF$dJUI27py@=wG;9NK`n1Gmw;BX7N9iuXCsm1~n#eo3vWXTno+o#b3)*(?7i#9KVq z$SZJ|oxV%GzAv-GWQ~@_xR#SQfX4tk)|BGcCR^QK7_FHdSxpd@?H)4Y%2g3fTbE#< zfQ^myzOeoJe`(=kg;=f+yW1Z^g}#T--GmL*gHY`Z@qqGw^^jv1KWJ99Gm*=z$Jd+{j9ftLvM!54oWPQOuw&bT*J4A<#5j2l|XPhTw!2 z_hqiVHJ#ng0nHcP-5W>GuN!Ruq=%WA64|z%Y8v9*o(YqxGfU-JXZ=y*8O}d6SG5qc zd=GMDe+ioA@5|uY-iFRbi%w`Mb5;3g2Ale@wB^RhK@e3Y?h16H zjnR%Yd%#|O)I3LHm^}#Fa6&~=>0D4FJc;<`fj5tZ0X`H7XrPyH#ut02!?(~bHI~RQ zBPb8nqun?mR%!{Bm6WF5K%v{sLq?ysNSw8Xwj2YHP%O1L>Pv)Eg4@(9PD3rn2pk4^>-V$Zw)uC=f4c@nZ1v9 z!Slrb1d{QaBbN`4=l!%sJF-vuWWJm;;8{mZG$Zan#=`j5u9S#HO8{4?*wq0;UBz`; z1{_#xL>ORlA`$AaT=OG&9yuNKf)839TllY4g-h@0LM>?W3!LFHYklZUgLMnpYlo@q zs*rAU40sat5`ob)zWpA7y`Zyk#v{m+t6|BTG z^^PXc-0kk}p~6WD$A;P8oe~kj!xUnYm?(BU> z;NL>gkXcR0CBG-LniSSr^X)13MEGLLm@pA=Wk;oD%W4Q|p(#v4Nmhc4r1sKutiAP- z-7}48#(H)l?Q+NS-N5efE>$6y+5QyUA(`s%DU*6sqt_lY7=mhu3qNEtxK-pnJ_fST zQ-W4!skwn|{%miCPHjx*`qvl&M0JV<=l2O8qp?8p&#a5>M@8Hj*T6aS9weajg6%ep-saDSHIw|%DqEh zbCI_l|MR`cc#h+?%PGYT$Yy!(RbvGhrpr*^dJkfb|Om<42<?vhfOZ=%Ih`FsqPM`Ac6f&7VUR4FR%NA(9umZvdPM zJrNI;xj&1ZH$pl+Z{$51c{_7sp@ze^xM;cI`;np7F585TLelWzT2+zO_mH+0xk82NyAHhRCIghRCNtfYYX#P~#)JH0Nv7btQW>`9qZR-k4Aq?I z!s&q)v-$up@gr8}Gw8e?)b3vY+iY`^)FJXpXgFLRnz8qb%+rIHy0#33ORodIzL%s> zm76zSB~OV;$^j`AEq$W#|Gco1!fkJybl2W_{7tf_rYby2=ye8zVF=vTL0zzlwG+?5 z48lJJd?tM{);6HfsmU%H0L<$APh-PSX-cseN{({^T;!U45b@O1o>nH(g|!XwcPxyp zZx}jg8NeiE%aObCWrQQ!AgAv^uG6eU7wiOu(;{`Mq0^0L(J}PaFPX7dry_hJq&|u*U2A$6WrD}zoCvEw0qdifoe7g>TgRI6|5@$X;X{pSo7;nMvXfxlomGn6C9iad0 zujis!`Q7&`3~cd+IOjo5gBZ-p+~X59t@`2Up{C)jB5XwD!)E#l{$M6Fj>^8II1|yo z-mEO2ytx~niGNpKDxcX0QI*`t);ePFsTF)~g1!dP)eMva-gWvAF@2 zWA+!}iNst|NF8B`Cw_esA&?2+b57dgYlaT;O1Acp3Ay|~AgZb#)RxZ#jb! zE__4k?&z2&8C8v(lw1vb_4qGKgZhD7E;zWswV*}`7Fs-McfPkYjhpwuRo76pB!*WE zA=yjK!oWsZEuW-qmpTAdz!fLhxp(`Zie*4!EImqPlO|nRoXhBWutiHjt`$Imi3S7I&%9da#YFMtKC|Lu|z-wpx zk%-e?H*?uE>hDgb##B(H-&tMI7cVjVFz5elCASmwUkCJqat)|Cox+*Imio+6)#InL zD`s%NNuIpR!#3%>s|wu8nOcCP;HNQ!Cs1Alru;$gO|I#PH0;WW-Kq39l|gP`^J()d z3OB-^)zzI2J?faXqBjnh44opg{ba^_*C7u_0HJf$$d1GVKY!juTUfLROw(1-&4RxB z`!}=0OYrJ#B2@GYXrcE3k1zl6Gb~HxfpA0yfu$f#PgcL@HvTY`V|1h!G;%#nP@^G; zARq6r(F! ziTmWbNvn6SFsI3kDL+Iz%rsS!-Um{xP(*!3jD}t^3kt={e^QTA7y=l`a9#M4LM~bX zYsA#x4$U>3wz#D94q=%lEdR-E+g45Fm^x?x zuyHG%HGZ?v@M%EkmM@$k(+A?AxrTGywe3@b21zaF8_DZKbKuX4~=q#T)EvHZ8G4Lzi=#c_gd@X$QN^%yhk7V zuDt0XH^&l_UxueqC*oJ+Ru9|Jjm{g)zMP53%hgehfH44Dmm(WM&!!5aw0!&Z-q4h_ zT-6qKs`Ns`t*+(s7XY4>jY=gL3F)fA@A+ByV8?7m$ob-?=+_k#ygUpgOD z9+~jY=RNTC0q3gQk20i$4>JnMeA#&Eyd3kIO`q;;q+PT3pyKJHeS2H`;^!7$aHKdK za7!3)yl^8|zvqvHL#xj8{QiGN6X$bBMzFkb-MWYLk1WWg-|6MuL;PsxcU3p|b+`;5rRu7NYXX?!)*THDl@mc@yYtlihdO`Zv};{H zdhoS5psb#6vfTG^>faMxVXH?twOXYGnRC*_%1o!;`+PipxtD|vF>Ku1TE))?Q%rJ9 z80by*{71)aoEx`rQ2%G$8bUauy?7JBL;eF0%Kme4Le+yS z&!Aqkcc70{r)mb{Yn<+;zyP`&KlOn|4hgutNm$;m_e}vnk4lkcZEfCa^IXb3q`_&} zRMBCjKWLox_#pIxYbNr@jqs;# zglXy3EvwDyr*N<$usY}ioo(gXqwo{|KQh|iS2pm%=`8m+e2^$f$ffW=dEb^H{?aTW zX`nRbJdn_sj^920a^eQOAu{+qJ{=Zes%X=51AGba%9qzgK5o{4Nsj2^Y39nS+SESoSuJ^12)og6yHzST%EP^w^ zMnbypd4T(rx_5{O{d!3b65`H&)~Ed)KCXjB$lc&xPgr0jZ{?Ww+O6);=b+F~%6Q2Q z<0!rA&mTCjat3~Fm1tW2zW?x1v(+7(__ts1F?*Ft5j-@2`Qs85-yFzY@pB?n;x@wHC)A&)W;`HwGnKlV zj~~_RQaA6wi%@G*@-yRk`|gR{f>*;2`p&*`qOwEftvQ>)BG#S}iU@2L$qOwg+ zksopcHZnTNTS5?DQK!MXFFV4&8nfjqn{@h=();!K>|)GiYe92az6}++1KS3D`s3^K zhhN}pYW?rb8VrEhtBtxc^eI*e*|{*j&o>5qpF_sQ-k0D0Lr^|^NZ%LHnKUrub?8;F zMl5hxZJo_QjX8M|4igghVF%#r%K#;Eu@` zX0_qZg!axxwV0e5e`EprTv3rOpPqWiS?Z@V?me%#m06KStG(+@hgnw{WGh1`Mx+=^zB$&3L(n*#-UbtUNF9VYcYw|ha*jK09wt>8xh1n0}l=#+>28pBPymoJ2_m01>|)`1`}ib6tWV zF!HXwOiZ+Tc7WdS)KP7J)v<=jZjIPggy~+ltE(tf=__k`9IfX4<#{ngNkr}4C=QB! zJst+gAX8*^wu@K$yi;^IFs}q2`0p1W_HdECQOHP6a-0C&5ey3#M7Fg6z_PToG>#u4 z+7BWkg**}!6)nQ?LyyG<4-T?b^VO?8iN0$7IG2aus0;1O^B&liciX)k2!uA1RhreZ zGsgx$)Hv^wN(XTvaRF5D3~_G8NP~vL_N_WtX(2onrTj!dRZtC0BQ0v6n)3>N=}BsE zRI~rvNZ10nyejy-o0D}~T}TH6giXs2q4{t5$L0I&*k4H^4?#jy zFV2@Hf2YHTe(E>T=C6Dc+5m|7n*Le=@?>mLuw@r(WUa=u0o@AlrJ~Mk`}7SafMx7p z>JPcn*va7l+kBepA3vmer}JQRWDEy&tv}9o-vrtur<+T7%>mBb8;}g_d9P~KVYc=r zjOv~VuK@yR1E`R9z4Q`zc@+U5&IvAifwr+ZE)Gle+5!bJSkP8;%Btgmhs`KB^BN0O&fz3_yY~8@J3X zY*OjnR};gtc3DAQIb2HOuc=~MRaF+% zrteRnd&mC)bmMNSomEIXzN=~Wf2M0El_Q?Dh{o{{j2LKcJMiD9Y-qpk1iCpd(EmI# zlX0p=QHuTt9EZBQyJvp%$ZSWXUvGBtx4$y6@eU;Kt&#DD7#y5C$7{F!6)>0~&;_za zZZVig)0pr!EB=>+VD2AvETeiRG0Dw>W~Zk#Op#)7*5G^H1h1ei*yq6S0ZKAlL)gax zUL3okBw<2&77S3jeSot?@0(;7yDG07J_l6ah#L*6Bllt8F<@$TY+hfGd14ZJ%tfKI zKjNf75Z|pf7y>wA`1s>fXxh{p`*vbOpj3~A!Myg4Tfd%M^+h`Sl6h!__Ul3F$K>n3 z%ifm|JD*S0e_vK@Y0e^DsPCM59}Wx5`eu#=H7p&DUR>0(>)4*QFx%ndyZ2)>`UG_W zU-uats0vCRBXeMNPyRe<55@lgeq_cm<*=ioNGxXc*$YuWo(r33#vO>|IJLu0J`^|| zxvMTgt8#gmq|>tl@!r^~&+W^FR0@Eb?W>2 z{Huf8A?*++eAa3w+Ot6@poF-OjL^CQuwWsI)&Wh1)SrNMx4<0se)Tw_;5>_G&BCb+ zBm?m4fn^$aD$_e2Yyqf`PQ0|G_BcfJrH8(pxOc)u>GMjIKsP^L)m`Mo<-9AOKW6c5#zQ1P6Thg*O}HEnslO=hdU5 zaFKvbfIZs$-tc_;vU_P4sn&seGO6(<4n`qicZ>8=e?n3*bm{VmaS|;J)$!nC3pwPu zyPy2A(6KH~&j7u+__$CeGxRmV`8@SqMrd*!-I?xt8XV18$iL z3{yPxofij^0B+x9^tz6}P#d$OX;eS;zawgKzOI-xeV6LM|5f2@*U;r(qMl5tA5Co{ zKq=Ua%>yJzC(wF&D+y%oC1q@%zh^mD9-!+NA-ts#YAnQ5`qNiKMVX(iuz95DzYjI# zE2`Dn6LLM~Dg4oEXSYUez!Wd-0`_&>#`19K>|bMWzz3kgJO&oM-D7NfHI=o1j?(}J zxsja`VXw7ZEs3S5+zYs$z0CZoPFvnwr`-;&?EcKdoV|lzvFHO{p;y$RIiz^uf9(VZ zA-PIsK43xp{Vkr3CF}emqeEiWKUmOQg6N3@bfl>6Z|nHiNvbS&e@=qy6euNg`SYF2 z@mEaUmnI^Dq}FiaTtTiRLkj5fGdZ0MOivnyf<6QYIEJXw&=^+p9B%o zrr`TGz>?ZXy)0c=4cDr+96no7cf*Waps45e zRegT=>azo^!7#n_=GPb^@_G~7^|1r{vC|;39eyb^o7*V-65Y{_e27uGvGpS)MYAMLx#6|G>aBVS>9V!(NBv(tJ8;1*vHTE!lWaufR! zoL2p&+2gy=R6@<*#CL90b{1HNm({xr_V1DeU7N__-6SRAKw*^=%VGYKs>oM6w<|g~Q2qnNx>IBUY;bymQRZ#q;PCZwV_nq)P7R;k9c< zeh1j+{R2ek-QWcHmtHYnS{?rrJrA5T%PuMLX5A98^e5(i@=M&(*k5CS11?)P77`q6 zH2$lUyQ=A&55aiW#RB5d0hBc{;T@mu=~lY!gm=ZndC!{4Ty8+W6W-kCXHq{7(VHmm zt;3Y83m(;D{$$FhG zumG+Q@J0Q~X(96iCMSYFl5sP6Mv{CMbRY@lj|tn`Gf3269ztBd?#s}cnLUBOS_Nv68IQ`%L zZ|?;i1I0kZE8@Q~P`|ahBLH$3lwHsy)87m>p=-#-!=)&xrLBz%xFph?_h5i3K>5qa3}?X7FV zWb`Qw+9t%z-2CAN_tD#9h~tC94HvRQ3jtAeBXkAw-g-ogrlFxkuHff$N7ii@*fBZ@ zt{Y+iYj8z0*R;0gwl*w2H{=D`;F5RkpROv-mG)APWuTZJZjaRc+OST<%}&TQmx~h$;Y`xfo|Oh^mSzBbGae96Gr?4r zk}E4th^(hEq&zq>_^yCt^9hA;7}ewX?9lf^ybJ7O_lJwk26}sWZ@CKHSRaGI84?7? z`xx+UH3Cg}fjy$Rt7_GW3kMah?A~6)vhX%QZ@|U4BDi^OM40G1)NXicNr?aSNd09o zjXx$EBWa%56RDQ1#SfzF+inbq7Y2)F5hwT$wSyF0`$(gfxAv~C{C_<$b7I!sq85I4 z@4eVuF3$T}?X(k}6Jc(U)(lOkK&zmm{QNNY6r7c*g++p+#EI_!30z9cny?Yqs3f0e5hKdN1J?3iSer;u&-oVK*KaZhh zvRRy)v>QlFCnpRWK@(B=fdJpDP9WhR9Oxg5vqx%1FkvR>Cb#E&STrSG$U+_5E<0iMa|?Y}$3^GN+ui_$Il; z)6Rk=SVc?aT@-tqABkg%h;OEu?fp<2U|8cDWD&rvnBC^b@EBYwRHAPn0LK6XiK}6R z%<_H%KeHEx6~(Pi?HuXt?k+nZ@CrOADSEqaxTT>X$eBZu?G?BVlc;$i6H&-@Jb!GC zYiX{xb?w;l*#q*~Hb9v7`1^XXUvHrLt#ahFz6~%n)*TpDFJGpfK`P;J$#AC4uCd!i-mVqr{vhlBra=Fy6emo}e zzR5CGiHIy)Mfvw$3eGp4+^)AZVz%6*6J~9FFd7;IC)9d+0UAGx5Ih0wsVDepRxEsH zt%bsFfG?qu^s0?EABchUF%*dN6?U8Za}&mp(r)EK$_W55(_hQTr1k)og%4!@EGM#L zx19exZQv>rt~WXN`0dz2zmZg%Saah@5P;~09iz`Ba% zSh)nnIWTOoMqba2=WH7fJhr)Ah*@Fx1QW5-3be%@)$X?J-3odTM7+g5#hclfz-D9kgD0R?yoLSy>%2*7BiUCd8&mhx2|k%Er`>+9++jL-B| zztTveiL6dd*SwY#q2s=2^k*utT@k=`RA=|@e{fjjs&E{DRTB(*f^7AhgT|#;QA3yQ z-nVut=|tX+d2ZVR>n|TOQ-b6E!7`@!P+7{lD9mc*Y#A#+7oHx3NGp$hOBCJQ`4ox z6v-XXC*^~w)7ScRa<2wVt~tJxCnv~w4YY=8?IR?&Xt;1$Uz_F6tlOH;pJ9o_d9Cji zKS-w@>I^A&v3Cxq?8wPqoUx8>@LH2cARCxFv=Jh-2?sKS@7djns0?77^L&8WN@-fv zTpg4zNxuHpDc2&qM+$T!$;O8*-Iw1Se7M1zYtP-W%HtZA#=ksNhfQB<2nS{QKacG0??ki zg)gFJkQdikkY-;aJK2pS8`zyJaH|qP^A9Q41( zXEBk>C$>`HGT&;v&cPeofEoyGMU4FvFHbZVI&LqS}Jk zxMq4aX@t52T#F(^V>xM>-maFFzWz^JVp1-6HP0mMuVGKS-9&|W$+JVoWtqQe9Y`m9mx+<2tncXP&c+Dr)?N!~Pb=oy7Dg;^= z@@+Q~)@om$@_S*r6tnY1Ms{kS+AFG9y%UpCZkTi|H6Ym{Fig2aR4555GhN*V*x4CPFnrCimAEm=MPhj}bnzrG;5;-*g}<00OF@GHAOu>&!@-sV?8sm6E(_Oc!J{m*wI9ojBV)^dtRH_1dzt{@N|U>zsz)mY7w6v`#smh0L}z@ za2iWBvx$4{fDh0GDF$E2^I2`8J;?0Ua>sGLAWLWU9i_zp=aKp@$hz?|dyyIv8$^?G z#?NSTu`>YvyVZS;IITAq;pXji0<_;i#%aeJH;N#Y712BcC>!#nUC@YcD1OeTT9tRGSe7s(WLKB&t3llZybUJ zIQk|TeNo9jhSlclX!c-qya*4Vecnj48d>1*D~L@tpQCTg9il(8Vx5^1Kn}| z%yVx#hJxRa*|jfQ7MQvL?$f)3%ft2l&-SH;4KgzwGo$xqcR(IX7ga8>=*h&|A>AQr zW!PvT1iA&iF&sTGz1n?#(rK3f92>?PMcWN_K#HmLu`D0sNsxxpE?~JYIInmMNf7;L zI-uuQ76GxN4o`u3(HftD#C1qn2Eo`?$x$kks~2J2E0owPhF0WmV&PEGRm=e zcZ|cOCTlgeaZLj*fMRJ^O^m89__ryYU9^wOD>)K9+f&|W^N{Pjz#GkOX?mv74AQON zA3Nv=3vN}9Uj>(hvKM+7(mES<)P*L@Aoy`C)HVwtxyhafRE6R1U#7{{;eCz&D;ZXBo#7YZo5I+of2lgOY1jyXu1L#+%;AOTYDP<@dX&}uOlhe4BR z99CBfp8(Y6cb#2Jy{BXk+**K=g-21zs-2l@t~vmoyyj{{s9BmhiG77&0dDd~-Ot23 z%n5=2e%birID6{Zh{j7}7SPqAhS_a)n;g54hPi?~RI~tJfX(Pij*N*>BylPL(K?1~ z9PLJq%gb@}VnJ0sU1a{#9#N(*$6qs*`SSwO+wO=q2ObljSQ{h>clgRK-7K}2fjp$9 zr4&(?u5oId7+nkZ(v$A4?zjQMKlKfRCArcU&**VB}`34rkpM zz_j0w-KN>MW~RY#J@OLBGHo0<3T_WZ&#n7b{V-@5N^j=`2xa!EEK|#N$f_fN3wPBm zz$pXW$5^o%gr~Q+w{dt3U6FLSy8Z)n@BC@jubKNY0` zL%9CxBP0@l9MczU-2kC_eWpET_D{={Z+*1x$)q)qu-ysuM-->C$C?uh(y$DV-b&p8 zeq_ER0aQ16tX-PYfm$EJjl^r3i9`nJJMTxRW4|8dXF|IW43J6VO{2Beh{otcaoYuja3cI zQ57~Gu^aQ;GL_Ic3Fg`l_YudYtRS0AYv9;)wYt7u^KSf-A*8Dj6x3?dLhBDitt#Jk zjt}P>u|WOKCmpQa&4%o@Z2%~8@Kzg-%$TRCwKeB=vc3pL$4?eY=1%uT6!PFmVz1;P z?g(-S47lb zI#&|`z8PK~k7*|lt@_CZAcq0uxp_o!=dPNE6U(Z|YbVY(RKD8cNa%+QFZFod&vaWJpQ- zP~QWgAxU;zfF%SNk5B8X^3VZ|HJsPU}wnAlR+b_jzhEX^N#>QLrP?Nt9d(BX%;k&^I zgjMn9){Axndf6lBTsYhY=D7qwY&Ig48TwiP`o7s<0IFsWA^`CpA=!!wJ-3iF1X~%B z*EQmaOP>;{t%F@M9^>h(lgN_Z8OD$9gJOOCv#hWae(+zj3;W`>rx29Cw<0taJ{LlD^4EbC~9mx`kT^*7)?}58(enBI3 z-A*?Q@;`nApw#vD+%4(3+G$#nJ{EvpPPQ=MRArN;7`XF0FyK-S7TNCzikd~%-StCS znu1sehS2gWUJkflq(=Z{4Ia)3#LNk?&f0%hRoE3`8YdEQ91CNmkemqFjxf|X2}Tx; z5mp`>T`VDRLclVtdvt=hdcoB1pl!LXz;*I+cgt6g(*bKRct zHGKppfW}~?uMZk5VtF9HjY%CC+&yFE4WXMfBpkWqm6YB;KF>eb1AR9)f&QQi+iBKU zfiBb{OW#e#R}Vi&Xsu4crB1=Jj|@Z~xx5Dt0$X#@li#`G$%h5)b9+a|xej}C&%Qzd zn>^6;w7B;5&|M1wQa#3#jP z%c(L@plfBjR4T^s0h0Ujc9ggLSTEWZ&)Qg@`llfq{_y;(9p?Gi+fW3Y72BcTfHm!q zs>JVr8IR?Wb#0GfrAY{hi3jS7b8&V3yV1aV*f5Eev3xIYq0b@7l2b`-tKSX=F9U4K5hJR#+xK~k&;W#)3 zIlp+PCOv4)lA7tb{iLbi>%u;N*7{MN)Zd6?4$NY^V2lg`E`)i)W+&3~1z|9Faws@B z7(v~AF-bsz*DcMD7(5xM_agBWAu%eBrQZyk5JYf#piAM-!q|bzTme{>7*hlspx?

qSCkBtD3{FgmuzT<^ml)NySCMfD4)9604p?Sp*;J z-p4!qltk1+Nq&i@>Oqerx}TW>L*fHjdXIU2px6)q(iQVSX7HlS4(jI|*=-auoM&Za zMRzX? zvxZ2qc$Z)b08P(qpO;;rXyBi>T)%9$WB2IyV|0lgzZ;wyr@I~Y-VGVrg2lLZBUELM zr_?*){-e0Ln%$O@gUJIB-m8AmaR5*sWI<0kdb!~0<{G}4a~mYJu}a;xOw31Zaj95> z^KoJe3U6Av-&P)_K{?K4Y@j(Z-0=m=41n;yhP}(~{MWCv3)Re}r#a$DDaFW0O~=VILlpJ z=$j_V2U}DDx8wm-LF|WFtJ(V;bF&u|?f(8-KKeec8N;=*5KB_Rix~mMQ3759gWNZ; zS$HNR(bg3w>q~Gg0JPRr0)u(^ZYo1!=a%THzd5c{h<16aK`8k7D{LWg-q2#}3D$~$ zGSk)|2n5fRxebdAWWzxt^!)J^j~5a5I&jKnkH`1u92c-?gs4NeO8bmn8hfhgnykff zY-Yj_(U~6zZSY>4H->_#`w-tyf+7P)XJ;j#Io#e>UIGA+Lof#9aF%atMwaHHM8@O= z`0qqj1$c^aQ!b!#y`U6&^7#@AOZcfAWQHW7cwpUf*d?(nTOk0KZV+?|fzq>&7{%hy z10G4#%tU9;`E@{n0)~h7+gT`xe5Kk#vq{2;@3%aKu z-Qsokj4@;_1qRfL-ft;+;SN28+58+h=a!2^__5GzKLJ@WkvSX#XO<7i%ywZz% zVe3rmTtl})_|BcZ=E_6AGTo+JZ~zjj6+R5+4$1d>E5NfFP$NB0omu;_x03Z-B3w7& zvAnr`Vtf0xTxWmC8bEEO_L3TiovPoEdeSz!~2H(jXsPULhZvOUd8;nuBSP?EIjN8F) zRe-$3^T2w#ETY!>!g&?sS`j~BzyH9CxBCdELwK={>*zlC41Z$8YK5ij*lU>Hj{h1% z;jy3ocq<(v6QCzMbY=J6iBs>mkNXHz_t;)m`Lc2Nn?BVXL>R93n?*Q%(@BM!?pm>S zaM?)<+5zM$W0bJ+1Z(B}R_`Nvi%+CV>y)5Ya&2)wtB2e!_%(}+oZlFQSM~J>`fhPRI z#(*;LtSvkcDCRZBb1?nuE(ZHJ^56=YJk9`KRh4Xa(2N%LCl;Ix_3;o~@qc3Pc0=N% zI76c3@_CorKVA$zI;R1I*Ey5zaER!~h70rGh0HCS4!~iNulryX)&SY>L5&=SN8G!2 zM^~3DWrA?n7gy`rG^7BA!R6*)Z$x3uAqOuTVP<<+&NIZf8rt$$+Mkg((5-I{#+Adb zPUKinRC>h0@yoFJE7D*sX?`>wSMwGq1iXy`3lX^)Mu9kF>-EE7q(T=Yja-1f{4qy? z!iF-VH%xkPJ(1e|vR`vgNmtVeUuIF{#*ty5ml=&{KlL(+7AlY>G2kn@dPwI zKwl^X*{<$!>il;YPfD+7e4GPi;9uWSW*Q(I+_Ub+R(=pnWSCO6mbizZ7ZN9x(ylt(u!IZ;Dv9gpmbe9jlFZ}zwG<)OE zE@&hJ*%Ob79Jd?}_fyH};A4i~gptS9e9a2rUEH7vzy z6ZwCc6>r*f=9?H;m-CHQtco)bfo6jse|R+bM>ul%wj8cT-D%Pd7+_3)O}uC2Z5b5& zSsFrmiLdr)sjTk!$sDo*R--1})e`*)$9~k}KwwdF!GgO9gX@|xXj9=g@}orS$!-9Y z$2?B$C(w(caVf8jRgeJpLD)*2CS|oDc?wqiyvXLLF~%Dkmahoh_3rOD09MQj5&()! zmiBPr1V_}jAAa{hkj~~k1lircsw<&`(MxHK7jIV3h%iqaIA@Bwy3N#NRjAAh5r8<^ zw>?9sCHNe0oDguF9r19WkTG}oRoqSn>oyz%wAce$&G1j}XZm;Ya4=9p4q?{-S(JnU z#|pgC?T635hW0Oi{kwUanxKF%cwQy6Op*%WX^A`ZS3m#itIcOZF`sckB|Ur(l5I#) z&I-7wc`25oaRV+W-93Y0WrYbl4WRPDjy`)R8xql40aEeH!t$i!LJntmDKIkM)<==T z#2ff~-dA7!@`k+DoBwYMBUy(Z47AIdq5CH?%q>u zRw=0bM7?n&0c!6EEL^U|*x3O}UiSuFmb?2ke z9(}P);uU2g+XU?fxbyFH%0X-(4B%zdsl^~j*PG=mB zz;_E;`|q9t-~fh?XluSO)2ETN9txkV>@82uMLFer5+!r|p6mq>J-WPG` z0?g~hb!gl=(lTb|L>~C)8B^Km#^7byI|4ne90uX)vZ9bkfUP35L^2}U;(ZF>RUWy| zj4Os&g()0RqHM(hGa^PH|0JgQ>Vig>6&*T$UiS*AL}{g(O7tBTgxTNlSnOV9u-HY+ zX)#7+zu;n>HbF`r@22RSbV!s4dF_<4)5Em5{D~*{18x{!YI5M=^bgi>IB}f311rUg zeW4I}PxrhoA^Y37fx4*WmssFb8;m-EmL})hnBXTTaOp$L=g0U~OC|{%K5Hq(y#EK7 zYn%_luKUApU;W2dY3vx8@q+5)4YcftW%;{~`y@%Oy1M%Rw}LfmCE9gnKnQXWgQCjx z)Q3qCH_f1e66<2PdDi6^f|Wd&|Hhcgo5h4#>R>p>@gX>}@;WWNKr#fHajSVZ=|WOq zVZ`{9(N*PB&|cWq+8@JpEPUsd`#wczgrU`eu<5l4jLXWKlA#fTueELEgPyb!)zL$i=?;!>s zwg{;v*SBxg_v3+J)6G$dz2k`5slm6$`#xd#Uw)wLSgL}Ao1ihT_6ZySKAyKqbf#M$ z{j@b6+9oL~pE51jmX~6rpO8tTVB0eu_Ka$+YMIMqO~E48eQ zcK`_jkX78V<=?_hI8`N$9E`Q?DOYjb|8MmterJ9Xibo5Z*VKzdeC=_7IAL)R@K)C0 zxyAlgj|V1No;!zYJ##(c%%6MG{;9F%p=>_BLgX)-P{A@~53vR(?yb1ambzY7`LVIz9l{1E^H)X}S9P&&Xe8DSp5(l+fGY~uNX0ie?B=D|aMd38wHRcu>e z!VR*~082C4(o9UCRirrmTxI+C1DF?~?jM2(ZS?BSjb^8KkFRQs%9MusL+akJZ)3x+ z6|#72RC;ux*_*>abDi1LN(dsXJI;umx*9jiu@H?mgH@=Fdvtm#xSLK*+IzXVPJdKg z*Z0gyxw?D@{|W@PTING*qi289H!i>E^Zhx&*^y>d9|#yPh=evmFBqWoI=m{}Q8>NP zFqu`+Ewj~G7xyL2oXe$Oy}`%0#D8G)4xrjZ>-}y@S=~T5_jhXy^6j}#|MuN*;N48U zJm+}Cy#&1dr>d=P1`m5CJTR3ZfKGpD4cA-|^V~5ujrrlS9(lRBQD%M4{qk=LXl3we z)Ns-UWgRF7cbOzf?6eI&JMenkmA}h`LRiUE}Pc7r_*k#^<_s;HD|m zjO~A1Bo8Qvh5Jrk?XB&+Yv3(X3sgbKmETDSFZB0DM4{tViCB|Q89Lz&a^QSQ0i-RC`|M?q3H0!Zw{o zuB##rIsLx8m_PMRSgyo>NAuk-Sojg^qAZ3ECj6>ccS?7*T_t#%uN*vs@~5Yyii$r# zi);`v%P}`Svqiu z%DiIj{3hHU+@*u}Wn;fhdMpWd?Wi$=S9Bz$RW*(FfrXmbpA48b;|>$DS6NrLZUvG# zCyW(PM{1RHig0t@8LRFOLF2@YpRVImC0nx*)P& zqiKCT3k~0d|1N$mfuZ9XW(1+}$ZDC*O4ntL$IfqICFCw}o6MMFD7?*fFUnhihnou( zctH%OfAl1r&C3zKK`q~VmOHlHSfPXzb8^&4xFh7W@Z_@VAe|ktxX0B9&wSP)Fj_e<}RqAepn-yT;m`W@H0tVA%mxepuD=*|uzA`Y9U!1P? zh3ncwpA%uJ0dGqYNK`~9_)3bkU+*5E>mVGtZ7*l?hpm$f4$M`lQg%>W2e19C&Wx)f zTk!DNa!UVa`-zEb?XUh|$LHXTCxFRm11`1|aGaz+?ll)kRp2$6YxmPIwSicN{}vK_ufZuFS1Y^-@m`~xwihZpnij|4wMbU* zKQeGk76`zM(-X6?+d3cyaT5<#@JQze`tMGl)BeGT#8u>kx1d3cxN8pgJv;ohK*5$= zU{*tDPYj`5@`1FakZ*3g1pb8lXghNzf_l-N8*rc8iA$yc5L#W?cA~Zj>ESi#jF|97 z^lbqQuhzi*ysblDaer?3=Q+u%gbfk+NxMc5r9F0QW+#Wde_Av9QsLUIw*&@=jBzTF zO+^5rYt*eF-f@o?)f^n(?Txf&p{0TT+jqjR>0FJimS_msR#WUh-DO0{A#f4wV<(;x zj-mL@>82vC4u~M_*MrNgose5A<%E&9)V&wjix+=)(72JfYQJqmd3+1@Vw7JgQ|{n4 z-*7N_I{zx9!?@*h)<`jX5w2X`)}BN6t8?QpzIWj@yxLm?7g2O(de3GSK_N_L2~@+y zFcv?XVlc$|CCcp@$ka8EsU5IrJJtR_AG}EIk}9Uk3a&(r*>%vOxj&$8(y!E90 zO@*xKQ}<_^rhQ8~N5?k!9PN7+aSD51+B&IX)rSe{dH{8CebUrJ>X0U9^UAqP?88Q> zYifUq%}a-oO!)UnRq+Ip89!C?CJAQ)sV0DPbNcpEz!BwCk#Ec=%Eg^$_SJ$lOgrT5sS zjZ>+wXdWZb#L=uF_zRLHO#i-3OOT=Ut$c+`^hC6GXVh@hWILO@*X(T@a9dzY$DDrt zHC84I8g(0JRId9>ad&iWD-CYd@5UBS}FG?93BOv1NTAi(jenK}PEA6|o!&$&B7Z}k4 zBT763aIxl99%$FHi|}gym4J;2Qv9dk?tOtV(Bc=s&>q7#a6R&Yz!&ysjF=cd1u+WS zgTIeEU&Xxqrfj+$utjHjz8E}9wHTY;{lVD?2WBvw6!?C|-o2J03~(%nU76FhCFIZt zP$HW>woJU4k)wymTTX%r3>YGwb=@acO&(w0(D({?nX@)K4*Z3K{c|?PI#+@-$Qrfb zF1>&cg-pA3G`fKq(}VH4Qv%R@(64~D=Cy}yeCAAX5cNU_U1q}E7xY%+{8UAV!6nJs! zzNQ;#s4orbjQ&K#5d&!%xe+o_JpD1uqloQxx5-8@5fr)31sMax9;A5 zR&^F=2ak)N1b|5p(`L~^?PvD#nx2az=4FgRZ2ch` z$sHyusl|NXPz$l$+>;W>p0u>LBu|C7<l zTF_<`Rk1E#A0K$OG{7J2!Bah2UECk^4;Lb}Vb!ZsTIca&ug>vL2VNrY$7# zy7yPJtbsl|QEw<4;K-En=7T zGw~J2J+UVM+|VS;h5C<>;5fkFk> z&)K1x3`mgMl4(+HcWIuaA6CTYBlNAkZxy_KAVsobtglFpS*1{6HedCo z!D7RJPSk277`LAVNn$1``ZoDE`@9Ensz@qDl75(+@l_wiRo9K;odypXU!YxN%KJ zWx-o6MfY~n6NV`-tD{AzdYdkx6}*ljU!|f8zDwS9G4&c+1oih);^Y(R1I&W zww`@WIQFsuB1 zV&8V6hN2QL6E&*mPcdBy<$^BF`!X*I6CEowE{#LLVsSvf-lslqI8=2e*L;Wex}n+6 ztjY?6+C_>H7qE_<(@A5GZA)D}(PZPen@Q3$_%9GDXjq&3FFn z7T0sAYV3R(H^j{4GrZ3G&#(9%TYPsOFKaF0-3lsA@jUT^#@JQVb%HCA>m$r}X8Xqw zGW^KF!Cdq*%H`(?gPlw>7Z2zzjExj8$t^xC;+*qmJo4dvF*4^?(2g8MDKgzRR?xHz z9J860r#+zwpagE~fj9~o*Ha(gd!R~FJKO=hxw z>yZ6vJwJ?YHgcPGhdO|)p)fp}43(Na_=5D{jA(Xz(EHK8hB-Lmit|Jdxby7yxS>nu zGADjz?D4})VUhNp0)l~h{oeuAERr@e(G*(`IACvr_GU z*~xp^PqkhiH?X33a7LlCxFQf{n(bdM8V@r+e1KBXilV4!Ciw`H&PIU+nGP^`86nys&_Ic4~mP(0lGfWaqu)EQ@CE z^U4(Wq&51_w`%IuHEsff<=e>mWoZGHlYIIw@_SG6tNTwW(D35H^-5a0W z23x4N<$YQ(#Jt#jN_7W%jb$t4!oRF1SqW(rLzfC}`=ZzDi|EiUKmaa_6E}%v#XPf{ z|KfR~eKI>)exr(NhCP$NEqd*42E%UB!x=g@;40BVL$wKS(@)WOem#pDxCFVvJbYVo zMVV3T?R>`~5h$qmo^=2FcB(2?4&VqnmDKM%J@XC%fF(oHJNC;A(Sp1cAS5!O?+%Iu zGCY}Izw2_{29FQlfWHLIY*^i#6QW1d6@UU0C)c8S`PD0Eb`a)ezX=)Hh!K(fC{OfN z5jbOV!9(x`v_tG(#2NW--8QqQYRw*2?+9@NOXaYFwj+i8y-ued=>Labw#EZCaQ4O9 zt*#`E8zJw^SLHL?a?2S7~lsIbqa&f0H9>#F58zGG_? z?Ehj6JPg?edWW_(`T8}Pe_qwDC`PEYW@z$AGV76wlH3NE)9_&L#Fu+zm07&GwxQt$8m!*Oa%xMj<{Aodi~^}Ul>X;pweY`mR+ zn17gql{fKb2&oYoy%h>x|4zdxDXhj7BVdZr#v@Z-BPY#pf*76(6Art~S^B&Lb{xsju}#|jPyB=d z-CrpR5%-Jb1PbO|uI!>_ce4bKiMfS&3dIx`L1N7NUI><&vG#-xTHIi9l7=9BbW ziDHSy&ZYzG>YY5SoF``pTZLjyg*kAPR)FigB#AgASGm=r+_{}N;rYUL@55i-f3d{D z6L_2Q`L%R}9+klgZ`aF)6t(k`b96C%-Kk78vrag?f#<9{HVj>@9D7z^PhuR$<2$6o z1&_fQ|KE=^BiY{OLl8CHs<4<3=SDb0sAk8ReJkVLF-S`fKTn=B6YWg)$QG1i#~I4| z0B({|9hIxLADj2U2Z9uXD`3;du{E^qfp`^qpaJm+eJSIjohWDj#1|$^t>aRO-<3wr zlMncccO85X$_u|w6b+cv4S`Eb-J95Rd8nnqwJU;nu*tK-Eqn`pr20A<27wWg zF~|*c5f~>4{)`DV^6kg?XP3SWF?|z|3eOqo4O>0@v7sb9%u*Z@4cj*nY0b6)3htFO zTKK${SNtMk_3!W{g@PIUGhIiiVPSUcuCgV;;zF~F!b;`mTOY%e}>J4!Ik^153s z)c$vx;?L=(va1hT4(tm$n zwb?a2a)6c%5X~ed;lT=w!yrRPfPv%0 zF%#Yd`0^E#!-_Qz(eVACS8VybcVp3DKbyVk(Rp}Ep`zS zm-ITvkbbyvHj3jKWMDdP^l+}xqFfTmo7Sk_;5&K$&OAs+1D>D?gq<(VP=rY!4LeeU zZA#wN0$NvwqpR+|D-tbyr2UvIY+Z46;2~y53r{w?>E}bjV{lj&FM;)xm#{g|?^!Vg#fYrbrcFmDzQ@@s9{Je_( zo-(FT65&?wdfAIE*=%P-w}K8B67u`&%XVtt3P@lADLp@~Ack&ei;^^jRmHfS+uwp= zJJsv~F4b+EMz5Kf{Y!gUmCVzi1%Il{LU?Ep^XfIy4+67)rWjL7~ zc?3^Zu9n>lKK(TL$+WWcJ_Dh9Y^ zJMVM4tagmxsOqz%f)GejXQjGgU ztq|w^51_WSh2-f#5_OmoeGrT_RiLA8JkmtX#|8;~Qo?kG)UxJp!5UW#bf|TtW_bJ+ z>GcvM9P^>`AdeqUSB2Al;|6h%M8fq*z}!YnVqm<;1qZ+&Jyny+HC5o!*e~1}tKx>q(hUovleEKJ~EwBnZ_FOOHEY?d@6O97ad{xPW zz9Wz@16Gt9JC=P#(HPsTBsNkm0@0;U_q@@r0sUrzb7c-BeV0G4YVBbH4=Bz)*Hg($ za{50HWY9v3?jbexvIm}oLXkO;_`P@}pfRro(tM!z?&IB*LZ1WplUzO#Epl$P*eK<% zK#T@Jj*1B@Iw-l>b9%m#YX01L0Uy(vF&`J(I)V`*Z`q=#Z}{M0J#{y# z=k8Gvi}ToRu0jm@(@-}Vb3+OwMv?}=~0s|NKH3tR9TN#P&W1J!hZ z*tG!sX%XeVY4P?fO59`__f+{B&)%nHL_zq9M|x!8bV1|#Bf#R zDKch~@(;O&M4t>rcqyMiSI|J|8_-uBj5inq@zL>z2KGNJ@0 zqokO?^4q~!*-|x#2InRcy(Noboi^Mk@UcTV5v*wl1+|xOhESyR-305g6Qp?QGnWio z;}h%(vc&{T5i8;!6dN}&yN@~Eq96yfblUxX;r~((ey>IrY%r!!irBNmdIFW{`>!0_ z1`ilYv6L;|#DSm#%)o#Qq%)Sd*{eJRBciA0>>39NMQzBd^pG9m{jh85{t#Y0mAQck zmrFu3_@B^aeJEA{__U;+8bUwsg5{BoWMk;h?dSF4&!?;@STHUrT=2Y} zR1Hv0l2Ax*5;r%kFvm&lKy}`qYtE630filL`*yZqY1qEk98J~Ch~zDn_}|cy?fKP+ zqX4$ww{swXp^0~x*Wnev>1I4S@$My5%NZ))d`Q=^EUV}4V?Kn?rYEFRI@31zuo}3E zu;v>qiSt!+bx(X{?i|k`%Hh4NL${=~<@n)owJ-r2KM-iOuIg3{d`Y=#D z+))~m_%P(ghhJ{ ziz5Qr?;?-FD>so;<3B0A`YSGHqzXwFuSUq^@f)sahcRB1k{7F+fq^j1-!E~h`l~r< zLxiMML(WW8;_sg#zVDnWgt=Eu^BigrY6dRm26og!+MOL9iBVrb%6{A3_vbp zFgNCZXQy>6BRtk-jvkeVi}D~Ix}-qg zWx}(qsc(LlE^ko@4Dgc1Ew6*WLo;XmZtSC>QWb2)PW3;~$N%QMp9jg3@b|+0E{+HP zSp)fd`X%|+ttpr#h;0>2n;WcmQAp7t-S%7}GXImXBPOiuNTqRVH3}k9^3Lt=d>A@# z$cr-8x088sx?85GFp9u}NA}4f&jiq=4Ug`Z0RuW~{CpLW`pO4$?8TOz!! zhy8p-H@M}~aCP&);>NlIsWjk~vd+Gifa`Ts*_#?O=6z5PvoIB4P?ZI-QmA(8W;}-E zFr%dK5DGB&8nA`Y~5KIHDI++G0DrQMx1g0L(aC6qUU zK2c8%EQqc{ATun)4m-Fzj8;;g8VNVY>!rfs>dZ~Ka4@O1D>Qu;tE%V@#kvnDT_(M2 z>;xPW0SzDMgIk7kOk2U{ZE?Z3cug+G{QH01^fJ3!b@CsB0 zd>e#a`X!<;?LK;RANwMrjbdd$YjYdus$N?#san9TcgZ#4&wRKTCN+wYGrCVV?!on^ zg7<%FLc@e`e*;kN+$bQ`E zUDSvN0=77a>4Bew~sH;p9zJ(!N2zd zbU9I-j%s#)rZY^#M?{Q+f1uAY9gZWRd;$wWwnv>2;=348vs6f#e&SEp2eSa+R3Y-c z075PRC*L7}OJz#XM%0EgK@hAU5ZJO*HzPf)UY=Uv_gVNr^7xjQF&X+vSMKlnpoCvZ z_{6(%4?EIdY5|C_(VP=_L<~j_Qa6M5rN2aie$idTV%wnR629Z8s^DOZi|d^S%O|5Y z5Q&V8T+a2iGb41@AX4|Y+)IZ_V6&~FNi!F<#|zUbUJ5qGiP-odi~9}bw`c#mox?1D zAquEk#l%?^)xzYK;mpqa3geG$s{QgSfStA5no`!*x@Y_;fXTJQF854uJir6_42jB3 zMQ0$tp$p_S&8D8T&)vN=NpJo}KJ&M^CqR&4HaPo;7Cm_g+!D?g0)AmzdfK0mU8ddk z-PoOQz58+Z+;?C3NVz%oe{{j(#KexI+?kpDm$SPc_K?9g~tk<-)PpKRO$2D4!9 zyHw#~-oW1v&2vrJL40l#x*hi0v?pT?4cp>nQuA|(#{!u6-U1rvW0Y+vxPM(q_n_GG z{E`H9KjcCCc|jiykot%zaq8YQwrqb-_iGIbPuSq!<1?4_W3RQxZV|+Mh*O;=Gd9m{ zDoX4Y=xK>EZf1}xtcLnkTt#76_lk)OZnbJC2cay&Hj^SCb-W=2yDgWER`-a$&g)Q1 zH3tz-WLIXOO2v)g3Sv+`$^IP1Wl)1ln;>=f45Q506H; z8H9&~3GcZlh z{AKCYiI|e1%>Oj(sF_onOAisPnT2RgaI}j^A0)7-CA#c?OD!fc75DXb#%=W_d*$WPwgA!RWchX4u3AWHcM19La@d`2()WMF{C3@CyUcJ03ZBG z?}R-gp_E(ychiYJMYr~G?M2$AsY6xXj$Lk@?Q>J7*1iI^)c)qmR*&+ueMAy^E*h9z z!7d1m63@MbrkeKw7~fUBrLGWucItRz2yS|F@bmR6SD@Gf1e2(fv{C6^McAVU2K|4< zcpdo+zng>`BY`4`MVCx&F(S>@B>#NrX3brYH~^&RYJ35gnIWX;b+=SZaRm+YSlj|= zA_A6NP9BtLnVCb3io*0yC`ts)8mO1Xr9{%V0EkhIOfrf{i#|{<0HHCqu0wm3q?A$C zXOV+o7S7@b6G9;?Pw5D6%gHyN*U8mU-GJ(`bzLUWF{$+ny{Xw*9f?C9x>)n}c#Zk7 zZgaOsY{~?AufE;>*5a%6iReDkB%e*Otv9+l5gz{CgIShkQa(p)TblW5YFya30pqHn zGf_{0it&Uf#9T6ssA%j{o|{d!xuwN<#gM~uIIM7p8U5I!MSm%uf=NnMe|tgbh3>r& z-QK}5>qF$BKWNPx8JTKboVlOsWOuPcA_2FtyD7RCuDSpG0ltP>mf5q20BILt(~$&r z$sh+CG&lrO4-7gV+}<}&N5~2 z%cv46E^3x}-ntVNANHTa_m+|0gI`~lVyuS8IUCz<%SbBdH_a0~x%8xRQnbI>ZRQ>q z=b)3hQpk_+i$&UAXgz13mRmLe{ZK=AZibD(_(FFGT&O4N$<(r(Uv3gUbTuP=)+No$ za*~01`N8;?_I2g55g=^GYgPUojC%9u`#9&v?u%gr!3fVc@cS8Ixu@wKE?0b_kl~}B zZo-ZZVDbGnkfhQJ%vX)$q65;<6QcXvwMV+7_?Pl);jT8FWUVq!Izzpm)@Xtc;F8iu zM}dK{>A_>4fO@}UV@;ZQ5C(NME>YgjfBp+0O+mrq<*jk&iAdwpm!*y79p}1oDJ;=f%PmK&c{w+)eyyWX>Y2+EEw~mv z+iyUh@?IKNe&?5lC0$4M4Z9Zi_HT~}AT6T(i;T~Rs9kAT2SnVfn@_pBu3GlMe%Z0o z-pSd|I=|)mdK4N)9rawt752132@Ex{Z^GT9pf^~2J3|kUn*T)@y!O_u_UUScTgm#P z)|X5B)foj=z}sByOzmqe?}>K|hWA%s-u=mh z6!NY2Ny>?84HJF=gMdf03gJAiH>ro{u!y=_;c>SMkRNzNIC3M-H5G|1$(}aKakR(q z86+s&7o4jaXNNTnc_K&aDn>RIgpZ#Dz+fcE8yY> zShGCJr`6-^#sE4Du^7|Tx-7ZBqV-epg9I3k$Kv!vGqWzD@ zMbuv@&D1{v)k?inK1OM)I#g!M+e`kB~yc_)(vSIi@>>)*|lL!N#R_mq2kp z>$#q+AUZ8^Wt|QqfumgQbYM?Xd*JvCckP7kG}I?n;$Mo6n=)@hhF_i1WSMB3t6;_Iddl#CJ4pUmO%0Maq zxbqCvV#K>-6rWgqt=;+EC5-~hppHE35%DwgpM+R$%vDlB@|B;Ik5i~_<62g=#CEW# zIq3+`i>$v6P=)P`^=5k782P|jFnJ9G`w-F9n~9XN|TY|9k*2ah8Bi}_FdChZ%M{g*}v5&!Um)4{H zv%5f4pGw@O>%a~)5OLM`DX>2O(HHCW(;iOjQc&$>M0<%iV+e=XdC z)*rw62)saQV!3;MY@hYpTRDWPj+Ho1Nc;3LAsVcXR>n8G>rD<}_euH8(c~UD>}7=) zcjos+wk8}DaIEZRM8YOKP-Y7uZ!J@v)l_z~P~h(e_?;q-3CyE_+|`^CjyfO3$Dj`o zq-Pt6um!mLh~U*l!n?V-|Lx-xT<)l53!00Q9y1bgJV;3=`RDZ+l3QgKf!0r~CBM82 zi_PF%K_g2L0*ob1`CGi#6LRaHSz2IBW$pCx;apg@KPfN=%H-n> z=z!kqiGbyLeJj2bAbA>uup;5Ok(3S*fsb9{iV!$0ZSev!b!Z&L?@sD$!4ag zleR4CRX;-q5y4qcm|VQ1gzyIUH7H>3DcSYU8u7(E>RHKfHWWpmWR&#aP4zFA5QsZ3 zZ$dycFp%dzXUqfBqb+QtT6H1qpVJ z@q(Df5?FPy znsk{r0dxbi#!C|FLC37=HWTe`Yj1GNI}kp!@vIlhqKM%GKD>0mOgxzDoph3e9mx`C zrKZzHFl%^cs>eP7O9{N)0<{Ur9nUb|5lEXY#|&>)>eM=XaKFq5EBh!(r|!5{WslwT ziGIq~6`)p8nT9iciVjAK%Zwp#vGMvU#O9PRbffYnzQ*VGCe&GAT0-mUkCKs_0(Q4` zhng=G-of9DdPv|ABFetRi`IK?J_>?W$7g-z@_05Vx{G)|;SU3Vgw@eaEcT0IL&cH0 z87z6b;RRIlKjom`@GcEElElH<)$&~XIu^`=7P?|}74uC=_4mDJwOoo{f3&+sVhg3l zS;y^I;+C~Yg{}8BW*w3qAr)hMp zeIS;&=`28E1h4-6x7Iol#1iCQ<{UM70hDA{zdbal`0ih+%8~*>J47|mzC9pKu zPsEhHp$PvXJTZ}`4Z1Qct6%B7HJI!bG+p%ypH0VK`CikrSAPGO)$VaHkLK!J7zPb{ z!ht@8IG^+jueK%2cGKo_l+8bl0p3S3+E~M3J2OghkhP=(k^51*m~fpmN;7Sjt3*>3 zcD9mXlVjy4?MOGXi-5G)kaSG5WuAO9;{G>MOQC?U7lV(GB8yjV*c&$fCwZ@F zv84necW9FjE!iY7Wq~KK*u=ze zoZzDJTl83XN@?2lhVL zokTS8iAk}_OnonOM}B3#6Axp$47Ar)Ass4V z*#jFQZI$is*Gu-jJ=mEN>N>Ki@B6CNrycV64mO!u1{j0V~tq%wQ>`xTH=mr zvf>C)zne(IP@ICf>C45RR|jFwD?Vx_1w0m1V-xEw@u}7eO!6-9BTJ~jRd(CQFQjj` z^qqFhApno!<0XEOqKL+dHHs3Z`F|#9vO{kHP7I%U`(*_!l84wXe8Q&Ml8}Nz5|UulGNCVZr3`#> z^<%k@CBKk;YwiSgHAJ5eRs&^SIOPfnB!YeG_Edv%0`{Gxnc>?GsQ9c*Hr+vG92Z42 zl<(zF#vk~I0x1x@lZ?5c1Y-pmm$rdN2H0<3HeD8x-UbPYD!R>%Bm8Pad5mGN)!PdW zA_*iDOPNfvZNy*54Q)bXTyiUMGjM%yq&Ix+xP{~w&V?RE1v=WEUNa#4&3+(iP}8fg z=+ZKU0(ptcuILWI1AabcMq&ih@1Dw)Jd#M*QI1e(cWTQ;!%xG9LCQNpUSNpSh1-=r01<$h zgWo+-7>@zk8H$6BBI*Mn2K(@h*USP3&XVwvI&Jg0oeSo`0qTK-3iNjtu#F`uPSDnU z)e8|yl{ja0hlt$64&(;=nK|3|tx0HwR6_4YJ`VCylg$DslTQ$#9Dyc&|IA|@cXzb&L{;d1i)t&bJ&-QbrM zMgJcT;(ijk9aUkN@ZzWDw#BFZ226F9XUQLApTWcVh!}zBM!p`!5xW7 zd_!q6Teu+f6gL7x#tE$_cm5I=K zA1DBdzk5OY7e@mjYWX@8n!hTZB~10h2ktX*SV!?Yl@9uVHDWUukfrN*jmeB+U{SMI zaP~3gAQnH`@#D6<{e*XS-km;0nF?=y-BkIfdMuJ>X%{*Q%4BeLYw@50-bL)qfOE|d z(Kts))bG+dl=l_e0w5C$tc6I6ekbIN`$^+*h>|syf^a@(poZfwie!u~-vs-397-$e zcUx_SA1}$mp4f~n&Y*zR&L#|9TZ)G2{^Evs7`#4)Pv`se93eS^_y<7HK1&1D9Gv{A z3mpIQqMs0kci6aWap?xaqxChafJ(vv3GXJBDYG zPZbm;80VDiO73yFZNLvZAOhS}sr1GA(5Veo7@*wwe5xh-hm8>kCyAsseFK(dywFvtmxlqc46*S? zz8;j$EbCnA6 zn-{+;TorgX|AY4=ZkGXhhy>_Pgw^pf(Ka_T&Uy-gYEm}ecXuE+*l2d}xvRUE=&!d4 zzWdMMx@)o)zy_Xv_Pn)B>RWr`uVNm9JTcDtl_1dQXJC$0387Jwx(P$Lanom;SZ0)y zPZ9t9i-`}3Y~XBsCnG<0Z)eHm&Z~zc<>Xo2s`CleGXiBMQ$0~(27cuQ8KMhC%@oZJ z>?=_dOJ`uA1o!VDx&NmnFBlhE?2LW;qUGGIu>Gybb*=O7w4#oJS)+dbY&Y0W=bAY; zbsIvlXVd7gMLz!ZR7*Hv7Ct62dtl(WX}XCq7*{Ort={ zwyJ|Ov=BRqi9XIN>#*K|!eBuO5;!bBnD%gCe2-Hp9OB@6UKbXxYNwaFH=r;WX-luJ zJpEC5vF_8X)BVWE=cMDO4wEBgEbY}1AzlLmu-QMRE4#CQj zlGYixnY4_R`e#iPD1`Kl%aE9Iw&PRw4Ob((PH0RX1 zHm}9dnP-%{wfALXYCJ%b2_$R2{8&=0Ak;Sez2{?>K{FfsW~uhUenQWpYTM@5AE&-D zO%`VkddhOPwKXPt5X)RvWmcf8sZZOR+dKv@U;Z%j>j+-v`f6*HgL^1f3b`(SS1#Cg zx7AaD!=AX%fm}Cawq;7}pZ*>>@}cTRzCj+dl>}xwzH^>Lr2p0}i?6i>Q6@my(;NKrYV zMZvm7$5@S@oP%REkF|Bgm|+ZkG?`CnPGFy zP?-DOI`VVQ=*gtb&j$Ry_1`!qfK+Jr?l5V8jGuu!*e)238+4Q>_btF{q;@)|8Nw;vM*{$}G68%RI9=ufB~Ct|WaMisn_TN~&&rk7gyTs8J&ekPU#2=VC$BT-|`~_p)#)7QoVM z{*c_FI|MMbwnF^^a_uQxrs!wx=0ne0GVL%>U*_nubT1ZXU!1vI%`LMwn-wLc+u?vu zErN^&zhy@2$(*HVd0bMov&hIhtFIN%>LTX2WyuP9zgvRkM$jpE1bWtpK=exc;@isDi@INEO}-uQbz}2k`XIAJBA%g1duXhJo83{xXl)lS^JQ3 zr3+T%yLP*quA=TR1T~5`Ra}V2K@lyNGuzy)iQbOTC0#kLwlS`Lzo6iU!onjq?eFA> zSqCtYU}4(4(oBpp+f-lN41+VXps_a$x|J}UXSw(|+476prV0yJ)FU{SD> zI&$tO>X=v^#otdsDUTpP+40YY8dynjdB1v7d_i+x$&pOf0nKNz(3KYyQf$2dFY50X zC2gh1m;E`tPl@5k4LMHM`zD8+bBSJ-#I$!`n9%47or+kAaV=F(OYz=LeYQj?_Uio7&X^T^*j^ z@b+%ZuxhG*_sQ~JO zgNXIQsb?#T+gZA!TZn$Q62A9U>+C)IQ!A8pvKJ&8nOQh0%?m{3xKP}x7L#V__MYxi zv!0QK6@l2M7*o@-*Ug_xGW9ZP(fb3teWqw*l)Ey^o*ZE9@31{_2d1h8bthb;8`^D_ z`7(31^Krw<_8h)*ovPsh%gc8JC?eXQD&sp-hfrX=yg&?YHx69#z-Y zmNhioLL2|lwEHNdpoypGBzRvSHFGXpm}}8yL10jQBwzxQU4@mET=;vdYWar!=ZEC? zqZ96>XITGQ@$IP8fmYz+sy=bGXZ{0a36pz|43P3 zwr;vfuJ>`dfMC)VXJaIpSvD5SksenS4nAR7CFBDhzju~V%S6lMQC2=aJ~CnqZLPwH zLsnnzWstkO9BstXERPF_<%>&LtVxz$>abz!)Op|GVUuvPVJB4tQydk6%>dPZYEbV4 zr8_AMju!yrvPm}Q99S)XpVs1Q2=Xh#4wzH=N3}N`@;BBdyC{6iXIb^<{W zBel*R;|B&q0;1~V%shb+Zj9?Ks|D1eIJZA00NVflhB!=F2@b8>Y&eJcDVrD08HWks zm1jj5DKUKM+f|AEa|IXJIsv_kGxG>~44iVx7VL+JctFM!6Oe+0G(ITM@U&)8B;`Or z>?G$IsxeH5VuOlFI9n~SiJo(;Df41fGvLRH!=Tv5kPELoBpLT)K9?>NOhCF`2b{hM zBR`Jy=r6CqO>8u#h}#e8{vy)YB05rApyPQg=?X*;YG&{hQkMF#K10E9$wvWS_+;Ka=rBtOMR5f`Gas|$F) z&7nTRv}#xHAKaKvnea?ZJSk6g?1f3QY;Ixiwns3sL~!$zL**&HsO`iWh=MK(|3V^IGKvp)ZYvxK!PMTrn^P)rmg^H z>+cZN$%x&;^Yj(NN8Z?!imR>mYWvF-f_XOO6`}A+nUQcS&uds6b>S`WVQT0dULSlh);%r+p(=m zl@NvfnHGQ32Wm2&ZC@`6a;`^XuP&vu_%uEFh^o60xq8vlUMrGTotosNZgIgNujxIV z5OQKy)UR(Zu8$4WhIHn&+$>QhI6U0P7TAx0@<;8gV<)|u1~3$vm+VY3)D>G_>^BEK ztg`Oan(i^BMZpt5Mi%A<6l=#Nmg{}Ws(^G3II`&aeAa*Y^bN-V(Owp&tO@obPES}{ z`yj5)wDt;ZCa76TO1I{tdXCmY-N#N8@9olp&=uoRaA0M{tNh5VKbC3FGE&3c6Qb@- zE?gebO>qW>$9()fa9jIp% z8+^0a-G&Ddxzi|%{!zFTM`=Ov4A%1g`f>s9++$Z=e|fC<&@Y=jU~%yVrm3sOUHQTj zK(VwqVOzxLy4K>#3`DML4`u+o&n|`P-U$d|4gwP5)jl8>^@7OkG~z(I$4x_|X)+Nw zaX)Tq1+X-s$%Y2q1A(HPh@GCwM2kdv=lf)ss-o_lJ5+?ypm{s^VYiH0krriv6`7Xex<1(>IY+4D2egs`Cr|PSUeQ4 zkDWm1W95iV6{iEa%Hlkm8laSm=qwRoiV&hV%xqNf@Kq2wgUEP+Ce)*?t?gZKum{ir z@P;{z!~xyqC4{$VUUe>e_wH1QfbNxoZuB8L0Q*(%>;8b_ts`dlODllS%WX69LpZaW z^ou;XO)UG$g%kfQ>Re>VU6-U*_8~DwJ}kd~d89u#>Y2jWk2?+IA6RO*(;&v)U1XIL zYYTP>+_iGo?5q_E8_BCfl9JIeF)s>28bX|=E6hJ{XTVh-k+n39K4JNhs9hw1CW^>_ zLV!)poLtIq^>PXFhKo%x67^caE{g!m!MX9AmPKgS*%}Y zVWN{9#qE5iYpK?@Y?t=pmrp=hssrR{U$s<^10X)Vsq?6M|6s7GH;9d>#5&oh{EmKT zmhqykFu?cPI1O-WzeKb|h+MBgt9#rA7f28&jiSBSd{d&IrATazH?;4aEmsdkLAO~Y z)!I9g56BF zcUrfU0@<|sFK5I^{|PY`2)fP)E;x+)pHuJKyWX>R=h_j>Dj-?lZ2iEjmY-|Jy7fZRzg7}RP z)8J})3-ADhd+i1II&(zm{qZPvTKf)Fk4e$Nf+%r_N4s$nz6Chux|&TAbI6lc83>;zeQ`+Ax<#qm-9z8CuJOJ(A0BBlRa>j;z*V? zgEk{UlOKl=LlFvW5ewxw=@#29FyrVW=92{rWl7mxB2&2vF?1+bTJ2?7@7q~ z?KsM#-%^ak?c28({UlRbM$e0isxMFK&mt$9vXG#Erg?M@ae4o#x-IgNwd45{>9;1t z3-nH_^2;3~R`i3_XuC5iU6SIWf4es5`}n)iIk&yU-s!-tgvDsJbC+doZ*Y&C7tPDf z-~QL<-_D!SSZ`?-pq{FNsUVdoc=@Rj`GF z%RXTEc7v`FdUXN$^%e@~eSlukxXoxUkedN{u}j2f8=`!$Kq+vXEr;|rhl`HHM)m=# z$?Y6zuLuNACVz1LT|b}3 zy`i)k(;*OGF_|YZFIk%VJ?Yj2Esvapsb_$f&xD(+eQCC@mgRTpm~zG&qWO@g7Z;Mz zWY@E~f9w-9wzCRPkzB6}Tr8v3R_}9ZhGfPfG9wzM9Z;iv8q4w#o4#hzXy(TRp&~hKAz#1ENWip< z2~vUu1bi&_k4-{;<6jK90~dB}m2yuEaB)+OO#Te&=Jw7o%4=PGFERy&oC!TKT6{&D zXA^$5b$?NpqTJQg?kl5z!9;@gnxO_TmU3pslPw`?n3xL+HZ8P=TM)$`3vq1 zW+2@^^iIe7C10(OPMZy&J;nomnT-C7Z2QsCcy2)^;&lUk^oQ^v#^ZIZ}9+B~ss>0K@=OwZ5v} zz1+Mr>A@;W>Z{hBzyO~Y6wK!Jpd$3WJ&aA9eTarR9g_YC6{s$M5X7z;P{EN3k)uk+ z5KES21H16vsbt3@D=?jPrArn8FsP1;i_0@rKCR{?_3RcSC{knrEC*qKmimCRGaTj= zv!hcTW1P96`hmVP+oJaOIN9uu37Zx7G%wRb+B`O&p8n}bP51T4R^NLsboYNa)oySi zjpo!nwKjvSiYqdiZFatG5BP8HNK(D&um09Eml9ciSB&==gL9d_4cD z!=$5gA~}0Rd7S0&H61fs@t9hrm@Z2RmY0$Z&Lj3L8@?{1t8kG7zZn>>8HTq|V4Z$v zHW;P5Q8+&WjdW8?0U8z+G#f5(H|ggLSgaor0?LT3Yqt#Y4-Vs%$UcPt$tqVE4z zY~X}*Wf$ICclrAc0*;owT;t``(8thS~&b!IcsN3OfYhCPl@fR<9cqUVicgk+^he}XLaz{B5CKsn z4lTBpOW1rVa;=cn+AsZ@o0zEyF)ND)TEM3ygqdvAPK!NKjw*d{ryT7CRpn0oNfh%F z-QqXf8|zd&G^l#QQ1sFS70MnV-8*H}l8c||Bxc%M3T@=`+O$jx=9=l&odGu*nJW1_ zst7Mwx;h)U6^^nfqMIA}nDeZw@yIPP7~`*a3y{Gdg2)6yhP;(&Xl>Hfb*#H+<0&a0 zqInHiKp&jWwrC}sQB5}I2|zL*I${IZ&9oj` zKP!dg^#D-L00%9Ii07a!?t<%-0Ebk=5J;Iw1Q_AsE4e5Df<(t?#h!W(lN;g^0`}P( zAyYYsc-E)a>{A128Rb;KBJp$sLDs9;uR;A!tPn^mQ!>kS#b@g-na|V+mcPIBLSga8 zGX||gl5`p9R2*5%)MX7rI7Ra~VmM=j`Wjz@PFhTEg0Rd-tB z59+1`{CK4=QgS)+o!sd=uFVJ>zD3*B*=eatTcXzzgwjiU$xpi?H$X&e`rAo!M9fKA z`$0nFfxhEIPCrkw;K^~C>&CjT#EN6lf+Ht&4Arp{_riY+EYrA*T35$Y1Si!0w;HtwR#pWpebJX zK-z!+=w67+@^IF~@qqNR{WsQs-sp=@NOsQ#2!3*a>ry~kR+dUtJ1QjP4~b8{M87u& zVg+A`4Pc@ulRyNuM7$DZ({RzYrc%~k@L*5kY zd4S@{Pjk)c{Qw&8h1j?d??Jh|VCMn+6a!qtbtCbmpT1-St51Hv*O}dACD5`vrfPT|(r)vMH9pjoF%Qs*RV| zQO!d3#Y@1j?_2Dlmb`7ff=xNcZ;SNrO+AU_Fo#w5Ifu8igu6~vERICpC>PEvH=nc5 z>u1xlzL!7J$9LkyebwG>VL_<8V*B=e{fA*q>vCm_yACSmVG$V?p`Xtqm2v=;>ZpYC zla)>$Gbp|QWe9unr#^SPdJnAw+;*RL-Jk3#05b=NFXenBF*=+id2P1Q9H>sq0d$jo zulTIuG|6dgRGS4{ylY5rkzN7H{SftY9}uj2xVect&X*u2cf`IPV%ueJKHsKa4u)Ol z!jV$+OzOQyJ)wGkq7b+>%8)erR-76h3bm{i#;XpflFGCpj9DoM4$t3w!A$jSIAeju zb7SITUSBVpkIMq7aIN}O;qPxftxr10Og+4(oCUT z8(~#ZcA)%qnmM&Sxc4c50>~pHiSY9EwH2L>^|dw^{7h&OA#NY?y3*!yMG4PjVOPdF zvQy@>xDkCK(rI90Om=>R<;sH*>8ROC?Oj4z54SB#8(PZNOLJQ+)<5d$lEUD4FZ2Q& z7E^iwZ1(uJ*gk=J?-XrI8V9z5KP8$7LnkRTM>As7TV- z(Wa`kklRwqP&l={R~t+Jb`VLf)DA$VcbVg!aOj$vBzG+gQ}<0yI*UDAbD3mOFNArX zIAOEf{lkzC>(ghj>qMIh^Bv^_rBD`;MCKkvVmjT0&SVrs)laUt`c}1P=-3d_E*GPfKoq$4&3Bmk+;ExpB~J$wIX#lhHbF@?axmwa z_OwjT%ujTpV7h1@aBcW#FFw<*lh|JT@h8Z=@T%+HnC%WqIp{1*sLSrv5sC%_j6TV1 zmuvUZP4L;B5yQ0D>M_ACI~{Zuwr`&~NqnJ%+4jf2@TF?~K47o#T$wB?@((|MXm_7V zih~M%5S3lDHcswiDEj1Y9c%-vA!RWVb8$izKd(8BD22P1R?OA(Ec-Kcu^k$y6Kn=0ZAQ0=_>x+1woXhuL77_oo+(822@mf+k2aDWT^ z2$$AdP$5>UuF_AJBC*jq!R{Ad5BZdv!*9!giLPFs{APg9^(VJ#h){qn; z(rZL#NGU-;)v8aI+wl&RNmJa=3Chg_4_{ov2)@uUcWqk5YS7nnIz)d=p|ffi)HWAAy@7*IN9M9Pd&4?c>L-K3LN^Td5XwZjL0e6|my*fF;r1e@9Py02tTW z8N{lS`bZ}VuH^+@cr~Z)Yw4k=~sHXi21DW5%DQXtGge~e0O~yIP!^A}JiKz>( zWSXy*a%-@p6fSzQEH1=&QIm5yYZbI?c`bYP5gllk?X?T&#nFd*!aZL+?EcF;=T9V@ zB1U1o@2WYu+toMzfkicc5-kY7eKqnX!=^O6XolasTvF_yw%t_4r1bjjx zGkZ|3nY!l3zXMjyeR0io?$UXM{1AAS5Po_UVO{oQ_NzC@Tx>^b`1<5ccLZUBnITA9 zH#eO|9D)iH(M!91S#zn|)n@6A`DlmML54B$sIcuIR+IRxr1y(@G`3HrV9wm;&c$Vgf!wCjy_}% z3eZbn8WdB0&=%mkPcEZ}G%17ks{&dYd4UwgjTKUgIJXNqx{7ZMWKrn#tP&ai#%QAP zo@%kR>E2argr9x7&;dW+^v;e1V5_t^S@e+zqspE1#dlpm#SY^!;3zbW5a@oIU`J;Q z+93*9ryzzA4%6=>YN8mJ)?DUK08a>IhCwjfY>O~?a$@q&d{fj?#Z->_$ztBhoiv2V z>+mVOt-MaeZ;z+~`Yh5fOTpdn*bZ4gS+cjhraK(tVVX*{3BWRP8U{f_8N}}8f}g=x zeLxx_^m4Z5qUOtDvIhR)vpP2ctPu6`1>rJ~sQ@_v`B)OU1Wi+beR|JlTsO)Y_i_T* z7bTu;QGSSVRihW|!(YHTeobuZ7r2HF`PagzBgB|nbU$~AhntYVIli%NFs9ZA^wUMh z5kYtjo&eoFlSQ@oB;1+jpvO+SJ(%55-N8Io_pmdf;FmYCV5{D#39&Q=fHfdq!JDU& zln09YU(AcYy~l=GsZ4mV?!YHveha;Odp(47TG+LgzjT_f4~s?)DRRRj zGFAN?JqtKMvY^ERb}C6Z3e>01WAD*;dzc1(tA!Bi?!x_Cnmbyz-S&0&YH*4RX~TK= zPF|mF*L=ENO_Y9f4rJOG;gYf;rA79Nvgkfg#nfIK@AytzD^hk?9D10_;A#qjBZCk% z6O(LNgK$W6-G@|Gv{K^C4-IIr4Hs0nc=0aV&CysvxXS4~(VCfvKfo_IL+KDe{9q*h zqfNHkdKM&YZaA$!W;0YrW~p_z%9i4Su(neOw*$4;8$_vTWo9=FMGxc;Lhhr2R(1!H zh+@mJL&;s(D)WqViRtQh$tI}f!gvqIGkKjs3-?=Y3g%h$OI7Ia0ye)};GaAg|F@70 zFC4pQipd(CU^$Hk-za~tpKYiK0UTza>gVC1@9!cieCx!-*l{_U zoFk=(a&t+{yuI5JQmx^S)cDaYUGFwa1ip6xzujSwRex;Fh}0~XK!d?~GB&}8ZaAIu%4;j2x+p9fKFutpMW9* z(^c)s!sE#zrncus@e^ICJmqg2xws1P8aRL~V8XP!Xp6B6CvCTy;YuaugDk7-nulP? zhU4Vp#mbX6N?VGYg({cC4tluxI1QwI$U5D~+sK9D-P3RB_ZK^7>A<20gy!Yx3-g|fDlLst}K^B7D zJc2vk*311RyJpZ50>EPBPRr^-TsSw^3+e#~1-9v!EoMhRyQ9o=^uTq}4L#lHP?#1b z&yIuw4~QssECC@4)xFwjIdjUS4c0OKnh6%>fUoGITLVXR{$qpagNTeAfiv)&drPXfI?0;By*rpL1F{P-or|H4N8n!-exZ zs>QsuA9Pi~rGumFCBq=@%854Uo&j+jzuaPw1@CI)HPtzZb*6s%fr;UkmE+nT>;?*W zLHGvg%icN1!4?`k)h-2hs>*n9xHmTGP9ULZx!& zlj<+XA#7Su)Y=eqYtRHsHmleUWep1o2pgETiu^B38F-N7MKS7+ZhvqcZ{xtl%%hsB z=by>%p!cu1=Dt9w7OhSI2mBJhJR)y~`@O82&#=@>URcw;upGrgvnmMH6#s%ZWWv35 zG#Z+jo#pp&Peal8gt?W1L#MhfiU8D_6m9&EkkBs(u~CY?|F74x`4pW)f*^-3_ip-2 zhsY9D-*YeEw&7GcF<#F_w+m?-j- z>l@xk9S>LG!{iF^Pk&_R+|5hzSx-@9Rp(HF7Xh0hDr?$sQ%mG1`+8!D&llfx7zACs z#shde_@s^L@bsNOC}JW4T*Ojea`0n$JjmYP)zP~5sx1Htv&1WlDoil_f}eP| zi6IZ^UvZ1Yvtao2qnop(Q()SUY)z2P$Excib>mcvZ0~O)I0@nAC zOURVI1KN#)cx{SX7f%`vc2A_QX)y~Zi9o&fSOcJ|9wBZ{Io9HJ8iGyx9b$R;G7^~$ zwh{Pee#{m1BCyejpe9@0ef$15=gOVghZ#{LJ0Gr4&9aZMF4QpL-n<{P!G-R#o#H81 zobm>c^8D^Z|DP97E^*(kKQdi({+DAG4Cq5b6DBrS2%!$veqRf4X@?N9p21V4zhQ|- z;r^1*1uB9xM1Sa#4Hn;e9*S{ce&8(N3m4wYh3Fb0Ou|8-)8Lgewcr92Y+eEf=Z~OJ zywt2%iiV@t=X@Bg(UlQ)C4~4G)Q|ffhe(K?8y;W5R5PBhrUZWk#g-|1889G?3!qeR zHQkHAwXmF1@Fq&gi!dY;JMO=hq{8p1DMQ3(cUKSU@E|Ww?fcH+R9iuK#~K<7j?&6` z_v%)h;|Yd>@US6cK09~Y(*v!$FtXZGqqKAYq9I)(_s1b3{fDlgP{X=OX_7qB#_e(c z8_kDWUN6@FeaUObu(osbz>#=HDubjSR6T_Vp^oUjyryOGhaE2`-#Bt#x3in>M1x*o z26$_Cox|4?&VQywecwi;ujbp}yy!Fa( zxe1IpXwe#1WpEzo?$7PN0)?qG@I+Y38hO*xTvf;pdCe~@NQAM%1(Tb&^DU#q5rRl< zg3cWb+=^dlEZ$jmiDKG)H|D$@(~~;!J4c%zR)f^yJ;>>+98Ac)5VxkCLS*N*2Y2<_ zk@Tg;S0s9-xXcV2k1pW(3I!B@l$P@Xc0(4P8y`Fbx5AJGP{mz$9=;C(Ed|{oOpUzV zP7Odpk8MhBSL{U$f7@$GY%B|mi=yUlBcGb)tx%OXy5NW|u+<%4L#bsmBkNHEPq$Vy zpPjrzu906l55kbT`EiJLplhxk%Hd{1owCGeAr7Rb=#-)P9MEcRj|qQc?F?q7v+T)< z;iZbRroNEF!TSR31t=D9QwaTb^gImA$=yd(<>c#5ckX-^qpykLu59zZ6&wZ!OU*&A z{;w=_rCwvXZ2S-|acmc!DFSRklicYLCrNm|K>>6yHX9%H_z{CnIfybA+6suO9)r8S zpfz`IATjWtA*^zDTG?xm|87iA0;$dHw!00M4G<3?EsM4vl+AMwLpR(vZ9~Dm*X!T) z6RaYT@M)&6`KILZbj|4i9W@BaFHf*Ec+`fqD(7r1#&7o-RBt9n0`Y%hHt;=_CgBI& z8J34yLW)G!M_aTGrZ`u$WhKGDtkkkFv%~woE(?N0VTljImfU2u2SDyG;CDX_3S5d9 zV1{}$)}AO(ON@}g7WcaJ<=V}$>N}CbAuJ5BY!`Ac`3}=Fyny^h;HKY`hg1l52Fy47 zN#x#zU**OL8p})P@TXLs>tF~om(fUFc#FSzimCq|BwCYIFbD$OIbLd_2cBbGV0DfM z(MqND+VN1^6*M;09h72l5W|XdJ?Xmrq%X_qRcR-~N3g^j6DPTFEZ(|9@D5ChZMR3} zB`>5u(ta2Yyp_rYG019Qh4IlFOl|IYh34$Ft^Dq?q%QiH@k4s85CCAW{;4$PmA;2S zguL)Q6S?;mFP;|fjIVB8L1wi$2y$ze4oAr~XV>}X3AJ9`s|;%8+Z}Jj>8QgKq_)F0 zAXuonkl8qp@nV4so8f_q^5Jv_gw$0We2cBbMS4VRU2#~ z!YeRv$D;)rO0!kRvwhHs|k+Yg@P;^Kuh zAH)qoC=b&I+LO^y@R;v@D8fg;N(A|`Ck{S4nS{h%c5k${7~x6VZH2%BDxpzGhl*)% z)AQ>oC5li@jpcbDCLjy!k+g1fk>4o z6IDbf#{rBHA-fsz9c^}1CP0yjT=F`py#*XCrf_zFc>!M^CS;Z(=$^l%AW_2!f08vyM(oa^m@K$mYtvcXM>T1#&Gc2;M)`0wbU-#U#%H=w*|lKj*Y6- zLJaB!sE`p9)63?$pOLutXq$U^c;Ewc(5wcl)`M0pCPRU_d~!XY<;uc>>;j4Yzn!7Xb?Ba*6AF9*fV$+QyR4c}`}HZO7zcC5!YCj96j|W3q(c`bei> z$@ii0WZi;_#6(@B83cP3E;faGXoYGveXBKGI`)RT&LFwS>E}eN?Z)Rt-|)5GUxy8_ z)DMQV#p|IkgyzYhnS~PVjXqlQ1szg}+EIIsqe6?uXYcRxIVy6{)v_h>x{*A^7q{2& zso_W|QkInEJOq;ETFy3MFD5Y+NZntQyWY1fuuUpKWf!L33PM-Be}}YWvast7v@4VA zZI8eD{=}y6d$(Ak=HRMnqS;T_r`xZ!%fX*09HLcSS)MVS_{63cwbc_iM8OQ1)WQb@ zDn5N#$*f4Mh8_y2^j@yq89*1qQx3K1->P(0mGKG_943aDiYqmmU

{*~Ykt2Y;x1 z=HMH*YZfh0=RstG|Es>w{hTUAfdC8 zBb$!GYc;s3O;P&eckR8t`re@x1$y{+jdYxpqZRHsa+ke4SL{on%1Ts+Nglwp2?s!k zpi9o1n)Ne1Wlh{i)P>R)!fn9>YS_2RVsgC*T_GV zl!=O$RU9zJni^OxdA|RXij(xia<+WBJy(X@Do)E0!M7f>(HA5%+GIXJ5-t9tI30%B ziOPYPK(!F$2)x#hQ3jEy?pO6v=^G&WZtg3zNVTv_Or>ZutA%FgH4HHmwh`{An6yy_ zD-Telv+F2iY(8fRCw@Bu!In~HrS+GHQ%^V(f3ix`T40P{i4M&Jp`$inKzW;xCNeGGR8b z`U7uYUYftS2uVS!RR8-0efVtZ@L*t(ch!FuLgo?HOxRMKKKL@gcmWShX)kc(OCl>K zACO1&=@l#{krJwf^8ar;>I49w4du@Sx+p-oa)lMgMpgCpU<_DF3z{8>0w;HWC{IWwg1l8D&pOwt6a2AELTl>l7xSI~g2^W@>=XlwyaoIO+6# zR4p%JO_0xK#cQp}bo3;?34#y+Kg(9k5PaK{YzBm+GL{hD{X= z2Kr>2>H@|Rtm#`yKR8`|K(f;Z?|ha`96O87xs1ce=t!l|?HwY6gb{_xps1kkE^^^g z`d%*{QXis}cVP506XFQ&j~n?R%S$$VXc}~0oZE<+5uo|lD6|#=M+yF4D^k5}Iz{SlvNPnF}YqkdM?-|M(sXXLqgS{uv#AO@f@(>)`u#%C!X(X541~L*mb>Zoh z;1)*B{zek0l!&_3_<6)R#o@I;Bo#1b=|Kvt%VxHCN9BmzX+GN1ScnEB)`+JVq(P-C z+z-7NJMiJi9So!N0;DSFj*OSQ)X@9ydlI1}02<~iTcF#K)CTf#I^OCr-eClep%TT?0OuAn=Z z(&zkD?q4%>2PTMg;3)*{0F;DF+|Ef7%$d*_rKJ#3c@{(`h>ud!l|QVq6AM7q>yFjxc3)x7|CSluIh(eM+LO#^sGWe=0d zLqHFuiQ}6O!}aemRCzZhu1@ z`AQ^#C>p%vpgm0o3+&HxLk?r$0M#PWUSMDLD@<99uqJz9YB-DXVn77Z0~6blX_xE@FBS)*1f@4rqZ&kk@j{r<5)K zF$=M=P@%!g`5hm25FMW*%kVs&4`bR#UgYz&+lXOFw8p=h4k{AA6XC>crqaI>fl@mX zEF6lp%EZjel2K~ksvI{-@+U7*hsUBbVd$Z=AB;T9#rMAm+P|Fus5!;F2VZ6zFVG^V zNDEdtD`jb~kA&t*5PYXjr42BEAq4iD27;{(*ItjAXI;CCAgCz(U( zh40J%7||H8-vMxjE)@*0C@apm72=C3lvHm%VJW%~USK5+rh1kYBD09|F6a)R$Rja1 z9Pz*B=dHcz$eCcl9BP=|T^#jUig_@QyN%;NZXm`B441SzXx7=|bN=HlBwP>VBIT%h zAmB;oLhq2Dz;N8bO)bbo6$*5{z3Lisdfo+Ov6TD&YG29F%`reeZ{%ilmqG}RGD^wp zt=fgsK0o07E(ca9s=;F#5ZdCQ@IpSD$wPYTkc$hQ$K|FGtlhWc*59%1G}irikVOVcw(nh+UW!%Op4?UWLh;c2R# zpE%bS(f<%bAh4uS+=?Nby&JACh^G{Zxy+{X^~-h(9nf~39k#O>Wg&gZ|K+LF7c^sA zE}6GFCItNq&pSaR;wS+$BP~SMiZxJ@nB17%N?urCcH@?GVz=4tf%hYn1r#2uEZIh} zz;V!?v}@KsYXC8+g zBy`~C5+dj3u>Sk|&YxpAf8^bB%<4N|c{Di%IGXK#*44K+pT%cG%U^k5vyUkun7d(X zF;@Xx=N&&u`T*KN2!<1zpCmawUFfV%)m*I|*G}L^*eeVE@YhyFXtXZSK|83TLPN1z zgbp*DLM0PfwDD6|s7fsZSxws^bKbfW5nLHVr2$5pnlm`O)Qxk_QVw-~p)c%V+hWz? z+%3UGGWp(pOBa>RjpNA?-_nz1DO1#aw#}>?C*z<{tcMC5MTwz(w(C;xoo0SiFcVPm zgZ1uxBMxu5-FY7`_CLb!MqAzW+u>W0xITCl`}pGO9_E_#WK^0u#L!913byZW&D^jR3I6s8IiB;`0MqVSfet0k(j@pKpETkXzl}K zOH>7KkT&%4X2BlEh9h~edkCcBotUp~C`#@7lC{Kuck?tucHfHP`;xw$%Dl z|C>;eZaz(!l-&Z^^eAE-prya3S--LKF!*Gm;G(n#m5a^O6?5= zA(!5t%QS1hcvmQs_ME0cr3HJwvF@(Nf9_8=eV|?NZKd#<)&uosuA1fb-V!@salW9d zk%u)~hI}PY)QHXa9wm7W=D2pRJReRtlZKg{cmZXNShw)PzQjeZfKau19o!NZmkjKR zq9*zp0+BPOOhLs=%DUjUp2q&j@ZrYT`>FD=w{w6#f~fG`)|`=S;yi~I|_&fPifQ<#y-uI ze4egPV`Fx9GwZ*`MtsEAPF^i^9gP=fWi~zQn=rc{9!h9Gb8>@G#us#16qlWcNg>!2 z+vJZwi`L)F-2Xh*yiIjmv9f>DHi9N9{NGKBjXc*i|HZQJ5x3a<@J}V2q@gC8Ed0FmU2~Aq06qUicO9LNiMV3#cZ}ydzu!`!xyW_-gJ9_2 zolSz9-SQaxNPJo4SD%k#NE-q&6$~Va|H6g0`NCvj9~0r*_*Yp~cB$!rXc}t9(GeTr zhAWKsT`W|{UUZfGZ~7@euqi%K2hRNcSahz_VdhMa_xO3!s7yhbfPW1u5In)xBq{^3 zkT>vVBIQ(0&XFNRI3aOm&gTIK{!NXGTjOux%H_p}pT?ZlF7(`297G3^`Z#Xnq6-+p z1XB`MXgzf)FVi@@efEBA8YpO1GOHiQ@VpNCKE`toqH6Cebg)7ZdUz?Xu`4*N=u=|P z_nug|Xkq2c9rL%=Hp=d_v>R_h$%ov>>C+fnDwybF`_NO0GZ+4u87gJTANl9aq@ckT zp5ja;1*(EW?qlE@lZ>wWeOx;h%zc^b{b^bBO3k;8#X?c2m7!@jS|_60Vn%pD;?I@c zF_r>nw#f12eArTqYV%TFoYq^+o}PgpF`kj*8cgo6D)hd87_#-5ReKh8%2{-h7wQVLD>D94;s{XJTC1BK|Wq z{TeQvEmK4g-$of>*zWpRWWJj|`Jbjpi1ENSqEar}H%cdzovNdeWyQjIszU^a3f2o$ zx6w&otaTE|a3f{IjxX^_+{N>H%1)zi4AT**K~mqT!oI)`hbY_A5iMzO;H_vMiz9~; z&|&BAkHa0xG&yw9DZY}G9<%X-@xa{WVeUGV-Ic?;c}9Ygp25143{5!!u!Dd$^_Bwl z_BtWRJHa-2C2rtxkNshZyc4k|@MfT7|i|Jc>Q z&UWR7aWrYIH^ErQw|k)Cr{#rVZpK`X{otv^vp2i85lX>t#X?&L{Nn0EQ%-2`hQ2nQ zq_;{^+*fd8rr3YC3bc)%qDCjQ%dU>TZ9ny|XhvoRh)~%nV}}SL6@e(dHM=z+M?p*> zzO3-8FUB{BVik&S%Iv{{(c@3S)L2nvpy^X{v~tD5Vcf3~Y0kX8S)?2cr9O&8nZ0d$ z6t$iB0v0XW@8@ZZ6JOe-EKkaUVLaz^V6XqPc|tN^T&S-=L>cX?!MoJ0NU=DwxBvr< zM19j$m}YyS=!2oGWpuRDQu3sok99zKa|+XmNpl;1XO>v_8mo+`y`@QCZtt}i$X z3?_Fi*>gu3Qip#RLm1Yg9Ids-htn9I%*+*UBY&XqG zON(1EW`lSt&kqU_W>(+$cPG!-nbOD?>O@`EBEh%p>pyn?~!V zUch-OySi-z;=_|_3fl|*z%>fiSLVO#dx1wa=s(hxei{SJRXN6i19cwtzc`?>u1GBt ziiOltf`-cnWD>On1TJ4dS&mdqY8Dvu9(KMUrTW|VLv;v9=ySip7-8_q&HK0FmJfbD zp0j^6VB`%vOnq}3>+1d-Pl}SKTCZLU?hj-xph^0J7E?SY)^M zguIZQ>~-;C_-FWbgev{cXF?Z3yu03i-C#Z>6JWK0BZ)R0z_r3#X<}Q?kkfGQBl0M> za0+m76FAOfJ+Vo`}^v|`(z;}(!8t>_;cvMaaQr(UMS%`H$ z7gxEB7(P?alIRs~-}U7-uk96S9~Agy^%eKrULDR>E!oQGz+oZgh59@`Dt}ytU`UaA zP>u)FV83kKE_nMrL`{A_L4xs<=cXtAJLNGK1(5)smFCHWUvQ8F^FOfj*`f!ds_NNQ z#`ouu(?5bc{eBJm`4AcwoeRDRNcjz?X|@yT+aU;asJq*X0C&Cy?@?ZT2cuEkRhXU6 zIiaQ2R(9J9*Jw)lTd1~*OGM{O`8E9+dI(UJ$B4+D{`E+_in%$4$ z?KH$;gR{XtYft<(_!#gu=Cl)Q*SqDt&vI9%D*@K&*He6hGM*XW(HD^N5b>l6mUyvg{fQw5bGIdTYpfn>lBt8e&gra=G;jN*un`~_mb3h3H%C{EP z@exj8%*hNVLM0Bf`pQNNok6wktf<-ZsxYcXIm`Ij5eVU>)~?%ZNtF?WwG^)o{;o0Y zye9}5y5bAIt^ZaA4#8O6_3fbA37S$I2*=*Ru#?7G7u-4V47;zaUiV8>D`+~1@A8SaVpKx! zFYZR`95B8^1>}|xbOs!+NU%?@6&IKrcubS8@}u;dxO2pdXj1#`-a;Exg)})><6>j< zZVa?1I(R7~NVbsl`MniHyYRZWGr@|OP?QkpA3v^t5q~7rfIX43wMY34#&Lf=vH8tp zqbS}NS3LW=id89C8F#3-k|{pD#fHUXz>Mck=g<_#kHJ`Gc~cJx%KE40zHTa=-E`v23&O4{Czb~P@>GsNM9oUI2YF-A>pMvbMqQI`wl7VcSyDsg=aVqAxt{*aPlvS3%BZZ zK(M5;PN@bfhk$hq+T6J2{cIS+&I)Ut?GYl=xkz@E<)XF%==%+mNwD_tzKA2~!ZoOo z3g5SXGT)-7f@gs&ifDK}KII9X_cPZ7-&w+@MkWf~S?E9(SAk ze*Z}N_)eG{53Qz!s$;2-u$X_s@AuGHvzZ_>K@4h89*4!nn*O$+dAjB&rI#~RgoxnbwQcvcpJhu|_w#v%9>);V*uHD;j2H ziMMkk034>2A<0Qk|k zVLb4jRb{z6reBb0i(&^Q?Nx4ireEvMy)hx%-;mMHX_4R0hPh6A)0$URcG3&a#~s+Y zk0sY!WsHSMb~O#2`tIoO%#rwXkq#nGum`&GD7lMe1AE3bBo0;t+~%)Ud-JOBRb{8u zB(>6%{Kb$@%OT#MW)tVrFMhsCO;no@IS{^5?=QnO_jb?jsQwK{gN_g4@HlMlTtFi# zJh&Oe&x2TEhJQisod`x(yn?k!cg0=Wa=$Pah-;DoXpwFHY`$H&EJ<{5baJ_`-+Xd8 z>>nS#pfz)BF*$4H#Cr*aeg{Lx$)6I(;7Qh;n@P2zx+en&E&D~#`Qprg8wNv*Go~TvXYa8RT{>xHc0NlBy+|IQ2~~BLp7a!*WbY(n_`S50>#xQNh%ETdirUA0&w!2dUn7Gv;CO02^USSiqqqGU zGrxS?neT@JxI>uL&JDZG)V>oQHiBh~5YV-(*oIf)i0$`nkHdoPLj|(h0R`8SnBkRV z#heo>(!2CZ*?vo=jU2qh0pi_u{+!pd^;E#57`!sJre3y&YFk3d&W(QNR~$!AB|}>e z@h(ar%dQ}`k7Y&6fl0G-Vki{TJQMS+(25))WHjIF)frb-_R093qej+;lP=5d88TrH zkX`J2yPWfIHg?qfBpjfISJrUm_V>!K^banqJ~$gD8rfcTM*Y2_+mlPf5Gt@9k@JT6 zT)TWa4omehhlSttt#xlWpu~cVzS>S*Ic&XQGXGTVg*Nb05oaICLxsR{>EZ*67bz9G zbnWcoH>saDkk?I9+)~yjWQ|Nl8t6LqlofRsoL8L~@hE&PS8ejhos)s|(spB(l{`{) zP}$L5`P%6KpF!T_7vP}9mtOuT3sQY82%m+PAvIXOwLI2b*9}Md`Bm*7K%%vLT|bWglM9#N|J( zmvdTrJx;FnzLaL(EfvyPf3WJHZAnVO&-}{-6Hr!4FTkgtiSvfsJ~Va)jq9J*yX4d2 z6S#L=$*4acDV%(_Vc*7zKG(|tO{=mGiN}Lw2frq@fc(dvqlga=)w?)$->UMmf+w%5 z82Zws$LsI*DKkY}7-(u`qz7yktWs6s)x%T19#5a2QfcxcS(U=S&{;=Fy~*o>8b^!P z+;^SezkV-Vj*CUz;W?_4gZK=*n{*ziA16P1@iA=HGkmAjGuqLjL<4jB8OR!4XddH8 zd1cX=?V`OJ&Zs7B+x_djb`faCYCpFov!r=fK1Y)0O9#EHrW%ejL2xo4+F)#Dqpp-c z&gNf2?K0tRV4CHZeGq-$=~tOb+Dh!u*!DZ0HT?JVeD(cJV*|4Gxk|BtJ$0E=o1+Z{#apn^(>l1hqn2uONV zx>QnH5QZLlfT3&}2|-#~x};Ny5h=-`hi({phym`}=(+!Y?>x^u<2f_zwb%OU{oe0e zYscGZP8C(B823DVSll)H4_r2ZJS|^$XQ)>WRB7I z+$Of3N_0U@E8#p8o~w%qRuaOV4CY4lRZt{qtw>NZR-38h4)!Bw#CoSf%Jx24cLpQt z=fW3m(glWMtIEEj33!xn3vGceWi&UXL=M%7EB-yjk9s-Uwz+8p!jNLVBk5*=*Z2$Ye3gM~w)I_IXVMh4^n(hL7^bjJfJ$Q&`~BA z72S?iCk^9xK}aQOV3~y0Qmw8|;sUxD?I{_@+Y~Ci7MgU3A)cx#H=?iKd(En;dz+%@ z1@3|8UPh;zqaH4dln64B_vx3W5#E!(L{rDiYpi}zDe@LyLI6k?S&)|wo*-tyrY(Y* zWf*q8CFO;kbL+CcqSjB}HkaZvvwkmm$X112Szd}y^m zK@mQhlbwkHoyrnk;WgSIkc#`|L^(Gh>IknPKcZ8){KWI1u0w`?nYX^=?wb1v0gy5A z>)9MF7HrhW+#%YW>H`z>_sI&ke^L5gs&X~E?w6SR2d}ExiQh;<857oVPLL;jB$6N0 zbuw@-qR>k5QyaBvMVXuZ9eUi++$N+)O7oi=B3M0o?Ib~wL}VFBm%0LoJhexr{E?k4 z=i%*Qa|EfX*$19Wi4h-sk|KB?1M^&}nESEsuM-vO;Y=>H4i84$99VHh=B+9X}7cvF;kjrS}xG11O+P2mg362 zUIY)L2m$rYr^eQx=Ac+m1+MlJicjhzDAU!o;~O+>GLM_WD{YIM739G8=ZoxBNBGOJ z?)IXPD!Ku$VI$5*=L8o<7dO*yghVG&OZ)T>6{W-Zj%Pd7rQu0VW2?*4JK8(}03STx zNLs#M=_!z8i?+TBj8<9Yj{~-{Rg__imOLU&GCRxnsjS>b=y*GhQ}v${23x?wT=9l$ z>U(wSNBCN|V;DvlFy1~pB*7PC1uFN(H`m;Zr;qpA5jA%V9VZEQ^FHbW*7%Rl9vIL# z&`Ajsy9hWn!d3#U2^?n+Xg73=mo(W<2B?UJpI_YwQ0nx<*Mfc8Hp{Q}CW3ROCY~I; zHN6~UKHbeteELSURZnAmR?mYd#&^6gL_31P(fjS7h!u5ly(1{4s-u_7w4F^L!x$VB z@#w*cq|;1=mka|$Yc8jB^W->O;|`_C;j2lV@=R%2!F>x0KT+gyJCqKxzx|HT9j9Wf zv)tjo{r%{TDHP*2g4tbLAeRbmLG2%(Q25D&jzrPU7mfxJT7`M0xGuTuqTA+W@t#T; zNK8hfg#u-3jAE0hE@`A4;J38VKGJo}0js7+%&=EcxzF}n`^)_fnAlqA!cE!vb)uq? zA#K+?LqNHacYJGDX)1TfcEf)JBh%F|Xc-#OIXhiYSAEyc6VJ*1qCdW~!GcZ7;qais zY<5j_edTZ)P$D%eDf=6fBHX8F00_h7Y1c@%vefbMfXl`{*2CdPPR5NGeW|*=-vbp0 zFExni1Vs!kz0qsZPR-9Z;&`Q{X=rJtc7`q_M<}g5AfQ~XlZQG?c;4YZ(vT>qF?agg+PyXXJJMW zZd{18&(SQ!$(f9phspM7!qHYXqHN!)5XM4Mj=f8JFXj^+aMQ$nG}^mR7^o9-`F){ye`1l_an1pzrx2vy8vo1TaxbNwqW?S#a~#^$ve)p3jU3 z)MU7Y;=PuWTC-IS@k41iz!X=oeK(Ev$D&n#WVc0hQJWlo2f9-2GpbSv|5o1A(@f9r zqt(VzkiY4Q4?cCd{RUqAv90K0R;Q_1>LiD>5hPsO$a5y6KXZlB`_#d-2s(@$8dA{< zD(hvv_q+-AA~^%#yh+b!#RWW=Py72dkM%ruaQ0oPew{tbm&4`{WmI0dRN_~fabAn9 z3pcqYAHqr2bV~5sBH6FGCEslL0F_`Eb1eKiQl3Tw&i>x~;f7u2;a71 z4-}$iBfF&S_-43Jd}mAS+A+wirR_}HpL1vFRHZQ|B6s60q!m8q!~#NfMM9KZZ}*C9 z^40EmtDrXOj*#;udZCqL6FS0D&ePcy?lO3OBcr30uHz%Bv5lf~u0Uep72boQq#^e^ z2Xcbyj*dv+nB{~S{bsAlnuo`T_{BQwhuj6@OhGZiZAb>LoVB0ArSw zGV*KT@L0Y72a2MFc z%%>fbbcx&>;jRs=h&pt{dFG|}w-+aoWH7kX{$Q~Wge*fw9?#V53r_dETUECT-#GqW zw3j)8K{v)-X$pDMC|5WB`zki22K&07SMUZdu<2sKj@n~HZABu`)v2VmYuvf>`Y zXoa*E5-)SIFo{38Z>v&dqaa6^Nr$(9%zV^sdFP58COJ%eU5577sQ0f3#y#| zCG6nE)P`&(2Q*Pr1Deys0cvwGtF;@Q(X7-k9tc8aEa-uBkS`?5r5`Xm#uq``g7C)o zbH)LmT4$#ZP$JDccsnt3!N+iIAJ4-qgN=S*=q`wQF@{kM!dxP{j4r6i#!iuHkeQ75 zPCemg+1^Y7Z3v}}8hj}H{>DbRAr%yuhniU@DwFV4V5#g6&~cyZ_Gc!4EaB>xQucZ= z2G;>S(a+IX-!%k^Nhgl;?<;mYlqmFF_JP*ftlg9l_+(L&Wa)qo(kXkX%4IP6bVucz z9Lo5S+Gzcxedh5|m)+Y$@e9oHG74HP`h!AOyo#vuy1j{ZR^@OFh6y2`J_e!T}c!B#!83GtnzcoBrHlcX&b8bRQ&CRn^i5a#yhM$@nszvI^!zA3M2r z3)N&!esi>yFt=8*e^UPbY&M`2YzTh)!0iWKQDKL5kI}@k&HL>}L@>6Ubzu z8OEfLS7@N<-H$3e>cQ#hvuK@6ND&_pD!!aR7?raRmE(jxIwA0q1cG8P3>oQKmQ?&)v zLf)&fPN~Vsw~yE6`q|(5gbs*=`{O;2Vp6=XNE^bNekFKqL_{Y(?>P!D%R!1l{$#Ja zWon5Y>*1&^B>b4r3GNAsO8lZx!7iu+Q!b~KeKC~X2ubhAp`0MVNeiFXLCK)$9lSlj z-Ry#z2>x=5(RiUiA{~6{sQZKrU0mtbg-N;(j!61eWFsZz+BO_M@EhDj9x-^*()m@^ zFyd zL)}$uK!Q~%7^g;~%td*zXnMkaMO2jT-H%E9I&hIvbCT|Wz0|Mwz2G=tkAyFSn9->GtCm z?t_RbH!iK_dI%;OLP!_@aXXrks;S<(V|=fHlv8#1arzUm{a26@B-~SFost__MkoG| zFRz%y`U4i=RRCiNIq*Bp5JUo>NyjZ+9zdO^rV$`7>q@u=N~{Y~Ja0!pOxOaoxD1C~ zE#UBq%1_q!WBZ4lmDPhZK}O|;^<)!HnxWecHJ_gBAf5tmMLYAY#Y16qCT>K($1A{P zTF_vl)yV5#CUl73PnPSjMBM^GK+tCW$)Xk)REV1Im_53=14o=#j8<78a{=VBJ^YYz z^~0kX?RZJ?e5p+4W3*;qC?W13Q+xmo$6*E5iXd_bBv*`|w)YnGrN9Kxm%8Fa!WdIi zAlSajD{(EOLN2?%HVwNahEZr7PI##*zE3U#;5cYYvyWn~!tCM{MSz?&;w=s+M%>i?FB z5ISC}&Y4?d~KF zkJCcA<#TjmwmRTv0E?=3GieLptExDd@;-!Oi0yRlCtH^$Rr(ML8?s(kvI~~5Qu%DW zZ=1##c^G;g%jr#H*M@H_j<#Z4TXLgBQ)^j;SGai!$He3Pk)Fpz;REW+1FMUncrR1; zrxAka;(eW>9A2%Jr9hliFBNa4y*FT5WC8GOPM&`FZ^=k3AiwB0!Y|D?FDI7s)e(N~ zx|ySsb*ihS--lZB*_)%R0Zn$Tpwjc-n*IGi$lRf18glxZ^tI@>(zJ;QiTJsB-jIQe z7Ii}ksbP`C!JE=6qfQSCYn}y=ny5y3)?M}4>(89(Bxer@H76tHkOqbdl13prqF<0J z$>fm)PfM$Lx6uz6lV1iOR6RyCOdsicXrTz9Ih`TWo;%ImeS=qxylhZ}!?Cy!p(_%) zC~I{>7f7h;9Xl#F4voAwBhM5|9;I$1(`q+!b0X2=M&8E??6ulINYz&3pPiZT0^en* zNxJpi8qb=!bS=rp-rDo{dtPRZfl@ZVq0|2B3Y*E5z3;!)23-T}=OAHf7u**)-n&OF z=aju6Z(I**yMUMr0&`KxI^|9w%nt9c3`7mA21_3-^=8_@2&46l;6DS?1Lr~X|8#|1 z_OV219#ZkV@8NsFjhrM@TAD%&DAU;Df-xs;MAsblyl^j7=*&ygAYiwbPR;G#^8S6r zWR^iuMz!<>RRJnO`)(9e1vy^Vq;BTqxeppkiXFymm#3-$&(@%jI8V*}nTnB6$;kvV zY}{eX=8YR|a!vl2ZKrpB?B)0tUc-|op6m1Zeg?ITnU_zZtVI(7kHeIQ&g`%NRE8uyJ41$B3h*E!Xi>t0b{O*2bQ`Clkm{*U|b(*T>LEVv}6Mt`i9^e zKS;Wg;7rt!u(d2L=kp1dj$6ll#vHh z;<&?Cf>DELhHkVsRBwRl5<3-sjltCcLo;ee3pZ~-h^kR#FQko^Fm|P-K1zeMadFhL zz(I1p;fcqnWf@)K%D%Xf=Tv0GJ+vSQ{3zAlCc9>k1As(H6_q200FP6tyT2aD3x9qp=DPmQQ0h&jiB z_Pw#hS32eJTXkF8`5>z>L7eO*r+qK7@!WmIy)i_dkC(2n^pU9GsD$lmSouA@LpjA; zS5iE)j^OC2^c*cRM~psgs!xJQqgHW|raVABOA~tfHyH6Y0o4N`KJ`g;p8paorjJwJ zICiOI#q&VaZg^uonieOCxRVfwE~gIyZ;4g@-76W>$E1=DC+`!XN~4K3Zk;2k916@= z>NYjHt=j>L++fU?Tou~&|HN$w6*nssf-pzT5DGGE z>O#;phDjakzE}S*_F8< zR-MNY#gj;Z(dUyk^cs2%U0k9zRb;>!pHw*H^t~h@tpLPph_wf2MrUFhc3wNpw?KIX zkEp4Zz7Gz9VR5EHPE(b(3inzNH7f*A3b=o~7}ATF(5*+_^4>2AZ8EzwLNRiOFE)YD zA$fQpXS$;xR)AQ&dDkOFrt&~m076TYrTn~1Q-C-N3avGJ&h>eW2J&77l4X+MRv3FZ zJdbmuDy#r0HxDWs{bNTU{1!;f@`K6~L|tzD&N%80zv~s@SOh{@X8X*0P@3@B&6{QY z;1jw#Dq9ud4hlYggEyg+tCs;j@@jI>)mYTdpj7;Lp`W^We+%A>wtMc>L&}DgUi^mr zrMQ>~w!QG(w(Uq)gE6$tm_7!(%0z{(Z#1iz77;?Kvui1{CrqVv)V20R6x40Q?TWIm z-5bG3(}75PjIHehvxk;B%7{r1@k#e~7A#P5J0MgSX>IdMqd(KPTX+NV?x%P|8g z4Rs|X?7HIfd2Odqk~FGt)1$;!6vv$&&dc8wD#s18Gt2O7j-zQ?l?v~URLz7U0=Xq0 zg|*V_oe*}_#i#vkTL}zppE_r)caL0)Ni$1|T#-ID<08%v3keXlMgHqJ(K!2vHv1mC z^<8z6|J|1ZP9*^a)e0N&D`aS5g#OJdws-Tz54@I9pv28&{T$F0HOEE_qN}UGemp0W z^H}M{6FQk2sQaTO<-YB--E|4k?PbO4eI z$d%}{g{Aikc)gfobn4-^WJBX<9C|m`ntaBe0lNU1)k{MP#qQ7g7r-uDW8FLKFbR{h z>)#5!ZcRyJGE9W#X>4kj0Mr=~!#{>2jhq?9TsMt{jr_RP`Q(2t<_)^vk#d{P)~Ob+ zT%J;{3v=c<-VfP#4l}(&a+kQjY=bP_7J4QUrh&>&k#x_Cali6v5sjB5UEJqcZ1(llx~Q4KK6 z3lPVoHjny28LCVh#nG!M7EQnwf%4+oeROf7JUeWdix%5H6SbOgahBhU7 zmv(uCX{ayA-UC(Vzg=T8R+e}3Zi$#5JZ=T4JD?u4NKUkVzU*7IdtO;>-dG>63%D6P zwvfrrvnpp;DeHL^9MmtAl>yf*C%At@0ZySqs@_b5qDg`G!Ph)?w6Uu}IEmVv;kGY7 zfVrZvN5;YHIF`7e*3c7otobDNu7%$WmKfn?6}^t23Q~FaX7Qv3Q3C#*=Cofdg{9;K zVeL`Wn&)8tvJ@#U>AKnY1J#9gr2GR<(Pg)v2;p3wb zfc+?_FTXoPoNQIM{Zn`nOVR^v+A}tZRS$+R<`6l#Y3g$d-yH6^HaT^F%rm8;tgiW0 z4;Q_8hDofL%W6jss0I1HTT*~;IULo-W!DB-W?gNSN&;NiM!86V!ZyEXW!iFE9O?o< z>EoXlOzj;Nl16X^3jrV+C~xzB_DuJ@&hw6(?SHz&N`*g_SpqIU5O|?Vc%XoS>o$E? z@}#o_2v7i~%VFi&^7SRy^DB)F^@}Vz(+XIbQUDPQQ7Ufsy~l&2f}$K_^9r3+V?^C3 zeZRQYux%$eL<~1x!LT0Q>V5DF>cR0Pv9?xip3vE#@RIAPywUm(Oj})S61KkkZ&LYk zzc#~|)+*~qUr-@W9O~9vHT&q>Kjsx7kQYfYOMYA`U0Yk8R$u=$KJ8J;6}wTNG}n%q zUo3zY87 zAi+S@Fj2lpsmVi}=g|H}G@^!SSdSfNI@uV9M<;nZxv#7;#(hJ_uZ8nqrAvA<@~jj* z)cYy)P`0Dlux2MPFMm#`|DvPWkEB8KQ|Fwixsm{yhmuLwQ3`=cwc%lGL(*mM3S^`| z{4sU`l!#-F^;i{72E?lmDZJ0MM0BzpmUs3VhUTy(*vo4?dcUL~Hd^bMId5AE*ny^9 z@0S!FD!>2t)O0~3qTFM;v5zi@6P=Y+EH$!Vgu0;K@x^KXY)DK8mHuSt5$28Fv}t)R zJ^m2FC|p?gJ9XgPjXTTpcl+y(yWQ}Z#E?fB%>$o^-mt%Ki=k6Mz}$x~d<>AcAG`*# z<8R#nRei_-b%XckeRJ-%+CS2IUuXw0K)1Wbs`|v!c%BrzSMke>O|w2HNff)UrPOn~ z8)QHJ3`rZTUUsPd$s9JYMak)I%mdqJ6xBPNzvd+V>jmHgty;q-v`oNBh26awS!)U? z18J$2SM*c__*nJNnnO(C4x1nQ*1)XbI?Bsm$Tta|h|` z?RTca*95~mn`@WxG7x#aMDO2ry$lVy6sZepW`Zn0y($yAecdY;q)(t1X=CcrTy)iT zO5WOM;?;g%TJ*na5hyMl2cUNjR+}V%Dvqmdj5h-UT^2fuPLOQZo z$657nS6ao741atkK@6J53d=xGVd%?EekPc{rh=_+sGognN)?FY--I=f#oXU6KkbjS zXH=Lk3)oZ;A?a|d&x>k$^Y+J>rs-MxBgJnDsyvJ&vyV9*J`1)9zjz}1c;N+9|4HAR z&H)ly(oj;Lm43K$If%;Ost3p}2ut$}^db|7zcYw7E+u&s&fFsyH?M``)Gx-Nve`Fy zCOd8W7sw51X*9c_CCde8!+i$U9c@wZoi#99adR}pOcJsDY58YAGmCD0xJ}u$7m7Cb zvQGL6UY>+F8s>0h;TvsUpP7iHf!yq$mTM-~Yp{?z`L~c3qV$XvFJzcPjpQqcYDjPO zn?^i1Qk*AG9G!62yLP$@LRo(iY&qjMVS1s-N&^!f%FPa!D9^t)z?+=5)XnnEn*@pB z?HW1wG_&;!`?UX4A5OXzW}kXGSY(D3XaEKq1-`LS!s^z_T#5iqB)oH3R#@9FL*tQt z@fS%b(K7OBb%(ZxLMaaLa7r^95#xfH6FQO#h~M^hIqVyxw}ch7-$I?tFba&;)V<0_ zP{;JcqHr57^II=mSZVaH3FqkLGi$5$1T&l`$&n)(JeVCFC}3en9*SpIg?kvzlH2@~ z_a3xe{a1zqU4X~KrsAr5!=OXO0bk{{@s7B>#poz>zPVT2gTj5K^~*B1-mWI&=PaJ2dOPGkY2rT8cNm(`vIG+<5m^4t9xLE3`v$hciLR zbt~9O?`AM*_Nh(x59sT{J})T=!B)a$G+EtMeu1%m&0q3YdF_-}1Wf9K=)3A1xuZ;P z*8S?P`Ag%7oI9;fan55O)s<|{+Dlai({cQPFmoTl5>jS0-$54-!k$TrHDGvq6Rb}g zU>llBHIq3QDVSmU_2D(k}`sNoxnSz7a- zsTg3n$rEP#HJ_#6Ca`V;1t|nt!XZaC_>1@b@*U1@jOl!7cDQZXPKz#?`=v{G`N@^-7! zvWJEXtB0L|Ts}=O%W^c$zek&fdiC)@U;C^bg_B0z`~RPK7Q3{?tZ_Sh>>k|l(GJU4 z>&VRerE6>Xq`^D;P#-y8)^O~3Uu%_=Gse+e*}pV?9DG`EhGW8VS|SGzKJ8U%GJlN? z;wWU~IKf5Z&itAA+EXLGbZ z^cId*`}Rd5Vc|4=auC#A+KSbeRN9OUBWVD;LJW=s&QwT&-63@r9^+bS;q`|PlflHF z7L(o-vdzx`nkEU);mmT1n>nmFHNNYg1i*?g^)H{BNCQDaQUN$#%C8Kxn^uof*T8W% zC(>Rq5kkfUzGquB%7?WyBkBt$Z zzu&b5Yxp8_))}TM!geXTTfXnPbN&`jcz8_~XX29{V=A42f&0$>J3OF;SmrhrPGILy znj{<+ zZ>PMbS7<2A1t#8R<0$fuCE?|6m6>hA!+$T}Qf|FL#?+L#NxMd6S?7qqSi@eH z2?ApE-Ja^`U4|}W4EsPz{NA|ON%?pUJQ&G(`4*X82C?*afUUqoh`-r?G$mbZnMr(# z495+t3REJR3{y+wMYnjwR6Qs#xyTq5axm0m2O}_vM4K`qJ}l(&eVresfd~L5ktHFL z5^vwIXqiS|)g+cF9;Wf*iE*KLSmgK5%m)q0dD|1I;Jg&@x~zLaX1^z-`Hh5C4+q@!Em226Nw3k~B{Q+kIgIT_VKm<60hCQjPCo)zd zGc(Lp6b26dJ!3>hA{zKeZ}Amb1M~wvw`=6Sy<{W}<7Uokcdv^G3m?e-h(X4zC|U^c zlb~gT8mir-cX>+iPjmAkl=Eznqc4e#O`+W^(Pg{ zc=y&(I4BCkV1n|XUmwVb(rbrs!D};3tjpO|=%#46=;*YNdOdjJsA${FZPI}ODZ_ox zQwv_~GOy{Zz@WujWSQ7L2VLdX*yGpUV~%s8wTNex$HmS$QNpDby=x(FLhEZ?3f`0`8MNEm ze|Y&2-VEfYAX}YhFW(^St$TVAU`z|Jcvs~$?%!typF6{Ld3I@Q+cX4j`@ij6UQ)fo zX=AQ0`k_k~ClHg?HZ0cG=YAc zW=q2Xv;pU%XWnWubnpqB-hiNAIHYF29S_gc_o~a^BrdOM(`X2DaY@WtI?m1WT7Wj8 zz+k(6=Xw$KwxWWS7y z)tkg;3GkQt(4T{ddwLn+OT<06oT%J@|0r6|#BiJ-P3+ez|JE&6==Pp+SQiUV{B& zl_L$Pe}5wuTh!5mQee*k3|1og{#3PvFNMK8pD=|9T~Cue`K;JCYahDRPXEi)c6F-! z@9bQ^5ZQb1S299VGXY+iOI_hbZqC*M`LaRNKQ(RoHlfP{3Xq1W*PpokICeltxCF6j z%nbh>s0XJ3y8dCX3jI5zdQ!1DEGmWFmZv`-6I}T9f-x!dkFO|vBuaW|jT8=jl}hhB zgm8{5x^V^-93og2s?3x;9mI-s8WRf{OcVj`8FC5-M@aT(_0rXj1OJ>4Ay4A^d2#Vj zTe;We($Xq8q#sD__H}y?$m78#?m5G}yDHAn(!+DlN_;@k$<1HD|MjASsiN$;RC>E& zlBC-aty3m5Ece^`>YfV3uuQhUa3(*EIA%7s?$WMw*2^lgm$I&wpXzBA*j=*QUR32_ zn0H*{9SuzLuHX!&DO;k0?)euB^WP0zkkl@pCkMF)ke<0^42(|1>7Ne|inoIDxS@M+ zEI-^|{3H3Y&-^J5eDq2i7cIXeRb6Hy6oCMx-a58&PpnHPTF2yE2y^8~b$cE+Ca)K` z_oV=KU`J**?=ZC0MwTcWloYuwku?09q}G2vCY$GH-#c|uWv~|q=F9v)i~lpp+o&{% zew69sN`($`>DBjRW7`C19k#;$y9bespNkx~&I1*@Z0nMoBrm_ovrALk)<<)d*`A?D z5;s+~16;F`gAtsRl)bA#TS+0_S-B@aMS9!*FDCg`H&EpoTaUR*+Me~sXyZSUt^_O^56YYQ0qO(L=XeLAj1e<#9v=Si zCp;VTwiP??x6>F%mB^xYT`c>{%Di#bW*>-X)MHcSfAexk2JWRtjJ-K;+xev$1~byDV-g zAWq?jxoracu0zrza4h8?{P8&=`eu&<^Q8-fgC{iCHz~921Lupm*< zMKg8-0}d@FsHT7D;CDg8)Uw1{dJRWdWYsjud7I;qp#=FnB75HomeWBWe}ksnV7~Yn zrp*2n#{@L~>l)5mV;G9PFuWpKvc}oO1ou_EbPLDVFlv|@^O${`5$I2|%d)}ga4DBr zkm8+9^Cki@Gg|}amGzA_z&`sU?4hsX2-N)%>7 zTQBqF6he;PRX$tzlx>%K5KJU1|06KKP^RQ@8Gv<^4a!-_#kxj^!z*w?6u5*UQBB9u z22yLK(}>ql?PmdLDOj^2)Ia`jfs-c{Wtotua;!)SeQ>HV6I)ylbNHr$YWMP(b0txPX?dZHoi zs0pa{0w3TQJwLLB7PQQXi%VSALHn>6aKlH08R(Qgn6GvEG=rfSe^I@$McgG0fo`+> zh!s2ZQ~93iASz!o#vupDb8EwI zbT0bp4^PIh)eCDY26JSyMP;tHe?!~8VQZg4P;QG&@@MT|7Ys6{ zq=6s`IPJ_y{jQ02X;7PkaUj1=kyH*zgh=E68zKJv2jXD*wc8U5qNX3tE&Q4kRVTiu zd=z&x#PhEzT8F`GqGHY&k9=r?eb&(v!`$!E2>KFn2fWMt{RxHrRr#l z@HvdRW)70Z|2Xwd$o~YNK0Wy_8HpQp>)3ena8(kP>CZgus5TE15?^P=$R7lzyB^cO z|6SP`7sLuSk<5thhShRLnV9JK6qR)fI*heYD7a(}s!;9%&-DD5foGZIS%0O6(r z%-jJ)rV$neg%DH5ApqcUQzZk{%1xcm^^km@Dv~aWonpFina7u)tJ_3{d>~$gtr+Cy zAzhj~SY9~Y>5`H<3+?xWP3SIGe27++hZY<4j56HWkSkH+#{;-LIY|PDILH_e+)H4{ zDfWU6l0dV_C~aMd1+hNQszomC`71%XWB9*E31;c`%L=+~4u{;gmHFyOfXsU9R^9~BoIRE1Wfa6q1ftm+Ni`XOYYk$=XhQW<4z551!Nq|2G!5CwSi0$_y-0^gY?URQND&0 z%|6exORT~@Mw2=9NR98P}#tw=Ohx=c@ou;|@GDwyZHg@6(4PK3#u zHDeRrm?PQwo1El|0?E@0EK3Hmwcy^g`(nP1pGsAg(ow2$!@wHxzrxUxxW}j>`xn zi?}pXD6*|0lE)Q-8XRgEQDBk=Y*N(wxh}*M{)Ze$*lrj(G=>`$@(}toE-}7!6mq5K z%wTm89r=WDD5w3cuA{#*x{dCL+wL11>2_#GaK<&Rdx z#`Q^mVwdLsEE%OdWcXy(SCw5M(_?C$Fg6nXI8R0gbCCWo%J4~qfy=P?dql^~*j15N zy&8iOUh&Th2d#%i;-44E+lH&o0Kg@%dBonVigSiR{{%@e-lV{oHscQ0|#y=f5OM^WF zLimGq-Kei|L-$$uT#SK%<;>uSjr3^anXB4-*M85(mPRN2jgLwfv$(3ubOV5lsQpiiH5r1xa*0fB3rVy+cGLmv&5+%LvxUf^ zTC!6OBdNwlJlDn-ij&C&HP8n+znrgfIZv?+)aH%U-ynGjbw+L*B5rE-pmbZ>t&U|D*=BTx~t0-7;19QWaIT<_NMCJ>Zoj z>udrIv4wK9u50Q@MpVZAFyEzs66dA2&w@GIBxm@`xJSP~meby)9s9ofFr4xq7t(4> z6w6cm0zeglFL7@6iD4$RHSE=|frgDo0E4&}wd5Y*%X@UOAJU-(#=m)q??-HA$m4@^ zBP*&`C4G&H#Ua^2pxygV%<;_`a~u$rJlYjrwOAIL+xl@PDPQkN!HJva?9~pgBNrF+ z&RmP+!8Q)tS4F?dQGbj*sd_fAn*W=gT1CUPV&39X>4h;sD2=<^s;m}I{EgMZ{r<&` zDouCsNh;v%2)0nREK|+p)w;9Z)kHDSFG*$;_?Rgx1U%hXCyLeV+);5zF}iiQ3XQ@r zCCX>Jt9{TFGeLW*G$69Xq}88KGKYpd`}mzcSt7+7$lz#e>j9n0&W6(hYa7 z+D$#s&>bE0|`QQnP@eJf0B-3`FDc6ZM*M(X8adyoJsaA=xU^} zGr7wr-_T7@CS6!mlBZscr$02#F?*ivXMTryM*5fA;ud10jl4CHi1C#nnbYNS#1B?v zl5HX7wl7avDXeo^q%^=UWBRM=55IPi5PMb~{qWZntyPTE6Wboq7AD)^>g{c_MlMb< z)(pZ^eicbuL-81|kNcE6IuhU8Z;==SB##_5%M&r7j}qYb~jZvVKX zSiDoGFiZ3Fv&&D@6_Kh(x#G#_Xxn}f2Ez=b>zdO3j^_T&s@0VZF_cLq%M_6vc_4eK z^mPovXz0tK;YeEP$jBj8V}SX&d&v^oCj#&^)wm}fd^Z6J6WY1i%il_ujd*I ze|8pO;1C4~eJfMr7p{aXgm|95qNS{K4Ra;YAa!2L4s(!jcu-SN%mv8=9nAGRQ#Bv+ zHO0q!{26S39?*FAaErh5u5b;MaF%BhJd#)qgz^-PJh10v1Yd_&*o{p!+#Beo!Vn>B zdcrfV=Z%ez!>O^OL0^`Xid|$M#bkv3l%6Tl5Qj0k@j_92Lh?T`;qn}l$dp;g73t18 z1m?Rv6dxAbsm;`04n+uCYabRx_+WGLMU@yOi?pcK3dHtsu`Vv5Jk=Dw_hBZSf8mn1 zlN|N3e^)z3n^8A|UE8Mr7#V1K{wOMhQS)m-0@l8;ZD5sJwQnQ!;!gjEC@Xv&*b4XN z!Y2Z%!Fn0F{Glti``eeMs7P^V7xwL+Qym8fNzs;0O4zX%SMUjF?Ij{KWXW zZW^OyGnB)s!aZD4kojBpsjE)#r>95jL-!80QaV%#_av6#yt%!f@Bd5gYcMsA5ncpu z(!HHA|1|IY9uMI1`jG2WeIQ`{ITwI8F54H2mMT`t9UV4r6HW3lF3K2~$ux^^$^nuK z|2K4_X)~{C1BqDrpsmU-JHdo?d%6Dw?dI4lJa*7v;&m9_nwzJ@649eszlZ+P;>R9- z;Nzp8y<-1>S|#ThX!$j$e__a!b%y<<4zokHN36gmH2*V>A@QQk?qCnMhj%|2If>-LF-Bx@$-T7cABlxs zIjw~i|JmF;;-h0mT9>2Nof>vjdmJr(0o|3?5B~O;WIdK|3U=H>-@;rcT@gW zP^81oI9ol$de=&1@RX%V%-1Ix<{hobx%Z?7mRkSCBNo~C(B(&WZWqyJ|gV9SS|Xc6U3z7L5B#zx)kdvPPwX&7hWH4A6A(m z?LR&!7CD-!EOmyth8fk?y!dS@QSMk>w?1K_pkMCF{3jD_?5ZfP6aRtLjz{?YLq7J+?{^M58WU@mdgc&|2Ha?^Xm?Y!PAIcIDS#$89DI6jy5LwK=pDM~? zEXerE75do?SKxG!9v2_zx-aB)sH&ZLPgtldJ^kG1Fwe|{5xIVISsMB@l8|`evYYn~ z+1gXdB}9(v9p(k32MymuH)|G_IpUO8bkjaakUz~8g|32S_kYV!RuFh`-Eg}tdOZ1T zO^06zghv|I)s4dQB3iDCOOoEQ9X&Z<1B1ZaFq<8DVAKl$5CIj1#Bm$2gBkUC!(p4& z1WPyBKXjRW`4#A{FZ@39`JC~sF#=Xv*wR5gu(x-evR>xGpZbqTl-Xk3C3X&8!G&!N z=-05ubAJFB?tg?O54)c5_?6H$fHbOV-_Kt^d8j z;dUT3*1TL>epdUos3-*5BybnMOlhn~3c zagE+LqBX7T+X@DRv7P<;9q|z=@n5%_CtdBY!N}&>|Kv&bms10ZoqHEe;}csx`k(VU zh`!If)0PvWEyVnF>9w*-ey5X%ZsBup^WTdc4Zgr5=x+84Iv+<~%*;GX)ET3*woPgL z6Vr*X_qfRSa&3VL$TZIE9ia*rOW};W$1W;Kb>m4)^a}#~+T->>%s5+l! z=LF$ojp)4Le9n_Ys?5xDaY0<|eTag@^i7NRi8^&EU3sHx+mXf**@VkSyVE5aG11A- zkrG+9DDi|ua+@dWAG2`!VlusQGdbdkPYlhUpmv+%6R%(3n87b*Q^+k=op%9uv-4vK zAgN3rk=-qU*WRYk^95k`*H7DBV8#ysxlhs%7^l09@G+G7!t%SU)9#4y4!ONWJs!pa zLiJJxQQ`7=&nR!_S?2_SIt>7a`m#o*@u1zWKC&q)#7(HK`=}I zJF<)V96>5UBLDG~nsK2>b(w&C$*g<~THuj)Fi%H!-;%_q8a)YvaPyG6PwZH}3>=Ng z&h>}Z&WF{Dj1;AypsF(o`vmof0H#pTN#m7yNNmhA8pU7R!ctiT^{%kFfN zEEkA$svo~Fh&yDK=1hxdiCV~_8oAtl`Hf~IeUB;l?kO*c0-C(z^3v3z=D{i_Eou8@ z*UtvpUrX4d@CR<-rgm6|Xfz{P+ltAKE3xp!vJ&(%v$T)Poecjo6^A_>*+1JvmrSEr zHD}DeN{BEeb&1UsIk9Um~r-~zO?du-U;f=;m)l= zRsdJ6B(`NN5I8;&d8}$W$pYr%nOWsEN!MxpS+fl9P`d3y=kdskM@wdh1tY&|f|$pd zq4jYi{!h2X*kFycicXDHR-IoB8F>R`g{oNOrrVsz?vFAnlqX86`WTg~>*numE5KZnf7M(ba~g^~!+OGCzpAj~;nr<# zI=0MbPpzEwdn{UoetlVuMlS{A7++5C==8F7xU)i;mThWkA^lpNa{$k0vBJkcYT7^M z#|l2fdRdirl)R?DP*SFzy(Q$MT$GsJSd#Phtkjt2!HoowN|OdtAuU;#?~xZJ_t@UW zjm_k?2!LLN_ost*5X6p-`-20TBZNDZ54J5$ZRnwJ>0AA`?0f-yvbWP|e!+TsMiD+} zB5?)4bFEdImq{H+7g)^>e5e1_8hma$9k22mj?)wR>aebM;_(Y4GT)-OKFKs%ef7&O z67cwGDi{#q;jI45w&>MSbwfkEQxFg66bG-%P0uOXb`Epki&2NviwPiE^z?otlP~49 zbi)?0+y`<#kRXaKZ4smZyfn`#63C7~f4ZEVihCd<_@-)cyQpfTkKbx|ELjD$%dwv* zxB-r9c)#mHcmJe4=rZ?bLG@H6N3yk6LxEJW*>e-Iua#{F`|-HGOaF(xw~nf6Yu|>K zdX&dLib#XUqEtjcIur#F=?+0brAta;14l)rEjksD2I&r!Q0eZF+OR2!O>FADC&tm| zdEPPJ@%{0A;~Vd9jWci`*n6$H=Dg#&ult&7f4+O{vpb!=7Bka9q+{R|9~tkKq>!+F zdab27*r~_jvq8_?P{IZ82k&+-<7hPfqxguI^Vf$QZo84$X(icqfU%!ZwGfI$1IF`_TjU9vkPGr z&NFEj>I`{l)dS-NC}kRxI^SRLo=c7OYVD+-%%=EwB+v0Hyq)yfe(!^;2mPWqa&M)d z+4xlTz-OEuLYxQFg!DDKeOra4qNJ?2($1+y1nR`*4@_L}U9RzDGM-*H6EYOL;8*=r z2V5$-r$Kl$t=p_OP&doEEYry<5fHuvPUbS#YjpkWdOvA2LkA6%m51;=yWvWD$PP; z1KOsV8%I=Vb~qB17KI zmoElY#mZlm*Pm1!j+y7Ix_iuF_RTV>A;WmSheiU1+_^jf9rO6+id5o|d9f4vYczgz$o?1^GaXld0d(!z@#C z{i~^xsxJ~>3zcMkP`Y%?D9Ov{UHd`lxQ|(r_!>xq6ZuCc&88bW=}kMk>WD;jf1rJo z4|socuq%%BVv}UCpM2PPak96K+a!g!pH9cBEJFRc_~AS8ug5GtHSZ`!Jr zEH9l}ThZxlElM?|v6xMP-0)&<+?d8xzqW5kl81z7tu$g*mq+aIZ z-P@f=pB~>C{Zbx6e4yWod`3~b?|JB3A6n(ex(Gg*g3bc#^+oL~V?>*Bb&U)mq34g- zUOx-xrcpgA=}}JJnKAt_x>v3=)dbldwV?i*u zE|j{^kKfd?n184B_e5?x`{*Ln_~dL>HmzlMi(DN1O#c>wT)J{nc@+0zM?~qp#@vHz zBh$2`wN>^AfeSAZUX!|Uo<7uaXR5pnq>PQ+%g5flIieWApqiYBZ`ntBJGC=LG7Csf z{N9D*TU>4}Tv;0^w^MNNzD=aV<{XBX?Dafs+TKfk$D9=)*b3vyzQp8x+R}kFWUI!5S;XRdT{EiuslK_!ko69)l7Fl2)Gn=W`fNd8h&&toR&P;XlmWp8>G8!8bxP zsyLgs!VjKOCoA#U{n;9K9&18ZEkmkuS7&BMz@-$6`dG``d|)k|&u_hCtxBH=w z!H+>BQ#~T11$9DhAU`|hrY;mtZoS^)aqEULWxMjKx{~K|5C>ZxqffEN$jk89tm0KnSYILUOptssqhN;k#-gvc5r2|n5$Gtc8Tx>yc_H$~ zd~JC0LQUOHREoe%2lE+OlyoU=UlYD=Gr)}NU!qCw&Q~?g$w@qRczV&e5-_N>;ljIz zL(6&|#EH+7YwOF4TIVlsSN{vQzFsboG`|~!p!+O^*g5r7e+~Sp(+-b&? zu;iGU^}G)A!dgyb>vF;OhUwx}YYWz4^)eQ>N{C({a9<{z|H$$*|Ni zv^og}BlS$)Bq#scFs)YrrVyDhB1G@8IQQlRWGhLTp?;Tu5%EL&mYO@HRJ%U_c4t^` z%X4t*P{9q$N@ZmP)Gd>qoAg+BQsLJBF0U-?qe%+25X~U$%5v6UdAE`sxdG3a37}KO zeJr|MKdoq4Ti>^_&<4=dn)FaXDEpQtnp(IbVS3Wwrpgs^HpgAU%9M0P-?TvHe|;+e zkw;DZS@SPKirb6K8{G|wl8?7dO^@%kNLnK?;wE6K*!0j8c~OcU-<-tXIp#a}bS)QYN{%{QSwm%^c$T_cCeOTVv?~<;t~2?>m3k zR0R$0TeovoxdPO$@ziM4bfsh?zK$j~gQjXeLN>Ye`5S*Rk7oMzW4QxM2Y@~g>f|r5 zY13nyUs2^@Jv@y&ccCO^yPi~YZ%cAO>xAG)p%sjUl*xgB!0@6ve{uHLb{9#?k5zld zKC2(wAyk`rU^!l>)Po9 zv$^uyJ?`uv0xlQ_1aE9;m8eqOMcpu+f$*}oU*6}cJuE@jpz|T6v)rUGDSVZwblaVl z!=s6KZo=O@=f{}pk|*cZj!|rhh%uH;XzF~Z_QQsrMaQAr#HrC`lO@VHsO|lRn9HMmoqU?6SW2~Xf+!1 zjJnn}GQqhkM_LIhKnTjN-s!ohTH>cSdsUjW4w!uw}Chuxy-XPzV(ODUIu@)(t!#7Q z(Wxp0n53Nbo6oe>dRCT}gD$LbKEF=g>sbP2&GoZc zjbnxgQ(f7na&9b}#vf`dMKQ4l{--r<%OYe0&t8xUIAe1|+@e!aRw$+j@Y4*QkB^Uk zdFTaw-~miP=qu?YZe)Yh=Z<}l(1GesDU`g`9RM?N!qU*Cln3{7v1Io!>O%e-DG9r=_G4;BKJ;%Xh9DZeb5i7zlm){8RM#$*KCr5mYwt9SNZy zwCK6bzRS*N(B8~kMs}uPIt1_zlt}#dvMW~waR<6MC6;08u?U5# zQdk5_!~=Id8EBaB;|uB*3)qH)0;C(36&0is?itp|0Hm-pB6>(CPfoM5z8yC7DvlZ2yLF_XymtxHz!0_>k-RN&8*Ww3J7-6QCW>&cgR zBO~c>$S(XQZHu1!&$Om$PZb0XK|E#1wavcIa#**gqcuLZZ%X|E@O^$S5AB?{E)G?q zZ&__9Cv#b>;>jTd<>VLxGRbCW-OdU6#)q?7K=L(F@4bzPv^Jgz;o~d>R|9c5=%Pp` zeqwB;Cr#bEmFGO)-65}(pH4iuiD679NUtZ zlQrgNQ;->*ciC})zO&{WQ+Lw^XCULWwF{v2(3Z2}h4*5vZVscAZro`z#a?kEr)Tmy z|KJqfLAuyEwMt)Q+{g1|%qpk0dX7|GYVWHUaEt=q!*|@8<)~Xi^WQ(Xe0IP+nnAlz z9W|a}YEB!C3v%62dfD?rO~lUnnM~a2X0~x#V25SppQJ37NoJe%Bxt!@Q&yMsu9apT z@8M7WVCtf0XytiksdsnfDeb$Zv9k10v@-NzjZ5yA6nszjyjJb&h=HU}R?wpgkR2fN zOUo0%T0L{>UC_kDrJ6RsmOiaf9HSie`1%V9dus657DMu@+$n+*>`7?A$r@S7lTT&x zinqCmu->&97(IIX(Ifro=o8XH#$7!UC;o^y(X;reBUt5y#*81(LwMEcdQI9zgXNJT z!jtmblA!Qaf?&M6;&9^Gf><_lNBtahzfvI@nRkst2ByPaobYCyU}?VVAQp7hs!2e5 zA2xkiaQn7*%dkTQu_}8G6uW-0Fc|@n6aI1ysoA{O!ht4SMe}7$mO$r<^J@pz!bOUY zFQZZX@p`0yTlSUO&v5*$7zoH=dGi;d9hPzati9~bNmwc zDU^GAki)1V)4sUz$?T#P;$l|8K0YtMkONA3mzA0%MxZ0B`RSHIiK7khV)ybEY#9XN zxs>tJDfOrIy_@{~*EF(hQgw?~H4~qRH>*+8Hy+9QwBr3nh@O8=ppH1cXb+K`RN+Rh zNaJEW?%cCHx~nMn&g1NC1_#%;bL?Vs6^F+CIV)M&IinYV1f7i`I#>;woi;U7uDrSP zOF7?7Zs188+jS>9D4Se_vPe&-1Rqxct2;HctH)u1cUXL4vTP6LN|}b_G}mZH*D6q- zcejfgXvFv7CMWVQ_Bekj%Os?GFqoTnBwB6E+1n5sZ_c@L(p)8e*e}DV)R4WFw)D;? zos8e-eJJjFPyXl%JA-9WF(S=ZMC|Vqq^c=ZAL1Z>pqZ~9ta4y)v~Os>iW^^hK|kr` zmaH&97Itl+JF3Ia+=3jIbnyJ0)Hx;XeM_+jHQNbg4+Pc) zDTKwYr0`w%`_S%lrRpMUT^eg$AF6zpL;pT}3&ZBUSN87t0}p#cr}~sPn*v-fBdG5> z>(QfsA%XKS-u#|AsM1P;aVp9D%z>9P8iOK;I$B?4H zp)dL_#7=-fnVET6v9w}cuiPK2|5XB-f2ej6o`*g`@`3SjJBTDz?{>A24e38>RtriT z6hBO-&{LAl+x4dJl0zI@ZR=n}P%67{?ob?=Q%WfJ#hg%XnT~COtMbpu8}b0DP7Qfz zN9d{h1Hl|McT&}$W2808R_~)@4($gZ_#_+6*NZQp&I(8)S`G-zTgV!kT_R_T;=k?W zE<>YvG@gmYhV-PF^=51aaB;ZF`#W%?#mXsLVFXKg^_@Ns0>Vbs@s;P<)02Yj-mlII zB;8LE>(k44zXf*r zsc2=XqZFB5@(a}*yY+B2SmQ-%Jd159oebRcYqFHED9tI&=$sseppSRQyo`EmYnL*w zte3w^3DQaQD11^p8yh3x)T`k?51kJpgzV?5A&-R5=cw$ZkVl}!v^{J3X(j92IcxlT z_h5ni_E#O7gtgD3u+1LQ*&DjbO8zHKteEi&OsM-?FO=OCDm1Vv(cw%!sq-vSCnua+ zJ3>G&v~|*;iC}8#!4&P<2Xua@*uf=8$)vif*n|wn=PG7~0#w!2PCP+5$C;cy-h7*6 zA<8L10qukP!gvK>)1bJy{+e)TW8{Mrtg1-y-Tc<+?${GGr;(6BJYdK`_qNjQhF1b_ z{V4X0=04lbZ+5HCcxA>uOYCgayzQ4})?xie)?M2?Te|PwlIU@3N&x!OTlJ2Cg{B+? z0Sf#>GVTgFubl`GVcqe(Oipi~&^Go3c@INxLUd6u?dpbFi6+$2$}-0zp=3KOlh_C> zF*RE`h}6Gn0d|C~?$(ETA2(HPiP%7trH5OK5~{0E2?Bv%Mt1*$8|tm^E{3n@S%Spk z72*CKw{6EeV+){D<}gYkC;Ac#GBe|qLo^qRwd{S~sNfB)S$guD{BEoByIhSK@j27F zJJAj?1sVeREppEigQ9kEJp#jz`k zeMJtKHh>m{c_kBK6k9CYvC+2T6tlIqrbM!}#Y6z+*LO3;gGPouwIe=k@;a{g5j;b~ zckOxd#~RcKw$O@}2NVpPS53-bFfsUkQvJIj+&!t%>88L&y61Vw43F&nPFg>58t&e4 zeKsoK<<~2e{pKYu>9q#T0!w`W%oA-~uKBX}B-jXaw&aVnrdpnoJhm$Xa!Jb&Ve}ng z%1(<*UUg&I7+1V*rSGL|%0VWE@qB_D0BVt1lT+g>pU^A<9Q3|#ov>L#!vEYm^t~VP z(d*fE#7UD{b$V?bSRZ6tX!sqLN#!4?vpV)JYJFKWv{&v8V)X?W)L;3itv;y)Zmq34 zwFMZEj@h}*Gyn3VH2K@!LhJ!jSjBVOqnM#lVinQUB&iOw5qr3KoP5ss@em$2`tTXQ z;Wc;XuM;$<%{rr6x;mAhcUa*Om%?xPl7=lx>>Q%?e>*G=ejjx^%&L&poMdNiq8RiE zGc$_jo>opfS-UOR(09zVW>$RGQoh9LLsFA8QzQQz1%7`8_7aKlrv|^j)??XlNm2pr z@>3Th&20vQUoKK=_)THv7ipP)bHCfKA28$2G<~!A3yDCD7y4al4PKGyA09im zuzlWXtb03U#FwQZeo*R`y1%K&e@yKSk?&r1)2-tsZt39xP=2-UHwu-lPHaim_sua> z`SntpuVa_K3qwUotLlTws-fKdZNBVvE&4KydV^m7@phT-B#hP(K;qllY8zrW6BL~% z{W8QydyQq}c>8(Ia{l{=O67L*3T@7^s4u{DyX%6IjNw8Gspjp7r!tzJ5GGhz9o>Se zSiM`tAm-UKbM4<31v~kDN7xxopzwhX1d+#oT<5PJ3-|AT!TKY#tyz|8|my zy0M*Dshmc}9q)6ToVV3gA~se&s}>K;TYGD!>AIy9&R+GV;<(tR<5I-nIFTm&!sUcv zmH%lHG1Vn`zf=FVgoK1f)100+Jq33A-=S^k|9+INz*L@1avC6ykdu&j+|*>zy}q_$ zGoGAd)EF&EYDsmDQ9E_MKh1WsGe%%4S4^+cr)6V(dZUw9>fcWV|4$W;&StVYp)b<( zLRNTeo{O%nxjEW?Ze*-hV46;8VERk8d0)zY+^867R6-=7wpOOAVzbTq`^j9tJc6bF z@V+%!(`K%Q2Sh%V$=XF4ocguRiK)d#6Z)H12+|LijJ^H)CpZ6(>InGSp516xY^QrC zVH8=GgW_R#KeHH_nVnzH2)7@hzHZ%cIop=%KP(mE_?P=|@$kiZvHfGcj?*>{G(H~X zx*E9_ug;sa*W;~V_2xV3oK;-b#&xpn=kD0p+9o6?OB=T)H54uOCbFgEUZkd`#`(;( z>-mmZMXZF~lRr%a5Gm*nYl%5YvR=%cr)E|@OX+)Nh#6eb@86X{U8_C7kH-z4NvA2EBQ#>x35R=J@RG?Hxvf^yl5!oxZ^1!J^`m zlA6t3Ry2EXi#<5u#r*LUMMp=+68z?tqF>JquRqX3-Vhvjqtve7@3QnEO4zpJc7Wkj zcb=HwF?}b3VuZrcXQRX!3*ICNMx0WHew~c{1g%-_g+5Yij?Z$abjbO!g)Vbhdy{`V zFZy4q6tJm&$?Mmzla?w)Qf{5IFVlmut`W4xxBCi{;cWQ#U`y(vD zV#eR^W)~c>n##j7Om=1&mx^q|zHW3BG#z2v&33aimM8m;>V+dFuibaaUy!?0d35K% z)?8yQnb-2S{;YWz82FdW)`qy9{y_#**W{9@21aws_S$@QeNV+180i{wB;7+^{m`wx zv32Kb%O|309AAws_U4$2$Wj1#QHbZdEMI9Qw1{>_{W$izZ@Ur6+;g|;^h~R!c?;DF zSkK|fuADk62{+4?$sDE%S;3hyDsH3ZEp0)(mbywRDpTCWx2yaEc`XOFpeL04a~S-K z4%>EF|K0uV9L}ptGSOKi^}x5o?)%;C6&4jMh3HG=A(7iaB9SWF^V-SG;t zy)-Yc_JA#xOEQJM416)pOa0^1=-GiGuXpOg z!>B}nLRCx@x>4#{b}yy(*Nhi(%7FOsz@kih2{VB5Q_pFsJb0xBl!p4DdZq zmbx<2y+w+NeL3cRWlP<8R*H#xe?5uZ9b4aHotluJ`D=F#A^@=T*2PH&E@~1SjlPcQ5 zSQ#tntgeL%e10@s6~I)nUu5;G(s)2XfJ9r$b#kk_#NS|9{Zl?{2O*|S+wt@iL?{}) zo_rfm%fX7_yr_wL_%OSJgY*Kn*NPs?gz=xKpx@jT`Qrw#i7;@>-i{(iyFHA;f(sKJ zih521W$q10>KTG|e)Nn^UoYscLK2WJdaT9$U#}Ym8S&UiO^B-A#B0wp9vQX#Y<2Xv zt03Tz4?@_H`rm%g?}U_pnKVz2l3tQ>qKakPbvra*^&GS7x`p8P@rzFr#Zwr5b9|cg z*^4~bTM=HYw>8QTT2P1V~we z(2vh;{@biN=Cb$r+dBVK>Ic_W7TK+7Z3t1m!u*kaC17T`3!TP`G!froHiMkEZaRD4 zQ~^Y)=9Q1iQLkSgB{KYWHUb-2>C?Xo?52IPjN1<9dtX~#Uo2sqF4=JQPTS31c=pjA z>gR9+$?{R+d{(oTSfO!SO4(BJe30y8y1Q5CaPtlEZR+{fh7;{+gPf@W{{G^ghfgb{ z$}X66q{md4Pn|h^n)qc0CK`4Y)^z#C2!=J@fe7;BN96gdQc}Bnwqn~yU`CQe)@OVz zA^A5`8F!@L?zU;WZa>AmvM?NCV>i_u=kD5ekX@fa~xy? zk(Uq~z_7{DgoP%GLl{?_{>^nFi|=B4Zq} zVvbqQ!9g~aq$`^rwwn(B_YW)EgOe?l`Oph|OMh?y8n~Fxrx#3Z>P6+AluQ-)>Yx`H zy-)uVdoA{OpG~Xc^^Z1MA>(*qIdEnVZsXSDBfQveP`Oi>id-Lre&%z~9r5_EPv8^> zKC4YzD%m+je{rfuAglAosW<;EFWquh^Z@_xOT~kOP()lyUhtykJUE!=@EcY(7zHCc z^yWxQlOndXC^1p>Rsi zSID1gx+6p18fN6b;gCC-WJGE0=_BFdni2FDn}xn9*pI??AZYRD6a*PLHjo?&{DBS)XG*ysv8s zzd6t$2wT|Y1c2$5!+xqKN4lNnYEVVEErr{(GxHu)4F|1?7mKFpEs*m0=i&MYO?!Av zC?Dt5t5*-Y^tf!S*(i(`^sSjGDJj9Mnf2u75)u;k#Z?pw4t_l5>tzLa(3SA>1n33V zp?$7fJk%ih4@PV(N03{EI}qZjIPY9b4le`R-taw-BEsU{G!z054C*8Ajl~2UoO`s7o<{7^o(??z zx0&X$MnlkoP&>d=vMgO|-oFNQF-0YVqY2=4@-#5@q7l>fw|_aW&qYY2Y8UB3dUUT7 z9C|9I3q^Dm;hU`W`)x(OVr949hDA@$H_7_aniq1I6%kv@3f*>7RxINq7@;okWyg(4 zHGqdANIKD(#RjJ%2TyPZ*D70>?6PV-#m44I#&GWlgike9k>4Cs^g%y-Df8b;pJbg6 zqQue-lg?*_&^pZChWfY$Oc96u><|?I-Q(d_Nl_T+Bi7o@Hv3$-^fNVKs}K3Glj zX~=S3h8l)|smqL+VfBde(JrX7UxRjhDzwu-}LeN`>}mZS+RD^$#fZr{G$0HBt4 zH1fd!vQ+INhjP{8SwCKgDX-zE7x~R(MCGAO;8MefJDP<$PUX3o9plupL*) ze4tj8K*XL+T*HY$uv zIy2)j`Ylh*VXltI26GuI47&U}Yo)~o5Xu3H7uB0$Psw83HoGgo%;6G>*uNeBXY>A& z61>uYStG}c9_p}->Tz((h8U@Ut=5-boxYyWWjoP6^Xpw=qG=re8~oP`WDdZXHn=0G zl(yt=iTo4RSu{LJBP*f)^ivKY#|5wLyAL~!5E+CV%2t=>cGn-kuKm7F|>L z>yKt}Nx*S7uR?yiTMS!QMFrgN$9l#8)gkEr?jZf$wlbklpq6PMUkEf^nqkwM_Iw*- zF5}iy8kq(MB38Qb1G{yWE&|UMS8s~)=Alp_l(gmgIv{Sr1GRyEz>dgj+YkHQoBhNz zSh7A|qPxDj{0(XO`}tk23l|zp%Bb}Kz{msyRz#%?N?*IG7*JmI=u5d?p!?;$+ssIa zc?ATq!5W@EFBl1XYpM<-giznTwC69WtE+RFc5(p`Mh+a2*HlkIB}XM4`5KAnxnfckv(U{M#tzG(sc&s?X0g4#z_2gePZA3Y*8YeIOY ziHp{go!q^^2Cj1F`A*1VM?wfqg*Sb-VjWO}QlPg{>Ns&|1BAG@JRG10Wp9?VHZZNa zU;E!#!fz_;Ux`H(3extu>y>Q5+!RmEJzCp=ecg!?4~u%P#Z50dzH{pf2h zL)b@u=qXhKY4NA8;OrGa;4ISs&MOhDr+b9}q>-y$w^4rS=NF@JjB;f!#_XjV$}<7E zLl(upEAIwSG$Fe21xV~r2w*LStoqiK+!V*}%3UXP&13;D3X!Z!>NM%ExUPReV_u3~?-$auj zSN&}g+#7*FgJg!tX#~Vr%?Xz-ne-O&oyqOLp9?5f(H=3JPvLtDogMbjob&eIaKi*&N3PC7)ul;`QtF!1i6g7If}J3qM>9Gfa~}rrY=yJcf$z?kz8Rf%8O- z1zN2B?64JFjV2rMewf@TWG7%RMB$=%PT+=@I@^j5BlaI=9m?#}x=nB3%WXT-mr#{- z56YTBKUHl>Cvk|{S~y~hWwX4*L!+l-+{Q2{1s9!e!42APx|AYNL z@VoY6oMY1Ug7YdVTGZ?%t9J|67P?ket0Pv2m=HgT>MvHIF1Xn>1x9cX*XM*x5!*dj zy(V^-wM_ zV^2?)pEqxh!bH!buAnF5YCoAfp9F*bEwqNUf^*fpP^3kvXWZe7D7ZWPITt{=?)!&3 zQ2`se48A&3%~@Bbt{;|FS2VpF*=nI~_%~Z!+HnJOz5C^djM6U+SGFC%VP=P zYzJZjv{|hMxYNO!Ny)<1w2pe)cE-vtHU4WG{MbkKT zabE`d7fiA;)u|~dK3_gOuDri}_iHGEvrJbw!MTnUc--!7r-fTEP`kRB<8e7R-ra{T zlCEwo^db()3K5%yOXBC;p|4um9IrSCjh!piA!l!1EF`vSt`JfCEpiNMx{}>_##4iSaJ2{wC>O%* zU{1-JDa3#iBPm*W=PG;|T||lN;Si5*DRR^RYKZu{w-m$3M&E>(c|b6k=I#X!;~q>A zTC6MwXMpE|z@1rkTUM5nh~vi9h^t53!wj(UEeWXXeToa?xAAaZBV7gtd}AZ^!9IRS zDU*~aKxOM9j@x8;6)(aF&gCt2Chs`@%QaJ{LE642h!u~Mk2*Ma@><}ZB1`Y~zXsl& zOsffEetHZQGHKb()!+6O`PAC9OGKa*u#cDUwPE|?WPpvZa(=!JL@-TN0J}&e@?_C$ zr*X|bk9ft{3J?nnKr7gjDg55ib)wD&w~WZzyn~$=TI3F;YpBMcM|D1;=|}1!7z3`` zsl zg*DS~8!6G*w%>I02I`3k^|$!rQ7XLkL0R=W1#o)az#CBJ`)#}P%MkijM|cKabK$>mMH(BB0*&kv<6J(B;nz10spf z3MN`*91o!kGps{43CuVa=?@G>I2Gf$TUS_Ztc2_UBg8kO>5M!5?bb|9yRyB3MLIE( zq*GGdT9?xY5j-5iv~UezU(wS^VDG&SAKqkg0tYkLHNO{#oh=`~pYxr$apRQ}S zVI?qZsOlXVV<=T$wy9=vxG_w+)6rze9+4+E=jRI$?NYjhkoOz%tnf-kcH^z5`K?Ev z26Dn`C>fyweS-blkaVCE7ffXizW86xa}ydV?lTaLqBTm)`-_(`-rf|`l>y4vh-d;)F9UO1M|LWvxg zk|I+*1_XI>L|7TD3e6)f$WrJ+NJGC~Eo z11)Ncf@>go4MJzA=0$k%HJSowG+fNtg>fB$pf7qD#w|Ky4-H@PL2zcTGuQK*2_4`p zqL=dL#7*1H;jf#9yBksCUX0F5U*cQqh^x?4jDc;QS1E!6ow zWvh*ijY}wC;8qsAVeQI6V?qtByeh>UsF+aXyX6L%^H3^S`@NxO5(ljiSId0*baKnw zBr1*Z-niSaihDh`LF!n`gw{YiEUm6gr4PO0OzwQ%G~6DDcvksg-?N`!Q3;gD%T^3wR@`U6 zd&I#J;nu)>8lZ1e7OI8YiaB*c=X?OH-V^bN=gqp+Ms4AHLvFzQ9b$v=fAo=jak3m5 zGC_e>$lHPEG$uMBlbf`Ul0&I%1)-;jSV(RsDm1fAf&!pD_o;;mEA54#RpJgBrOL(_ z=w@qI*py0Su9at6$!hod!m*oJBwzqwl>!Z_*bKJbm6enwOXW)glqFQ4 zvhaa8a2dGE*U;!guvx9Z))ZjX$<2xfsOSM%7m}h0r2UBSjRpzE^2iGhHh+aeJj(_b zj2e&wmi`{@*`qGka`2n%1D%+0ZB&9xsS-I~ic<~k%4hV7;oFKq?sA`*on7@(%OeaC z$gwyV80G*nv{zz}D^S1$FLPf;nF+E*C0v*uQKKAs6^L~ngcR?K8s1R61ZRw(9Cv^B znJ18{FGDkpK!5?!{0r7LQVv1oTp{3FEulqyVgx!QWk5Sop4Q0Zjr@shH*rd2W<6*V znt6KRiSM(?kfvs$7}uCplGF~=3C>+ZwF*9j-?0gD1A@j-Ju(Bt(76P`p|+0`0!}XY zt+Dcc%%B~v>FSgLaB2WSp4|CHDM(1H9Md2Q@NAM1m~|CxT19 zLoUgKT+$3e%uNJ2!Q2A_+fsE(atD0`2+?mgebOzEN4N&oV(H;#V0bxB4$sZ#4MS$# z5g=;_ZuOW;gl`=wZ346%Sn{pMo(JYYBbiFT*2D-0_WkMSg|xvR+!0Dnzg=~3ZXf?> zB#I(YU`jR$ZD_fDF4oXS+(EhIJ!GR&=g(PhKef>cK$yMi6`Q37gr_Vt9HFNl{^X=| z@bM9$wfUyBdou%qHrug7+t3oWBRG9?qC1Zh)kaHm5gVa_Z4iF%k;Y;d$22Dw{LoG9 zaSP>{MK?v*ziD7BZA@=K^To-Iy9ae-oD_~U?~WQA9I>zz4EOr~7PR@}`vs^_^mc}t zw!E!mop^738Bab3ExrNh;G^oh*${_-xU*Y0&#rgq0%V&PhzB8|`wVdW;9=ghJSQux zh&usF@N`>gkWyA{b8`srLfSEXjr3SINn5TF+hRLC(X_;#s-bneg{B1oq8lPMV~r>DYY8ohijy~W!b{j8$TvrW z1-sAK_1ZIucw-nb9Hv`t0y+QG+H61xiW@`K1wf6UY!bhS5M?=&@$YdMNRPVZ_;{3} zvmR^JnZr0iRr02D8zxr>#gIRh4otW+%@&Lxv}u=U!h7R098Yax+2FXw*!Nxicr^--B~!isljd5u-x|TGFQZ!sa~^e9IK2W2`^uy4D;5O)Tfwtg3 zQ!tT^R4lr^kmYF=-&}KVY+T()O$AetD`|ObAN6#zPNZp7+KS0Z+$~B&Q8d)^b!R7( zR;avo=R>i0Um1k=gM(;w{_QG(_y`x_GsQ~-p?$1&(Ds0i2I5cIOeJFkVB*M|sNber2pGwp@CU}c z1EpaO6w*6G_^j@Pf}L$bv_d34nOPe2l>jDTwz)$e1@<+ih>_nG2rlUk3S>SG{Y~&5 zE{t=~U1ePV!g#RHdMkD%9l%~7kGZz443Hk1PO%4N5M2byvv@$tOLg8v&7>>)G{^Ky zMHzRP+Wh{FH8U`+&B}LIIT%IyH>@9K+iBM2Ty$$6?j$EYuMK!kucTiy$MsX(ys0jFCjYh8@e10v zp!R(WySNQkc01PI51kXz@ozJJCODzx9KN<<)%i@pDY*SjE z9&5!`eWaEeAmg;EBlgaVrD>5MM0=GKq)JaojM1Be>wI#l3ha z)ASBOPV}h_6gcYgyixV)mUYl!U1WZyl2!GTg;^X7pcb~~U;tWE6#@5a`e4Vek z^IV9$re+8+Z)Lhf1mK{Zn(;PlEC=i+ckE5bKpDBL*R;#VN*WY?p~-6?@Tml5kpdWc z{%AZXO5crwAh&jb4D*q$MTphXXDc?Qps7hqdEHtbG9RoTfW9<~FYl2)#@ik*SaY^h#AigF?e;Y=PVzy;Pp@4@H1 zT&2U%SPZoX`#u47?5P>#74vzCfOikbDuH~VLka~%IfEw5;iK_7N`gpB0V*VGwGG1R zUY_nh_X{ue{{Ok-@KG?CBe`0Zs z1x(`U8Hp8GX?P(Fkm%E2embcj)NtsERgOaVBFv@c#EkW_>)Nz`=OSLwWY` zS!ZV_qL_hPS$`T1+*y+z)ItprIp>BpykA>teU^x@eh zGE9NFX}`dRs=T~>=)D1Vj$0p}jsh5`b6K51J#zzyK$k8#0pOe&i;bv2Yo!K)O0Zdh z$6d)w+-XH3r6k@O$bVU@k^Ib7DpPlW7?H`yRhi0hIQNr^g?0A(Pn}7_E_LaHPYhH4Z^r;N!S3s@;(HL6J9`zaO(OF#?rmHHfj+=R`I*0SGCN z@?xT#!w^FZ_Q4rT(`vxR>gjl4LFN_EI;0_03}lFbkiOMB+N~vD-|rqw&guQU;wu5~ zHmnZhKr}xBV7uwJW4t>c24FsSkYWD|JiN34oi92Byh@Y-loTgGX_f~{|0Um1m{FP5 z3HVtZE+l|-^rKMB%Rmlm97n3C7c%@TX=?zwsR1*1B5DX!qX)Yvu~L|Bi)eKBZs_iL z6(FLxRxkrqFx2ppMRAjKg=okNLN1bDE6U-5Kv1IwoXx-v}6H2<_NMM+F|@3oH?$ppX<9oa=73Fjo4-0({j;8QonbT2gq4E`Erc zi;L?JKkVd5L%uQ7ZB+*(1e-3$W})%T;Rx8`h?fo-7)IYJdFg_ZH>d|6tV1k~ zs-Kyif;933y!$+9F@oDz<<;PpZztdW`iJyS^j$Y>B$HQEw5lJ6qQeO>Rokz;Oe)5$ zRDgoNZFBxzI|4d1_j8?L+(!?-F<-kKhM7s>q3fUW?_-!mA?rcQ;{dI z>xXfk1V0C}yUf@`kAC|^WIcjuo5z)IxW)hoH_ffjLsmu2s)I60yw?kCYt-h$pq@eH z$WA8I)qrD{^tVUCL0&3bn~xRo1{FCMKdR(1O*+nfx#WhnHeQCEO8Xs(UcLG&rDUDN zYtb*dMdAC^+(p~EmX>@aGdy?5W03L}|8 z!g%jmgjs>hl;(x+#zu$Sm0hKqFEDI-HUKQdzEms&00_Skyjp--l~8>dTQ8vGv@=%H z*EqEZA)?N2lL_GNMCkWzN6d$|-}rVW*R7h6LMQr4L6Zqdq0$g;?mO6Q5k4+1Sm#>EM8mZ z!L&x9enc%W+XofN3B$rW05%&#e^&#KPfKHW*e;j^sEsUSLLzJZ% z)b&e=C8R`geGtNWyR786Nd50l6>7GD8-4ZoT<;A5Ks-o@{NBBB49fQ!-jz0&wYGL> zP2V^CJ`)$^eq;ycND_&35B4;2)`m!Jxd+9yx_RnaNXc@@A5GC+&+Yr$^cAx zB;1)a_H#BQeCF~=70=s58e>%qVpSHb=S#wJ+ z?3ZeQO>=)V4Q=XLXwRD%ShoT-o;#6Vbx`J|Giu;Nw?aR31MFG)EHKyTc*^yUMSNDl z%=YDMh+jguW^h8YkED_b&isx`!WSAIw?l>IsyR{laD(RCXOBphyY2h-60=C^ggI4G zR=yp|^LVR;sj2BILAB&F@5Vw-N!X3xjXu!JP$O;{fmZ|y+ViaRn_F5g!`dM8XaMho z(Bhq*p3Xa!JNP;-j=8}JaRb&9?Hoo%M*D&%dy52+-~uqMG}m{L_0v87j9wi!!N3V` zhx!6v`i^Uv1Gu4f;Dw?xz!l2N+{wwS6hH-q>LA2yz!ri{$fBd;a%CEzj_Lel7Y~#l z2VEBQT@LH4bhhb&k2b&r77m*N?AC(KLL8vF7smtJ`2$b5-bsji1xNi~-=`rsV?4D) z81~D5xwPm6+^24T>EG^C9f62-hq|wQ6c*!*r+&Eo$!TgN=UVKs)7exXfxm}>a6yX> zmBO$I`{M17a%!h{{ZO|@<|QU2 zU9&Dh9T2pCb2Qw0d3CN%Z)TvJ8jmQ!@pY(%XF$nv_H$L$AYNp{UZ$$#zyWYLPt;Q6 zZqp)%Mn=t8r;9achs2={iON6*34D$A0%{_|u}kVla6IA*1sy1oSsR3qIs*##uOeh3 zz|5pUOUi4`9K;ItT?HT?LlT0e24CkxQ1;q);ZcVsAixG~t^}oh9WUDXI+y{%q&}6RouIGZyK=TUUM^pl@f5LwTpmK&9xlH zVm6tS)a%S0yGmiY5Kr_+)32YN0QRh&&>!mS#0|X-0~pWZd|bp4J{ZN z2&?pngcfPxHlY2GdS4GjJC+~^taRP74RxyI6%-DZmzV!=1=OtoT#wp5DzMuDbQ!*Y zqK8g6o&;mL)4B{=nE}|JdyV;r-~RE_@&$uI0s}%7`gsy;O-9PR+NEMBR+yj-GwZj2 z#N(O!GiW(X;uzz0)65%kXhW2TlV!?4i#_j#+F#!MvURVlSkJc{%$xIIW6h&U+z&fJ} z3kA{647F?%b+iv;2KWfZhG1!GVW)c)TP>henCQx3_wZc%v9+>ZYqOI4wl;bVP{*9B zg$<{cN&zm%(kWdb_fP}#UA-J$vNmbXSqr;*22@K(Ee8TzHkzT2t_ytiCi9W95}Qu( zW}HAkWsrRj5*om9#s8-rZ9xi&L6hb<`JE>}6@fjXj`+FSIm;FEOJ$Jz{48xjeOL*6 zaBR?N=;O1UZ$1@4d#C~eW{_q0 zxaPfM>lVAGz+pIR*@1cwoeqkABb;I4X8dhf{i9Joa>&!S6l^ND!Wf~I56iovj%NzB zxLCUgoQ-~~J=Ev5i`NtsBRXJb)>FC7ucHJx$i^>k_$mz z9S@u^UmvF=Sb75(rk54ZcQ7Y9ch`EuXwSD3Ssc=U{f8ADNYZreIb#Tqc`g4mFo3m- zCJ=dF`upDr6+u!e2&SRaA<=*d^h0rwM}A925kJ%6!Awv?EdiOwSt|jpF91m>*|gdN zeF2_HtsnZ#G8-y-)H#CnQ2;wguMHt}e?vB|QICJF^L=RQ!Jj_tE!A??Rp#R&KhNlM_bnE#0=uGDW@As{|V2&>X(rJW}rjg1THZ0}D@ z$!7(DNEk5)?K1>55+Yw1V3X_;P?@vOPcZ(tpZ@k&KUX-?WP3m8oeY2r0h|;i$Ac}7 zH8DXPw7pVyMm_yFygH0j(>u3r3v41B$DFmi@lvWpKqx0F#G-PqafF4AfHwX4twLb_;?kQ5H4U=lqEl6qJS9XkSLyvAUJ zs5K6tqDkohci;B@Cr^+z5={+2!5h%bJElJlPj}!j%NzD*hD~KiX)3Ry6OoY>G5{*f z&4btWA8$F{wYL;KvI2w@Cjw8p?80sP%9v%;!fFOuY>*-OAQ=rrK&$Kp*!DVr8b1h( zAgx7ca)|d2`=k^2VItVU=aW17q5pR>@OTM&V1>>9YVTTuqCC&&CJ{}n2}8i(3L%UV zns@_60wN$f6x|p>OsN_O(ttq&UbrP7*BUxXx*}P$Ca{7dAuS3xvZ)se>^1>W*Q|Gp zEeZwV67C?bSP**7etU7!{_ad?^bfki%e(LQKDYCn^Xxb}9Zm;2EWtpXL986;YydoF zGpG!44D3jF_9yqEp~n_|Q~W2DQKQWOk*1@srA{?OPDk+*`Q5w`U|WQp#9DN&-o{OS zfP|?#4GX>S`VuPNp=55f%ozBT9lUuE_Jo7Do80@CTWy$%z~LMYx&p`+r6e+vUB(`v z!@7y(r!MyrcYbC5m|d%IQdh#vC*}B$UZvId-IH6 zlKoydi$;+3Y%cqb#?A|`@znL*NnI7Qt)2ixXmS_mh_V1e?OkRa34bzhRK@GEhCw~)Q%}ZV_Rhw6@kmSAtT2=e8e=+Bv8wL44MsAtN44i`psDQMDq9GNvsA$t1W$`i z+m)7$CcEH?FtwJ^9SFUc2L#%!6>pUUjE z0)0QcR@S@}<%mMV%2nQnAFpGNghi9Pu)@wnb2g%&6uP|}bt9RGldd}vkq-_FlgEVz z2Y((>(EL%?sXK_{_Y#%H^6e3+9r8Yd0@Xmox>>7bE_quC&HmBf1`b=d$oReQ2g zzk6%^@iMy%)SL&dKMqG8S$;pq`j__-mkB#MGGMwELp|&Qd2$kxtE8%G`nx#FHdOJe zUDxz2PD&kQ?v5n@#Y+{0u~ol&E}`0xh^$REdA*cB_6Gcb;-vww@fQ&V9k{_Bix+nc zztYM^H-#4RibEH`h;GNbNjjGTHV}#6(W9@T<%FRSvba8-;reeWGH|exVSh14~>!puqEff8M|rL zSBBk=TK=!K-UF)V20^M;UcHSV(=J=RAcsmG2yks-DSK+R!#pXh$j~W@8^A}b@=b*@ zob_MwhO>o>kX>&8_EMrCy9k84gV!Gm`^-u-o45)Mfe+9%ToT$(A|f0$o@5Y=Nvr^^ zW*KzEAKDK(AbL-%hkQcM0EB@s_P~l(!m*TqWN{K{`kyN*_O(omKRgKs%3lkG=i@wG zKZK!BvDYKc=MJA3TE>@zGe+-mJB$o<3 zT=aB~6F#W+rHYu!v(DO4!)ia7)22KSLEoToXlbD5KeK0tcWSO$!p9l%tQySYA&2n}uyXcH5S_v~MpCKeLq3 zmw0x7^n6^^ST(9HHw~2+oL^;Cv263j10=jrb^u&wmw$|VDf}6GImwt#&<4K71+~L6 z4B1+wVKN7Sz(sZ4f4|47lbtwaR;S4*H&{Bt(rt?~$5Ys3#1mp@+%lXF&cq*}nst`z z&L7Skf5iT5Ks2LRSkldqCAYO|7p0UThyfHIHWffQ1ybu&{}^Jq3(j`P*zs>i`6)%h z@}pBsB;Y`nfMm3M`XQK+dr70Bj;N;BQrN56VTy97Lizx-|9u(_z%cS;!gY6m7L|wB zda>BW9T`MEb`GV!Evc&69NmKB+8XTq3o==p$njxX)1#oAN@ z&2WtXEL{2>rz3zN?cMnRJf$`9k`w*N$1{fVi=E`o zKHU3!0CRj`7nQ;{?wl4Ue6B10nNtXrj5i$il-j$vH5h8c?%Hut+0<@KmiyQni8THP zmz1s(>;a{yOjsmq#ZL1ge?`$)0#lt*TZe~BX8AKOPj9+-aBe%W=Ix0eV=~=bgVm}Q zo-=LOrXF3@nSi1Dm!Gh;wQWSP6A2QL#j21Qh(a0j!p;mFxiyMLAGM1zne5rGj39f% z6Kh~L+jK-=-_8ff2^zqK2+s2V{UER_kN3v+jeNJ}g6VztnBTXB8xT2$o$H-F%rbEy zo#k(AMB=d!o&zIhytlmd+i$a_4H3fIJ(4olgx-j9-$&%w41ef@si}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_l}D4?4n1#VGV48uF``;_yXviCmW7-JKxy(hk7_{Ih#h5wMj9&0_)oALg>&U_$b0(}q` zi6M=2r){QbEMNt*Fm~_F&IX}EG20Y?Zqi;!x3^HeZK3^WVHlTR$}Itt;L^{Jj;bW* z|9QCP0|1r}L8aeK!V@Ur$IY}V3Qk{gKAF1WD|+6li>l=nhf2@KTK3j(=E(~V2uIcW z%CRgkqUDjOlqd>^tB54ZlBzXplNx()Y9@d{YS6nI^<`*1y*_;W^lu{-VZbp(>lpBf znN07h%e?PA7pLLkO(&0L>EEj>#oliOfkG8&JL0D8kB7)r9<=#xIBOh{ognZF7*+SQ z_Lt$t7)-9h3m)m8{dGU}H#v>kSp!0{j?saVhif6GBBrYOTQ&3CecgtAIcb(UFn_s31>?fYU+0 z0oyS{^4R;=tE5{^5erbt_O_{YW#SCzPG(1&7`b#x0yy`+D@^>zD`nL5nF!JixDPO$ ztHX8tU{uJfpgidY%d&ME+M6hm2Y)t}JPNgV2aD-0p+}}ooA$eQVBo#2w_gZ}!g%f# zmaHoLbE<}c2M&6#kq5W%?%v;#tGy@al9Z%SKL!%$RYT2Iluq+emot5C-hlKSDI|6* zeTLb>(XNUiIctaYo`+G6)vZI+o&hfJIq4ZM6kj*dAL3M%D7?RBHX&UwgO*YP3cP~} z&U2wYg5(Zcz5z=4$jz62eR>#&B*dVue`-lHi-gLbhYd5F}?%`y<9 z-vqVfd2umU{_x016Dmxlt86f#F+tDpm)^kMnjmu>^0DN?tu;6c2^ph_>Ng}EwPJd9 z5)L2MWQA|2ymR6+?P2G=82b;<-{@<9d|+&m(@8D;J$o)9Kn1l208xp1c}xE+aJ24D zzV|Lzo8$Ce4Az%d;w3*c;XpnMtoXazJjhf*7ccJQC^YtnQXksq4bs~zh0|ZDPQ8GS z&$|3Tv3tj8fztSL&J>`iHOBp)oM@g+WKRgpq!;WJM*MwD^;7ov@Eizq@<5}-*s&N% zN7UfM{cg_upeQA3V`I}gOA2~AQCKN}Hl)beI57t2|=4}?$C*1mc~mXF}~KbS(fg0i>1 zJhBV1#NWkoEdf;TQTsV17o7#}VG2dL2g{cK31ATz172?mKE$3+`6I{|%-mPZNtiCMy6^6ur?*Qto!Acy5BAFArS{D)Ia^Du`Y-Yyd)5Ep zJbxp?3Z4ECcyCuJ~q=E#vdb z+za!$WsJ4p1nt?#D*4OTAUJUdvJY>25+UP&Erri1-F3Hu z6-L2%KBC1bc(84VNumvD>Ojlng62yeoD5PNs7ZI+J@f>@u!gmDCInrCbmAVg-F`u_ z2iCe16lGAzyMWrqk2+pp0|*f7(4}w&gA{!8qtyZ-+yt8*%^jse`dwgESA4AkDBwq( zq1Ts}v`87pbvh(Bg}ti3KQL}^^byGslkc!04pGdxnlQ@%Fm2RhT{#vn_5!TE^?bhk zS{QXKRKhvMl+$ttr1f*@{Y6NHt}eA*1f2t-OMrZd1p!31Qbg4k?xjn8h;1Fyq6WK% zy|Ua82XLzs93FLI(Ejci`Ia%~qL9{UcwBBs`+5%?LHWV0NZ!xmSM)_17nAF*?CP3PYIkj&?yrb9 z+p~(&&duZXfmJ!^2Y{p){^yvZ$o7qWAja}SgJ&HTN-4qV1XiLizY-tK`HrjW*7k=$ zYQPjrfhtTe4G~M(7cB6^6f{@zL=!cQ(fR7S zhdjM*=sV2bET+0~uI-^(PVaht|4+Lsh3gBSb+t=AQ*w#ulaEZQPZ|kJ3LA8uC)410 zHzwv-nGBLLz95Z@@j-Ue34~9GJ3gs=+zCP#bcK0whsOpK^#TjiBp=uJ_*oRToZ9+I z$s*?d{R=)mJ|rc1VKB4#svc>=>E1n7ZB_AbIik(V&xIlbfO3(9Ynf#lX{usIZQdxR zcP8sWe3G_Y$f?MYv!brc5dmkfKP+_=)(0|ekxn>5xR1X>gbjH^ziZo|^>~qeY7YMM z+W$w!oiW?@1ACgbqwKX1vbD!{hHrYje*|?O1soNN5G~g*=iNhhKdmCMM=H;8Itv zUfl*APf{Es?a-k@qw$4sAdmJuQ->$c95;H}TVo-XzyjO7Tze;XWq^F5#u%6r!oy!% z+38a-2ddDEh=L+%TU(n6LXaM~%;eUa0?i!TrWCmRg?O>d$}Wt#@7L0cJEzAfZuA%* zCE3b@8TFo1rkTKfUUF}F;goTCmMjH+RuJ-`;9YN9cgo7bb3K7+8oh_+ap)FMh z8BVZ0Z$NH161&p{sHv2r&DE|;WNeMs=_W?MaPSy<#%}^k9Lv{2%GTJ9LP!@@wJAdW zZK+G=zSK$k#2vPB=n}<`CDMkhmYevuOL;l5p5{e?)b;2rKn6Y#`y(f$Bc& zT0n(e0WWD^kqoF4awevzc@)i7h=hK(9a2hp&^-tbyzvnjX}vLVU@cNAJSN7X5)(J# zT;rmvI^t7+HO9x=Xe)uF;|0cxw0Qx~8~3R>Y@LJRQYjvHe;1YX@>;WYtvAe!B4nf3 zflK#+-Q1?Cs>;E^;X3*)8_q%xgpYIKiiKvlyL@>%izu$0pUkaY#?wu6&x^iJg_0Dp zjGdQc$JTjBNHaz)ATyItD3Y!cZMjb_<^ z>&bk{nU-{r#C%PGIk1rM&4?wvQS&gnZQ8>TP*x7?dn(%!#-37l+EP0o64IW#gS%6zGcu+X`#pvCG~XG5nj7oHre?T+a8tJ%iS8|lZJp^ z*@GizJ<>rF6^w8)nI}}`fT;I)*|9b#H5W+D@C2x32}vdM*uN5s&60w9;0A5!hx>mi zJFe#3)qxyx4JN)Pt;8)Z?}InYK(dqjSTu^)dEM@V>Dt}(OYel8*g-0}`)@|W;^)xlO+`Jk@O< zxp|)NSfWPq9|f>w4<#)oR3Spm@a)_M0*O4tah;7;8$30h7a&=I_ZVjPBsoPgKwNlNQ{AFtt3`c*yuA`{`}BRo-ux zibiDD1IUFe9I_ORvFKI(X-P3LLbrDYFT|HVue?qM5-RDdcI?=3Lh93YY5^eAb~oyT zV%PHXJY*lA7mB4w(Qf?Y>Yn z$bRCI8xj}3m_n_K!sn}+oUO*yN-$-0w+4`VK0-3W>ZNAI;FVGQ&5k=AlOt6M~?iV7%XMpI>BPUnD7O z6qE>0#;)@4wLHMb7sHgv@`jel4OEztD7>tk(aV=F8)3El*mub+7i@C-2=#Rbs4^%a zz`F9zE_AP*LZsg>(w6s=e~QrC8Lx z=Yn0ifn)P3z_{++$w%^-7YkOG-_jBpE{*_&fdji*DjPx=@ZGz2F+ZKbC8=)h z*h%uRHzerZa{Sdwf0-2k97U*HzfvNEWs4+cK8gK93G^VX(gfU9bNYi4+lfoONIm+4 z)4D0EHz@vN`W1(J3gP9SBELRb#i+r4q^1ao2Q)r$aB=0sSiL(Mic`%A)0t?f4t|+D z#;<7DWwSbTcGp;n-a8EeAQPlU{gS^S6B7}XKz$gNS9cp7BD?l;83g_p0np|Hp}%Ic z3~IOmns!<$T!zrcQ+X}Ey}g#jK@#JH_}AsVgLtY30t1pT{(+@-OE((lc%mk-xyGT| zDgj4+%kSr4+NPswd9vnIxdF&uArF3w7u4zYXmT?@s6H*{JkN=rAq>2_ z=@eGhBh^E9&<$mI@OiW9cWGm4o&Bj6ndx0mgb_czH%rIPI+Z>&_D!v5?mB7586Q8% zpvi>^$ZK|u-hxLSlzfW8un+aCwAr_y8$h#D?+d{w36Tds90BbwCc=_~MgkCVZU@*hX`ewK2PbEqbXJew zfkZQJPM*F8v0>#!hsM>^QH=^6OaBa=eGBmWRu*y|F2*h`66n5Xo!MU&_I@wOn7bAF z_lAm+6c#i9N+2BH%aC@ zX(Pq1O_)b-i2Ipa{dB?<>JLaeHp+CRHf^kP1QFP^|GtqQ67HYImS`c3P6u5h(UF26&8`j&|C3Tu3V3BSh z^)LV?*eg~JBgbR8boBLWZgGmCnaid3JJdT{YsRAoPS-ptMwYMgfdd?jpW9l}W#N6+ zKREBa2&7unyIxhKqWQ*lxJN62y5ojtUo<>u1;IEwoV835exxFbohI&;gm33PwU2r& zU<(8$yxxLG3bXy=#{_`JWl%*De`_v4Gay;6&rYXZKEH^lkPt~>Y(t+A*A}_@o~cpt zJxfw-X3Ut;12sRH@vnE3^3bW|TF*H0GfT+@AY0HaD!I(0CEU^9)L&M>y*Ds2S8KNd zCsKF;Pymn;Np1KQiE78JLd#3ZwiC>*ArN2UDJ?DSX*ZhKL=T_DxdV(E4)gF++UxX^ z*IA>#iExtOt@T(BhsV{nldn8j=c18}vaK<>11~qL2EW6}ab3pFB+81cK6)p}-n#?r zoBKdgWFFw3O-Pr#`nf_$Z%RW*NJuJj~$i5+IqJ zcn<$4|4l-|_sgUT4xQ)aI?wBH0CFa>AX@!?UEF*Z4T&N4+5sfPDBD2}Uw?mp(ZMC+ z+|*J9PN`#3)e&I^PtS*Axd1^PbExKce8+wyu&UkeohwZQigD8SJHaW9Xg;()D5Si&77*sz`-0j%ZL97;v!2+PGZQ7|HCc1{73E3vg8F!j z!Y%Tl<|d)T?EtHWxeZkIoZ%l`2JAu5O`&hm08oF%X$KI5>u5ag+5ruqa2{_bJAyE1 z2|8=IP;iIN0iYpD)*m+4*Gruk`rP-e%Q2h#KaC|s;El7x$MJ?ANeS`5OLjZd)tktD z1FS0_>N^w@tQ@=SZ1o|-TBL9HIGJC7O4|gg4bb#R*C;`jo7R0Q3gi7RP>E%f+0S<4l;^IN+Ni1ybKR14r1ebW2MLImN!-o>rGJi5Cp%+ZCwC~ z4ntoX-6hnn3Cg&K^(I=Fotq9CBPdP4F%iK31tQ#sGa&w*fXw0D*jPV=$rOlyP>H0q zUI$wGB%q-{-jrE93&_c&)(_RSF;0()kqM@PXitS{Kpq^P&`gTx8j&aoKpsi5iuYMfuoXP}IGfyNjSi3#+$dfM*C=ObOnCn+gOO)b!V%l#w(geb8t zghK(vh#tEGca5^$-#{r~F>FDxc67C&6}AdZ7>XGFNQUN;$A;Rq7qrDy)Mcma}eJ{T8;`sQ~(!HsN(d*-!793a@i+C?Zyo`fuHobE`_l`FY$&v*sH zY`37-$Z{H)bvm=>TB;B7LzBeU11hOKNIQ6pcEi*0rCYvt&l?zbYRy5I4fwCOP-15W zuZOQ0m;m17k0S(9TDClB4+MRqf(*Vn)wkD&m+P61zsN+ip^DSBNonHS?x;@GVisUI z+4#r2%%IK@<6q7zNu-Xw-a6k8P@azuZ+)H1Cof~@^x^Ex6vz!ok@xk?2P>>$D>I$J zQ0_&z#fuy8BL@op;jP=Z1;Ah!>N%!_43Ii%T%z;f!d1XU>N6mdT79o5RJs6ZZE9nb z01zd$(Sd^1a;QozAa8dTj*h;aYLpdD@h0f^ zjyPoA>Lq^?M$-BbvzZDKaj!I0EnLRGwV2}6^GkL{^4An8YS|d-<~6?kuVzyCA5W=v z8dmg3kvnE-$!#@=cxo+oV>)CJ4>XE;d{aMDjpOfCDm)(h1Da2=Mw>+oFpK34 z1F+W;Pi}3*h0FpOlX|CHl_7`O2n%KTsE8~Ws8{|VuJh~c1N$Ta+MzS6$+C*UW#Q4Dfs0RQUGJti>p!n$+-QNcID4$qCiFPWO8H~& zFE%QO5_s4Ocpdf6R7<0Ih>pRj{qux(yn_~R<6gGg*@Aqv_C|*eH_mNB+eO>oV%o!P&Z5kRy+9{+pfvle?a@-|$hcO&qCRo3wi8d)#Q|5~= z-J56ea!{i_Y>iADB7$VDXQsp>VTEYM2wOvf+}pY5Jml^@-}e_5VC4!Ckc~bV;o6st zXBgu@|9MsU+PL?H(xEC@bsG>z6yg_AXEj}eZpkEyighSmxHrvnjv$!h^>sibkv1NVT4Qi^}v&x?{J%(3l+ z!$$c5-1g`&b-pqll3vjW>&rfl1-1;bBh=C8&zEsJrF8yNEBGi?D@r`pWn3N_@<^omzrX5(Hn>U zG!}ne|M;~!rzSsUe1M~nEU7>>p}-^1&H&@^a`UOyAq3QX=w7IN=6*dNaxP*>$nfX{ z=>f;*t2EZSTd!7|h6zY`9Dw2l`?2K5lYJJN0H<7CO7n;Lm4Z{@b+* z>VFp#vM7f~jT7^SsX^6qsVT<)eCTo#5Y4_{?U9r&Km$h(M8`{7nHO8cdcOkN3`j~f zHBrAklncyntiVM)YuF}D%(As8+xiea{`3S69cJe@oNJmW|2=(4UwI;GO+DF*|GaVp z*MpaatdU-Z5jtNqB8PXO+pXJ0Q&%_m?4N(Ib+Rpt#*UgZ*BWJ9FL(rWCh|Jghyh&0 zPZ>(&gg4HU>v*_k&6?+jey6Xf)I{O;>iTcgh-~s}XwRW6>|vG{i`8ZRX5osznz#M+ z!5=3-EWPRZ+Ygf#IK891W%8)eJIj_&UR(6e#RZcmfZqApYw`rsJF8SCJvhC=_Y>*Dp!YVgj9?3T`$*a04GNWk%DC-V5BvKOvA1%=VmA; zr`0hSiADW0V=0c0RrD|fB;@=t#`9TNQqL~|_?io-B8CI$`g|lp`u4DW8-Q66Lw`5C zi#la4nwQ~S#_O_FT6 zzB|_cj0NNW%)uB^8t9Twec9W=KQzPp`9iZdD}<)oT5@u#T547~mkJ$B(4HY2dqAJD z$SgPZRL4H$_s3$jZyt)iuYPv#KK+A1nsyevyvhqWIe6v@O^to9Wx-Unx@`Bp@gpJf zg1_~J$@3^iE*XDu%EcqTW@~3Fe?8xSZgiu{qa=lzyt1-ANV-ifhB4LI^;BjY-7^O zUqwSLBo7%mk_kuvD3A)fnFCeAgfBbKcls!5`H$0drcYiJ#*1z-eo9Y(p1XJiUQo?{oW5Nf3%+|@#NIDFfdJoFp1t@!SGfUihDIz_tfb=v)2k!Er z3Ke0&00Lb1`u5~6V|4f&lp36>{6Pbt5PyY%3YibTu{War<%6QVV8SRj8-X?e$=X$e z3)ubfqhKze$cvD26@8sw2^vf9V##CsKwnu;CA;17Ju1b$sF#6z#;h0s_q&b?&{T8= zk7bc@(`Y*Cx#;rCqg%=xs|h1pr0pw@-#t z3;FwX`bH6y**RT$JxW<10zL<6T-`o?QaYN!*z=Xc^N{o&O-(j%7K$x@>7PJD z<=cxTj_#p54H^k81WAC6AieT~HTL%oQwLHnP`n5frB(R+d_5pN&Y}SRbYK z*~ZK2A}H+mc6<+Vb{Xmt?Sfsyz*kFnt;lG9eh(!oEZ*vR~8(>b} zs9;eIFzi&B?i&E<(ZKW+G@S$>n9E1=(DchJJ}-P`F;I}jHK0)vEvUEO@?#!A@q~si z%KWEfi9yY=R-Llg=l%MWnuVwVdzAZ~~X0vYrQ;bC^>cz&XGL zmsji;Z-%l%06~y@c7ldO;MRcp(NEF@n+S7sK)sl7T|fhSVau-U=^(TzN{AIV!`~$W z7DXkv_HbUnWMP0Jh~5rNy=mTlYG!?Nq~*a~&isK42mm@<~|Gg#C9M>XN8I8FlW} zOM<&2^c$>LR+t0-?3_Kn0T##)$x9pCIuzguyY&dhQ*AH>T7Q6>XRih_0hY80n&nn+ z$BGW)W|^qeo>$P+;|E;NFi^Z0+)zCJ&c_I)Px(INxJvYi1IWC;%EW zZ1DTD1*rV}(p*h>i6N)UqZm#qM*5L>0^75YcrN=!U)=fvz*G$Hi|6lrD)I8|Oh zvI}&aECyki4=cjb)(}(yB30~aktjtEG7~_s`?H9O(gdc7<+<4Z@x4MqLO`M1e)^4& z+$b5pQZL)DW55aUnemxEAZTdW8796>M&+4MY>mN?sgguf%FK7V7@#8Eh;gFG00URs z`rtOWmRr_AAfc`j(5oe&BG~*Q&0=&aGS@J+vOy!vn{3Uf9+2_N7-}k;_pOdd1Lz?N zr7lrtNG;nHNtUmQ2*ww_FDv`BT2uqJJplG(W(yU%390&0uMT);!U)eTz7LoJ>dMZA zmJjgsDNk+q6>(tnYV(0m@z3kVAfzBQ0o=~^)^{cu2~OgB6P=)PqwNaFiHX<3R0arAkuW} zh8&B5=M1~%2mZo4aIhVwiphVY5^CQo zWz-lLGzsvmmk@lcF&J1>$)FAbwA*Fji3zJKRQc@-R0&oWzdN0hUlV@+eYhy0j(`g+ zl>_Pe1Ps;fWiJ2B1Ae-J{ceh8Zr*(aBm;X}>qQq>?j7JJdYc1>8@j_m@#E=qoHlo^ zy5S%cD4x?}9U$NPGqFJGD#=z7g{Do8<*HviFy3@DE7{cn{;{tw0LNwSH<5 zJquO!7bnggxDZ632G(;IJPk$wI$eTB1M;?eHS5YS!?dkZ#2J$N?ddH3uw(9VBOsD# zVI1^bejl^;d+~EqCtMRC`{V995(sy=JsX<_Q@CZ z%-6(lqJ@G_m^lb&A#L;g(z3-|xDLjJzjaT^H~TnJOYlRm=wlqqfVP5|;Bmvg$yZ=h zh~eR;Lq;S}rk=2G;Lq z;RDNS0$qfAEv{&5-#?xK#tn>9_-VyTEo_~JlCf|GqxWgcT*i$BuAdl;x1aiEGA>F* zqCEcSTgGNBiLZk*J!{Xy0Q|CEFL_mQH5`zO3h;5S$&@@cw||arZmh+kr$Yd3|H@9c z02{QOwwPRa(*0q0L_{(yx@rVyD4}ALT@wrHe`GAPQbd{mY=byz@qc~U6h?GW%iPN_ z#ZrT_84^iXnGXwa7<DP{gm5E;*EV8TbYDSsBuk0@-a1ppbmG?$irsugRePdeIW(Szy8I>z_iUG^hyr|%y z!c`|yMkBa4_^a-f2~eWGEXBWlUjk{93}pP_A+XBI55UKk9RJy<7LnoUUDP+mz#MykgmA(D~LWg<=z;GnC3z(}rx!^_FuLWSPRVeX7-rm3KQtT-TQi$5Tn0&_YoVWbo6!` z+=Sv2HX%0G+G~k#PQdtM-&h{qEC4pqTYp9anL1#N_P(gga&rOYbVJWh?KwGYX^t+4 z+xHe0pK`ofKX>woxY4GzXSY_{I=jivqQ;-StX6uL%9PV*vi-b(smEMFS7)vbH8Zd*djf zbz!G7S|DDudb~g0V|9dV=c9MM5iGDkiKM`a{xU^hHRsKnj^!TtaMB|l2q!=dRx zd?66A1Ze<6@xEAut;OIw<%&ZPtjMJcuH3>FAcUu!Y(Jb`Bv8x`K?3v# zP_665CQTwzo#Qc9E8-J~sSQ>a&6KbkC%!8D(%@?kki#i};6|9!C*o?UYgbV?OAF&n zA3VG~@Cw3HGK|LBbP_;0nAt+?UtGIoJt0f~et8TcjF$O`@b^c$im?nMSCH4zYLL!$*jhnl<=GAL+KUfKEpCbj^ajEhd6h`s~2Fua&0 z_%SYzf)TuprS)fc;|y~}!MR+JIIi?(bcG?!B|4;*ECF^QQ?P1$3DmE59UfI8JTJhm z(lYfp>4_bS12{B{j&=%T8dE0Fr&Efuon>rM>-urLqWN3iBwa#N!MlZo6|Nb%J4ba-LhK@pVD7P{U~h~9ue?h>iT(&n zhuCVql&tyGE3(|OLJD)dvHo=HcB-PNxP>v5Q5XzOE zX`#H(5K>-?>F^|OY)>&fOcHxoi1R?Big)rDdp7Q=s+q%RMH`GA6n`Yt=phovp7BF_ zynL|&9(Ky3kwgTNG$uH7fht}Cfx6SMN)I)I>xc5C8k<}wiMrZT zL)<&$pqQ-DUGV1#R|)|UMG^%d6HBKQ4sz}>ji+##nYd&AY?f8WNZ){|F~Qj)24FZ7 zsUGP*Y*E|?3s31p2G(N%c~8blsHQI~4h z)RunJ^|iit5lEi@Qum%l^|BHr)S^NS9R4)qY#dtX**Dpo2G z^K2N(!jam^Q^DwXLU~PyjNNepsig_g4@u&DY%V6iDWS>{F6a}lO4RYl8zg3)F_j+VH&o^isK(E9qxXwtwSXwoNytU;Oi0%;w3m z$r#2elSmTux$hVGJ|+yt_jSVfzIVQxg72o_yD7k#_}vtIHwE8K!FN;e-4y&k6(Cr= zP6s;SPb>hw^Se9x{S5jZnKHhgLElZm|69%=&x-WEWy0;kHVv~vGA%ecRLnT-boRYp z?4>zd{4HKnG^IDEl# zrmoe}=$mQX{M{GgHHXvYe(iLB^365oiBMY0*Y2>9`@396oAj93<+cAMdhz`otcJf| z-$&!`p}-H{N8|r^H1^(!S;TnDBn}Xk52aU9umq4g3hK+6kYJ2G_?THz0_0n#)bjRQ zNIdb8bSt%91XkB~5ji6bbLD;8!uHRVUvDBZh5?am9I3mg+%KE;rYkop9Tl z2M-=RVq<7%Nb*Q_DAN=ujlEOKBXF#D=4JXqJ&^QUeS25o|lvapnQ@` zrHuj}`<+w)A|%&Q2p;YCV69CoRbwn3*i7^Q(qKgOOSh|jEwoukTn{pdO)1%9R-~jy z8qujAFRPzOwRrO2K*9<_b`jJA+E3R;22ogCg!OH3J7-!fy~DRI@pjj)J_KYF9c`zsEArj`IG^6+w|wmP~IC?18S0?Z5_`ZZjj@_2+(qxXrk9!a{X zwuhj(tzd^gDB#r5*IaJSQg~d(_-VwK9{%2)h@~Wcb2dT_V%ajySF}t}$>Th2eUNx6 zgfAJ&6Ln`pl`Q6=J?XI#h>3qB!CBJS^ zFZ$YgJuYyA0$ShQDIg?jQzz@7abeJIQq7+>k_nJ?-b_{SiJ^cAQknF)L+XH^vFn%{ z4#ML@ATljQVR5Hxk|h)}Nym+DmkiOsu*<%)KsifLoj*4M?Mm{9;sAb&|1|W!kn6{m z+>YCA+O9OLSpzgHsRpiDw{EArJr<-U6#6i8?+iPQ_&~1lB|J3olL%-3Y@Xb@_HID9 z6v!UUm;a(n%AmR<*F=r@NXHTystUcmy+S5dlPAy9ZA)j2A>+9p`Yx0cH!C*+fTvu5 z`5l&w*9Ju>xa6Y*y9gK|^$tB0Vre%u8%XXaxHYNCne5Iy-Osdy>GfmQ*RWA7p@B=t zbg|Q4Ki@@nZIf=orh<%76&voj9ZRSQJJlc3P2FPdqeH3aVNl2kX}i0CB81r&%QEG2 z0jhs=ymDiEH?5W)lx;gZt0vzyV}t{9@(bybqTH?C@eR;6ernGE=|Yc`V#Nl}X^q%2 zz61hKh)2&aMWCN+H_6Q^7X~# zTTKAzJY0q=FC}{o1>nv%-|*@g?JE(?8Y94`7?eL1Hf6_i}UPQ5|g1XA4v4Ot3SB@J+^^UPu`-YyHWl-I)tI_ z3{Cv#E#@q^ulHtCbM`z#=Z#h9Mj2Ys7g|3mKy(Qmd$geC2FhQpV+mlQU`d>e|FrKm ziT!U3-Wl8vOmaRz>FMS60AOVu1?W1sf2RODP%I6GMTGiz6)G)C)H`%=95W0LiUtCZ zxMR#!P>j1|17XMU!@7$2VYm z2+0(b$TCaHrvx!eKSPrg9kw|h<5eF%RqbOA|AbA8?DCSX+|uDdqL zomy%@npOKyA8F~WhhSooA?z-Ixp5Dj(*`aWjjpgP0lwfwHtCc8{ZgKb<3{rNm9<)p zK*tCt)#1oTqf?Kw#XK8~mES|*_SG=X-5Av`eQ496{s7pxQcWN*W`_bHnTf8OIfk8A z1jygPd}ecnj1^lXU&x}7v(+pbT_!h{m{xkorBciZ! z)aMZx1i7a%NT0Fk01PGLwrYR}*!%yvo^k>3Vs9r9(XJMAIS&v*Wy7=Y zBz6Y1y9k%~(nb8BBn+(DLKpH@cT}+e({G$+#|Ec{%K^jz7$CcTM~(-o{NDW}91OqR z{>iflQb{*aC?DjyG}aZfl`#Z=Qtd$sKD)`WOJA+}zt_t&5~H@<4S)W`ldaChq9qYQ z>#KLAWu^4K`nf67?HvK`iN2#ipuG2So&2mmSMzee8In2hRN331qHl!Vr*uaS{pvQL z^Hx|zpjAoCMXNiQ%NE!3$Hm_|*~pRTbQc;pO6Z(}H8XKL!&^S><3=PW&Ff{c0GM+}PY44ut>2{v6;XQ+( zxF(s1s)7=?ql2`GLUqLc<#Qc%c)L4ct}XyhFOO5eq@E~kpdkl6DvcN+h6Wbpekl)F zc1>W+4)>|?d$2Q<v&9V?AnKy3nL&8<_ zT~)t6U~5fHZ*#DLx%b6kFrm>=35TnZyp5{IW2P*t(%4b$$mY2ZVVrVLBgXr^&b0aa-fDB+(M>u+yxotk#e^P(m8<`j0irPi;){Py zeUHe5<9=ZD5L3qg>c{X5$;ZU+St4&gX)c)4WV{=jBQt<8vIz!$N@C{ne^&eZSRH!#h12O?md<2tqiaTKuhB;9)DP$I5BCYh7LX79fYNkr=|gu?`i#9| z76 z|J*!pU2RC2pJ+`!7cQ`m>_S5|B5~4zd0C3ZnYf!a-Sg(mqllhNG83of{JsC)p0=Ts z06DXWu-He4enFiigr;GYPI{GIqA4X_sfio>%AmvoV1(J*D+eCTwn$AsE*{fZ2g)il zRzOHEIB*KQUjdDfD=%$Xm<`IOR^u4X0igWK0itmfpLsxj3((fN5fU>!lWJ>`q=@L_ zB?viodVMuc{aa{1L>i^JS>$CQ-fn6*Ge0i6Xwuy=7z1<3#1L}PvV=I*VO@J7`U;cG z4;LnD#dXKZi^G2l?c;Sg2rdJfv?`#7!sQCb=gZIM;(~Mz20dCb`GPrF& zen%w>8Nk?RB?dty`Qm3pzG3gaRTjrTSkT@T(?*BJ%hYu0HVL=Jq^l;)+YOXy?`-f2 zDB^EnrR8|K1z}Q{oivb?E7Q_lpNgxGvUmBf`?auCm$< zOS2xj=8aC^hAbSRs2GOO4{_f|GZyEVk)=-GgM<~~Op^4b@EyI~;Ny}ef5F*Bh6ir;u}sMGU3j94IAT|q0kXXW?R6f!4koxWVeu0L zJD0zu<6UW@Pf2h9@b+7OwD?n8P=_Xv6rr9i9<3~K=c4X8CcEK^6DQ9X1j1YY3bFPm zVyB*=eh#~o#=ho8AU!lY{2N$R0%g=l2O#G7*THEQ*LR>>R0JVPLP#+(}4Jtr33hpO1D#8n)<8`2)@KQjYG%z-jJ>gOVsvf5l z3-Z~smcpc0=svInPMc^_7M29y?z`~%R5r_cv2vq)ryWO7bpRWyMdT~DmIj`nE=aDbwRs{V>dh(#oYM|3qWcE zIC26j#L@SQ`t1&W9wiZ&IOx^nMqrf9=B~J-fix?zJiHaq(8Ew4t={0H``0RFBeGND<8q61(^O^Jcc%YH6GpzREp=Z<$dZnnSO?=ifH1A=j4uz0B z$ju@;18K2P)0M$vbzNk6s1rbt6pNX=v5Aay2Pt5@LO)g{n4>nj;Bo1DNTEeA{N!F_ z##UFQ*zn`n@~2EDQehd0n~C>vqDY<^i{Ojy-i_b0dKV%(Bb2=kECzKmzvW>hSuP#8(G3a>XPun#i9t zBk|;o<=6Z%7I!P{4^e>v{95Y+Yw~K3+mDQAid4^`HaZ2=Dh3uQ{-QX!EkvQGc4icF ze|#nJ1btVVu=;(m${zkv+<`0~@o%Y_&}=!@kUWI$PK@dw)SnY;ib;Wu68D$=be)=( zA{iz@f!pl54dF=Ia+2Z=o!pcGqP^8AzEtY?Vvvjv(-PViz{d+K^z!NL$wR={=XffH zsvylREd|&~rsye0B^B~cC^aPp8Yy*j`X3c8qLz}ILVUAZFdRY2mN-XN1isi;m2sSY zL0h1S4kN6lTo9bOsMdrqEe~cf3jIk|tU#+)a%QLsmJ2h-O${umo0ba)Pn`h{?o;|m z?#M>6SQ%yOA28TmUMv0akIb!@^1BZ7n8dpQcTuNbh~@F#Z=i+3@)o0Eg8koQ4vzoo z2JrozNrUG3eKh`mIvV%1O6R?(l)gPki5&;>epzzc-oI(@|lEMgSK#-4$92*Zw zE=X8aNfgvi8h!le*`~}${Rwp(KZuU3r-O!+r>L_gT=3rc3c)*%q!h11(>bCRLtrjT z%M!O62A8zw8UOf(VjRda9S@%k9P?nkZj9iR1{ zU0ig+B_=e=|104o0AX-<|NSzhQI*{C$2JpJbab<``+RLmYIOAwhEv08JL-{3>VM>8 zlQ9+?WT`?kluN7bOwEByfO-tK5+b(7k@^XDDoAPS>t__c?k*mWzR{gBExmbctz}BI z@|WV0MR2C628|+b9$J6*QU0{JizNbQc)m>8J>8SKrl0~w-PoYQWJmoZn`e)8U0MG; z^y`uOTG{vq;@RKioyF56+e$l4_{b;$zm=1Nt zrmRKxZ?=v??R_>?rQDuKb1kD@k8d3HNQC+=g;$T-p-rFtz^{{@PpAsX`KROW;3o}y*8_%&&GQQ42C z+GDKT!wJz{`M zrJTrSrSCIbq8;{&?qQofXAU)w_NCYxjlsv4kB)RoH+TIsYY_(rRZknKNj;>nGO6l~wCDX^ zRtX-)o_Ufh7_NouQ*z-zX3raUm-~sE&1lw*L;Ps zVX-iKxHO)cW0H9y)X4t${U4C#SwPMyK@_l#C|hVW>z99RPWNN_44J?exg?WE0+;KI zvgFVGv}7SAG;xu&B*jP!d}4M(yJY2x47Pu|`_YoR5pqv#N&_ASz4tr_e9!}rk{P-n zAGkkLJBUCIfCdOqVlBS@2i8@f+`nh#)EwZh0uZUu1fh7s!o8=vno$QQleK*@I0 zp7Hdssvf7`g~qcBeyN@Di{=aWPXCzvsUZf!bhGx zmxEiE9rf{CE3#hiE@i@xMqGx)1l;9QhfO<@sY4@S(oA#`HAcn zvZ=?nt93Beja!8xU_PwCYP=cMnhU4=ixYlj_P^iZVEcdlJD03==kF21slJeuf=pqN zG>we-EkYbBl7J@3ndidAI%A#cjEpl&mo6nF1XGq2wOUi??DPz`#}|Z1T5ggUE>gR^ ziVCswJebXw|M~mQt&Ey<mluy_W4u2!paXgHWTA6~mL}86UrK@<-1U(g9=!(NK|C zdCT@o=qk1C0i0}&rvF?IKY8w5#jqx1U=zWBNX6l;L{UL@B18FRV-8VbYJD zdIS||#D^?S71UpS6JPr;QhP=4^c)RpJ8M^MmGbyWyG>y~utNn%YtdmR25CeRnxU4x znudnfj>fEaQpY~UmK_e5)ws(|1CMtSeyh|Pk%9FBU`CKKjB7+iyT8b?+JiL)QyaFS zl_m^vG-2w9wI zWxb!z>+o6R$+9Knc3oaIF$P^gZ`dZdW(u25GerRY`TV9}5iG2AC`PFh=-}<;wm=v(nevYu;9AN0NUwkV(UUvYC_Agt&U&z(gdU^3|M?>N z>9a4c0|k@Was0rF@yf9vFc^&R5Ju`7Lzm9|wv;>WZczKzU%$d%E5ZTW7IIrJw!F0T z@CKHwD=rYkNY#WO*VBHS8R=&PS?}+LI6FgnDPToU`=Qf$^2;jL%bz@g8HpUq6QeV9_z;bs2+q768^0n>{o_crV;{3U7GQ{3W_<2oqP32)raO!EKeL||vy8f(ZrLs3WW05Vg z90e&^{jo>bY(s8S;!FmKHdB<3m+WSpCFOey87U@6Va{0DfVyHX+Idroip~MwJ1n_j z#*Ozsc%}ei^dqUCeTEN%CsezvqN0L!q15Qp4mF#6I2w!L>G(lh(f7{3>rs+9WUr^-D z)sU{`psv!Z)Gi0Ohn~xk)i`6!`W+RTQyZ+PfMu~q}#-<-U=McW2@z*&bUgyr8^BOWbo}QVb zbA>g!$QfD9u>L?+5t;05Tem)wdS;X$%6gBTn;A7U6}|w7AW``K*l4xHsFiaZ>;w#* zi;A;znlh^k;yI|os9`=mprh*-PbBMeBUR}-{4Ua;6k_Kojee0q!aGV&T1k-gySf8R z9>0OF--u#Bt@Y^0z1?m?)DD|eYt44Ces)JF%mC>m(M-?~dxW0L2Byu00-Bx|yWKYy zim@*GHFns#BrxPqBQXx_wk3d49$o+^E1r45dhO3UpO`5qCtSyewXu!1!H@!J<>SG6 zz0V79J@f@G=^hRp;btQwA&MHV+NP`@d;Q`E7(BzwCrpD!En80yc7?w|f8xonlTx@C zGVbeA-4QgM`k!V8paP*(0;c@$U%PZZ)_K~Gd~4GGwrQx#L|Z&5C4kz->#PgLvv>!i z=IH0wH)oXN@}2V{ShuKW@lHm~X8@5zQw<@-|1@y&oukchFid(lDiTz__{%6FyMQ+2 z;UCOcKYLOD&q>pyZ~JrxjAv3mmM5hn{>wyF{@@upR8^kE1v%Ry{uYNRS*YjSf+FR! zf6o>UGL4^jWHumVNGTP`dHnb>;SbFvI9b0s+#BYRQu;!|!hHp42A))%%SY|&(tq9L z%&84rz`n9U#L$+ix!G4QctYyl~z&Nj{tv71bSSh*30$<2$sgHde%(uiOd&Mj``GkO}m^avs92EAQdS( z;?24!0k!qt8JH2Aes-@n&r-d-DmKFA3A^pPCX(7Baq>Ko` zKStGgjIaLt^i0bW=~G(#t9$>IE_$edQ9W2aCG~Ja^;ajo^qDDwZ^T%JQn{6lvFKsc zAuF!s*4qF29i#KUdKs%pL>G3`Sq)P=;#jSkvi9_x_0bj~{j5h4z`tn25k`~{cS`YfN+z{2@wTJ}6+dgT`_@Rxtd%oRF+w z?u&ie+WA}OD_rT933dT~j|nmW1|=W0+(bUsLHCpr3TDWxSfTOmK!%eYp((^%hrW=? zSb3|%^l@a`_=vc|13YaH)S~6ll%%HBoprHz8tAIc$bn;#>#?-~VyQAn&6z@vjeL1k zoNxK>9>oRq0=FXMlRiMm3me$p<#+r+$-aQte1CC!E8|k zL16}YdPljYw)opGhyMnE@9tc}0Z}ao?y2bQ-I09oi-U{mxg;ee3EEF(Gnyw5s+#^U z_TD?Js&oAU+}0R7cEO50_JRmVNyLH*Y7|gWF<4NLCLk7Cn!y6tiAqti(?qIt6N)85 zXo6G&D$+$mlQwIedoyt#oq6V&=b4$`%$R>}E;(nPy}$jH_g(K=>-FhqHNO8wv9ai0 zEvw9os$k)NHoHmugQ068{J+Q@PA^41Kk%q|fsrLgVTzuv_w}C38v6iVTcLSC5^~C+ zu(PvzH04I(myA0e zU4(rKa~ZHad=gPP&EK(8JS=%jF=b?AaF)5!Zg0lD7pF+QqZ)|BZM{X$znN{OnfU1J z)NQ~{W<$Z$nun8kC|bH$fhE2ai0WH3jDMeqnIeN>YhFbq4**VBG{b|UyJIN~>HYn)bH&2%wfL5Gxc!pM0~@0QSBEYHGl-?` zQgExE-4c^_gg=8BQyt1T_Hih=e$o6WtpVd8yI8V#agv^jFiC5`?hErM$*#QMtwI(${WFp89FdB@mTNrxB0*_%>+>&4d6&>Y$q@-nMn1mL)pDHCFGhup zExRk1Lt>V+5Xg)ow-Tsh3MH8siS$4J z?2kDP6lIj^p@!p-JdwOgT_P<%8DlZrql5SH;{Kw6cQ%q2ioWLihA=Y;9Duu{#N+5Z zAZtRUcoZbf?ZtV<1t0nxB6)%tix2W~E?IrV4N znM(x_3cPTaf{sNC-wo~}rKg~Aa-a~wB%6)ZW~0HzdI)S;W&orX#;$JuNL95PbHR2h zK@Sd>PF=bulI_HfZN#9s^pRoPsl-dIqUg>5D1Z;mhbQ8~N0ImrCER$3c%Dsb zGMnC@eQNtJK5JiZxmWlT3SqJ`6p2aXf@%%H?nxw#LH+jZud)wcl_1=yEdRUH8*Vfe zS+}fMuR`;xcUI<)m)RLywlJ{koLcA`c1R&M4TZx205DuZQ(8)E6m;hi31-z(@xb7sVge?fRwv91$AH)@+-{VK8dcY}lXq^D?9Fzfx3 z&G7+$M(ntg|8$jUh}qO0sR1)_{v#nCN+um6M!w#CEwSRkc)j0CUI@fn!9yldvyRhw zABX|b+UXXl4c`=*RaZriYc#F)*6x^OhcLxy@gBH&an=Q2!xb|_j1!b5&< zCxc^-r^g?G13!)bOCn3%j?oo57->Om)^Mmi!AO+HtQ-@9K)8b;veDDO{=XDw6i9-Yi*C+)PF;jn6}xB3|m;ySE?` zvPdT0DR>>jzy&?d8J((J>HkMb@i(W&AAwFZ(Jt=UqO=s1Nx`caLFOrPm1(4_+Dlb(69R7_mY=8X3&{~13?$Lw9ix8? zbiqlL!OD`9%U!i$J=qJ?{JHc{=`0R{s*ILT6m&A@;lYC_LFmujkUU_-W#0Ac&r^Gi z?obMBB+%-XAl_N3WRdOH0AW8ar#J(9!4SI78)3UmJ9zcVESd+s7NSGj>zpoBChL^`Ico_u7ab5gunCRm};;En`#keZd>jup&H zzzTSBP@LEc%J*16T}e}Mzw+HP=I+&+;f|Fyk1Y~jWCVW zlK#slQK*<>kw82p@^UmQMS9gQ6aVm?%@gE=Rp;kSAh*2L3Oay`-R_eQ z4-1AdzkezIp{=I)a2at~8K%Z053xwvdJnsveeZ>UXZ)9lXM%IgseaC<$3JvROG;3J ztwOvJ_(TMF^@5JLu%gz|CwB?3lIB|N;#*i38;*;gTSH|^^TB!Anf6&1$3N8bDQG_T zmj!^NceH5m#ZJ!_s}gXV7zw7i&Fe#mFI2kaJbwIG#YSp1xLnlYP0=vbeyD$|Iem0 z3z4gj=g+GuJb5TIrX32ORSQx6BN3o12b2B^PJ+>0-4XPWf&%EmAta>HPFmDl80q@M#VzrmYD=0!FihH4i0oQ|w1K$E0H@ulSK(ZFYQ%R}*NX=+x7%48 zVbcTi=;|Sy(L4kvcx)OVBf}O598!PA(Ys2RCHM9D8#M; zGpH0?rNUQIz}Owra+^+;V-Xe~0n$3(;PK)Jty7Y25javT98-#bDeSSWPCfdAb&jH{ z{^VsK1^{lzzux%Y+1>6FtI{thD(c-A?O)#S@zY|NTMw?^yyWZ>+1sf3-e1d8ZeJU+ zdcHyRpzjiId8NM(J-Q<0{u;kQS^M@JTQNu`bfaJBQRTkAm+nrP{GjBw>)#Aow0^*E zZEdp;cVA|{zUE0E#h{#b1z)^XE%Qz*8m8wMM`MA?6FRDA9SB!Wpwe;W%1p zV-w!1dk{FQ(Y3mEl@>{ccI##jis@)?NvU<}XaQMwRnk83bhx>=tMk+~y2}*LBM{Q0 zL<8O_HQ~l+o6#J;+Oj#w$NsI>wXl8HcFLc00pXWzhIkZ57mgEOD9lH&lnsMOo^4$h zV9Se8ojPq=LCv}6)E}WM$HtdW;$I@IyMhW+ou6UbSAA9g{?jHxyhUgn?jh*U!ahbf zC!Xlo*fPHL1!$HI)mydso9VC-L8v*CK_xL{P#Vcjo@e@W8vCcPjS=fqpeXyC^A_LX zO;tQ<(-RBFkm^Q80Hj-@T_{(;a??WS2@|K>@Ekzy@y1H=H&?fODd=OO^`*8n5<-r- zh2ry2uw53rQc?URq18()kr9L}`OXRA53N4dL+a4bnEsKCUzp4Ptryz9SZG4~P6DMn zqg*$d;lQ9AYG;%b{p9w^!JVEH4`V~3Bve2K9nqA}tj_w1?}czV-J1~FJ+x5~KlHkB zQ#%7fhU<-_V+%W$vqActLY-s;b;fjLqJI_pYG+o9zk27`-HE~onUl-LQ|r$hl|4Qw zHu1Ms?2Lw5(`YC~VGm((+PIXZim$NM@SJX^=boOPE=}=c-k>L(5&AB%C9|a03#hll zYi7ifCl*__9=PrtpR)1 zfw=YWo3HD@k^_=ab}}ACI1koQ^5C`I%~TTK*PYr2M+HkHK@ri_;YPyzNs}fGIHE~{ zsuh;?5;A15?C413(4Z%wqQtj8j@JZ#g2f;5+?L`FWm~n!4@gIf)7wUzb|=)}@^4^j z=8NTr;ggpS@739(W7DXvI^ze_J(?P%iO7RGZ#R0~z!!#Xmxfn5>2nd9!$;~hcm^y) zSV1$GjDMfnr~O=QbZaBw6h0s5rE{{yie@4DrsH+FWk0hM>(^g@&8AasJOjYZv+J3t zH{=8tGbB>1%J||yB@;QBJ=!U=rGM47mLo0{;FSe4%Nq~-u;Rb_u@r48ZSv)BeMvJGog5MTQ zhln5hDo$RE|xkvn2JZL)l}T{6)Y^&b+eDSd{w49q7sOC%$whO)qzX% zr4&K>>6GZlzt?3`dQ#9{qg&S5u>~%<0e5PO9QTE7X?_PECF%@0o7)iu z_mrxfY(J?yP?(VeoV^K*n*nUz%#4s~Sdgh#%66aOQIYRt*Sn=={h<^~OAzWysLL(| z>BfyEO;YPGs7TdLOf=h8DxT0H6h(0x^b;e9A4nY6kPT0sI`x>#&3Ro%$mDn1*QjS( ziK{A;YDYZ*`zG$N6^Bzdy((;k$W0J3P_~NjPnKF|NevGm&RA0Sf&CPjo9kYF9=m4t z8w1qZNaXays-bJ-QvATT8^!yAbDp-a{|gp<+1ifmpe34#ptVSNVbo`^lXD7i(xGTG zu9Y*nUys^H+V^SvG;r0z**ePQR~MkN#lD%`bz+O9s0uCPJ3Tj%Y#YdulZjr)$Y779 z(y$2%^b)ptWrHxN22Zb#FyBm-5x}D>u#REej!oeMu@POqLeXNguS(S&*m^mPK!>in z01JnyzpIGjqf7H;gd%Mqa(pe^xUL(BM{-QB?8i3ZL`O(KH(&9e{tq9;#jtTpmD+HH zF~X)Az{eY#rKJXJr2bvBUSbthmS>XJ26J5F@K;C_zj{&P5IzLvjm>* z;NBB)X6y3v=29EYwDCf#E45S=*)8#)R^nmImFt`^m}+x6Oi3Es;nQz) zE*HNYW0|zo^1JW8qr{qADK;9Mm@j^~F}*NmMsSAX%q3p*;?*njp^$fVWpeH1kjkV`+urG|k*Q5P>|+oNpp2!_F6B>wsM@w&!*=f}JP z{OpbZn4sp%7yg*rV*h;--u>$6FNNBlSIoFKz6g<>MCU}u4NSI7+yyT{>k3*Gf|WRu zVdoohY9ZV->+0P2E!0b7Wx6tnps8WullXt0f$Tkse@JtIYW|P)9sJ>c|H+!sIbli$ zQUFG)68+E!D46qqb{yC4C}){uj7l$q#U*%xQdCZg=ZkMZqi}-YX+#NB41QdqbwZ(J z+{tBCHvBf08G;f5MF1P!_k;L1H%2@J!W=DOK_8@0C78m;srV-QqT0MYU|83{rfDaa zCDLsdpojb88PU@a4V(;a7r({_BRV~wX97(m={9w+yO@rhCv@{`#gf{HPPI){s5QA@ zOI8N5?>2e*^d~Fd{rmL%x9vX(mVFk`aT1ZwY`E9$Du}egq3vbfMREgt^9B1$UDJ_U z5i$7a2}}@+^|@sj@3;wuoxzrW{WffY<@0@t9TR&=0_YF7tnplH>byo5?-o% zs88+J8Hx8-G~6W(38b^_w;jZn$bfov2=8=v6nH_2oR_|?n zIn(I~%@LxVJf>zM0i;sE7mRv#@J;OW#fa65ylSHM6o@<-65^I)=`CNef@fKNVNLY* zho`DvtsBxbz293sg}Bm!{~UUQeYBw|clAwEg{9N+vnZ{Nmf7O~r58mCIiI8Np0)>wG<(7AFYaN_o6pAIGB zn2H6Kix6{7bSr?zatpp&>pRw0X8DE+Ll{^FZ}dN>kG5?Rz@iv!+R?2y>8!N-P7My}>T zw(C{QsM17u&*CnPtD^^>DO`hnfi*@tSkTCZE^$+;Y;ty#iZPnIKg&7WWg^oXjCoM7 zFQgVFZ6d_^PoB+AFsR#Ey#3uiW8hu&+n^)YJ^ag5wL|opKxE{CoPPm(Z*R_>@N5_S z!8uztKmX5Eh%w}e*+s}afZ4W@At8JCL1_SVc+*hSvNqS4jG>(#p6?`j^kG6_aJ zUV^FwETwiPvT%>v{tPy z1vDmLc-Kn{*R#jR8>+r3X^BVOQwcH1a#!OqhJT9?IuDYm zZ}wd=?DQb;Zl6)_b^7!`nvU}Xq%&}2b$GrJYVsuEAKa* zyH=|{e0bs6O|0ab(+L?(pBBAsS9t3{8I>ourj6fJXh#H?YHZr>)9V$sJ(9KoGac)W z@s!@D)M}7U@}+uP`6`L|3=XYon-+^CAH_ID(G-af^?zNBk3sY>i(9DvW?Nkw>>`g0 zerS{cJRpc1WjUKh)6*YpD$+kti~xYse0=8Pasj4CAmJT-&IiS zX_fJia6da$zeX=D`=Rt|o!ja8@~S7*aY#`tH`$~wW~jyJl)Dx=8w|qPTY!+a?6cp= zeP&)k9~{}vGddh>FKaYt6Rm=Q*90$XGLwDa<-O~v|1a(RvN=mGbu{Z`ueyE&9D)wFXPa=WYJI5b0UEQdn@LqH{dH#++MX zRgSHq4jV!;#O-X@AbB-J*fBc8E8_u7NlcSqjTXJR#{vYP!YUvxl-dN3(sHNc5~}UD zM}XLMfGIMpwL_OymcgxvmBPQT=K>rfMs;^-rSYR5y7i*x)iUL>8|rPlY1VpZlY~oq z92(PdPac67sUKAX*Q}AAMfrgCuiQ?s0IK2%H@7-EX44O!0TEAWygA7lqvGp#uUda> z#?<%G)O%b>?fv4tv?Br9ro6WLq~yE>pL~*+HOcshvm0;gU<0KSpjO$+3-hMnk;3(D zO)|jLxR?2)cyJit3~FFw1FbDgv+KKY{Za678)2Gu1Gd_Mip+(z`nvsc)NF})L&=&9#)a}B9jVvimuyeN@=on z^{-uh%1j%Zm#&)!n8WbkTKnzPLP((Hx^?TORmPKui!?Sc8xXI_@0rX&2Mrlgqw6IV zbZBfIgOnaX8)H~W{{xDBC7>isU&!y^PQnUJmS05eD18?9*oECCcVDy>B5CikCl@_# zg)a+6X_7v|r&I5Nu`y0jQE@_jMNZIY1}zy%xT#=N9?xX0xIuRv z@jVU$uUqGq1v4hVf5cQoJhTa{-zfn~2rhCFX#0&Ygog)v8%zl}-WDV||V7rXzOXOA=-R_l37aQhNQ-bo5zR;-gY$<0p9=l4)xmeRrSj<(k{l zF;zv+BdZ?_K)kn7xrjbMST!3>M)UN=pkKA74m&hU=jV#lnyj^}v<<2eluQ^|oN4{| zQ;)q4Ao6vCF-eHN&f3I4+POQx2|L5Ykv`C-ZLF-l1>@Ua)twwOl*$)ISEN=0em{mp zsBq(4xkeF&xY`5R=2$xN(6WBOk;L$R&lvk_r9|6So_qS9-trlBd9s2xuQtoX+}xZM z3$uERqilVJZktaDehM7)`{n`XrDx!ZuFjS8{alQuKy)u^uZ(Y>%EDF0n|>YrVVL^B z#`J0e$_}R_%M{N5qqOlOJFr?ZH#)7-wKIqDi91$WXm;A;$Hy>g6TL#BjXgg4oeJZq zP9}PY8%xR4qk%gmEG{m&Fn2v1Ek9Td$NJS$a>zDT>PNJLXPCk3=jcbJ1;i}5s~%sd z8vW5KFX_JZ$`;j*VO5n(`A~dVsaytc8*S5mScf{wafmUR&`u&V?{{xvyryYYf@7r|t1r>ze`zl}j z^JDMgItf?vy<;t^JPe*S3eHiN5WooyTYxZT)L~fI_N~CQl{fnsdsKWpjVG83 zho`;4MmBL|&_m%3pku!gL9Un6@+|k=>dO(#FazkqO8jBp1ja0<@-^GGP&xGn*P<&?E3Rx zhW%Cbt%Lcq$Qw5QSg8;9i^ooj0Qk{*hdC1z<@e4h{9uiQZTziRA<#G6yzoN#5aGd{ zgXhhK+(X!QwNlX6=Dfd?t?li~xdTmpe|GJCfpk=BdqkME{rkNBO$BF_!)E`zK`s?u zxc}ZZ95jwfZWOs>`F^Y|*T2_n_QJU!TfWUM>u|`5`g_u;W5ocz)9k|VD1>dY<-SqM zI8Y5;{|;99-?#&W1UEn|CfL&XwCGg09eiPBRf#R#YDqYnlLix zKl5IHvumO1e}3kWhh8vi%u z9}ZPrl`?1xR+#pSzS|!7_lC^dl~W4K!lx?0Up3yK^3#(H!yVYLB%5`s0M&I7j=&zf^>*4S+a=n6Uf%Z zQVh*10ub_tmx^M!C(c2)n{g3j`k00J85~-bHeLEW)$buJIwz?WqAH~827;@a+2yqJ zbB&XMg#0JAVs&QsEw7$*nmz3nkF~MeuMO0M@t8Ids%=GaQn*0WH^Q*HngsM287P+l zyENEn5|5g+Rtiv3uX&!Hy8)?cDYqA+2g90gzdiLfiUo7n5_f1Rmth(g`G$S;m_K9D zo~-!cEXem-D++1AQQm|E>-4#(TNxNY+LoOy1u8ci&ctVO+8!IW55O7dzc+>f8`x2` zpA46V-CYLs=ad^8wSc?yYsLkJNF)=Kds10|_|b%RRm|$jJyBjeljFb`*v$|WkTv+K z>PD4M4e1c25|?pTK*!c9W1f6Xp%z)})lx!1oPZ2VsVL5rNq|< zSR^6e_!d92*V=j;T&3}7;9g_YB6GrM+|7Ps8A?=cqYC%wJf!!A>-ZTOHI4Ur$Buk> z=vaMQ@EQh5vKr=vl-wXvjzCT|kY@I5 zBX_#!Og{c=Q@XojXv!ymw&?fg&9@qcf%`-X8yh2$_0E838-i+Hg@rCn`8DGlUc7jb zh*l<>#)akD@rDTDH-QU#+jB0`2FBp5Z$`(qLrXK93XBXTpcsDhT{h*D1VW_^2(tcr zQ-O_1G&fWgAs~wF_~jdLK6($IGaiI}FPkE=rLk!h1%&yXl8O-@?CYEm{TGepsGLDU zvJH^Nd2@1)aC_UM`j}j1O98e`BhSIlbM3lygMiiPu&r91SFOFVM@~DOoClG#fC)Uw z%MRT5rHG~M4ix5AEiut!Vl@IK3x+J-^x;uO^<}2t)K)f0*wSEsN;^8lo9A21APg>F!04l zps=MBJkU+Qya1AT3B`$~eW>s%mlqHsjDsCt^}e*QuMuO=9+R2w)py>g=8}QdTIcR` z93Yjhk_FgM?ESVFlAqgs9zmrxYZTZA51u?J^ey^$P@7 zszZ>NEtjnUO^Y2vF&SyJy%gOiN|*~HJ!hv-qGZH*P^T%pc7c2%n4WdHmG{jOo64ut zDV${iBjW(8G6=Vmz>kunw-WsvQC~U+c#;6Lq$TFX`2l$eHuq50N`}wP#iP@!#!GD^ zCjz=U`^^G0iriqT5sEh8hwbaxw)6dvEo0HO0gt{760>wP5|zwOFLi*&@cL*Nm4gs^ zGkG$Ac4JaZvxca@Pj@fj{sPOhYkBubPx*(4U27FfNth%2L2Bw6?G{TNQ)A@F$OubE z^--2xl0fXYihg4ue=--u87xm%$F2GRmS!+tg>G$J#>O(bJ7N+oM#hz~@y0~-j8G;( zd_6XmhDB^DnOCW~y-cdY;3~Z73+3H#-YV*5dkk{J@BV3_`+dRDv47b(ZPg!1QV9yg zNdTrUo~uuTXY8*^);seSC7+)K;G3;lHk!ldJkpAI4!xAl1bMBLewvF}D7b}b(KQo2 z2N0KpN7qMOx$Vs^QmCv9VUrQO>*#A98_QTBBN|Dlvg3VFhb+0bTY|6-AG6#=#ln== zcN(JTJ5PWbM*FN|Eq_W6aq4%{5kH;rkBFAuZl57b|AD3|b?pT!3LgK%1!$?&mwj7U zw*kb-ZR9@UPa$si%KocAPYc?)>@u-%;y zsYEy-Zl%y9N7$7dI~|?W@H^inJ-5JIrEwFRi>wU)a!L-?9m}%U^K;82gVInf2dUl@ zo2gSyOKruuL*blSie|L8|2}Y_sgck*^`(cSMevnyDe#s@d3O`KZ0%{ZZq`l!=4yqW zsXe8*ajVCHC_|%%uTt7e)!Ti$t9+2BAl14wW1!HU4A2@>ph@yZ`9U%=I9-mR^UC(y zA7qeB$|{Dz9~o2=i$-gdF@WS##eP^>>b_=No=%lHGVBTAb!KJZz0zLwe zBQT>3Jh;HWba?Oo{&Vv&2858BS)(=H63z?>$s$WkOcHEQf|tc2DVVLVb<)_76=m&5 z8cYAZ68|l0G5AC*Yf0{BG{EtX?+4VK`vg~U_~kpMK75E{Um{+FGFkaYFY)VGjR0By zPoNRhIqi$;wjW0*A@dzKr+)Cm&pSfwoPu?88b_xT7iUcArqu1m_DkV=e$?>)X59AQ z`j@+1NifuRpDw^k76U>#65w=U+RyW!G%bglHsB6%Wp^V_g%*HNnVc7|=n9N)%r}0GfpQa4BPqs%IgS zO2Kye@So!oTsQQ4a5^q7?mJ`mg>RQpUd}^%*{SWbI;$OcyPezyIP8p|(;!Jt+Yg)2Vnd!N(aMiu%LKyFY)F5Yc*XPWQmU zQr=Msx#NVulGBI7HvAO1p=*lxrjExQ{>bCWII>e@&xlI#S~@YfljYCzv_r%vqo6Tz zpy2TgYwxMl(!6Pnr=>sKLGg72+rY8X78D7?J8u==)`O4SW?#67u^zMn{K$ApNnW~D z!-$WZEZllX`I?Sd+BHG^<0r=bUv@jY|2UXX_7`5a%8lY^G-p-wXnc4v#9^lR22w|F zlNZ{NEDX{*aeWy=d!sR7tpH4LVzS{JU5i)+yOt;qe5PmI#&A9si^wPgPF z&d*O8<*t(b+k57k>gGXTiD!?cdGb18({z`%d9!Pq`#<%bd2){U0zNAjNgIzj&rQzi zli-sR5NV#%P4ww8Q@2S(v--8-UlDwgf9>H+bG=Qm{Y2jo>^I_B&CSf7WQ&`&2njc` zPt=P)D?INlZ9@G2jcM^eY?l7N@OETFMx7Xns_8M-Bpm`)Pu4ti=#cAB@rkh7y=%f^ zM65?pbI@}L2nks$B_r0*?%{k48}c~q%l z-j^58)QUA&HE*xP$2&c+E}#Frp`l^gEAb~*-@v^>DX=W zRTt*nN?sxU?oH#)&#!6+jsCcwhDs+OjdDBh+ujzkUzKVyH=`z?Wz|RFEoN6iMZ&CjZ zJ__X{4JE&e5Js!)o2IO+JZGbL6Vgz{fr$8lZS9QS+_UNR=D%(n4?en{1`bwC6+1gS zum!B%_z&u&j+B|n!t2`FG|RE#2baVj6aeCSMu_`=G``j&($8-yd^2du|LCL7pB46Z zCE<>wne@CoS(q9mp6?ME6f_gkMv2k}0826$Pjj~P68%)d`t)Dxofno@R?5AFsOQD& zni@Ai;YrAnM@q!xGBQxnvq&0@Y??0Mpt?8hSYU zHC>e$T@JZFTXa`~Z_p>g19Ktpx9TYI2cbCJG*&y)f0Fpmt5fh;2+%z1#kVX}cnXn! zzz5=^2*%6w!9npg1k1xxXYK#EVB_lS%1+y!BqV5zSh#;y-w_MAUff_yo(RZxoIEL% z=~-EWAeY`vHWpzati#9qr3U)|!i?iAmNyZRW@ArpZ|~d)3&Y;MdwXUU&!0a(8A0+k zuxaXCE$qiJ(uRT}`E}n9%1ao!F*#ime14yfDQ6nL0`0O@4!;R1{>gQm}WUX$#8`zyK0qkh8S6 zvvMjfE*_2gBiouLQf0R%Zl3sl6ebC3$50MQ2Hrb@R^=rRPL6~1unSjxP1VSmBtI55v-N-CqH4=wYQlNpyBcUJMeclC{L z!}7m}FFvK7ap)wQ0!qk|#ueg~bz(}VH$C{asTHjPOK?`Z>&;Q^dc6+%71kJ3pF^bg z{89e}+L;oMImkO%EU*iWn=gKv;ii8a)EMP}PI64nmReZUo_G_nX-Abo2CU}@PM|8W z`0{EOZ1CJjuq}WiWCfrEbf|tM7=q*M^rGXV))rj5VR)x_(9-MLYMs>C*^(4$wT_wM zC{N>h*92XE6x(Ph6p|c&?Hz3(3G311SE37m2fFopPt0J=RjXF9Gtnp@K-h+c+jo5X z#^BqipZQea6-&H+@e1u<)r#fR8gcWstB$b%yGe$ODA|s4zubeqpU7}-n5ljYnowJz zCYb{GCRM2&R-h&(N2zHc&J8s1D6mONu6!?F{_f4(ugD@CFcMT((>PO{(2`?U#&UN)$aKT;v7qJ|q6ZO{zyo;~ge*Uf zHQTZ0(6b#L6nLM>4&9G}hQ#64W$s@V55d5aw0YFa6o0$P^GoMr;o!Da`48$`45<-z zurv2>cMONEcme+JqTh=5s_d(}Stk{1EkTou*Vq_Fw%RpU$20#X{cOWZStFpKq&&C` zi<&8K1oN5=E5*6!)Ts@BOxjKEEnfN4r z-a1a0p=?#6nf(svM%Mm^58%*y+uI52Q(=qvjuUplBieOP&M0-qnB)~p=4YH^XGrM~ zZrF7ED27>2wFBJJ4W$#twdBON>(<*}trictrxRW{J2%bK{>2MHoXUTn#0z-mC!Zw9 z{^is~-mvn52@76ydU3H&`t7-Hqt!>@%>dXq>^Vtm&K@c0e%VaKn{dljXsUgC(HTad z9m$}}pG&$rmTP=*P{Ze72FT#UR0GWK1nx0=et>CtaVCjj;MhcnJb8?2tbVRpBEbMA- zVscw{rg#}yIwFFmECYd>^7z*2N#W=x!7>Be5d!LT9F^uQdryf@MEcw z?LZiU;PkN9*`*0^>@^_fu8{wZ9u|)6?|k~*tBc40j%pGvo(sn&cjD(z-9B=PMsEL9XhQf`H^>is^~HeXYfxKaaq9}y;nn`LL~^{yFy)7DTDF#GYqw?h^~04E@!BzNLT`cG!OBOK-f&J>sx>>z@9CK6Ugq zHa5MNM7&)7wYg>@s!W4mmRrkJke8oN1)DpirkD|qsXn$al*zqkZA=i2Kgn&8kUCPA z!}fY%eaJ8;hUU|LOgzm`tRM>K3ovyuPmCr^8MPPPi(D?tSeCa^5FGR60Wlj~I(`se z@P!_8Koh$5!6qOPsN*l);$@7l6u-@RQ zgpC#2hq1U7gE&c2JDv3?09M3CiI$C}j%qa)Q`IMFXEqfz#to$`WhKtO&^W1mS!oQS z7aZnHBZ^yJDXy73NNs*sHu=UOF zbvW7*XF4@MCX>mp=(WN0s*zI$1-7;zO_m%LAUYqREO!Q)4or)e0;Ck4A~kxKPER1H zNRBZrVkw)vQxF`NGJ435mWN8_ zR;716rGlQ+9?t5|6J;kfgy-toIXO?=4OQ{(mX6a(-^Ui z-ud8oVa7(RYqY=%t1$KQ^6I=*{QD-zr?c|&<#5KSSnSyYQ!D+QcRq0uW&0+}@mh1L zNGBqX{bNW(_AcO;wzjrK-YX(H0aP%aEgoNIaAb>hCP_%SNb(r6bHn!0HqXSB)A6wlpD-Uut$)%|u^Y;5c& zFJ6dE;`dbe!$T>*^Nu*TaXyGU2WM=}JVnKRYB1`SkwJd!3Nf2;s5k(1K8Rx+MeR*2 z#N%EYHtOr^cRwb+*PBZLi*p4XK0LQ$0&;m^EGWh=zz9npAvcHOqm0I33fd>STN4U` z>FMbw)4vj5u>y@fzA-j7-ei?D_{TJqSx_z>Kwp55uJ=Xf=RGl1qN1be^hNZd>3i79 z!udnf$;s((FY&kydyM^%Of5E41G`*y;nc+m=#G&7^yv_^HC*@6=lxJ_p{sidRNk)0 z#sK8Vr)nm^kt`U^5$LQ<<2|<#N~h{JiXS2QXtMtoFSHB|i%*mxe_aYZhN2ZRDwdrZ zkE)1^3j$&`-h&Mr_Zi=Sfaz?2Np^o|XsD*Owe_H$KV#=g|8rK9m+gubk8j3FZSP@t zIdehXzn>6s0Z|C1DcX&|Am=EuC~g`ywzka^o}HttqS8(3PO^RyB5&dx z=h`pI&81E1AD==HZ6JR}jV`wtsWpW|!>5TOic6yukR8r^-_r8SLJ#vU<`x!dM&htu zuw9PbFe__aeGGc&NQcxC$Q3-hn-$H__nCYOuf2fd?dopjD*LTl$NZ=u9?&c_GD`=P z;^!R?*~2F{q0Q(_teXbZ`qN-AVvk?EuI-jpv8(xGYaj8|>v8AkFmVOR`Y3z2*2&8^ z)D+6KG}fl=lIj9fzeLys8dxO7a=h0tfP5eC=9oHU>G$bl+`a;<53xS$${69^9^&b@ zdL}+fA_sy=*?qm2#~-{pk2U6*X!3cVKAnO zjh$Tzj@vKNmdm`MmTIb=zYCJ6-b2MNb=J8ro&AUJE61v@p}t}mx`S*P2oR_KxQyVRBiy~URPAy&Mvq=y-Sxa3T-RJ-(BL4 zQ(($lRgdB+?mw@XE!ED`eh7AtafK-K)da-IL_U?S0&l~&kFJt^x>KfPr_2a(Dm3do z4tMd737&s-fBsd$Cpr%eW;Y!1OA(fzoH%Tr^&6|voBBiak0_Z3+wtG)z{GI)BSQn_bKK_$J%x4 zJLW-KYrDx?5AWK;)(u5vhvo<6Y@C*pmu9V&7NS0Cvth^n7F9PeVjiI7o#`QQ0wcIt zcTO0+7xd1o2Jy))j3_&5dPqFAh36Jsr7OjY|EK+BIqupmmF0++kIs%ZpzD=)g!nne z==Yo<*aPNssw$(V70w28)AF~c!LWKD6YHgFGr@~O)hzqBCE~aI;+y;3oB{KUhSk{U z<{0G88+r-xfYC;`G=o0zkj_eaJMBH;x#a03-jOtv2W=9Xg49NwYm3yd)JDtY#%*b> z&(a)+fP4B!g@1hGU-vrS7ysPPHzLD_J~#_jmH!t`9b0znc-hhRaMFE4(Wjh$)4kK_ zx&2Su-^t7o$7#=-zU6;;GjWUP3&LG(X(<0&&Ch@NcZ~kWjmFhbOal)xZ+GuDk2jxT zOfTk1W#Ucc#Efnug+PD**7$fG@CPTZ^7cF(Vy!T4w^Zi)^Q}u=5=NhMf9`K7^BypCfM!MXsPo!E64mCq#*UR^;e0g|uj#t4TE1sd=) zRT-}t+>ipM&z39!#77!9MSfC*z>(fRqupC2+De_S0@YCRoN~~kWDZtBAz}%w@Fb8uaOWnU3FfA!~tngMP$=v(O^FK zqSMv|eM!-$6sw~pzT;xHHLSWHN?dh7sNJBds7>w-@N$VGi$c%#_E^fz;{LuiQ=%7P zPMLR4Mh5@u4w1uLOoSn%y;CRx>A_v)(%%UY)5vFT>Vk2U+IT(@9f}LKK-2eqG>VE; zX>I5e2m1YVO=lvJ0dBg)=!{CNCl*V&ML68;+6+yosLI7t{#G|QsS?OZY)Q@P1{jrhyo6+hFH!LSQI8bM44<09WA9O5+p4R%^x0X#l87?W+Laz==Q%x&uM@k*+i67SNk6LaMlPZ z13PV}R6;`gx@=tmgybGeNNp8;#P4DgiLMmF@}cN+L$+MDASre8nEJbA9z9 z9}0wv>!}wh1&Jo8&Xd(BtPwx|T4)9+xis-H{Px=cY&C-Eo5GLJzGN_v3fhGbNe^#f zMiL^f!}fH=c65Sw9$W+^^DuNI*W2j|o)BvWJ23I&sYKhkLr;wb1Ox#dxz^Z#mf);$ zH4cMkA9Z7i-n^B*qt!MAyfX;hC8OTaoaT#tF#CP;wrpILYSV#-h>c^Knr~?kO`w~V zU7as$K=M!g>te3;^C>srhEWS?G;tvAsOFQo;#E@OYpja?rzc38-lpz;rjv- zkAmBw93}7auA1Ud=<1go)lbK+3l7yKZd^rs@URB)!)09fg>{UAkGNy`JcEn&o~+i?1)7X zXn1kz#?27*SsAsl)&WfB<@SByv`ary52vCR+iTbAY^_bH2HO^84|Pd|HhmwWPi_+OQKK1m()M{20S z1<=YAgNq<(U1%mg_#(a(7Ih*4z^Dymh9}RexFBgfksE?-(ep{rEx?|TnW_vp6lGWI z9ny^7Ugm$Jxu(4ccQCLLzBrFFCyG|3?L{mJXOhW+9pTAXX5$FA@d1^)`v&ifie9Uu zG~vem?3H#A7$L-u51zH|c{E5=uwx8a@qyYniGB4Z7rhc;MCw7*iAk)wUo_KGOokej&Gn%vr^&M%x1Dj z%3Ciy2sOYJp<##S@7LVZuUcCC=u@=~ofaJ4equ4$79c?NT0avCZtSTqZGOSyOn5rC zdi}*Y)lYGJdDfmNZ_gMd6rr9=)3V?jj3N+CEi@BRSXc7}jEul8nRpOq(v`>s5gj*a z{~jEN`O5(+@0)$LynT*C#GVK9#$~#NRZ|X#fMQ|;HD{~xMPr}kfYT%edZ_8a-tG~B zqn;dJdFbi6C`+f^vC%Fr(A-hKeKwb7r;)ENn7$1aB@~inZd-sLV_+rr(TB}_m(CrR z=^b`$MuFkR+8OdCriLvW8IuK<$rU#(q4;x^oM-`LIa~vhvU)Bex@G=l;}SMviNeLm z1-rfOv(w4_D-lNxuygA#=)C=}7T+s36LID+)q^(P^KaAUjz)ba-YLP-^;L>v9Q+J^ zoolRvP-pcCnn`HkyO5 zqvsuO*hn0B=8F!)Rvs9K!@kd^jBeCNtGD&5N(*CAe6fO&*3K$9mi{4A?I)N02aZ=c zr}vpYCT8u}N{pb44V&-tcO4XyyuL7I^g?jK?!7wDMR=f)CMReF9w-{~5T7&wE^V^G z%50{P^#^v00hQOTH9u@NzHoXs?0V*@yew_6$SbTyYDcqvK)a8R6C&H~S zSt67k3A1&)$&?ys1{rhF7s<%*m%bwyaJKMJo%2KqmFF!D z3x=GpnIW&mF_TB#|dZ_bW#^* zRnhE@mDeLuMuC+ORXO7HN^4-lZ||lAFSroV@(R!Os1R+=)s=5Yymx~+168*R_lW2C zuU(yQh4dY%JP7fsU$uhCX6&Z}Dw}%>qrr0y_WpN>ek*Kak9wQ{+a-})2|S!1{J!K_ zHnu(Xb+lG1BT*G~dZ!ofN=iy-I{n|N(VQD`a_G>Z>=8R1KR-y8Z%1waD@e+oyo3MK zKNIC^TgX>)P%Frq(`oC?(mAms8xp?nf>|=-r}Z60=`kA=M>l#jL|=r*A{!N=)ARXU zMf9Oz22=~ zFX+?@Ek2kz>wd9ZAhhfEU!9_WRTSKA)p7Dfuk)|A=Y`B4@#J?)P=JsN9;wfZi3V*q z2|T;O;DYN^MWYps5%?;IKhNBFB7S)u!mKPSoLQ^5@UU4I9q*LRSr0!W3Yv{psnyKP zJf0U74H!0&d@JO8tEwuI@-sADz9M#=s3J5*4#%XM3LN|fR3fxfD*kKNPTXF2*3T_| zuF(cKGVE)teU5=`HojrA<^67T$WIo7gY_;{B=FGq3un4=4a_Wb{NdoJRHi~s(zaC_ zyCm5D)&ADOj?M+_Gy`X)fi1Z0QIPc7quX!U?zta6pL6Mt!Yo@oxGr2lwsEO_-BK)v z0hOqn9_Qv#S>+psX!JjuD2`pF!pl)}3JtH@tu-1*^82`T+JH2}|?2{uOPp;Y)6h)pYu+VF&uv%<#de4N4jt1sK>jW~3( z&6?zhQ9d|O7)BkpSS5~W4ssYxkrpS9d4(IWj#_m6UFHY@r*dGeIrbNN7$$n#7Zl?> zW%5JUvBWs6mPGjU4FW0gVY80-?xrFd7mU4Z^^6>V9w>RmOAf^AZ6<547c#&HAf$BB zr@U4hZ=)1lh#x;|b#cMOSc(*p9?C}?FaWNg#cN^+_eTAPs*q*i(DDx#;J-hYPzNin zo(Z%+SZ@e#4V^N!HVQ^|*yx!Wbfl&*nhq6b>zT0|Sj3(UX+B>Qi1QSEThE0wGtFjy z^KCBCNZusr`7b9$hXovFemF5jX#GXKb*yoSBAEQ(xh=2KvKAt-LD3I6(R)*o;q?&f z19q5!lCBEyrZO_bfo}xG5Ui$+U+ftw8l3heyk%pxcjpt|11>T`aI17)6A1xoWTUxcGM&Bu`?zuf+x!TIMW)RyDw8c2jW ztbTX5Ak>9tLh8e+m1SGt&ZBhxqIQ?=y_fmZ+h>wB{2a-v)2VtGYGBI&Rr%gV3wX_;9$w;y&*THhL_VV4R~Q_QDTHQNL|&GFwb5Ks5` zeF52jN9yT@nORcc~=P@MzJBP7$9l3PD?Fjvn zu>L}n-?0q{W{2*EnYcw5=j^cEIRkisGX3}yy%`c!T8~CXoOtkh{Ed_fQ0Zpdy#DjJ zg;^lto7P6B4!ghM5bO6&^r9Ci>z_)q$bpr_d9d7#ZFdH? zzEkh8Hgdpb#UKq?Oh;>4MiQaTF-f+i?;@qp|A}bXJEcvrh)e+1{*^=6O1j<|Bn`E8b;G&va0#5N4)3R4b8LA6E*S9TPj_+orlb?MYERW z{)__L73s&=t5&2IrwfJi!f-=Ug+loQknA=_>nm#8O zWNjr)dI{K&e*QelNywu^@@?C8Sb&xSMA0!?1&aPQyfvZ%w%CU$H%jy-7RT;TCSLJ) zE0L%_mx3RvRn{=$8RwqXC764MQmzQ?cGq619 zJPLcL{VR>t(OH3^6PZe9RpHWAciN|Q{M1fQ^DF_Q&|h}|n*5e|M*?3h#oAixP(!R3 z#{+wyjc;hnRBu}gEWGJvTEHXV@RAM!$#LxFyzRBa%PYlr0LgzW>wVE2 zFCJS^T4GLIL)b9*VbPIVw;>MtDTz}rIL^t>Xl};#$=P`-eSj8>AOnStSj6rfI_eEO z2D3Q>n_|zvu@A4P=G-{qkDw|^P;j8|<5SJyiNYol3VG`CC1~Seb{yt6+YE88&})Le zx3XyqH|&tw&7v56YjnAks|UZTN@9|z_-ExM~;2HpJ6~<%(mHE69jQ3)VVid4~Y>F zJengRtChfhjgW8=cp@_~tc=Z3A(Pwk@}gzs1@0rHW$wq+pVMFtb`css8|og?!y!fo zAGAnbUoDC`gvldV7(Sr_I-#WNHO)vfl?YW2;|amWS2wKRmIqxfKnn26Mh7^UqUb594Hczt8Xa4Y=_$cJ^D)|N<;GEvH7L=z+WU61*-XZFYL4e zmUtSI%LZ3uCo!ojGa@XCUqf5PY?V@h_*FPa{w$2)aI z!Y&LAM5dLg6rmRr+cCYc@B6`)d3ONDV}6h1pL!f!-(T*iQPS|ieHL7} z3EX;%(M6eh*DJ%u-RwU*v1pF$wxON6t=p5UaManz_kU^c&BJP3+yCJk8_zawGF8Y- zrZx&`+}k{5$WV${(IBLfp+P-+Ks4CftjUznB1sWVduuROhE{}1sc2Cut9kf+KC2Av z{XO14-s5yORjse9e`bzj$co!5DO29Nl~E7z`Zb6b~{9sMjuWou;=L|&?0 zEGhzZc1!&VMQb)$*4ekHISYz|{-K5W?O$3H?!JxB*TeC7G{!1brTha6ApHMx<}A)k z>nL=#1*w$~dqURiA3&AFHG?_M?=u((PFoiPhJE5wU7Egu>3Gbw*XE- z-9cd43vl0b;Bii)McX-M(AQ%ocMNlGzF)p~Met2{w-WUS;puQ(az2Z=b$wv1|x`Fp-|1iNJ<;xNO(Z8KfW(ek9V4 zUq8J24fMM^Cjk4=6U`eFKi7(91n)ZeYoPBq8C}Ud^cB5;<0!Dc_3i@5LZd>X$8QDE zY5SX#yG4MGI_la$DQX-V@Kv%6BIylmL^il7$QIi^LwOaA~s$ja`(D9;2a zGdIsiFGU))K(~7BJ9vz5_`+#XHeE;Gq zvC?QlI>e4?p*iDT14P8IV*30HoVx3^Ms!W13A%{jIZvVn;*u0wT4~Y>I}x3&#lCg` z(kHCh-LDrQ>xSzml)WOVywdk{i`QkO*E&A!x0UcVVl(j%ECse$Ki-eHqX)^A#>PE72B3r^FKJuzg%$xlvHxjk@q z0)%Ap=(kc4Y@o|_D^sIJB=?B22Hb8{cHGOsvcHy_J#hcRK2_&w<7WBG_Arz&SfEq_y$2-V7 zYNn0?pB}f7NR)`y`>Tec60R?3l3hxVH7>&fOhDsV!I@wL_VG#fnFyIOKTCT0k^z>q zr`urriZ1AfFS}$Kl~sH8Eq%5DPC1*o0?o$`(JjdK@w=u9eU2XmPlkR~{!b^Yj(5Kf zxXfulMk1y-`)-W%0BxtBlN%z2IsgwwA>rYk)x)BLNH;fC4W410Q_SH1jD4-d9Wdt+jN9kzP|kj zo8D7WZ||l-Ib6TZHohlI2@ta0+XsI=Z`?cY7JgJ82zHzYBAQlMA^CpbA7$92K%B8Z zbnZ5ZQt3ej*kEXe-_Oc;{UTSaL{Enl&EPBtSXA|dv$8lW7AoKDKF1V3Ne4YD4|jMe zQUbD+-#{REzxou-#7OTa-7pMb?d-|WGAkc1rQ|ZUhjb(2pm@`2;T>K<70!dE&J~?h zbhQxz=FzgaesTcM^yzxh{7?*6^2*wN7Ol#W~aM;TvVGTQl;R}Gh zPeQ;wxKG)ZbLPN2+DVj3dChA(tev5+sUQVXb}!=D>y252XHdc0OGf-A5IN-&ZCxQX zJ(f-u>uum{?a~)r_O@9qw7yo~8Z300pMYT5A4~dDSS&j1NeEhpGme3OW+09OXRj0s ztH9AhiJKTa(B{9>%=4U3HYFV0bh{^uW)7{OzS|D}WB16v1nTudqy$7J_Ubz{g9n?3 zGkzEFamV*?6AaVcoD)yOQ0aZ*K79J?baw`iD+;aoTL5|g0KS5&mkdZw#=ERSlB_&r zgv8-pAE}Jeh=Ph-9?%EpBf(v~465kVzqYoRq)+#Axsq%`d%kxxLmnCK;I9SA*(C)9 zk1;+9Qs9}E(@ws`p(`w986CW2kd;g(-?cI-eFq{Rp(^6YNXRTEg7sj$zXe@R077xt z8oZe>08*5sfKd8iEodEjh9}r8a)lxh;lX#`xsWoWAO*-}?z&9?_=!MAn)B{XPlJ@* zG-P}m9JuQJ^Ib5JGsh0S!_B#+4zUKeogBiS#Gv;ShdrF395mjUQyO-2N>a+?AWP6b z^sIV3(4Yx5Ac`Kyd}sRCJJXx_w`gz$=&5x?1ksBKtHDpUeKolSA;*p5^Z^=Z3YYOz&=HbMMry$#t|#L=Z! zx43rQBm|1qx|kgaH5f;~qB`)dhDgGJZgt%DeACU18zP@soPUt&xD6;tZ|qD5nd$@cHIV=L z69NzqgT~h~5yC6Hn3)MA7p=q>tQ*_nPVZnd`okCLU){&Y3p{in38-fHa$rU^?#sY& zr|av?G4F4V0^S8IrJ)sP?A(|}KxzI|X69MnO-f(`->z+`%_H%_J=&YO)jNt}&YT$% z33b{f+n$0DiTm8TVOG@E=j%f*F3uj9Q6JPz=s$k#EaaWy%uKSH5HfZIwxGJi*B~Oy z*aY;9hipvb(?NUpJ+42Ug$*sC22d+Tiu8U(BQxsrYc^Exx0!LNpN$mg{XGa5H!@cs z*ycfs^1f8N#S=q!sE<+e`FkBdVr-wx{F;=lzJV$-NANhP(%NB{w@f8l=uGzIsoJ3t6| zL{`Qu-@?vCr_Kf{3ljliO1quk;c_IV*Z^nd1$IYFohSY#dv^YZ$_!9(5}b64FM**) zSnkrLOVcGYy_A+-4m>n^#r4f=TtHpwJkbsCZ@MgW24p(nbks@$&S1=T77i2~O75YwR1M3SMW14-}^w{C+*|=NB*O(1*D#j^r9l z>^8ISqLLPHLg6)cKzlg1Upx7oyBw|V|1F*@99%eW*gj~$ViwH|!W|Cgr5)WJ!`eSIj-+SCY zt})69@WC{j*Xclv8A;6!NZ*HPwACvgli`Q=_{+OR%F^N}NgVTrv=61=sFkJk99#np|6{6M`~wi*ViSaW8eZxG=g#YO+IlgMFY_HFSVQRa(9^|=>S7w@b5<*jb9Xr~&S-*UV zJwOq%XBQ&3{?)ekH0)YMTQ(W0!w0VqmT-{+nel-*<+!<$`f8W+-}Yy52hez1PHb7D z%vBHUq*$_(I>^~c6G=k(G*Nz9`Jdfwasq#GpRoyt&)MSTl`7v`-_{t8Rk_Bs|1R7B z;M{Y?8TrM<(37LYaYO{-Q6f~bmrMTv(CfsPo*B8(*GO%eyCaUbOg?~?$Mh!M1G84N zU|_LYhG%BhOJ+Yvw$6v`EcD-2bHu&H`xy@ktx^<7HQHgTK#cl2Ol&MEhElo@Lda4R zt%|4SdB78j(|5G^^&W>gSHUTmD~6)Eo~$1kuHnN&TID2dc8iF*NeVA>`SmuWz$3|u zS$4Cv;7Q0F`2&045eEV2 zmq`71N`W}#O7nV-0n<2WRnqDEmCs#zemY~+OxF>=95QIikwRFbOLsYs`SvEhcdg!H!Mp{!O!NJ zY2d|J=rs0+Ec;YZYE72eqf~vyX=Fg>(>KjVc6cz{5+_^_8JLwbK+7nP=>GM%>K_2Y zaK1j!g(4&w8j?7`A(#AmSibvhgG5EdGua`VYgDa3+yb6EXnf;7wb)r=+p7;}gn@{k z;hfTM+lxgd6V^*TC#1|0mtaD*j{o`_g!B=c7^0tJb}2|zTt57Cp`0Aj1SjSI{$?uR z^~~#3ITqCtD0qiFDJZ;glY|c-T-X020QF}QVBglAde%=YQhg_>$!X39@`VrFJfS2p z``zsF277=1{F^PxlLLU?PW$d1-ie2dRSCT5#m96|I!JJ0RR$*sgLPYD-=QYsA;Ufq zJW&g;DzoKFIm_(boy!C#O*8YD3l~NXGw?fl_nm1W8QtgaKL`e&W~gL1NQHM_*v8dQ z1RC_%(*rh>T8zeVKExpVwi~IO5uGXqTp#GtVPS>)r*^qh`@#i$V>66%x=|qT`S_9H zI|6G#d>hNNQ;*2FI^@chv#)Qw7^)#pWBm9OtReiw|d zkMC*IW%7X1jbS9<0|GuKbON5UBB2Jkd_SCp?o01qWd7g(3 zt36o-E!Je(c5o*Y76Bs+4vM`f6(?5_Ld=e1l{kVWRh8x`I2&l@AB?^~@;7?y?mC3z zJ(&pM@`)ul1tMz$6Fm%`o3A&vV3Y}7^0OVH(5elXs2UQAWWz1bA*OH%(n1JdK(qj- zp=nSwz|m^q#OE8rC!^4z;Cv~rp~eVuy)l-QZ|6B8Apq>Ct643Na#ntT<$}KD|nRyJxO?&7p3B?vno`vaU4o5IG)U@yMfU!8!zQ)6uX;}bYE{ZZ|s#9 zS51%GVV7XG&7KPtlN)D`kp*BWPlYfX9Q`iY%9k z0RAW)F=Itp4pa;r2fUeE8We^?eA`>I;Aj=bwR>#?oD@l@^0#R5WocDR;7O7tW4F6= zL5jaJwOqh-4q0aD1H}g7pTYUkr~tDOWsesRt=fn&ue=ajAhrORKs%`MB;X7YorQI! zHHji9(B)q*%Kl?!e?`<9%}N|vOaLo#*1o4z)hY0wJ#?52BdVw|W%RQ>7zzSOD9|YL zY=$j4ks?UQu;_^@&Uit6eEjYW7gx`A4yZXMkw{7NCQ&w+B62Pu{Q72~&~zG{T#^su zwKE(bN^xLH2GfG1g2MYah{;QqAr~X>W+Z=gqcBhX11S7q>k+KHfhA9b_Hv*6{CtlX z%9v9wiCXnjQl&_4v@w-YP+nX(;mT{bhC(+HbcyW1ZOMPP5@kkh?68gjOQ9=*^MTjY zE}CajEL(h0+Lj)ZKDO3(q9G}3XjfsXk*>+jiZweNQV$gQ{amwPL?x!*d`D6dUVt}a zcULv|%#;?o-R?=OEnRP}V~QZKG&jEvr47wh5HO(x(a6F{XYj-n=h_r^aOaLjs%pm)5R#}edkYk{a*<{EAU3G692V_&Y$>GX8pdK<6E(az#_cdbO052El?49Qhh4_-jSK$zd+YuBnzQ$ zpoP5!#FZ{n-kf*}sT6P##3%KBUWKCbFtEon(`;Ja`0Up4ms?3u7Du`1^vMjXgDb9W z>c{dYJ-|E1%=y&{MN@LS{#8$3@&etFmY+tv%9j5!{$I+P-~Q$65&AY7-$tWp1isCL zZ!_V4-Awqo^PjK&g$3YK{x6^HRc`NIn(Rqm_dNcUb6-Pcjo^N#Ha>YW`nMnN&FMPm z_SKB}54|glkDmN<$-)!g9qx6o-;x0<4i9%aVWsTl@yopDv;VWV=VXgteE(J&EWR^; z#FR^wIkzUo-CtyB@!*E#j+JS5Rx~!GK7RI6=W9b~8=G`E6vH#$mv>Iny){-&WJNIMXx&P5;&Z z7J-`v;@jTTG!EZ(?WS?~md`YegYYedXc~zBiz&pJQwvA*nB)4rFu5P)=wY4Ze7_Ki zIi4tE9?qF@FcW{~LR~T0B@0FVH-KM$zv(;SpfVr@X-fCe-VcMzhr4J3di;qNStnHK zm)9QB$OYwNSKdf~3iO=KgM}5oD3-05jXq?9%q_n8W%G}mwUnHLUWr+ejgZzM^H5C- z#YRX^WdFZP_218RZ6!=zxn%kBnXaz&;{pRAfkv6~BYYxszjFb9!4siZK<$(N=O;oP zH+V8cx5ov-(eOylMB(5se40Dx5X^OL`={dM&8wkiUwSmPw&J}q%+rQm?aFpxCcQfPeiksntI$tG+FSrXl*jxDft*7`&<`gC32+ za^h5ptU8*C(so_<7wv=*GYdKkCp3-%QS)i$H@{=`>9CF;aj>REmm1T!(Rz8&KTF7N z3jegn`IaCxz4rf&3DO@GT=(&B-yrl*2_HE0nGmcR4wQK)8X$6h0y?{Wpo_Q%VC91~ z$2k^5EqxdfuR2z+lcaCR0>z3u5WgdirnEF!WhQK;)z#JeRz8ECQy;`4cwdYpmil_} z4e5$fdG97@o%|yCB~%oHVkBH3raqBK`P0U=orMuG_JIicWy@jc*C8nOJ3(KQGN%x=8%0shVR3mELN4tk zE`Tl`y`mL`v}NED9Q;^E3<@@rxlZkcoGMryqSG^!+MsL#Qa>9_ZUr%YN-AOm?lu)F57|u`;8A-dGlKlMICoc$Yy-H30S|oL!BtVjX<5T3G@-7#+(aYE zV~<{q=Z|_p>Dqno z&tY!w`v~#YtAPd_2TzNqksD1;r^-NNVo&=z_3)GQ?>m zsxK7QoB}S3YEd=JOZFmr>Lu$WkRAeH$OnK!jEh@^rcr9x$(Syk3460lp zAL)Wd>^Oi(55(5q!3uGIG^(&^lKyQ5aWAV@uvFB0)zxuVSC#&BRDkQx`!iXZSY)*S ze1SPx3Pf4I$|&%?5&_y!0a~Jn&oiPcd(|^lT(3UK5QIM=&%OtNVLEVvxp1KvEpu!* zgcpBxE2ee!n{s$K)2V@0 zrAY54$ug69^b>5p3rk8H(9t2fe>UOdl?6#8)@DAr*W{gJLt|t{?zK248%DMPNXs zMuhQ1px?GI@1yM?q+A3{9m41GV`8x!LrH7+C$C1P4$v@)8ET zvEBg!orh~y1Sj-wE7*_PjqkXfPgV)RVgL<0{Jr_CDwPFknm#W;JL+MfMQT7lbi4Nf znG*6$zHGd+C+~B@*$}_K*$k53V-~Ub^9cNz<`>pC8d8 zX^ZiM7zR-h78Vgb_!VH9G;DgW#&ZN;lN<$ru3Iw5f$Qt8h0W4&0fv@eRkH-{VGUGfEf$bBY#I5zRjKB}afG?d`U5|7^ zKaA1KjbU2-At3UZZz{3k#@>w@?oj zn{bVg0VW+=w_9knEKljwfNq05dU+&y%=mfOVU6Rn`g(bL%w9K7lyuH+_TmE@J6R=q zboVka-E(5rkPiP*uN^k>dd{v6Ug|cm;W}9E8(QJ2blf@6xwb;OG+)nEw_dZP_{zuy zDYB1k;!lpBNx;^lM|kQ4Cr3xeUyC(xyy|e;9Dqp%U;@l(&Rdw-Y{`H0209No<3E^UP4yG(U?3qjLk0j*S@p*(TJEOA$C z7s2&XDgy4XA59~;3mWg$-W>$>fdwN3 z{ec)f_uO*e%7#e5egnNC`pZ3A{ihs>;LcviN0nAXt=2;Zh-1N3H`mHIupao_J-o^3 z0nYOM_M-E_@;u2hH6WoJbk=7#-b0m=6_%8syEPK4Di zbs_D$7eMRo-V%HE>@Wni-pn+qO^gfnqAseb)7v09JF#5{ zv`E?5zji{s)h6v_0hY|PO@WiT{EksCgkCej}a0JdsxcrA2u=pmdqdKBsGnkk!e^j%7vv*&6*1~igV-A_M1 z-LZbs2iW%N6$*qLF z?tB6_;?u!ocwz5)sSCL#OoQZ#-*zl;awXB8xY!_;DDUN2ZlfD z*L^t7E3I{Gd$i_Un>VHm3h*bwo?-5aVvup1e@zgcC}fwO zk@Xt$Xh*_@&;_oVt=yA>kuuo9pDBrXQ(*l&%hOny9)->y-*lr{5e^hd^dq_s0c>+D zic&xeb?JP?#T%nTO3Kmk>*i3kn2tUdRoV(xgYc%^UB+?ERFFRlS>U{c2}Fe6%&s3h zWy_n*Mltts3bLM4zGJWgM)HKQJXTC(ba^BJvy0N+=5+j_eHb<3o%EjEIRm;e|IWi= z9Skb>p=>6p)gi7F>^O~cDni=TW7t`&IU{nf0i$<4=a-JBu*^zdkbrFIXP305asoEi zv%}vPdijiJ++B;rC+COsNom&b6yRKQ$cg{&5_>2GUjrz$3bOc>Z@~PQ6mI|rktTyA zlus@?ce+T2uZWg{;Sv?WN{P?Ruh+M8#=*!OP9L292@b@BQj2+%4r0X#>pRKiNi#7Y z1(l}xSX8_30^K}@qAb{@AoOZ0!E5T+Mti`rRaD9gQ++_aOK_mQBZcNQ?_sAMjwL%_ zBj-T0E-;kDmdov73U6$EuLNsMH=+?ox$@iI-p=^Pw<$k8Bl{}_`9^nXl+x%{LL#}q zgxfF+IIS`*t+!@dhWl+02LysgNtQ^^X3EV?DyId*`zY_2l?tHJwKyBOC`>?)y z=r%nAB9n*gs_xVC@^vEUUTB_u2@{AJr&(3dG(q3o649c^C=AuCWE!(jthz|2l4g3P zL29n5!xeek*L(imGP>ba9XG-*P-%FFc6td;Sc*cCJ&t?n&IMSA^9O#9BPgeo$O2yw zC3{)2a}s5?ol;-g-y2g3$psxtOFDZ#qsmp0k!@mM``G^Gn?38tT zI3wN$?yg-Hfn^_KnFV;dpT*>(wOxk|7xY(x;C9T&4Q$%S-y<|T@xt=Z{O)F+w^nYZ zP3XnS7f3_2!F(2DB<`@cDL;4dS!VA@>x>jNe=>SoC@2?JhFhld4>8 zftdLFJ$XJvC6BOJoII~V9H?@q6oLKq- zn;eDv=c%UaaaXY$@w(8O{f7n-yzct)CCWj{NmPt)Qen^#r)&q zT4ae;VIx$+DaE63EW%XP1KXVnh>)s7YuhuGsOwO_V{jl}@MdFqN{BTyRB~jD$>GNh zn3?m%J}}c{B9*&r2GK40>yKT-+XOc&wqj>B3w=g}_ zQgDc5g(Wu%RWTj<+LFI8=Z0|UC3y>Zyyv~$NT_0{E6zcb|r2nYj#{l?} z$vuJQ*QI?g47h``2CRw3m(Ig+&JgRO>D!Ft-=>3|jg%7{(+#w@0h6BqNV#8SW8)@F zEUyLT&RMs6e_k3&Z{(ycy$|tiG~a3=P$blV&hGH2H=YOV50etJ*nW^bm}8AswT7>1 zFkY3_Q5wO5u^__1#G??Feab%CWwYpD8npHf=Rm2I7&Cb_XYvF2Om=!O1AGxn zO;L5BQ7K;h;yKIoIQ#l4l_RKdrptp$nm$Xw3I>x0mfi>1{aAVc4L(HmaE9`3sIRq* z7%rr3LB}a9D{fHZ`30^cf%-R`gY2^7r!6G@OaU``zB&c>BKeP&&-A6B5m%-@k?cZL2 z%Hdqq&cebC@`x$I!0s-UWagvA`z^X)9{31CVf-jVXs#fmXPOLL^xZjb&<$-O(kT zHxRu(PmY5r6R^K!AlD_s4TPd1*t<~*rdu&{Jk_B#eK>Ko6U(C4U~0(^jqz)a!#)kB zKEvhtxj9&Goo_T^%ck+%&;V66wb05o!>|z_gAocnqKdEQc_RzyYX8U_OI0q_1hN+D zu|ophKRliMlWSEQVSfVR^zF8o3?t^T%1mb()YyHu7vm)7iBbu9l$ZzG<*%j3h^ITYM$@tBqpnE@M zSA&s9Zw~G}+GpaXG;+doynog0Dy+>wz1tjn&F+snpg8(4#WasW!G&fyulI-3eh2Kb zEw{5P7h&NqG*YT9-^J$(03TE3Nttxrk(Iqb5t=pdp&p$$bZeibTI7$#gt#3la?bh@ zxp9#Qd)t7yTZ>;PGKmFarr(ol7UF3(O`R(g4rZdoK}S>`Q+{m-*~lU*bUJ3Dc+qwE z6k(zJc-PD2ZZJpTVcz^h&R=vfnGC|@X}q?F7~MU4w!>~rgfnF+_+^Q-!-gr*ZofS6 zcs)?Q(OUsq)f0i}Qn>Iu26EVItr^p%y+A(6md35vWX!D&bIskdct-#GF)sfUXTex= zm;12(5h1BJj^bgcEaYjxB+M`O8&zg&vDI1Qez<}SpvUy|%DTBRh1gtsfyQmKISx7Z zQ61;Vu8yc8g3tamY*wvjwJYk%(O0)dy!8YgX1l_f7_R&bI_{ITU(`TW@&(Oc_2MGyThE8(S9N=YG_evx_qYcaFVI(kFGbyzjF>`>@h&4I$g zb2L={Q~+Y#nYCXO>Sp2Ks$^~gp3#z0w(;MTH`%doTj z>x0fjB2&vAC*!t5x4vN>dEv0Y*l8q*8&lpPcnFCe}(5Y{__&rdYYzdX>fT8~_XZsMm<#=x0ZiP#kU&lw=Wi7>;d zi8dL#8_i3z^|}c9JmbW_V%@Kdhos4-NKDeMa?knt(y`g#?%zE~dhWFMUU1>XDVddV zjrHv08yYmri1ldw<+l^D+xM%?a<=u4;CcHYTA&9N@{_m4mit5C@o{o2vX=_E)${&l zU9j7eKL7TaO-Pw&*p*?dti64+%X=HMxtfa_DEgLns)QLNs|cFS9?|=4Kfml*FX>Wd z6tRA(e*`qi#zCht!2VR-joiJXXc(tb>jd})+ta9k9@xF4=}GltKZlqR0+k039z6J@ zIu%aq7%AfjghfCWl#9d&yra>T@xybN!KN?Q3|@Fr@faLas6=;Ap*e6>v*;%O3`j){ zwkPtJR3jC1=k{9Lm!MPRjne3~l+3vL=W#)PXE&p%HuNEmNKjMs)nevm1^!b&%W>ha)$=Mm>WY|Lw4lov{$J`t|-1%gtOh=xO)m ze%gP2*E7Kcm48)5IuL-glYWX&^}{Ih>1n}paF zEyTU=wf;bsJ`{c~hEuRCaa?lW1GtZ6*(S}Kl6$Vj=XdLKcko}&E{0kHqWm|U){r>z1;V`dLP%V8;(l1jcPGe$`H;{J!`Fv zg65xL6*#)kzu0gdnpOOqIWO;9$^Wjtlpqiwgw~3C-)j8N3iNHTILvX9U=}mQ2Dl0jw5fs)2jLvZMmp*m z!&$?ii!kv@=Ss%lKzZ7G%1CNtQ7Xix>_8xk0W*-BI~=}-be>(NWGqY*OL|{_3K1t} z9Rd_fQlQlwv-HQ^1d=09uDPQ#Y14~7m}>JPELTDcQiW-)e*_eFhO>t3XDJ6^pg?Jd z(q=M7Cw!|dMfG6eYKPjU+@}&5XiDZw6?D6nxs>iR6NfLuc?q3ndpgO+s5K9Q*#ov# zA zXwKr4+{hD|=(3WAGypgHqsrzeS#M*LhZE%8*=9{&G9ZqHBKha_LPS71AEpP8imz^S zxY6fVteChY^b^NRs9stqt|Vj&;+UnURq96oqU;;4tCAV#=4Md*9*1*^Oq$mN7jW;( z^~)MPnjcQTn=_DJr-9r_518HYwDp`72JaCS`a%#w^KC7Y&hxaC$z`gpvA z>ILcP>0f5}>d&ieH`Iy(oKoSA8I)Ci8qZ~pDmn%x$!i}boVfBOs$?z=<$*qkI~MiD zF0)q%mypAvy*?$eS$7|Vgtt+o?yf-~q^aUe8VG~YU-2*`ei zR3`&np~)D3bG+D6j|DD+sE^F9EuuMUe`7=_%d@V{^+3>&iFGkSArsRr!_3W<=Q*Mx zk3!UO%}e7zoP8`!g-ehx!jD3tqMJM;TnEEOZj2^-WlKiyllp_&G~J&s=Y zjFh3?w|DjxTfCYulnFg$rqT7222uV<(S{YWz7F@tX}(qNrfF=|5C@D{ck1q>Si3b{ zWWdT#VMJIQiIUNF1cC`v=Q|`i{*E=kch9e>nd>~aedSe^Y_b^};PJ4A>Qpyfsm|ji z*(IZ`Uo{ImTe*B*kY_ePQ_Mq_)X**mn#P)8St!VfD_>x4iDGcZYWmF$=oYffF8@6G zvOLz!?ii0SyN`Cz*hgY<*$jzfn542KJ5Uy24O{o+SmD)!8)|mS@qYlAIK_D`cwvG~4Is(OUg!$D|t1%wrMj&J(rg{DfC!AVVj7rfFS zRXAP(2~~g5pD$Qt5XAs+U|fQ1Knf+^dq$1s>(Cw9f zqQ2xx)8*$-?4ycOVDaXRo4<+m+psL;iGCk-Ae1~o0zKhANF^K%YR(4Xl!`vY&XT6< z=;y8Z95SXunRzz0G-Y=^lg~yh+(w1=V(vBG9}E8+B%f|WlCmn<@GP0 zws@;4UoJPoy47{a^)MMlvUEE`*}WDAbd&_N&V{oJikXzi6g$|@evZ7ZhHE<=IZ}Q; zHrr&NWwS<37q3s3cJG1g%LlOI#351a=O#FfJ>qAJiVGy2(tZlm1JYr%(d7XEVIAVH%@ga>h(md0I|B9wKPV!NEH+AR9H-{#BoE<>g|Z0te!eIt-Y8D{&g zN2=u?p2ax0yT8*2v?3p#D1o@G8$%4yt&UF2x*j|INlh=~t{Ff+%cXg+ms{k=vcN$pS*i$QjtA~B*%UPtq34Qy z<;im;l@esC2mfrktPmwnj8vyKAg}+So>&0>9|MM>Q1ZaY25=7IX5|kvX#J($?t|$t ztkAL7=sm2JdZTzQet8oc&Gn)Sa%t0@@L5mFig6C#y3IBE)9gC_C4W(!?bPN2z}2VG zNypmrcZq9NHI*$1`l%E4O(9~+G}&xJL#(#+y{(%TyC2AK9%RPM{xm)GAAgy;LucCx z{h3?H-JEsRg#6+Svuk1^ zC^U`^Ye`akLuc7)jP?Md74I;YN1xP2XFz& zlxXDkL{u@4C)o082WCfM^J8Ov^opw^=+gY_lg9lYouxp4sM{3Sx;MpM{je{a-7jaZ zHO}b4c`uV5F>*uK;PLm1eIN)a$Bv_xJ801Q_3PybP->K!`{?un8hi`j`h_QoGjX`! zA&Fw;1w*7z-BU)gpeU7%S=k)rz4qxfHj_Q}|8k~n4zfgIl^5gbey?knGlU2zsA3;Q z?Vm-_PrlK4_%39UZtud9b0K@=Y;YyLQY*yv?WY)xov!%{&J3__RYl7HN_!q1b`3Sp zqegBNew|~#o%t^0B;|hga`*&_*hTdLEaYq6S)6Thpna!4`wzr6O;Y`xpU;}J{=(${ z96z;KHO4zvq-fjhar3vbqsO{)AFZt$a-%dI3SOUSL_AlJCRVT}&yTv}=k;p80Z9o< zlNMrmWKe(0PGnLhRH;PR>o7mPfoZx9RkBl!f@a0v9o5!~9g)hgv4Q)cm>zcSeV#Hz5rpZRMb6KQQLDU?Nn?#L1T0V40@or# z)_4g5(&Bl4UOJQbgoF#sP+#N&=S$uvvdFxwmMvZLjV$^C{VuL(o>XP2 zpO4etLu0yCP#q4blTM=gTV}BrFFq(TahGT2uyg+-qIUcateZSIxX(=@a;y_Thc@+G zHc&iPlx8(FuYklmUoP9vE}@%;j9DcHojw-`XO`mOG0!R%UWCjo1S$LA9mBT^u${n})s29H25g zY(PXf5?!g73YFzS?5gIUd3FtTZ|vE(jm#o97{_#c)IJXiefw-(r6!INs<4rGMmb{6 z1SBw8Z=8>eHttT#6xI~NkcTFO2m5bbp;)V}Ls3!;w5So!UN)8aixFm%#M$-5+wvd}JNaFIte?i^XhodDi=czX2fBX-pH8l-gQM< zclWN2wcN%YPvj^e6A9&)IhugbPmOp%_V@ZF5QC#4Bi$<2`d3`4f$ys)qQ7p_W2`!ZImM-zJ>TDo``ed){RDL z|3SrZ6wzZSh3s}*?n)Iz6l3-PhHGnwou%MRGIS=To)Jh02s|fRLjL*ZTu$o&WO)Ls zrm5QH^EgX*AFKrs#Y}4gWYUg1vyls!1JbD)tm6X6-wYH(gHdsSDmC|@Wi>p3kdMT$ zMc85((DRr#g*b$vnZp^rZ|sc`Je9IFx9p09B^DkHvA7$O*K?~RkpnCw|L}&UJJoOa z+|3!#lYF9i$JNiLWbzn~>@{_EHcBQ5I60e>n#EHQm^*Tp53C3+E>Nv)#hzHC(-Cr6 zh$cjoX(VVT$uK8rtPDhYoj)Xd<^$LSk?v#po{k|jw>Z@I(=B}7HV0_nZ0v!6|HK$) zc~9)?2Nik-pdqH)OKp{@<$KCH0?iQosq{I^B;2Jr`~xyr1-!x0unKgMha?X9-5NDG z#UpOP^NxwCn_tWE|JZ)&Hw{=CSo0(}*Ve7}d2%dTt>tp=6`G!1&v&>*uK={ptDk1j zNr}gQMOZeQPy{@J0xT0FEVZL+QYRlrm?BqtFMsz z>6|5;*@O+J6jnKI@1&?~c(b{PnRRUUl4{xSYAypCJ_hT#;{RF^u@@_8I*P{S`-zyx z=XQI1bxxyANf$eX&ZmF$+z+PR-WVc0uf$sNzaz#ZK+=%ge(fl)LP1?DT7M7Sd=ET+ti> zg*wxcl9K$|+MA|hk4TDLbeCU$69s<7oX6@x*2g8A#vfa9y}4vQE2m9!wY&N0gzu`C z)_(eX^Pf3t|74PX_b(l+AHMwvM(f+SaLVX^n+zO=ZF3qI{2zgy`=I~; diff --git a/tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png b/tuning logs/2025-02-25_02-59-27/plots/front_wheel_angle.png deleted file mode 100644 index 9b29424db8dc89e7b3a5da1115be8d5b3772c36a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 144089 zcmeFZ_dl2Y`v$JM(+~|r6s5AVvxUm2i0nO66e25|x=TYwQuZh!TlUB(g_My!5=F?! z-t&80jrZrifA~JW-#_4fJsx*=Uh;BX&*%9(&*MCfB_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!hhw?6 zZ^L(5s?|(MWh#wGLK!kOph0Os5~)a%GG-Q5YgLBOKxK%c0g05Ad1z%Qg(y_UZXua6 zkMZrtU28qv&-(rGe%toF@AhurmOs|x5!ZcQ=Wv|IuYy;i ziON!xb~HEch!4%pzXHTe+yfY#y20YK5 z@%LOHV`4#G#n!_XkuclnJI`h?TL9j#57ae8xMQ>4u(GC4p?;{GtC&Bs^sv;*6lOyt>Q)~;sohc%B0{1-h4TLbfMR;f52S4d82*n)~y9ASGE_QI;aQizQX`z%$wkD@Civ_p>0|Nm?C{J#CT*-VgQHZ~6&FJvqT5!5M^une?$;_j(?&a8| z10-tZq4nm?o7wbFU}VkX47nK*A>5ud=Ek+%uk6j6954a$w!OM!3BxnD%qeKw(vAd@ zqEbKAj)Kqi+%0qOW0~{dS_>lb66;y+q@}CN3rV-bu6>Wf#e0^Ye+2? zbUlBv90O}`yp+(AmDK@3ofC%T`tW}t%%}$cS2ca`kwU1qx3__Rplo~mpbo%oCr+Fo z0m{=woy|Mk*TMn5^s=}M#bwQw=kJqhoXrnQ1+CCL>6}+@IBkJ&L~QH|5{9h(+U^jU zn3(vgo?dcQ(KlI659{cJ1SqYpWd@taJs*DG+uPfDPGw{v0@N%0f96L5+b0F`?R-?_ zSM)454K10F?d$8iOJ6^v`p{XD2UWMT>y0WBXzSn7_h(|FDym-qe?ZX?SJSBI-Yal6d#HFBV zdyv$Unz7OTrh~%j_Z~l%fx|X8Yq+|D$@Gy}`Dq0pzx2+)A{=xbcq&xXypO~&A%P%~ zIaC%urzg4rg1NL4-U99hJ9Yb@?X6?Cc4Y5=c=-7|9%0(85C_mLfc3+>ezUi6h`p@c-;{uz8ur zLc?#PjCxAI`7F}!EQNVBM))TQig?VsfI)@BwKm0lDo7&?(iC`#f3;jmPKp(q{9cd`Q3ew*nf<{W$DIv z2X~W6A|Ft+&FADbxNz0(ML_}0NGIqwDhQxvXJMx>kuN?E6OtZF9mm!k3YhIoE5Y!X z4S170iFFRVugIK3W(6*hBe-rm#H>=Fgvq?3Z{Y=ZddYClozAG}Xp#1mrm$paa~dQ0 zQvz}j?hrq~XL3R9WWvwz!g7oIA#g{uCf1Y8>CjuIyUEnFN#we8@Jv}g^;z93fngl} z{lXeGH8oPOC6Q3b4K5Ho)l=fwnvibBfR zltpThUPPUQ2{A&R-x{^rSc9zebj7%2ruR`ZGq3XU@??<5B5&n{PdnEQ3|2m1@Mo3c za9cu2w|mtt`%@$JLjIPgTJ*6Kybk#*xei#7sIJqsW3A>E7JfosKW$gq3FG7`}XZHX}O?@N5G24rGAbXc(zHI8;tO$aj&bZm0Bh1 z7v8XSFAT@wL%Qjdf&16q&No^+auLZHBl7Mn5Q{%Q6x`ud>|z9-2Usi*A)n?}bNcmb zr0=<8t50f;d|ak7uT$Riy4@ZFhiW_dP*ImWD*!jxJvv6hQ@MaC< zCc}4%L?%ekr8QxoLBf3=CiF!?FY=X80xPhowK`4K+1Z&1;ZaZbuPp~8p~DL`RGM;_aUX0*GN7TS`rgsW zK6>=1C&~*nnPmR_Qd3hmxGO9whqQ@+fI#O<>0(tBZhD}!tTNi^|EZ z>2b(jsbU9XJ=9>75ScH+3GY_}0L;Mg!HiOs|8@1vq**&1;R+|ub6xHj4}9v$L*o zYRW~GhZeL1&Ib(tE%-%6S0@dojT@h)30{7FI07yhM&2zw``a(BijCMnc7XNuQC(lZ@If z&Zt*l6ny)7XN&0=cy&&B^>K!4xt=MhvP8nK+Hv{&Uo86YYxeiwU6ohm)O3B3^H2wB zYdKlpetKcSj=wt@cu0P{xJl3p@u8%8m%Rrfu4~X%7rgU*c$#OH{XJdl{EhFo)NTaN+)Rb?7vl{wm>Ms~0Pv}*As@+x+wE(ctbrg{UT;#m9 z!wQnV^)UHfK!W7^yN}d!g(u!v}JfF(ZY(9yPGe<*~+nv&qb?`9Xyu(wR86`B3+60pr#dlFnhJ+u(lsn1-K{ z`TY5_X0zhAM=o&RI$7!a(;4SCL5bXm^zF$%G<`k-dLgi7T{Ytl?B2~iL-ETx2%*U? ztN5;Y{&3Sj6K-sPn*hGqLK1rawCmf@Jh;C1Xn+j&T>B@SygA?`^5amP5&YiYVD8Ny z_VD2Yct#aO=u!Te{`aDW9+Cp|ed8Iy@7scr7Xd&#%?@&vl7j9dopa~TeKr`pX3ZMN zG=Jm99s%NiW47#t=I8 zYZ5@LNd9n^FXGOfrD7G|M>%=pKkv!83b_iBQ6?rjOv~5uEHJO+QQYK)Ni2cR_3yv` zz6+CuK!t2d*blwXu;hHLuOwY0PhY@RPEsjA{{Ku|w=<@+?P_*V%SlL&x(HkqYE>CKIYq0tlRLvYi=%FBEwvti}W57!K6}iFKV?> zIDFaPZ9HoLw?5H@ia7sz&k*>(%-dHDMez$C_5ZfH*^WEmJRor@-t%|22l~U%o49nK zn*QLGG2_BSwKIa>Ugw|xI)?mX_rL#)`(J%k|M*uk)`d&xL3utHDbx}^ZHWgnAs@NM z$*Z`|*h6~^mN#chJTDKA8t%DqOF0;M^M|J~76`SK^+&(;i2Q#VGA zv14Gg8;|1HHh$egeAa>;pIchU*<6;PjGNC9ZU;TMFK5;cRZGi`E%6obdyt5ovWknb zs{E}bgE4rpcpT$n@Ye~93+8=%jCFDEELY7($Vv}}OUZihY@Toa??123s5`-N@IU{L zzT5oohOz%Ev+?sW-=@*yf7mHM=jP|!{AiFc8~;ld=I6foxo>{%8`d6Ju<++$_<0!q zPaX!XWWNN zghhX`GDmD;zU#eHndrWRJ)C0q_Zl#G59i#sYt>%&=Ggr`HxJ#qr*UStw!yx@UDjp- z0_$e-%;uja%5gt-!%U7XHCb-mqep@jm;KQls>rV#K5z87or`;X)yB4Fp<2ObGdU0b zGdHYne*Wag`S>{-KWF3H4E)>)KX<~M_)p;E@uSEBt>KDBL#`h; zvd4Z;j#aIBHLl%-R93D>`Pc`5FEtcSe>c_Gx-|muQR~Ja)4UmOUw;1tqRcqi!YcrI zOAYz#siCYpxXmMsO~gQW>5^MQL5g-`RcEhdvNH_O5CQMIp%0!?(MG@FM7bz4~)8_)5Vp z``O?965d^1d7$oh>YQo>RIjA_=*aa{bOf#OMo+vPU?2Gb5qbXl>^p6JeLnQr-obDG z_K>7g*T<-sm}6c0QCy(^BiH)iDHDwZe9?hf(IPmGQ0lO&N-Wx%%g8-PhS3H=ij1CL)Oxa@4(h8f)%i zZ&BM($AJ&$vXRAp`-B)KoHu!YjI8dAxL+^#x+b^>Gi0f||vJly(-nw}D(gPJ?%Q432{bDYqPYhjZTfMK2*D^nH= z-D|2w3nM9gO)9nj^R--ka`w(!nb_CKb*HBoVHjRb)8#*2aD-@hJz${J#xPehpMMs( za^6UVvrZSP`7|}?Co4-WdaPfqpSYw(cmI9?UIVN3t|-6{j@V5;hT3!|#Cey7K}S*z z<>aL(;Tb~;(i#<4H83n9aBxYH;S-Si|+3>%oM=5 z=E_!0(8%CFGv zH9BXn`2t`&CT2R$!5*dCIgWfkj>e<<9LK8JHvtOXgx$ytnx!eXFwFULG`e0qoeu3= z<9tV07A6`9?@*LAE4}3itd7H{_7%y1F`)Jy^TY{YA0sd|2+Yv_r5fBFzfD4?R(HN6 zY#Kl)RUgt`TVcj!_Ns>|I@$b|#J0oUo?6b>$TeTZ&6Rr3KXC%;#~A&bpgdN&w7M36 zp8>$ct_-v#RVG>bL+SI+E&Z}rG1&YAV?z}=(gX(~$jSC1IkY(@CV`hJK6eg!2Cly> z-Sy$m3PT^2kqXBk49W zkRuIxgD2MEdV$C->IaKT@chtzfMmfXdhl8vKu?#Gz|}o*0^EVRVk=yKtxe5tA-VWw zcn(k;=cx_vyvP5;=SD|Gc?JguPiQ*FZ?hTQ8>A%kboblo@H^K1Hm%6~*fAq)JE!Mc zD@g_%EGREii;UiK=+pITn*NE~#nfp?!hKK!m~8vIkAjWR^9!_qQfE_4h-oW^%2_k% z$E7~lAHkTa1`^FuOwkp`Mk+!B_L2TE@XD3EH5CSz9gpBc2$gs>ef4&fO@Vjd3l*}; z9@mL#`EpAq09t*qBrxdswZTf8o(v-Oy7zB$ItUPD}uE};}H8; zgOrC)oG?ko*j7%3{4&S)w&D_-Rs?<@SA2TcRzvC6Uw~0tT7+6U6Z==G>q-T#%ek<# znr#7=fD1~x4txPXuhPA6tA>U#dZplS`kZe6yU5S_+y@G~VXnFWa#>sisg${3c@~== z0ScFSUb<+r;$`#r#>Zd`(fQ{thS=lcj+B&kSCDp%3FTOP;u*++LI9UVJJ{og`M^i$ zJz%?x81|+xJF13gO^`DP#F*CeLc0#MyS}j1A`^W$dZsrK9?Lp= z+{D##@j$QvvCyQHq>RhJ=fDV)x3>tSIUW=s#hMa80dL}S;2adgCd+eJX97UU2Z)Jw&tDSTJ4mY`#AUHs=etVm0p@E#mnWD)J2`}RnDf+ zB=bSfYsEkVw#Qz=UcWeidxN_P?ZvEO22a(8VK2<+d+HnRDfFrC=|Hrs?X_58~hI~+o!O*PRRH@Zd-HDY6UgieLye|*Hjd@|B#=((Ngiayug=$$QHCIFj1 z%f!UQ%haar9luT68~9Ui9G(SUEGD4@eRNP#JZ5g*a$Q$jTNOX(zVaQm^6kOdesF+< zAHa3U88mch)48Bz)9~^ABl*K0+9nTLV0Y-I!)o>x6{(Dk$e}ZP_m%HxkZ*s!?sb4n zKSy>EfK&UK=@&TbKh*3| zH$e4e!`-;O&_2-q^WfnfI6A+p^gD1co=pswWq54(5;UH%Iiwhs@As}X3`S{V_k`^w zuWI=i_ChcKzYthlj?^I6_o2teex_nYSm8o^vZn)hNuGbQp21l&zWKrB_ zctM`HxMcO+fUg63CgEMzb3ylI43EUY^l^;Yr;GW2_%Ox=nQ+<7yMZdJ5@Wo2xsUa- z_u}F-L$6+$bEhR-Y}r4b2vWz^5r}NZI`rMQJcaGW^uAv7vgi{(4o!Fm6U=+q-#{L&*QWJ-Z@Kgw z(^l8ECFBeGz`uD|qX)t`5dybovO6Uw7t7Xq?B4(`7xDg#2@8x7n z>9jY?s3i0!T&`(FfR0Dt3f!KW_SUt{{D2Q&PKv#u{>nqkfw><#pkfIwBsy9u_qsm3 zi#4yY6vj_(kGXO%oIZ3RpUs>T=*D1?E;rp zZ_c_E>HGI}*gu^nn}e}@z7G1|as*RvZ@KuOr)8uOVxQ=yp7v@5K(R*f+1MVTHU%Ql zO_!CRkm(0CuF;C(uh$ujuH2?+j2kmu8^3KY){3(>!+Ndd=f>BKP3G`k2lOH{J#*~l zg|pyuNwH?&!kHwE`f9LG0ta4)k7{=urvnM;#r7|F<_}-9&%)&Y2Eg{RqA5CzqQJ|T zJ^by9{r;5$Gvs z+MUa*s=cN(MZ7}OEKA>53eJ5=lnb^hwY*FKq}sU&>=Q3^qjWyk&$h#FJfIyK5E$4n za^)>}C5y`hY^rNv!stB1M5@6O&T9JhP$1r;T*#|Lq;k(;kD;L;(0R2Vs@Y#Qos|gi zM?=b7xNGx6-4Sz9c=e`B1ueI8oQySM&s;H&H^|ae{@BunE2_FK7F1tJ;IReXo12oq zm2j;F;@=d|OipG?0A$ClhYeQ+=#6irufo$4RHs|PS@898obWTPLdzHfm-~hpYs=&I z^C805T;h%~vjTqUK}U*AdD0oKueZxCDRSxgbn_oL9qR>l`d=x`U|bNwY;6yf0I<9a z?c|!475U3IUeoRliGiCS|02UIbAOyerAtQ!$#z6Hu+8NKCD_EpHas3=>VR+Gvc!dm zqgEgO%8}L+XKead(}q}mtGGf%wVs z6w%gNKc&96+7G)wAP%r+jsPCNMSK{&TQozP-m?ep%t$WfB3vfLi1(2I+21M+(rV8lmAX?J2wV?R)=e z7)+{JIJTU_mo;$nGF7tR2&j))unjwH7Jbe{fs;GIx0mRA32<9iusrZ%IZi-^MWWH7 zQ{lF!0KZ+61AH^znBdzla7c@pNTgInvs;nnnpoPyD>HgZa|VgfL4K*>Ljv#;5s4W@ zp}mBjnF2ys+8EP{&>Ce9T7x^(bh-83JCFdg@Bu6dRgEA>AIy1*#yhtmPFUbUl@P)VaC*JWw86?pq6#Xa+J zH3nS0x-4uSq8)(z?{4YOLK`e%do2wUk&r0XQ!NSx0(dTBUuF=zyWAyL4Y(2MD7d;K z!3I&36_hk_v_M$5YtNp?PuUIFPJS|A6a`}NVL8%hsd0YX_z5|+K-&wX4oBY&^F~5N z3H`VN9NQ`Dh3{HlRqI&+YM)15A}iQKOOCn$P&@cebx@K3Sv?cWhd* zTtvi+m^oQJN-%DjA`oQ7A2ybVzUj;mz&oGcb{pl+N{}rhQUfksb(|L>SCUmyH*u@y ztM#O`&4H{9kK_@qYAJEpnNS4c(KBBkNV8{0fT0X{^X+m+aER*(I^ zBh5NtIu?<50HK)w=qmTTd8RpFlI)h4CwmV3tbDk7T7!G)v1>_m;yj=1$_@v%tKdNk zBJgTe^ypwhamF8!&?=}nT)L`|2Ilq*rJkLNNY9oaS(RQDq(+Gu(&O=mLUKb}5tv~l z!6^h2SyahxhGtLXJovVdj)XFNjVSo>Pp2!yZgJpu8~8vJAIx><d zzXU5$?Cf-b`M6)-eNdoag?InSUFa~V0-X;oB;_>@X|Zi7d%N4X2zNRn7vOU*E>)C> zNPD5ou1KLDVq9WbQM1qgDZfuHCs^8iwE&tkFKnDH@|K!@pNG?Ux}l*I8rY6tTQD86 zhWEb=Q&KQQ2XjZX4PvpCkd}X&Y;CNnN-iqQ4gWbo=c9B6Mw{G6mubp31T5t__vjd+ zGOuoE3(Pq>>&H=hFp<+qOW8O>Y4voZej5#quj0-KnJZ^?a4NstgA`pe8EhN#b{7Bg zpFi~8{Q^}B_OAhz$=U2bxv=o(PyRC_KWF1VbHQNzoQ?mFW@ALcrJpxg=j%kPk=Oi6 zslQ1+aDTL6*O7grzef6uivJq%ayHM?3;SJW-A|nNmQSg!q_HtGho zMI0J%a6aS{yjGa|WZsbnJ%iOFVF`sN2FC^mdYqs9cKy-Qe%B(WxLQ{>Uv%@oxGP@& zq9kzri>dN2;NW`~Qm*Bg}E|$EgEH;OAgi6SD5-%zWDz+&}jWYa%ZEJWZ^5 z@c3zGz8#FkKP@n8A{P9-o4##`pSSk6dHCrkW7vkGI{B$9{ zAB>+a#J7p~|A7m!`NZvsQFEZN>4$V~Zg%#%spumQq1vg_rsYC_^i4&@CgiN?e;~X< zVlbq|q_*96lpT%ek?>3Q)lXk! zMRf|2!-V?Zc~od}3xPBAy~CDDW-L$`_a$opAk4_UEAjx3_N{yQRooPjz&$qr^xY!i2q?EfAaK+XMXCBA(=e~b#>VBdC+iNe50_E3;Fs)K zkmh$F;MT4cb4b%vFhyCf)ddC4{e6$};^h?;`B8xMA+_FfLT+;jzejjpbdQ<`sd-Pp z2zwufv*Ae?>)bf%##-9ie9?q{wK6ikB#q=brM@b9L#;;jugU4B&{rT26{V>oltmV^4GiL>!4qr3sCDkRFHhy+uJ?o@^xv>X)>Iq z)wWb|G^N1>ZD2_0ECIhqiGEVrp&b6vW5-fOrP*>ejGazv0tIhyYlbTekX{gqq$KHe z(!s&MHC2DQ)eA0*!J$w4oi_2E8f)OM-`+0y;D2& zyD|7~8(ZpCco<`VKbE|IKc9+sR49R%iu?KjKCW34vc~3o@tffw(Rl4x_46b1gvN)f zxGUSYzU3l0Mk<=2$zgm&6B`nbQ8z#8eh;JKDN_9`(LpGU$wAZS+O@~WN7^$lw-qTE z-rVV#mzPHfoYgWiB!LI?rt!xpAms=sA&=I5^S5nB9GoV6F z!Z?awvd4E8DRksu=bqYC%f1Ue6l2yh1fgv8`0-d> zM<@v|i7Fq8Fy%aj1O2t``G8X}p;1PHQy1&8dR~wm^ba}_k+ST)xFZVgohW(bE%I07 zhCrf);?So^-PMcOrj${!qijMpK~~WRD5oQ9Oxa{WL9a&vV7j9aMgv$W2Y4(a^bx8! zT!eyKK1%M!qa%aR<_^Bt0tm4eaA)~|S~5`__CfFJ^S?aN%FS-*-W@#~XPP8zXd`2+ zDo2XLPHnGY-zgsV?tbQ|16nf|_1U@jgUe^LE^{W5Dj%@|pdd>xUE%P>`Uudv^Muxsd(gvi>kVyTP3Gu}}{K7TC|RyHK_sswx1{#|*z?|JWGy z?YAc;2SXf=Xb_7!J92Xp2*wQ)pggg=di|MrQWZCqEYZMD&Z+D0NqhS| z)DUN$*>LD(ny*_{ms7O1_md}2NS~dWwP>?O;e&0x2s4fT<73t6^I}8Slg9H~d_e&t?Pk z=WCR(_jxD#D_z^5!Tf zmG}1U=NA7p5Lu6yDIOZPcSD{FEipEY!2S}=K*#x(cM3_nLX^|zo6J+U`%(|~5hP#K z(P6lP@j+$&YUvyh$ z_piuUv3=p(nA6K;v{y`0&po>};yM9-#H$QE(ZAHm)&t00_`W*9lRwPU@ zYMrL)?ZIQ_J^N7flo#plBSjVmU$k;4D5SlxyZ-c0({NRHRlnlIlOy%@Y^BdYPsS?t zv1to)WV8Qdr`M#vRn@-#!@4EH>~I_gf&|&8&!bKI zK1a4Yv`2+6Za(aM{yf*;igDjZ95oc9!;m{574))a5|72E>B?-gz|dY+CdEjPJafn) zCz~A>vCd9Me0;XT?gjRnrYQW^A35NULW_2`_MP>a<&|UKw(tuZkb|)^L+1sZ$So;~j^pB19bBsa&(sz-?)R$E%URE>Nxx>~wwFK=Ef zEGBj@r=NXO?d-*0egP5d_2YgZ`bfdo3$POj;jPoZwgVPqjiaUx4fqIfwy1J_6zGuE z$KEVQpKks&$KH5`hK3R<1`u~CaF}M3?i+q94?5E<;p1Um-p|#*P1U0TiVMM!PlW$a zi%m@U>+RoI0KAXK%jiAh>P`Z7u!9+(rRimvIk;3fqE4n}B%Gv@KGQyCoq z)=<6R>wI)gffT#9rzhYFVt#;Zo&FPGg%yC&x#vP!tsW9|VxKOL4JVqtWeahBg|3$ zG})?|==JJdo9XSmm;e+bj9YUsH_H2!*91{ENSA_y+>;04H$O1sYX9eo1X& zB>z%-s-K0mB;ecT#oSz6oJno=XzIe^jsX-=s=NuZ+vte0mc&}cErttcj0663EqVk5 z_OVoT|MSSGxg6O`k^$*A#!adJhx;rqRcQXp6Y`%nz?mXj!qNE3*6ck#X@H0n5Hn5P z(8PY07AXDV;X_wmuGS7EotdMBy0~k}zl}sspLszoga_cad$UXb506E{ASBHqxol}E zwgNwc(V)Rdo(nWX%bfUb%dxMy5^h|;_!Yg<9&19oks7AmsCc%&Qs3T}A+i!1wb)0n z)9@FMDSD5O>!o8V)hxz*Jpm6ElUh}Br4JpZAp=y5VRl-+&x=vvA!cm{LeeJT^0gpS}sDzBideY{`}E+00bgCcrJpw5Djee*AqE~)(4VsI?Ep+bsyL1~5^BJaM8cYtfRnk+pN&Ygjz<`?lR4bZ2d0~7mtxSiJOKA*13~H=8~bv9 zs4K87dC<)E`6XbHFxuP-rL{fQ&pQ(N*$HfqdV;3$8agfn4Ci9kl@^$=9N^OgmR&!& zn~>7P9Gx7RXfuejPLRa&usq732>eOID;R=@Oe6;$v|aE6SXP}zaJ2LdK>X@wmu0peExiB5lUO9h_3@* zKkG`O(Zv9yg!wQxn)Qil;`>uq)0A9;#5d6{0jAUX>_Pz^cA+29o~% zPnhb7H>Z9sujSY*UAEs6Tithic7w8a^02AtCe`CycVHH4;W&f2yF+`xfcAZ;YuEFO zXxPFv#ycb)3q%}`(j1+agl>z9^z%lWVoRNYBsrl|J-g7iT?Ku$<{^YzdG}W_Y8sg< z;7~;t%MbS5;oe_aX9%fG!tbBZvy1W)M4+_^O^l-4!gYt5c~~bOz<=|>cIhS!`hwY` z;)Uo#Qh%1u!jmovJ=5ztD_z)5_5y~1DwsLO=r*hW%kge^&Bff*#)-7o(IoFHkIZYj zzyLoy47l#S1)iZQJ2HWj%JUdEUiA3Vm@t^YT<4<3()6{TZk+yNd1z32zg?LQr}V}{M9ctYFwoq?&X(djx@Kvr6I;VYXd%)3 zQ^^oQ&WXJw0vUm*C*kn(OE%RG0JKsheM`JYKNP)<35G~F6Tu}Xx3KwQJF8)C7mek; zymZ=jFzE}$L4=RYxv+2}wLue08l^o*Ku=<|C*wcH4F!Rm=DF3Qm56AQhd$qXabKnE z1t4p)iSGOU_Z!a-OSwVRH4iAd&~jxS6F`y)x=9I<_b!E?w35S=FrC1o$+!IV8X^pwOry#Y{uu;2?{XBMABcX&f%W8Qv;Y91mM@q^GdLGtDfcOUp_hcIc@s=wI?2KK{@A~CQL$9P1 z6H%A1h}NBeeHDOd&s}wJUFgZuEeYT&EofQIi!95H)vSC7I7(m4i2nEEx74J4>$dT+VDNv0aod0BqOe)3CcYYvq7 zy9G2hvpEbgyyNP)-=NV8N&BKt?It9SqBc*Gi#WOp4MLxD{`N#wn2S7slb8wefZx4) zN3@qHBoJ_QPC(zXhh1^Nv^L0;t*Q#j^#zkiuYOU@HFN!|6ZInM~ z6@a^rpQG>YE?*3v5&n%49$JD46>h;j?1jrXr`WCU5%FbaKRr9m2Rg)es%&wzC2c-F zBZ>PY^U;TB6=vA;xlBwGiUp*4V4PHKFV?F>ISS$nSl|kC1iWA4emLNx z)#LUOOK68Yfj6H; z@$RKKpn-6b$6Q!CSkQYrhgN^wQ8tSW01(kcgP0s54C@9 zMo@0YdyOmap>K7L8t;DAJq|bFzO!Xv@S1ueXVm*CtX#T1cs5BMtU#~a2A3L8J@79I zB`VTH`tpM%cUS;7&|Tx4oxYa55l zu-hO-@16sQzE;Ay^?}shVeXn^+6BP?`K}-&xYRlK?loqmi^CvtFZc1n#@*$BZh8C&+fd!IoH>q?RvYPEiJ&$m-7-TG3F(54A0lr~Va`$T9}$ zLSJB1yp?V-bUc+yb?7iW)+RLi<=kF0|FG|6i(cMdoW!`g9#?2R<=Eq&iC<|g(%`-7I z%_lRwL#bCA^oE;nD_vxD-xp>r;dJwA?fcDwmgmWivh5+)|Me2x26OxAJ z@O}|rxxirH6dL1t5`z>iCYW%seL$fxWk&AKB{vcgy;iva?s^3OzBbLeh`q_)?JkGQ zduMCa$PlRWYG{V$)j|>xpo0YHXORd!`e*4eo$(KffX_FSOH`96$Zm5S>44GoZ2KZ+ z+_<{73!4`+N%VyrQuLCY-;v&}$?{xrYre&0MlIjeHat1w4pN00n0-Vll05wE0*TWY zKfknudXMBlnc&4+v%A-&zDh=KSgIL17YPDU>kP!^*5Ef>H7_QI6zjCr-~bww1Ws}r zZ8M41>E$2?02%OA&|hhRB@oUTgPRm4X25Fc8yy#4R|^woxwsjzI_V?YK5ED!ASG zq-lelbFv`CPkHE*O`CpL*Z7fWxVBkU!)QjKLOY7PqSm?P{$5NhdIZK+x!ipU+scJ_ zN!tvqi8sj=g{l zUN^`hEr5L@Vop4|#2#fZ^moS6K-!ihaAXUtls?6rgL<-}`iU zNhu z3HK>rO|xQJY0(MDf}k1Y*~DIn9jM3bNU6aH{`J8SXuX_6OWaNHVlzy2uder*AMAasZ^xm^(hOk+u{3lCNXd@ zsiX;yTNLPZRR+4nq9S7Y9Zko`%l-4_{G3ScUm?;tG1!tjiYiP93w#WFcN{nuNuQ&K)iUh zuZ9dK@xR(mMTLUr7-o|pJU$yOu~t}TNKMcad-_hNjPV7sQA{);*`jwD-aaYqaBfd* z!UqN^Ib$2p1;;=fF64hRVevB^LR zc<`R#zVN@t(N@J0$bz3vq8ujGWE!c3mgrH@9~PA1@p&V|QH&C@afm4>zjHC$QuyMt zSK2$}H^iDWYrQ)i%N1DP8uLD78f3D_u?kp2>2BhcfrR!yJT7_a9!ScN&`&x7P0lB^ zOpYv`Q&X&jFIsi4;^HD#BA^9n`=|@@TU#z)y{fy=_P8%iU2_$ygBMuFdyZ9)pP@LD zq8!d`Y({nGS9pL%xH?LZ-Wb5477p5G!8IZ-;u<1)Eo5x;#I*KQvukibes9G!B6irX zbm$Foh#MN;&L?LLiU|S9hFqq)Iz?@uX*wX>PkfUKvZN~fd9j1S>{GLaA$JDUcy)Bv zG(rxXYnQ8|gZ}uG=o;O9j>)mZ59-l;*1n+Edotth8*@SqNqHIk)S$k!Q#kY+`|EWSKLOS0y+~1 zIM1PE6k5YWeYl@G7b3j&m(1C zVPIQ0Cw|f6siSCKwSsiOl92;Rn$&Dzcy;UV6Q)H_W)p_tEk2!z=4ig2p7@T{U~#UJ z^GTe;7aHu4?E(QI&K1Iq1mU0kurh~UWnW>t?OVGOclR!*@#MfrG{kxHBZYR+4KNn@pm z)>{X2ly{`asYaK=?KlD_eZF=#1wk2%CE5p!h)vt}vOkfyx@|CqSXcBg!6j}PNPM^S z`~0_sR+9B5lJ7U`g78L=cKq$B>||7J9ggf=ynN4`c-a|aM-c3QCO(H;&X%djF8Bcl zw1%QuBvn^Ry`aS>+P*8sYIgnim_tabz>B~kNt~z$FJeC25fO7yV@7h~qkEoN#<)GU zrWlqqJw~oWuJM}j?wa%bTqOv1C@DMgX_HFKjpski41-}m6=eeI6Gik-VcB8I@Ga)< z%vTweL^JTchq{T)+KHW(hh)Q^FDu+1Q$keaZYVd_j7MfhpcZ^Wjr)Um-O{xi_4*`U zg!0@^3@SZkVbV;Wn^=6o68F9JOUe8kB-Vl+THxGxQA0QQzM@B^ejJR4z&RwhQEhT3 z=_{_ztXGzZ$vi#bBQ7F^#>wH)$lP|0bQfp>(JW93H#zoLCkC=^XunSA5)-NA4Q)sVZ`HB-GPTm(6IKy!@oqVqz0 z3vMP}_=N6USIS3kw;kBEu>5{tv#pqhKejA3jVeqh6EWfzy$ZOBj?nju1U|wn{MR36 z;^3wwsAb^fX&CTE`wa|)0B)Esl(g~0M#%$5Is9gH)C$tD3TT1t*EAnPX@xdr z<~ETNafBp-qf}b%j^KwniNa-7PNNHR%d+dUh1>=X6{I4eLfVAJBBD4Qf_y7S+v$NO6v@ucj~3bdOxlPV?YRV z0id2(VquI$I(Y8dIKG_)|Ks!P)H5iF>$^S#p>X89loTQuqCN zEEl_F9+EW2_d%8Chp!vUF)Bonx~<)~*snVI<97p-AER~n{jlf<$V#D}i1N;J`;P5p zIv}7^=CmM~5`f|v8dJi@(0y{tJk6rS(!cK0nOh_)n^ZL%2U9?jt^sSP$duC06HVGE z-+BZ9!r=3$XsuWnQgs1#1T(;mr4H!Xi&N~lnysi)Znlx>-M@dDIM~K;twA^!VJP?jh1b&@S&O; z#ANiD&REiVBD7b8AsbCOR1x~*X{SE^s#3;PQuOw%;tCr7)G}s+%-|_ zHe`FMKL<@Ve|6&ttMI9+x&oQXwEjECurm%6^dbhl>ax=nId;;+LHMMkx)1j&)jYIV z$&IRE6nfo!k+(HzDGs z%WBJ-^qfDDd9|Urxy859*2d0?`<8?99DMQVcfY;n?3MmiK6 z0+Oi#<%wW(TUbW1KD5s>r*UMWx}(xCM9wGWO0F6r%$4Ysd54zBtdtZbgE2cI)~Arg zw#G@ms-Hz=MwFBGGM#ZbL;@w(P~L$ozdyX!dv8)z#s-V6-MMw-MTmmHQGCbkDC-fa>52xd-S7ylS)I#hqlGOL&;t|Y~Hik{J zUE!LF92~K&24kos%mzwv#Z|-RJ;+QYqmYed!^#7lm{FZUC_~cuD+s3fg7ckFogpkt zaumr>MA5jP)_f;~gnb)I*`N;|CzfGzBa7^FN*U$p`|s}}iqx-K94hon7-}Fu+}Ko3 zJWudK7oUUHnb(oaPV2kv90li$^bkeN2~Y=ll@a@1Cv4hp={!oKA{s5S?;XTEExNe* z)`%U%ypHSoyYe1zwWefFPA?e-x&?6MBhp1|NGYqk>0gszTnUU~Ve4O5jb))8){oz$ zw#22ajLRAwvT0_!TC)3aogFSl(DXO%0cn%Um{X)vdpcZp21gT8dbE=YyE9OQ=majt zBEfRBgCqN68fH)M+Uv{RV4eroT0rI?*WPPNJ*EdBV+0vnUpD0Ptxt5&%y5Cq?#)8c%Q1zU#GA-cj{&h=|tOQ0U`9_^k?y$2t&&ttE|16e73kIl!G#&v5R=&kO44>>~XnVS?hGaRda$^zB0WfryQOrcx(z zn73nFknE#wjV3ioi>ZHXJ*sW*nc>E{^AsJeqTTnfZRe=H6xf^CLfw`=!U(qk3a5|v zhG3T<7ZS5=IMnK|UoQp*@;pEMux`$Wk=kYG7)yO5nIu~l^NuPb1SEKS_W_Fd7G-YQ zmQ+9>tQAa>mQf+b#snzKj}&$~-1^gmWe-}Cgbk^Z?j9e@#YL47DyCGfcDPf9M5G{+ zHI#@n##ok=lllswkdm>{BizSEcfr~K77ev7Di0z|2pm%3qU;FNWEN3ww{2)DVT-A& zFQp|O#$m}>Wx?9fzNEI#No$<@+XX1^c80x15#zMcb^04CN=q+1zVQfyM6g_~_h zi92x9GtulpO>dNM+WR2A#yAeGM(NgeHoU``r41mx!I0n8UXAI6KJr8|8x5%v zY|F0`!snr3g>*OXuXPBoSmIK^@0rwqC8JC=|I-gFG7n4XeOWQ)H2UZ-^TCYnrgyI4 z2m*63l%)RphvSce?2?Yix)TFc$2DAFQjDBh4*5ESr}=a0Sfc_8kM*D&_##NXU)9$N z4~7Ju{>ow-%j|^=gVV4VsySC~R(TQtiL~I8j>TtvZL=g*;Mu>9SY(bh0$;G<$)Jq8 zA&x!iv{Ten9ami7XM!XQ3r2waX#@h7%EWwNet7U}EZ}qz6t--_9@reia*)b?Cqzwi z>C%GqU*%_|&t>;`i8uhyiq!^ykV8*zv5ipMj%7B>5FDV7w;LB=3u@)?y;F2tC_*qq z<^2w#5xIlnFv8Yf`!N--CqwM^gLp_jK7YYKmsgi)J;18zRxN$os_bm%#I;oR@VUB zhkn{J>K5>&_&fqB%1saef#NYjZ`C8xsJT=3rF<=$EceW_wcTqCqThkvtc5wNpQ;+e-YYY6g!BS;GA|FuCFWdVF1(sdr=r+ZRb z31kjdw`b}P&(gz3a7|bWf<0nM2@$o4q^#)xL1a=5{;8DGTDApcm?0Ur9y)rYsFe%X zLF&Je^?|B;{)?=|V2p11?~b*iT;mS1KR8PDm;Zv<-{6i8Y91#V0x*LdWvY!TG*!O# z44_hN@MIR7AJ@8>z@Gra0mUIsQ43`VTH)Qz z3ufmBcnGNBEuxMi)0>dng4~#wsxbV}D>uE^2TcWg-b;ZxBNwR@&ZEfYoG};*!UzuL zlN31xb-MqJVr}&#&mB7@q1YT~!6*L(4bXo8y;bQ%n`-rlYhAt-vb2Kk>I@_9feBK72Hk9`cj=)Fs zW0~TMn{!|tBGJP{5-OEbHQ9nm#yYztNHFv08gS_vSgT!}Nv$fV-fT_yYZy6cxrJ<> zz$o)&Sc!~wUCqitp2+79kM6E6BY3U}7*Z~*jR3U@sS9BL8*N^WY!fTee8+a4ixQBi z;}x(4kZYnUJQPCh$Z(+mIg6zASvrEK?M>BWC(^Cc(UE>VUR#|oHVMTctIfEHH%7C! z>x&B_D`dP`y%a!h6p6Bgl>n+o?r#KtY-~@%eRwAHaI;D_JA({7?vnFJP(E5vr5{R@ zhD6a@;YsN!-~OPzjQi1SE<-N>jJw7D#L`Pzpv(fNSwaA>@oxPH{O{siE(#<0ec2%o!Tsh=1pOX zFKoFzhDYJANDaeM+Yhr3fiaKX4#>(iuNSe8|H1D>N?`xW9{Ybyp~)UI?Wp-ZHnw=Y zpUOmgUi*~iCZ3+$RW}yQUN1W*H)>LFp2imOgz1utOZJ8e%S;ZuCb~-8*r-(Itj47$ z2hV%mlFT#P780>efWCF{8UC1mt}-B0ABIqFEwo-WrpPo5TK*%T8aGVrX7kJe^-|CY2zl9}2waH*em| zc8=X+iz|YBCYIBiHFPh_yX>Csrb~;@2(oWUk0Wv->L9E9yzYysqCP@sVB}*QW6H!ku{39z`J0|-zyTNB;KHEFGhjspYlq5{SU@UD-V!z&>fJ#PV1X~mqwwx3yF`*{a&Rh{3E9&y2uBwXgxBjmw66cZ6kuAbF=OV*E5!HJHOh(eA z*}DrZf=EbOTUR%qG66ur6}=1)7&(%qVcc;9gO$d4JrUrspq0v3drZQ*0f+AwLCuXVCY#+fdki>ooaL@+^f z2NBem99OFdun&yWX7|Kwv#SO+Td>JiL!5RdJYHYQ{tC};zZSAbWkQ_0k}wn5KO$8T z8`sb5vFlCCKK||1`YI!B@X)FNJMIjOcU_Wd-{!o{mi@5ooO@!j(mHd*ruSHIWN>Mc z8-vY-BS0+1S-iCPx%}q?mY-`DDFyFSPTf2SBYY6VKE5^9p5`^*DuL-v^U_M9j~ zlTY5}@W^o1m%2#MYZouVjIqIvl3 z$Gx8Ceb;qa@Amt)cl);Y`~LWB&$hPpSoeM1*L9xfb)LtuAN#%^->>pRyxz&rLsUq) zsDP7QQRG9;)8=o>S!5L^dV!LG{1xnkM1IU65RSG0RISzeKlA%lh^26RjBK#qV<{m6 z{Uh!jE8klr^gkfeSQGEY_4A;wClvLnQTUhx$t>a!Q|^j{GmpX<((CW7eyBwS z6(T{CsGOMm@2V;{i+QQtJHkhcAF`Aus4IZ*R}6~zyGiUp5YrWM9*^>ps7AH>jwUcoRAO}OIQ zO4kJ16G$S3=wmyodv}2iuMAaiEdsP?nKhjK zCMlT-*NFcPKpnOPKLgfOy^9U=cDXDlkHg%L&7 z?~~`<+R*41`JF$|$EW}Ju$+)t^rFibjpHOYNk%YcxwiQ-R)8+F+meV9Kcz%zXO zuyQxRm)W+9+b)o0!4Z3;RsM6lKdv^Ap1>loFl!@Ti+S+IKS6Mn>Ahcwfa~=#a$Qu>=2)CSL?p6VSn2^ibK*|70oYlV>#M!`sNp@E zU$Tyh6ri;g4i7ACZJp!Odg4`@o6`v$P7L{nDC5f`eWC6^o38D_zM#jl{Wej$ThoL> zV1(YL<@uRTW;lwNe`D9Q8L?wb%5ai#fKYyQ$vdf5pU&`~yos4*-T8+E1z~sXO0KxW zTf7b&Xpj2pbIxGV8({w0;!|;CiXY+xS4TIl`ydqXlJrH0nv1-Os$Db|4Uxf_NDb&v z``VXmR0f9O_5Eb3x z7FQw_SB*+=n}$dpoi{AJWjJ$l4qqqX1LWyg62GfY9++-8?ncDERlSXyG6Qg}!_N)^ z@T6vk@^Tuhg8ir&)l{w!c<^vu(=9Y$qW%%1YhUjlhSJp-19ZI@srJUR#0mf6dT_wV z6GV`ab6NdW7)HgAu`Hr4t?sB($<_9K(CBNXehgR^vs-=@ly|DzkP|q(H)P+s-EQF; z50EU&KHNv?J*ie92(8*mB_mdcDo{B@cn$k)&|5u@DNop*6Y#8I!%Pst@EvNEDKvf0 zO=`5lFLnL$>h9IC+dCX>|IG!cWB*|BVUeuwL?deO3{^O_>Uu3g@DPNm;T;-q}+ z>4S9>#|67ojPQJ@4(>bHZ`AWDZ?PF~_g7_Q<$TYroD0ZuQnjnNJ>_Adz7@7@!wneo6zKsa*k<-e{N&fnj zsx8?o*<+tLMaWqPwo*l2g+J{DBW5C1VMfk1jR#>y%_9zx)dbEE)wqvk%2iPTT5+fE z+YMcZ979Pw+gif2*WKDs-2@Wd&&nq3q0(DT0UpRg2I1<>eX~9mtK%s`6^Q$&>0G1t z$fgIx8G(C_U&lek!k>P@L|#QTUuNk>Az0(#4A{7j4U88y|3%_K3 z_kKIl+75Ce)*sEqB3Xy1KLo{;qRq!MKNg`OqaRYr#b5>(?`f+-Ycx{%Xq=yx-qQ@h z3-!K@Q|AO|c_G*rU_LjMFZL-ffJjEcLha|XW7A#&{w zk9u6WPEohZkV0h_&#e5$7<;%K)yZXu2Z*X zUxP2Tszu%?dt8IPc}K4m$&%d$+@|%oZtqmV20q^Dph!f&j3{y0NZec~S>b!SKN(AD zbmZB|-SsDYON&gduWJn%=nQEM^X&>#`F`>555X{E!-bqxshaHqkD1PL-@fvQxf-4~ zs=XS*Lz^SJ(?)3=bfBKPU`I%IonU`=?KeThumrTl?J&in&!|o6vuPd?;jI(Z-LXJ? z?2S9ui{2nNY%Or|X>(6!k;)ln@N{OeFyYnKfPqO!{BWwXzT>E>7sgrNo9$=y8u2}m zDCI&=vmNbY@;-iM|Gd%=;Trk9jEhw8=ctB-h4DoFP#zkeKMyW_t)PlvEftR z_?NhV@A-oq52u=U`_>K4k~auWj3WmT@d^Xz?nHVh^eXTy|_o>8=Vl5#POY_!qkp-MJL`hL|3Rq$6Z+>V=Vz0~ZbSP16^ zGHnAyHTh`&7WNvmJB*CwqhGuJBDpI|MtK2d@BHGHDMf?=C=MrdhOxnw=y}35)8AEY z>DWAwv7l_vtRaZ=v0Lpxjf+}GfAEWBAMAQfgbwG-np~`IuzrbC-+|{H^*!Oakr$f1 z+W8G9cnJdqKOH5PN9*qAVOJ6p)u6Pk{7}UnlElRb#&GUZtM~WmNjPxPd+^Dp7^zcI z)ny_3!4;MypCoBeCjCKg%EL_2v))CyKB6Z<{te*xBE#$J$Ux@<#4GjK^g41eGxPJn z0h6>+?BRdAkK>aliexK70@thEaqN4rJA~+;x=ayMM9U3logh(0vHy@;vr(u5dR5o0 zkLuoFd9Y#^U4T$BpvCD=Y#rV_SU`rPahyiA*mAXmoE8d0*|;7&p~a-nb!(`h zyvhglm|Pro;jrIQtOY!P2y&5#@f~nl`YAvo%8Kc_T3`0O@U|D@r4>t~JstA;@#|yO z_#;Vu|LJSEf+4jBq_7Ds=LiYU1vi_zmYSn)7+>6jEo4-whj}u@9(P0TOINd})*8f(ve=5QJ z=scIdMcz}QhCDz)j4BoPWxoYXa0HVgiYm&c-uC27hq2EhAzT!=79l}9SY>+?`vU0` zfoRTec;42FH;~@*1@@P);&VU`alOLt_CW?BTlqVCToZ>0Im?jhf)MQsuhiqP@CDTl zlz+?}&fz@IBY8FvEb1*i6l+OO2d9zew+}2v6r6`{osz&-9&Yl8qu&QOW$xv}{)ON` zMCJfP8a|y154HhbAc=g*{`(Y^ctO*Y130tWs^=B z14>O1gw*+>ezQ7{A+5FcYKLGQQkuKsIxC& z9?YafBC;K@`@P3WKO5WwQ{L{y?#Gby5P3GCyt7oduM`D`5I?(?NU*1MlZ4pYr>2c? z&8(h|<`C4?8q(VpeZMNkX&Wu0&UQdi+^G#N{;N}&BvvbN?IJGyy8hM%1;cR&dH1CL z%(>W1T#PtWkaHU7zZ1D9DvF(IcJ@jw=sOahHGJwq#ZH=N?Fr={`I)}eZHwH#Xm`J5 zKa`y)u7X!RXsa?RB{_z{UdLi=?%VqW%T1fyvQ^nPSbR?;YYXL2AMOLoykD!(wcvh!GhCs<(~Ys=wnff4W);l-%HmJ> zisZ;0@^S4E5RMgsj%7OyNEh3pF&uR$Z4f3?;kP?ErxWpKsK`DJXE`5G3J5-c2a? zKncz@L(ve%fr!O5yE$_z7(f!1+DO#w?+nL5kwn$l%PUS)B-q*>{DR$HQDpJ^GwW*u zRSWIf&5?IFIurhYV>#rIF?%+GgRsQt-1;?Bv^g(}l9h`WFPcT&iiw#HM~jke9sK>n zyZ}^bc*fz(2LI@g+cMkZq|po19w#H09@OVC!zsr*{A!mpqyj9AIQ(o zuY=#sqNGRcRYk9zHVh7esY;~(ZpFO{(H5NL#JwX2HNnw@ujTbt(a@kgOrV1cnbl!O zR4saz+|x`orWAZ8JiQ;Ju)2Z%<^jov>t~(~K*nuXne=&HCMO2YivgG~b``r^4xIMt zh}ll>>CCfFhr3`(>Z@qH+^Sp*)DR6)$asG%A(D0izX^iK!e>$a8lMA{ljQoTZ=${K)sA&{BLJS#za$MT7sArO>C{oAW?dI(1mDWWBNECu<0MO^v9n7nTX#z#d zs(=CKWGd}}ykMhq=T?hG&uf^z?5NH5H-P!X;?8YUyllQt#ClYjL+o_e*9{&c)H0MT zoJre4r@_tGSo^U(^&@|2dy<^yw7%o|F5NqL6$uQzs^IlTZa>dl7#NjIhp|)o)|M z9T)z_nf&Mj_YuY_29OI6_OUvs*aJ|yAF^mbUA$BMz>7`3czLg228jUz=7hoI0d`LA zTsxML{RQW1u0}>{5IlGL$C8?5!-fs-vL99mHJ3<>HXHm&!4RyyasW8hMfHD-B39~A zuLJA{GxujYmB>zq#5PV3TUQ9c7oZp`u%BMMpYLRz;i)`xW-Yqx29v>&K=6!0>Q&TY z<2tspFD7P*^j7oK0r*njEfClcA`&KnKH1!oK|Oh4U4>&mp^2{&Y)ueZ>B`9wBsO8f z1d_)SrG&UNBw)e2dIDn3DXUiXa^TUmX_ z*mda3=uXEWCwJ-TO&hDeJkVZE-)KWkmuUe@hPZ`z%t}@;H=OB`e=tzXbWq;J z17ZinMAtrXS)Tpb?(ku$t0_W9&M{G((dSc zc=vYy5o-Ym5TV}-V{XUA^I4`kfIyRAM5h3=$MJ%no6RJO;aY`Ssd zgpd0lRCLS2gSDWHQ_t!h%Q#+vLzq$|l#7Dm6C5;7fI~`^{*me?*z^DoiQU#^|9a|F zrfL}J;t4q=9Xc`h)vLc$MkM#LSNF-i!dVt};Gha}h{Y(z_`TBp7LKHMo|*ozDeR3@ z0i08DoSDHSdnEqHoWTxFBYVZ={45^VaJ-&V6`6=f*eGis%ZCWsFg*YG&E{tdjb_g8 zLme{u=5N0Rz^g=^*zA6twJ~qHmu5P?Wv59~Hi_`0S`g>Y#CG5BbmB;+;~;j$ZHj~l zuZi}UP88@~Z|ig`ZJ5!ckjMc`3w7CvJ(@k@etU$H8wV` zyuR-HF<<+r(QtdD2#$RC#HLM~c61`!ewX*FC{r!4c|~9g#ZUIQmAbr{XLyk%oi%-0o+`*>_Dxi&?6oCe6NcE|C_2bHomu&*aJQmDoVO^!Y5 z;xZ374Pa|_Ao9miNzUq%n~FOHmf-!d;dQ02Z_5!`D(;QsS`gp~Jha#7 zr54pAG&xKm!|6;F57V2AwJ(8HD-{JGY%>5uX_su#R>0E|&I{R(6}pPiJVNpipcc}% zHteZOK*T`~&{Vu2i`=Y_>@TbYF@F|$L#BWTcm;6HU%!F&+w>a(og>_AthxM%mE(kJ zRGeX!BN$+$qm`Yr5Pl=zCGWDk5Mkt^=p=#IKy(QE?cNrfSeS9G6S&*U9tp-#8;}(?zEOJ0_y!>%MEmmddxZm!dcq6*De;!=O(;-56h&_t=#dvX7PBAaT^Qr6 z^92EJ&{TdmR+(Stz~#!<2ksZi$&r0wC!l@RFQ-<2+;7g=_NPo0;i=w~YAo1rM@l5# zBEP+dec|6{2-S>gOna1^v9>v;sBxr7!|7=DE~&R~7-L)fVw;2OkbU8*cI@0puYWjW z`vY;?)qdj#_Qu8V=A;Ov$e`ru#zl$;gS8!k!0b-3Jp0zxUNfJ-iMp7Yk-}N*PZb~j zfyX`ahgJwGKlD^cobtbRq239}NEB(emLzw;%LeS{nle;`mwA|KGf+p`MnD}(bs`GQ zNo_ml+h+F7zSC=3IwtF!XH#7A6_l`PLjP)7gx49N{>&E6oBS?-aUPkBDnHp5*S1$W zg}`@cdG^4VKK6Tja*c473d~w`CLqS6=yo%F*Yv$ad*eLo?#%rcPO{N)VaLC@0ROrz zy?eu$8Yf zd``|-fUSYTK(9c~!c!g36ea*9%3B7GC7zmyDO43ba+&YfeI#>qTm|ZSI{>5-E<$Oj z3`ejOojROpctTkfzD@K%n2ZJa%{iQAF}`~;9CUk8W)Gq^2kEr#coB#e2iPS{$k03mfIPDmPR9SYxizg0;4S!4r%{jH?%0aDG?ututpW}nsSWbq9 zhGbSjs!>h&GY|>#&_&KA&aDD)Na!(ey&xe1fn}KoqRQ`oym)LFCr_DzJ)el$!~myUmbyd8 zNxD@!Eqhdhgontm=^8@pWyfQjCxb>31TC!r)&}W%pMTtcbt$I!Blb-)I!0D6PN^!` z7mG|3S!;`_i8W?4<)A6@U5;;)*nlXrqSn8N-ZS@`)ZIfZ$(OqUXv=^J zBPd=0SpBNDfc^LiYD_O+hg|5%)cdQ>SNhmDk#{Tkm}BI(XZE${*Cn#Q(sERP2+#iI z5YJ?_Z;1aYC(hrwlAeux`{OJWyT7wPUMxIq@mq6i3aW=nJL}OWkquJ6m4XG5?2qo9 z-YQh{0H7VtQpC|zyCM1%2?vIZnz;5u3H#$y zw-96;!tgthg^Qwe9$?{^It>t-Sq+zgd2smzCSLiHu~RPzy(tn|PGWQ5=&i&wJ8+a{CyUrGaajkN?*Ci^Ad?C&5g??)mL-JdhxEx(-B zo!4;Ms*M!U1uf!`%~8+AENcUcGWfE*OvoRq8Cs5*)%3@kT%PT`K6C zity~uo;gEi^xKg&2{h55oXhfi>oueveor=wvG}F*<9^83r}V?%J&!UY8cacJ0h7gD z*QVIA=dUI<4sZVf2P|`9QDu{Z7*#cJ=FWk0!8)f`$!5!vh08||%EUYAf_+#}0fx*i z7%{3YHo8qGRoRDr%ggnNSj5zTg>0@#n1V_cabsy}E;tR2pED~0At$^B$O}W@07j<3 zTw zw0@y#9YSn30s9DTZ-P(+Uoi1o+{O;Gnqy^q8!;0_%}dyGX4i_``!dck0cV6#BXS!i z|CUzl{pr=wPFCT^e$j|~Sv^)8nypuu0D;Q@S)LT^8E>U3gJmp+`J zLD+>HM|G?3uX9>9wdS=h7;|-DnZ3KHU4;*F&ul7rpkbTqMDNHv46-RE zqKCMe?S#)z7Elh5dnyz0zo|+Oyz*vhSAI-PFj;H<+0AbE{aIdNw z_;(7lV|8aYZS^Pl<7_nPc?Ivc#?gbyZA-(C*!wzBnIFnJfsfd~*8sc&Uk56($3HrC z7=j{X$dfgyoR@h)^FrMLG#hVTy@Gq+;xyRtLw(Kb1}X`XW6)2FKK)J@xnP)Kv7pw| z#h#VNV}xq7?Xl45JQ2v^AvThru3+Se!j8WRY{kyUnO2%3v*7 z_JvZXF;#&?0wg&N;epg(iVRAj-@iqZTk%Jhs3_G+s{dqv^CUF6gZF`Uo~sLcc;dVh zXV3+95eE7@A5KU~+Nv>%6I&uGme@>W3~-!?=}k6Rg0&3w+RpR|?Eaj*o#PnCB?oa) zvdy42Q-Ufu;gI1DNfi@^IDRnO#=fOc_~RU12)7H=s^rLNmAp`~CVUetIDpSe8KD~S zcmNNrvIDKMg1noozEW^%5L3kZ0rzI!jb-{rR3NOZ1u4uG#*4ZnC!|IMS1AE@8qCgE zYhv#lxI8qv6|h3>`5nRj)YE|yO0pWbf*<%n04a^@2UPxid~z)+6e{1?L&3a5o;6lf z6x;3z2%Htc0hCqV6d#D?tPQs6SgH~r63@dvEeSwJ<=c6c=R`0>IOtD3Gbj@MxPKuP z6kt6Q5WnwsUOWT5s(t051*7n3P^LQUiPh3Rkh{qU1;U>(D#WkN%j zi^NSzpgyO5I~0-a=+uzA^5DTjGMW%blIXvZ=>RFPY%ZqkIuAnvOXo*}$?!t6>2?Ag zD_f4B21{uN%oVet=AMLlY%l@b7&!i@@wQ={3aQsiSZ9kKLRM8r?hPQ?K8L@hoIS_ z55ISk!h~F?$fMIqr*Ty+n<5;#f|)q(3ox@l>nk`Vseai693M8|``~vW7nZl%j6`~5!ZNA+8n~!P z*mr=bKM%VsO)Gp#7Ev7rlqZ4ZB3g^o2{=sn40)H?d|m{gft;xJ9SEFb$eor|n3hH; zeh9-|RCf`s9onE&iv#L?CH`3ptr7%-2uHvtDUNhS*f2PLys7dO%0@9-n5yx+5%SaP z+7Ef=BE(3c2a3QWrCxaxiK&K8Bs(p8K#83XxoPpu3kg5m!W!JdO}Gogo#m`c!7oE) zCQ^Hgz39La^g0c%9cA5}g>D(AT?FQ4)D!4xyW?d0#)Hhb2C2P@%Ick4`#zO==ABW5cv8~JA+3aNLk2#TQU8s z1H4O-U!HO)ARZzZTa}GlNlzjfiA^(2&<63PBIh|kmCiaj1(i)IqT5)ylFk75g>m|6KIdn_6kT1ihW;qV>}TIz1)^g_8m`W+<14Jk6v(+h->VA--;!U)lvDI3}^e+ zn>Us@CUOB>GX%=NKk@*rkL-;Lb{CNfOuce%={9fZrsttWbVU2J<22Db`p~wM*4ew; z)>w<=TW7Igz4||280zTUZaPA6$UWU%MAeUA&04=e`+Ef&?MT!{uVURrO#AzXPDwh} zcy&p?eY)M4^X3HLWK(zyyEN4@KrbI2ek(|7hMnkzu#D8NxZ&jsFFF2R4dp9Eu=}bz zC}Kjtq1ZnC1xv=Wglb_#= zM!mo(eGL4M0>8&(By$b`syQrMN}7ZnePoodwWpc9d78jod2Bxr1AasR`O90LE^-U| zoSqKWBxxX4e7?Xr48_J{?fX%@yTco+rqF%>IgR3u^y@=-FnPQ%FVKA5x^a}(R(Ch! zy(sx@q&r8LAjKY3nLW`ONsh3>c3k^U26%T^c} zJ+ZlO7FV|7_{a6(zDmp#m&F5B)L3AEdJKFO^cdh%kAbfa_8Crzj%NcD=kzU!gw445 ze9Qz7Sk%tj=zp%2RACeTu&@}#G$j?4AncV3Ql?i%96jj}Q$K8$ZBxmsj&s?nOU4y! zxwo)v(+zpKjV22ww{|tw%M52$&LW@qdVx>86Irl#34G$6jCwLkVy#hjH?2S2?iO_7MdQm0PREB# z>7sdq{bKmtYHaW}7p@}zoYYiNKkL_XEnoKaRfppGJ*drGh4N!tpZ%Ua+o^?JlgZ^X z`ue{WFZ<6c7hk#FXH_S+asB%BA4D0Y-_4+Ic;x}&$)u(@3k{PpU5lu_uHs8qySt_O zIB{Rhd7{|a?1ukRr1G(J+_ET@w{M2C8D49{uqgGgKjeB~S50_!D$WG^b;7ffiTLdM z?sRU%k#p@({9uRaR9k~8;U*Y(5*{KW6e=BJ0bkmk)4KN^We6ksK8SO{0O2(@I|aLi zHPOVfFa@#G`h$6R55_`LRlGwCwXi)&Clyspu$!uug*Wko)?6<2`-BI>UyPJFSMc2v z@6%TY1POlRApX~sK#KInrpV&{o(Z(Idit7QT<~}82Ty#?`({arThyP+LxdSI%M`BB ze)|_%eGrYV*p+5w-6H-y1#RA>LX#O?N6g5DxG`cLj z?qBnBQh!-{zsIc2DL1R75-JmSkGJl5T|Q#&1m>g~+WOt4ejC+YXua`H(0U_-T5r6o zEc4u+?3x8+U3o(XuXxLCJ&D{!USBRc5ZW41)d3KHs5|g6M)=-Y&!Dms#mOP32 z4$?9%Ps}d1O>%?5`;~`9zr*T2@O$o$M*|HCAghr&!fI*QKWwbpPzY{Vz<`D;YipG- z%~d^lud2h7)FiVc8ALetFMNJ@7YsKroyad|ejB!SELgFG#1j`z(oz+>1@SA|)c+K0 z&&b1MCNDbp%wizsH2?wCvV=>@68FASt0~F*)<5hc<0ddNXl8lYfOoipx={_`fmi;9 zJYK51GZENKYEoIya={^fZ^P50mYHeXL+^az%x{dIBN@m|YC_rIsr`W9u+gdXIvVN_ zPhcz(jJ7gg7}B@Wc4b-m%8i@<{dMFy`Sw))`?v&i+V=Js)W7fah3^4k7Dx-}Uq>fG zkb@;SsQ;_OZm&=cot_|^wLSMFkPt>4_}O)XvP3IvJrR$8En8GsZRGvKej^A3s6WIN zWa*>JHpQ8rO)hRA3Unuo{-tgwqmdh-k`KQX9wp-Vq$Uu}3M>RZzB_a(_Zs!3-{Bsc z6!hpLCL<>0q;hiAIrLEn8BXAL0s|-g`Q+$9ge|tWbzyZwNLX72)r81krtTuq(2QO$ z;>MKX6jN3lK8wawk5}`Nk5Ad*4RG|($8cpT4-jzls2hjD{*Chv*a8_K=n6kO32;<=r-;rg5R$I+3l&+W0H%tKxpXisFJh;L7mDJKIv z5l@VF$>q&~^7ps-5Lo)=07{U&-GSbee_I`p3E`eC>=n{ zDyVt@*1u1?o1MYvP8f2^;v!0)DR4Hbg@kjja{+ABq=_G1h0O|4YhAyt7~WCJK2RPH z3~Y*r*D@k2hZohOe@J+DT>%B-o z1rIS3)%Y!-m`b}on@8nT>Q$i{9|sW(0cJ$qQ8v5%IOQO?0WJ_hse9C)iw3tAxp6$P zqjL|CR2TkTs>A>%BE^v=>9Y{)cK~_M*@1f)jiY#BNA(g2z)QDr5h&ER!aURfp4q# zFPsb_EY)jCGe@u(T#;{3U`_UJ)cz3yc0aPoJmK*LHDed_iEC&aHux@Zi#&3R!cZT~ zJwOCx;A%Rv@xD>Fj_pz2?fzuK1i*}dH9-?_CGkUA`X;oAuAbzMH1qz0M?RoFRGlc-uVFF+(q<1qy9b>?slYL zij<&bV+#q)W~YC9P6prl*;LwX|uHP+6;K`8{gD zOL;HhV{NZ(;rAr)_d-bnz~K!7P#~4#ze_KoLzg@%UhDwsSG3FACMEPpaOxN zy^fOn-217{FH8-VgU{ad#uXw6t&dCg9e|7+ma=!T#1|3JuT_yi%2Q}kscEbv4)%g4 zkt!wBcZP5=D&J^Tl1*YOFoYbaEnJgqcl>Z;tpl&pI;O-n^|TD!88ghYE@uACB#`}Hb%@=EfQq3!8?6EH>uv~L|h3%E>3z{D_9F~q(RyWNvv|sgnUg)?*hs%FD z5x?!-xSWv^sT&-Jq>bHta#0jtw!hG&s3IX?Uwg!^j@I*9e|A0ON9jbBA0LQn6K9ft zMgq}#eUA4G&r80IPBw&(o`8k&%(6SyvSck@2ikoA`BPGJJ(R=eG_IjC7+Pj0F5IGN zv|ebgfxsdh_-PIi5>cG~lGiPu|Iq)Xwlk>JU4A_N;2PSRwYxuD6|}?#J1YOe!2 zN8M_}yprIApw^>fR2rdl2v25eZEgMaf@TIWn6Y=8f0-A&2+4xW%Z;0IHg2-o_{B6J zMm2+7_-VaqkvjB)A2kNh-1ly!eq!+69w0NsrP)%;_wyt7Me<=1O*P%8Po4z%pw_bf zELUI(T}fdJ-%InH`xnM`Hs}r<0uSZ(n$mQMzMnuyd9LPgzXJgOnV;oYUu6OenFw3R zYFbfn(9iBEajNH&v=>%{Pqlw0w!nz^JLdO)%RbHi+S4oLcxS6;al{Kz8j`PZVDg z82T(UDuw$OiA4bX%qiWF3WDN@cnuAWFn7*a1Q_9Y+Ug6m6bEc*|J`*yhB{Y>TS~AI z1V(xQMl8_aSUG!RlbjZL%>k}HGg5pIP>ozrpr z|Kqq|#s`-Vbmr-va}Q0rKY`h_Y12R6=Z%<{m>Lhf1pbPv}0>x4u5{t=>-@ z${KK<+&HFT66*KrHysG7pvTJ1&BdVDsu+e+HR%Gn68`;9^kzIC^<8$oq+ob$w`5RI z(5{P0<Y*CdIOFF6K`SDRQwoNU`tahNbLTEPnj|m)O5!R#2UIQ; zs~d){EL9V{0kH9@u<3a}$9EDGp8q=MAGAa=1=@6<3}8!;6i9*{FC z_4E6bDJqJMQ_!n=mMaQ|#67NP{Kj81tQUTiNwZuzPirY$Bi#RW&cMBw=JjGVi@v1D z6TRvAq33ErbfiV}hd1M`ne~xfK422Z2ssO(O6pBNE>}IqSCx;Pbu2|KXrOU-XPZ}( z1wR0lse3PHT`2WcL@zxYL|dQKvwuFiZy0YRZM06_O%_^;pOZ#8p^hO-#UQW(Qmq0I>WZa>@mts6F+l@jyCW^6ikDE%)WH>fTRf9G4;EAd}IG&g8Ws4}q$x2vzs>#G?JTjSo4SlB=iP-o1f1 z4w3`BRm)*fL{Sjz2tK#e|9x;6=FADEa~YyHdGwl{3}nAh%RhOSNJJ{U($H3gHl+p) z^M0dxK48IQ53~H@y8M02x(|`P>yK5w4#$KLF+;X*Is1M-v^+TL$*WsJm>3lbkrH@q`&RjNL(RFK zqwo0TW_l47`M3LOhU)tHcHi(tF`O;RiGBuKqDO!uCKIQLnu-iwR^wMSvGa(raAD@1 zxE2l9W-1?1hzw3k+@)$Z&y^Rf$MlL?q1U3|oP~+|_YY9&#*W1W`ugS`H68?$3W0tJ zkV&n{z&Dc4X_dfu}w7t$3#OD0$c89@E95%~7MOFxmnyX{6D? zgjc{Dz`Ae~`z4On|F@NoEcVR1P`-46-!z%>_Q}*VLcO-{W)$fv0OQqK4}7=Yf%l`; zX`tPSXohEdI8&o^dHhoyJ={Rul99LA4o`G(;6TPkT8+_%o-Ol*#|$=K}+Y^p@#^HlWwrj+vuy~7>Oll`c3xBCB?;KDaR#54UCVH`aZb9p(e0Ob1M58@GsQ$c!0Ws z%U?Or0vC>O-yWCR8iD8yq0uXt={?dBVml=0HI&3v4U#q?1`)YAlRqzQ7dT9?fh!p9 zTP%9&jeS>F3MjB+5yiPa;#(s9RZ~|NZ<@e?Ze$ zSCanp@MU;s0$j5E*1-POS{dP*t8=mK!L2f5EEZG+STh>k1tG3&@^5w=AU|%b+I_XP z3WhkJC_bx2rm@_UZAQe<7>pgG-J<7(+$<38Lp!flpS#iPQ#>OpXYp`%sI)7ZReU{> zbd|h%wfTkZk2f)f5a>>@6J0fF*%Sf~a2lGO|DFnJg=j(<|)8-y;13J{L$zG!38XH=^80HC#Q@7pod z(1lX{F$$iD-JJO-v#Ld|^A;I|lPQ1W`FEHG*hm%47smU`%aI8L01~B-v)GR*2H#U2aS_^^`Ld#?bhCe2qt_0-c~| z-7o$D!sV+yDn_OBo=@WRT8XBgB3<&Q4h6$|e9$|0049Dv@z&Y(##+-F7OL9feb>rm zuc&B0e2J=n6p+GvgYct(fPnc%XTe9@I=Fmr7JD4>V3HjfB&AUw(HrgpH_|gdU;N|s zh*SUgG0dlgr7R*@3VM+TjErwaWc`nEv_sB)0-))GAbXFD-(+TX?w{iQ8( z3ZePy5j=RYuIAc&=1gY_OU?8vv0`ftUnk*|iD*(Yl9wZ2!ha05cPn4<2F^y&{#H;M z{{JHFLQu*+`9BbCK6)Q15SUwQb8l5AV=vkpShcUv&yTXje^@>dwwP+X+=IyT;h^7o zUKHXQ^$u7>t=43*%oyhL5(LeF2OYlj)oWzVc&iY1eYYe)F((DXbFk>hFu@lI=Oc94&u&817kGD&2;mi?%_sF;qzR@hf1k}0 zFPITf(vQ?$rGni#m`RjHgif3xvhzVBi0MhNAt5Y-f?_gbX_7`4J%183ID*2yGW1$O zPe$9N=ENqBxAGZy-i!tqY)fgGsAxrJ(yp<+Q$rskwC53v13R3A(c9QATat)Ff=`$vDuAGbe-nqszLjAVn?u2Q&Y>Pmc|joD9nx7 zO^S@x26zZjw+8BBK&}krD;2Kc)Stz7+OsEsP$Gi2$qIwo5TfniY3~*K@3b}K+j?PB zWL3da7(>z_y^iHL$jXZ}bW{{mIbYr(9@@THjfBnu{4?JKR=j#5nA{_M#n=SCBx41%pb6eRKHD`d2ZGPlhrD9 zZ|m#p%{s)pF9n_}qE3folcHQQz`i%;x&pI!1Tt{}atH;~JyXZ&kAwUoHYe}OuKXJ5 z)z$IdAg8Otrd`mV;*QVv*fG5v6Ru!uobE3$$AV5O;E)F)&oonPU!fm6-n(sCwU_Kc z-~3WuEG$R+dzwQ~Gd1aDi@A&ahx2r=-0}WwPi1t%fh)DUI_wfB3{CF6^sLzghNZM7 zt$S-FPPDV7Y|Q>Oh_T-ixTOuU^IZ~cLcli}1L>qXr2l4=Ux&$%_&aw(sOv6uX9k|7 z(!jCFTq~z|2B}5`tyM(M1A@{M@fQigrt}HMOGyusi=Sj2H5QV=i6vNZf_^b*xtnQK z&pvpg>kuG5qTB*hDKfbtLpTEL{u`k+N(~N_Mbi3E52m9XZiqQe?@`YA-({y-I#K$LVsRkWh<3F&Y5Tj$B75DBOH(%U2(I z>SPhBFr#A_`_f{+z!*hZYo7ucqwvv77I16o#uke&ok{W{oL)I%$B{$tMS+oa;>{48 zt0$_6^`2AyL&eQ&6zj5jE?Dwe;Fi_FiHB@d@oZXmYqiZ zwqfYbI{wnPchlhnT9erXe_n__jvL+HKXrFzCI|Xj9Lq#t+X|w-e1E-D|8(kl6I#R` zH@ybHtqCB`5n642sS2rzy5L1TF5{t8xUlK=zCg|w6cKy0fpVJ%@vZA&{xd{k2BoiFop*inRY7n*Lkb|zX^<5C2H+RwVm-^vNn_bV6edQ)u`-B6dN|lGS&^?kY9(~Y)FDHgQ^!&3?njr5F>}F%r!@2m5}h=7 z>#6}FMW^Xnh-+v5@P!rl0?~(QpMu9W^6AihvfKjuZdzh5?2^6{CEu(%y#9e^NaS{+1YjcCn$RB%Q|a@nZg+AFZoOO zS)8$OBhw2iPjbNi%4O5LgWPpT7?-N0MaJyLPO1YmUqJHcxbR#}<%uU76e;eq=!fdpI@v^)$lgWS;LqtFO2C`h@)(_4iqvccs_E^H47zhdb z@BYD@_`eA;{Wnj-A2Ba21h0u<1Wx~}Cs$)r6Zvnw2ZfgPXYqy`qj_O-tYwH%ATW?8 zTNtnpgqLszYw}inQWY=|Ug434*;|q3?ET%0reUa``y3Ih1G%MRIcM1Mmmde!AU!k; z-8-ymU*D0#H9!LEMIPa8oRQbbx+7-)yi1FjV86W|!d=vskf${*dop?5%)RQ9zkbzB z==Uk?Rlp1Wt#oLXsOj7r=`?-h35PI;qPs z%F(vX5+dwnx7HZLRJaM+Xfj+v^JN45Z2a_g&;to-B=IP527w49bcD?x77247YR-mj zMC1{B7_2sgjpVg`he(`O32qY{Fi|o{pzlJ|pZyr^&vGlo23AS~i{8A~tRuSDn!Mu=_=m9vtns)+Q=^usk|wMx1voW}x? zXThE`oVko1IhOJD6LjlF2!hl!h>nS1X{~W2+aL0Xil!9zc=~#ZJi0J!3uloOcTvUw zDpw9hQkocFf`)h$rum>xf$fnRpg*$#$ev2i+_0ntT$zc~fN!4l1lAz&=EFblDqV(r zF5zF)>gLp(;wjf4vX;^?d*n-=TBKG#aWdFL)7F&;3=!vS&(_-y${L{wO3Beo>}&Ref=}1n3R=J(T4?j zOG!#neWN0M`_N2eyu^vTiNp{Q(L@bLOVBwcG;L&mSxFw4{WmxTzzCC`)BF#xUN1FImwT zxAXwX-q{f_xi=DJecS+Ed;;CBq_ZpKOkVPADdr9Yfsz;&tUuZ;?e^?>`em|xOXXK| zrS!)yHHc(_glcZeXK!x2!mIfrS(IU^cX|WaAWwJ<>yS)j-Q=deYX`9-G(TQD9nd|S z^@Pm+t(Vl9tzhZlPGPz-FKyGanq+K4E{NW2kMPOt1wxD;zcv|Pi;s&dSdo@9%7+9M zum!BBA+{Mfa;D#?UGCrhe7LyKfr&U3^KstbOu|MNX*U8)4d(`BG zi7(_ib7_W;TI`wBAB-+GwDm?o+Ly1*-hY^fcUBM1QZX4s9TUh4-39hz23A&9FUrgF zP?jL_Ckg?RZgAiq<)(EwT=K_ulE3VBs9`8c^7A8U7I~;jiIo5KsQC*xc%#)C+?DE$ zuB1R8i};4-&)8u}m=7k%2|scWrZ<7ucQ`W0>jo9;kZ~OUAH7X4ZVjqg^9l)_af@f7 zr>H2|vqF+To!lP${HWmvP>Y>MYKZhRQ(3vPZ2^0{KP<)UXrm5-c+?N%BdRY8&SO{lL>UuSekcK*AAQ)j zBaQ#p(JixjtQX4On=#Oo*YrbJKaZ*^#7)K)a9-18J6%sWZ0?5;n@O{%~oGS#o-H%v;AdecBt7KlDVp7ImeEtuF8T zTBoO6x@Tn80wfeO{-e*z9Ftbk%$ZpYi-e0l4DYXd^v8=G20|(W;sU=8ipwCvXwjho z2>K?8!vJlGcl@+0j=d_2|G4ij>}-{jlVb{YHr%CP`ZXhijKDz6)Q5CMAbZA%vZ;uF zVX5;=cevPrkS;GM9U|7y*Ox}^^5rfH^j3i7lW_13du|hFIoyNEH%V$x<_@G3gs>2@ zq6Y%EQR1*QI1SXA^?R??3=so;axWoNf&x`}G>RQG=Jsrn5ad22-k+4zT`Cn>oM^n+(=fZHej0yt=sL37>my|-TcuzfIoW6M2-bF-}^q1=r^DFXrX z{Sl8yGB5sxlaejH#ylKExlOg;9&CwoU1>HS# z1*j)k==g3L`G^b@ND$o$6nL7P9C2AmB79(~J8B`LBj1!$rYJ|$W4vN`T=K7Lg~oJOZ#Da#AFB+mnFR{? zO0u9N2B4@YvGU`Vw&0M8ZTPZhY6_GN^xp5SVq>6;Rtys%4?)*vX_$z)plpZu7kY%) zk&mFxA(Pn+MGlTrQ|dW8tV+1Bb0is04jC;eAOq>^<8@6jo9YhyG$C!%{;{p> zGh8qK2Id?Z<69d$`v9E9=H1)U8Q1jy$diWReD<#oUM1wN_z;yB{5tpwcVzN+y`}bK zFUJht#`+|$Y>ANj&{^h*O6WZjyE+rrUN3i~&g_+O&Jq$>1R!=f1BWC)`TPhA)>oP6 zqiY$*thD9~i`bU5JuiQ2ylW}p6Du=70d+t{hok~PTw zQcD`VCKfbsc6hsKuXhS{!U6R5;x}$cD~P}FUtC^4@sw~2IJsMK6A10`sR=&NBCd^X zsRZAuzKXpgG7kE&DhwYEpQh&Kl4R@#ok?R;ms0P!GiUU%#f6XO#G&fHy%gsmo2aE? z=TSbm`8UgkXL29%Q=pjz6MvzJM)|25`~I04w7Ry$K*Ljz5`k?6rK-a75N)=#)wd?Os#4vVU0beIapM;yRm%+-|;x_iRioHf;?H234_24L{l@zajJ!5>e*yNSU zH!t=D)uR5p3(Mj>3eb&FrxkAXr`~*QJ&ko;J^Sbdum2FZgfx*3)rB2{F!z=Sr5v51 ztZd)n0Vb1c1UvNS?Zp=RGZ=lB%!|+-LSO$AJPx}2*dUVLu^F&;C1&tngxLG>=t=^X zhIQmR_NdSZtB~gekp)FtUp~p)NYXzqefAzX<1BgMR15j%$onWP$1vfj1y*362s-ZmuT!QoCBT35R+p1y9=mE72Xqn!+& zaGcC(NM(Qj@k7CeS$r$CYx53UwT;^{(8qq?8SaSMs}8QIj}WffT;gVHJg)G}#S6df z1D%JI*0t#8VVc2dpm*|ThZv?R)P#w@^;<9O=*ela6_G3HSieS$VBG_6%?xah&sT?D zE0eFy|LO$!sNmtJE<5&4Ybxub%!L;=#!URoqAz~A#@!Buk{33pnt=UU3q(GIBuPN% z&V^~Szq8XMT#3;z`%qB6uz<|BHNO=v6S&_Z0HVHLViFP!+U&4_NiD${gp+PhSuf&G zLa)HPJG<&-cN?_=2ETaMjE`Xy1!H*zf-gkG!GCgTbdu_9EVE13OJJ*m>ge4!Cr(D%fRJwMFriGyo~z!Hpa*YXYL zaZmkJPRYvwDa{~iblS|WC^Ctr%e&a5UWV~n{(trWd5*_4zlXXgHQ=HORLIeh61jwj zqu@o3C)C`W>fSIZHNJ;sNa{J`cFqgwDaH%mjdzwRWVxVRN|OyPF8VV3bnJ5{BQ)Rg zGGPz!d=rFq4k&Osf@(~b&*X?H_guo;b<5)dgSYHMmG@~aQ!PZ55<(rRPrUgqiyL3q zH*s?Jh%BQNR8~okc58NjnMz-M&o`@SJ6S)>D_bt48AOJMq+j*BX_e@3`&(=vJ1okI zUx&^!bRK{*WMt9naI+=6c|6Ax&#pp@Cxyi6m?kub@^EGkRoHzZb3q;%Inc5vV?2SY z`t$22)^oorjx|Jk*SR^?kx7D=HYG(fqvuU?E=lFcCvOLI{RIY`9mrgCaLq!@1ocjf zb=&9krlBFi)mYF}oRp$rt*mEd?B0vey8Tr! zBwzmPHw9HU_&OHt;ACOui?9sI;+X`OWs3%<;Aliu?lAc$w4GsR^t>{F9imhjfxg`= zjEBeZ^P{R1u`Rq-u%|Y90-~6@a~6)ogDaaU=rN3Bxb{;*Q7~wH@3}`!T#&G{B(y87 zgrbv|)(d4J^0jb5eoBq4zDBU45?-0UP|9#Ps9BH%k`(zK(`wK{Ee9aXcB-2o{WL(T z7+K0*O2yCb7rF74enUV|mUfW(n*vb!ix7ZbqH=PW<{ao$wu2O0f;*pxh(a0$;dha! zqFJ=g6(GaZu;jf$2NBF8KCz!#uN|Ym4Vcf%!Te({w1=lOs=)$=7|*1oCw$s?U)dQ2 zL#kdk^sw*jk8zy*$OWxTc?%2qIC{G4sd`4dqu3Gyj`HO#6YRrE2

`-F*i!8 zwmU2iNa<3NX5ZFHoqsrXa)xK^*0f@y3p~s9j3dl(emwG~V4V;e#200+H@mA?lFqP2 zX;{R59L8aTX$Jc?7{>a4Iicb?x#GO|8yDbTKl?wMTnWy`ShBT)0oqkUT~JtBNU@_u z(q63o+S=L=U{k>MOqsfCkwvBS{^BKvjMnQ(MNs?X#d>z z!0s6gxTQ}>%pnt`JV@=u;dgfep;9gc^%KYf9E`vEMRKgkQ}J8DpY0AZub|J@t@Srn zz?lB~_YE^&e!7ne*hIL!29f13v3jZ2D%)E#RM4yh?&*2Q6i|L*6gSQ z-{`ACjdLCuTN83mWe(CZ{+W2R0bEBxBOfwfoRj`-9dVmJ_af~VsCu!v3wnE&;5MYE z88ySCBpB>tW%3&oj1=n4q$8symB2#?zNNuOP4^Sv9f55+>V(oTRHe~-g%SAb%|6oO zLIHO|XrdwL7)FibPAgR0I$$54fOdBjg9v07#IQ$4a_elk%O!a5qUR08UUjJsTdA1+!vQw5fjtSyGVC@$y~&AA9c^Rpr&Ti#}?M ziHW@;*4TR#5CJL1f=0zIpa=>|5fK3a=|rOe6+{sW)n2F~BGQck!~!THDAj;~QUwI0 z2>ZI0nq=ku&KP@q=Zx=+vA6tq;(%y-oK#S1@e-gH3+m?2>Z zPoYph0Kw_6V-C<$Y?k?})c4QA9KD`&?V#`uiz-oK2|)Fc5Xrhyrwwl@=t<#3l61A; zX-k22{XIv$dHehZ%ETY$$zd$+WOH*+&pQe)Ar9(74P)wAY)mfNbD${ZO3R$at3hSC zGR+v>YSU1IRkK#Ue8?Tj)$j>qs~yz_(~a#+3@VO!H8#A#seP0mgsIr6NW~7cVN*bI z(ZhgDVv_~LVa(EGa<;|2EjWSdl`|vzTDzjd__J?~SW)uW8z4X$Fi(x zj5jak1{Hl&u*R{*cy_l-?j6n8xKtsB7-brXuT=gZT_jGg+jz05rT3~-j1(lV_?rJr zLa0ey)X!<*(6bf|3eZPitIb@+hG1c{}TgWv&F+9GQl|U8o4V!jYA%GS3j$o z-mD~ifG$l`NFI*vvP8_`b_N;}Eg1hNl!J+`45Lyc(?JDHEH z@P7+feMSnWH55v?yz7D{4+uy*Z5s~P8qswib`2afh$e^>0SVvo`@X#(Zt5aURk&G5 z>rEDUukPE?R>M!HK@eGy|L;{pv24x!==J8yt*_ArDC6My!3G6>qQ@j$md@Xz)b8 zJ!?RQyK+B=Cfkf{BGM^NDid?aN;Q-)za*e{z%j8bJ@*J}n{}f1gVL(kNhjmM7J$tT zr??f^qZ8{GB>*Jy+1%mgBGTl?_{j~VnYrkk6;reWhv|kPj+Oq>T9KU;;fJ}xtI(n! zLmrT`fn#ZJ&n=MT1bvTVb$`6*|H?|4DG%fo*^{&;aw2Uj#Tk zNk|HKCWWeZm@Gj*p#+_aBVcMr-j8NX0PWT6w}v^Y;59?`CAPKs5kkT!jJL~rd!bEr z=dONNlg? zU^}G=V`@9TraDXxlc6W28Sj+VfA_Nnlr4<-DNUD4p+{R@452dIF22?bsf#LRt3Hud z7*vZ=8@$+?4WWr0ts3#RmJ!)A22vLbpE<_M$adma?vsYYG9%1q9WZrUQ2%b4GWXTHjZ`0q5}jc+Y$6MNG) z$FoO^szDD!`)A$rTyn2;+=31q1*b%g={T`8ABt3oNX4d?7JO^Z$*V4`UQ>_%CdoCD zZT|QMW4_TnYDU88JmCCQ!}5+63aIf|U+*+Qat&;Ez)fvX3kiT$O2hKF_WFlL<*?;Q zbcNQt)s<$^lBT_BW_mRE@w&*!6yjCA;Ha3)vma@k2n0;Y_u6`InO;MG98EV2<}R7( zZHO)8U5_~uChAKS%4yt%B&s@7iHZQ^6IJ_CKMEQR5u0--=1f@OeZmTqp+7kvt*Tcd z^p=duNvpwm=;tZk$eixib@vFK575|BO;W#96qs2}$~|$~4JT<= zOl}}DsRx7lh2uj{%US3roL?>AUiCoyH7X}2O9IbZu}LHaQ|*iC*i5~)?Ri*3K345C zIlu%$e`g|J19q|G2nu(KLnv#y2akzg%Wn!spxdUt^;b`OBFhZ%EtThc%m3F1_dup zfzwv$)Kx!H6OH^<)@DZyf=mGZ^Ba%_53{pW?MpcwRU@&WvT+XHF0+_VvjvF3h{WT^ zu9;4l7BRj*>?l8c)z9x%InLqb3XYHh%xZg76$m4h(h%>4WJem{UXp;8h%Oq(V!hyNqB9@@ohK{LDtB+ zx|&v+^Cq;d0U%5d|F==Ci`u0%R7{$8>4zfb^_a;UmGgL+Y9||60}4ujmxGiM4r`-( zN1-c1g@u%6GB+jAeBQao9#=rdG%jX3xG8E1+S=Ow7sUHbgba+}x%jpfqC*zG7tL^v z>znFarH1>e6!%QItb8qRS zfjA>qC@7)odJa9#8#kIk^}m44h08X5dAaVn_oW}t18}o6D=<*w1IFJqTbxF zoad91DZXpgzh^RJ$4^?>LrY4tpwnfn`w|81)bZJu3u8HW2}*v3KVkg9k~X_346ymnryHH;1CV#>I8hf@x{6e(JC6K0)9$GhG6esC(vre$l(ioSDdI<151wT6c`h zln&l?GB6IIBTaR9eK1Ny^c8%q(mA(y_Wg}^099M#YzQX_R&z0{elUTi% zTBkrK-QRKW@`Lgf+aF!Ie4`Pr+m#aDww*oWg*Z^IX~L43F2|lUPQdilVr_(vO93_M z`POppiCrkdS*P6DpxolJ?ja?mo?}S2aACaXA!Ge3)oh{U)`8HqX!UBV&T9ZaDpbEm zM}Q`jK@wIQ*4FB*Z9e(!is~opQtZ*)%i|EjsGJzWe}^6=gdR2caM|Vrs&z?#`vYAq zY?d@$!s)@11w*_b;)vwb7LGBjkUDdCt-AHLqxKznORtQNb2`vkxM(30KeIo2$zJq( zO4*T9PA#W~j~9EUqHs&SQ?wMv{*W-GV}mAzI)P+uIW(9yK6;1;D9Ya?${fB!jdyO- zmP3n2u6LL)>?talV1wt!6ulpunK}K>4^y+6XZ#=yE zs1*)S1C#K=(`fQq{(dWPC+2#(I9S-~q+;W#r&{V-W{YTw-uUzV^)INUYFJdLW3cHa zPWYQ8(UY!Qy?#7~=^;##+|nl}^{+(tC{y2km7rFRSFcA8Gox}UAyJHR`1o8K9{1Ez zs%!%mq(?99BE%9pqiGfe+>Jm6usE!3xgeZ*2?b`4?-IZ&ej!ptH=#f}|EO>wJfjzI zMJa~e=*q`S4>6Wmc8BG1@aEV#Jb!`o(@ev-T!Oi6$WP`A9Fbk=%k(%9bggS8+6n%i z!~GPj)qE~p^KH34_KbO5hb5%ktM`scu%`YWu%O}hZOBV!p4h|HDvk9!)S~X^br2V4 zkDzCh7jU;ks*A8qBtbpnJ=CZ_{_z&osQJf>4M6F?LdVi(!wEd=*K{}QG^kD23!avt zBorA89{kJv#n(gk7x(Ymf4Iq$DQm12xj3)6neDPDC}eQO;GoEJxifbh@z`QgaLCdq z=-{fu%a;8zdFYUvw{v=RksY|Y+sR8mJiOD=VR-h(bYCec-_jAcLtlNhH^9!nO{vd< zc^!2=K3v~0gZuvz;wO1W>8?W5#r}-FE4*l zns8IA>z%ZTLjE3hLZve1NihvLVhJ2OE1N-vVmM#tf@NEe|1y0QxQU$2xdII3c;$}C z!m2$|yW#dhDm2)7=fU=)X&OOJ7hqvTmn|I65^XHZMU6m+0*X3~l(`LDA5>Ajw&;6` z3Q#yQ+BWZ|3M`b;Zu?i;{iuGU5%|1i^UDkm?KBv&`gDWwQUmK3+fUJfL@N8{j%QQQ z$QX&*-}+xx)X(D~qWL2dTdIf8CC^8AkQ|iv* zqamx6UGGT1JBN&S$}1ABY`fr2UPXn{VHc(Zz%0Huma(j?Xxe#I|DMX*ZzuZprOu;8 zVfL;Iw{BUrncTO#0da}#S~J%Pd)ZyeiAdA@-tEk_zU4Xn(`!hS=g8lcL`w7=$>ukCS zlfDX&6P)cE@W)iy0QfB6kNeBeGMe1q=w(7EP!n2>9_OblV%yFr5Eb)8* zcND$sGvj#~dVH>EFb_5i%#UHi0qPs~?L;C~sJ9y<%b8w++*B5?d|wLtfP()y{%!t( zV4hqKefhrjWi+6`A4eD2qb}ngy%+5IMo{i~zF%&X=_n}I&DwhR*CShtOy(EG{8D5R zX{qxfVb{H|f?HPL=5mnLuIgKjzZzf`pU}B9^|zf4H~5%atk=0TY(i<1(x~fSfL;MB zx7{D=_B1iAO?Bf&>UlABOyQ4XhQEI*=2_jd(W7~_wAC+IMK^R-zQ=yS{yWh(_1knedea4x_$*P?%)tD z95MfhC8q~yxu|NMSyn2RZ<^1C$n(MPCHkAj)h(vltJ&lEJ*o#5r|o%Yx?otVw@KTE z_3M*ODOiijX%P7Gk1FjhY|ll3J3Ex_7PV5+msM}c9lkW)S7%mw4b{e|dYynu`iP~- z#gf{0$Qg$i&i?1EI~N29yQOf>$+HcPrMHX6Aihyv!Wf76iP2H&v+r9<8m}q1JCQ$LHQM z@rmk)Js%h-n!kLV6A>S!m70A4)t61cRv&WRPgHk3o>?tZD3k%+@y168O!0xiGU#f9HZD^6PBK~gDs=&6EK^k0rg>La|G zfstHhau9gnA4^(6MfQ#=jGdC#vfa)!+T%onUFU~p3j1lADk{MT^#V+jDy#4R^F0dE zM}^(~>o;uZ*>YT+TGr?_+yjtXGFTG~4DD`raO~W_?f**Hee1=I_^8b=VT$2oS}J>B zaXVo??9JPwT9K#(HN6-*bgEStv)BZD`_FILvU2^JsxHo(bCBa5siYaFcH2xaE=p`~ zwH%t9x06$|J@S509WOd|@%0cRUf8O-&>oE^s>V5;;0HrCxDOPT1^Hp-{mnkL(Pk3NB`9FI#akl%RZgxT$leK@JuGUV6r+PReKF zbwwP!9lPgEe?$^xN-uvAf?Y;2ayCg)V%T~@Yyp5`q>YalgUY$HpAbr^;G@_v*=;e9 zo;j>IGOO~Ur`m(t37q6$_0?zEp~otbL&WY}K%*Nn71W{8;A8dywf&<_wL8mCncOPF zBiu|uK26i#LczR&GR{J@6&q%YlBqpHF={|3i#b^)SAG z{gp7YL*#-VR9?b@gWum@R-{EHU`iwUsAZRGiBE#Rmjqm`vWHU@ndAt-`K7Wk8l3?w z_8>asS}2JkWujaz4{5iO55_(w)Y(x!HMumq*R z+RAeAcA`2rg=L^9Bt8lj4ah&XX@O5~kZ!uN5c`_bCN`swSkl8Aqu6;INclF2-ScRL zE-&Q~%%YwKz_AyHHQ7O8Y~0<_4Q}XzH+X_k_&5YL29D?a_Lzk z$T|kp-Fl8re-e$9eVf{$;OJ-Oz`hCEeE8N=BGZeUE122pI5e(LZ$&G}f+I@(U^z4a zEwW8fT$oWWkMpW<4mz1vak!IiEB5RkOViXBRF}eXG*YI$9rsuogHr-yj>u5u0jE*< z#UdEZ4MnT+zJ>+T$XDoo8h7A?x&~`2lF2a!QwAlyJdN>lD7!M73 zPMpyW#HB#+oqf_|2z^>)ioqP5%dpt#g!Fu@O2i73mRPa{FI($NAC_RoS6HfqrAPht zBQlu7?twV#-cxpienzK;?za-gkQ~xUM)qkHorBF3QJ6%Fk{a^>6Iv}`xYJ{HHeT*~ z$f=LQpd(FFoaW)JD%^JGk(`YBQ7@hC-#WTR)Y*gw5WUr^fH_}fz%tq#AxZ45wA5YW0sP?@hJ4x073@%Lr z>otHHn?8|Fv#8sSHvQ@FGM>>vVF@vsZJ4epQP^vg!@JcfF|0D+v$Wyp2&lzcQqDfu zlBtRoI$N>%ef}Auo%4A$@W9ZqJE?Z11nu!DccmZiA)bQMUA;6&^7f~K1bewl?TXL{ zrlrARq|5tdIDbdUQ9AC<#_zfI^$@Q!G%PqTCKnqBiXHC~=v+pbU6Hq(<=DkXTo5p1 zZHo@Vsct-{6~UGin#_JI_0Q`P4y@l$)#bQ8l%`i}YbPkaJdH6r^3JJYas3g%-4V@W zQwRKHMODsuIFBU$xJ>O$&P8GKIf~lhgV1N)y+0Carph9Bs=nZ~Tf&-uP76 zQ5VkDhjT=e9fK;7LrWAX)#e!~80AGk5U;6wrP%9#-2Yo4hkJaeocT6%&-JcIE;lwd z7LA^;2XDJPonHciQ3^W4L+PPvkFHLy>}Oy;l2=aG6M9h|g=YVZ-b(LZ8iHWX0w4Xd z;pjNg$>H{DheYVINmpdQxTwH!DYeb>Vb~y1$;m6l>j|NC>C)}%g~$adY(iX3fK!JJ zCn@Z)(mx^FpX@9WbIHHk?B9t+YPzm~FMxz(>u8;|c&!?O7#?u+cU@lEqEkRdb@+#j zyj@)qN>6Sorqvep^UUN8eY^FU_aixa_n_HAop}jk#DHOBg?ImMuym{rbP`YvNBr)y zdy{u3d_ND%*U4!FH#yQ zwqu0pzX`j$!CU(lhn2TFZStnyVfzM&`Vh0(hTa^g)0rCc#huzsqkzR>A@u}@XIz!e zay(PB48`Uo^k^@j^H$zgixxBezA3$w-u(4H_rTdw*h;Gq_6=pK=WhUrK14tpd^ZOm zH=LTe?eQLDt96Jz)J#2(tQi&#NJ8q6^UDw)!W2@iX?b7(!m&uX7*(734IK<%7zx6W zT)c*Qwpx=I%9@P|-`_F39*M)DK=iGjwWTpVtV7HhWF&9sjUav-tEGf@#3UOcL|z4I8pwDau<_4Lzl0zLbBFvu=X9MotjR zjLu#%w%upaM+#*fkpnzmh>b!N#@mO%FXXZ}yo06%O8p_!3Mb4UdE}5Af!KqHit?Pw z?5&Q>p=31G7*YTk8G(e&g(GwPk{;-mXa^o5?Qyte)@mAMiBN~Yk#+ZrLYMg%e8_U8 zJVByU?dtv1gO)|?r{Fc$N@;WO zMt`Mv@x|1FuFy9{ZH3Ln?1Z7}OJ)#Q`^|e;R;;9bj~PZtBK#v_v>E(vQfA#7K7e%$ zFp~NO1A88L49+zRn(%vu$Ka4Eg0W%u=^hnpr{3AMcy{DSnqI|cpv83KLo<%rHP^D5 zic}ZIL5aE!14^grN@n3Sn_08w_-{s?Q!$~!+1zkT`Jc;D5DttHw2m^`wDn3<2$XzZ zFt}@BolQZQs|y1M;bmb`raodNkAP;iFn52)H+&P7@Gpvn;hC?Tea+a);#rkVqeZ0jADW|kf0c-JgiyA&HW!^Li(K*d;jH+_u2F*fd(*ep_eSpyori4J z4Cwgm*rg4jOdnV`NtjcYk53yeDcUG)?@x9 zG^H}*n}1Ua_kH;{e?K~v|K`&;G04tYml?PDjSRG`>I*MSCKi2Pv-qYO9o2MNK%cp= zqq2|V+x>CXeqkfsV0HKR1>jGQ>#JvVc{#%5yNX-yMk@S#X-)TPv5ZMjajZJl<)zla z?UFrP2haA{^!oZNu@4YhB2>S2w!R|iT<|Y7(d%~TY>NL~;ZA2&KUpDmyjWp^@N~D= z9r3^EF`6r%Q61UZU_0@P77ULU%n{}Ra!YDe_&xDob)N8Feeair_xDr!?=HMA&+yAL zGHE@MRZ#*#-X-yI`H(ENJ|R>jL~weDCM={eSg$ ztiBf zIbow#cuTv2q9)DB8%EkeZ^Zo^uPz$bx@8nWjTDb2_FN>G360znUS8{;7eV2e(l~?) zkP*R&oXjpCMUgaVM`KtW^rA2;t~>f1*k4^IU{gexCWsg%gDocMHcTe)@(Qt$&Q-UH zXYabIG){)DB~?>-U64R@#r*Z&`9+8O{{d%W1*<9-vNs{mAexVn4-Axx_KHmggdB+` z+r-En>?JuEv(ASSppeq^hKK+Td6I#*Ayv=7o37KHaBm@@G2$_2v%LaMrtFpVzSHpO*f@k5%39&P0Z7gz$xxlLkooH35U#8EMBc z^QQQ9acFE!;F`D1of{!ss%3tEJW+9^brhzrScWk!aTVox=f!U3Dll~Dh4(52;^MnL`t;m#=ud%B~5$` zR3(8A{e!-5L#6bWS6I-A2|na5!1!KP3X0)+BmL|i3`f=k0J<6cx+u|U$C&CsiU^bd zQGe}?xU5Q(MAtj3REcRKeACyVd-v`Hpp!UROoBTkCTL$rXagiZ2Vi=tPTE1a9NxxJ zAQzGV2|xB*wQ)9pizS$V9|c*aw8{j~NFp6*0z)*V$g2c^dY~CysXIZOkRdQu=@!(& zNQ5pk`tMKq!_WxPzpP^k`}T;ZI|9Mva|`5%#GDaZUBqnRre6IryG5 zV}@E)3u)q1bS7G)+y>8>fYbLt9dS3QRblDw0?NlItSRj{z!yok%}V;)Q3i^m^?c}{ zhC_d~bY2ATk0LWI$RAiV0W~8HDtpYmw##oYt9AjE^5iCC47z1Z#oBP!Yx@cZ<@Lem zBSK+f6X`A^p%Q`{{9W6RY_EH?S3Ib!>Nac;R?Lf_hzOC0GiKT98epAmjRWD+3{E;V zjW2SvELK3|baNzj!DlD-n-2K-<+iGTOJ)U`EBSF5g31O_QdHxDeP7$acU z`4qKZ&fkdJu{iihe8&&NTVIfJbX0(bGPgM?$q$3^UKSJd5E;rr(^^k0j^~Z;F9XQOyE-c1i^Plp%_tWOA)#> zmJ7|y%m^5ARg}%&y`Zpc1aK1^=}u_knl)|6L>N3eKHCml5^8_t#gWB;C!E-`k_avl z>88-%dydIQ@}WwzXF!C7!B)mpY>0ThwjbW5$Y>EjWpxeZVwbUuSC1+mA(~IjrdAbY z_?F{-3){j|C}??06vT-=ic0yl*D{sfS$#OP4@33 z{45Nua6xdH6|Mv%=cGxKQY#-p;9)W7V*TxC3mccd{11#gi@~G`y{^4(-9VVPWVGc2 z^7CVO2Twt~WRVHi3BvA;Gsci^rDj2!TC_^#U_yfE~odPd%v8Do+Qa z+AF$68v8b>m1GgT`-g4$Q~()0in72|VX@`sELCGyWR2*m+YdK-KRAgmyrG zJM#mc4O`38{rFN(w%z*k?%lg!qMH{MjT93&QAx(P^gfMPq6=Pb%@eRo*XfS}!Dcmt z33^r%Kuu-(Ymd@T0R}WadnJ6Rvh>S)>X+wEA4TjBz+{BU{!-f>TV~iS9~>q^|WT!bK$6=2|xc!bI7J z)w@E7<%RCdx^l4q^|pxD{T}GJGaAZer}ftO6(JTU*`DlnC%UEvyjB-ro90HgMAz(k zlX(gH8NLsyh@W8I+$(S`D`E&)dc0`h8sK$xTRX>~T1|DiSZW zreI7?3#hXzEFIUs%AH;vI~7L|AmkI8E}A(J3JDNncz!NEdML55q!0e%r|Af;(VVnB z-FW0^X3w|&b}4270Gs_QqpgCMMq3#J)KsDHDkc%&VbU=Wz`Qm|D%$QLfvXl2zkmEZ zm%>7R7y<*4aAXt>SJh`0C|6*?FAqk-IvqU7wFT#Hm>1}TW}NI3t^X?5%v2FjR-Ou{ zHdO-3O*x~mhJSpZAUszPedMO78R3OU2D7Z6drCw%1y7Frv!mX|8carFv(1eU95^t` zrv6n{w-T}69_LxVZ{sfP6W2zZ^OqC;@PCvVX|Up2ujW%3v9Sp1WN4ITBe{y1ix*!% zM+~as{9tnMo9@nmFSw@S<+}!hWyXVW5fZKgikjaGpjC~l8NNEIE0t3Z0S$gNeTO&XVO@`m;etx; zJX1k1YQX=$nAY&M*Xk#ra<=tGOfNO>uEFiNPz^89|_PbOM!DCK_ zg5&5emt zBo!jlKrBdj;63aJL6ig|ZS#t-)g_3*9vWex!doPs11hm5zqPxu)-qpbqjePG5P3+^ zkqDI32DzZEICI}o7ej0c;tQ{3kXwV4^h08T4w8FA9Ih1&_x+LfpKO~`k0gB&wAhTd zj1|s?*8M*%jz2q_d#DIQcSLKM{#FpKry5zcTC&?6yL$bCira}dYj%-=i0EQ&%!~;a zbZJd__9AZJa|?dEtaJqh3k?_AbDCkKKAcJsyaE!XuuR%@ikh*rUmYgnPJS;KcbR2i z3NG;>?asts_UiY4?iSkD_FeUmlpNQ_`i`+)o$9`}h6lC#f9#R#-6I8qBD1*@qEningvqgo(JEb+9cjFE$oQogN}tX*OBW z6i;cc5N8kto?;-x9yZi8mjEru3aq# zqEl%cAY9I_Kx&LS`PsFw2k+CZ6FfCY;D(skx{4~rNW9r3TO|D#aB^L%S*00WGc(8F z;cr?}pp(U_mNO{{yL%;MUoOS&6N|v#q>GJfB!!MHJS{EPsQZ+stO3^J z0Y#Fq$ThiEeH|TxkH??Y!^RhZJ8;Q$z`2fVs(SNb{D<#}wH*n|m-yW2_d$3xZz6y{ zybyd0qKFeVh$X>SrFgg!)eC-P?A=yWU*0<&n~M%WU=4AM2bxz?sBRJzSNHAPx30_y z^`mPeD*45~^&Sy8uN@t*YE#+!A1tYCP{I21&vA>><-MJSqS% zE}sZ((Q5CC_CTU~b#GgvD^Ld#>XkXlIR&J%Bky11BbFnnfcm;%gvV5&9qgWqbL>EJ zp~`WR|Fj;?eNfsNqO{Rn>D_#)vT9n<2(btHh850B5X6@T&xCmmwQL?#QLH7r5HE}9 z>nRZpr68QE1!s86OpScOH!uE9vJ{yFig*(!e^KWHbDyliC`A+y-BUe z*Vmkh#ZsYbk?zXS0nZQ<%wt5$9O zKnOjR#%e7BK$T3g1-E8)XVW&ZPpePj^#HMFzeNXNK+7cR z-y}sP!(}6h-x`-bT-niH_X7$(H&jC9miil6xF@x;Ie_{hEiVrC@)N24k>pPeA5-z< z;i@8^##KMb@exBJs#NoGQ<31F2SsyGHf=RgLs)y2WA7(}a_aNk0ub%RICg{P1;q@< zC)QQ!bjpW|i!27q=I5$t-_Up!H66!nUBh}+HB66mtw(Ae zxhm3*F(2uSm%J1Hok&nqUB|)ed2?G)rxGq{ii}wBa?a&yIt}&*`CtR=sJKaVJfB-w zI!!C-*aL%^sa4nT#`5uoBIn$ZM^nfU@mM#5QemXmU^(d>&DabTlXs9VA%SFKlOL8l z1^pD2#K4@+F{=2=vye`ifza#qJOV0rb4yRG)kT#cSG1%JTn_^COHiz3NZ7`M_H`Zz zd%Jjx4bn!L<0#(b+og=XOseR=huPL(#FW76rdao8sOT4?B%c6XPAHfTrFM@ z6|82vwnZKFkH`s_oD2lgb*C_Ww zv~uf{qs4ej4|DEaodqV58{H0S(4kC9pfD{c2_@J6=zW;PZIXmhCmu#eCj|j$09i~7 zM92@#)6uwaWJwNizhBr+j#7n|8YYA8r6 zT3LA3nFibLld{;ky{JPou%={gZ>M&P(OnzY6%YJ+g~Tr|doH_-oxf_?;n@CvW{#GQ zewID(=CH4STDJ1+{BOIPeY4TrCH?W^{>7)&R?I2L&vWqfeQINzBh$IpNjb5{+rZkQ z#2h%VbvoMZ-n|NpMa8;J-MV#)yme~>0+?c**ug6p+}o1aN3b=}*S|bx&YT^(y63Od z=EvDY%#oE1da<+VouBfXfJx0Dn<+Y6d19D_p2H3^v+ygmVzF+w?KjSU9x;yG*oeNf zx1V42{f@hLf2yvk%6k8P@5-h&BSXWh+KG;vXX+#bFTU`k@q??Yt8Hh81JcE-m3d+x z<*VIw%lq$^tEpxG)@M`&a%7p=vopQY@V(gx;X520;*m1uc%`j-`0!z5RFt}fg~jF< zlEa4wgA-J-N8S=OW#~?^Lv*(lE^g+mdGoYZ`p>(D=kW~h)!5v;exX9hh9IPsYyH%& z)D$Hal}@#QGbc!58%#`1bN2V>vt#ex_ffJbDJd1Wt!Hoc?69YLUnRvL8J7IV3nZtFTbpWarK-aA7J?MMfqj>Zq!!HsX8bojUB@+}*Rmnyx^Q zdA1|60?klMXu2xfn#LA{mXwqzx0X2>Mddx)6;=86?RC5dV{7XuC8rK8EWnUa%8pr2 zo~(vr=d;w*C7{q_^xe8%=s5Pvq8{na}aymcg~Cx4kkW- z_ioRMl`EUuj;uA>v*%`6dAYHpV?xoDcZ(uk1cSTV*d~V3c9t@_UL+R5@xnU$|CFN=Xs;mcwWJq49Kb4QKOSb#54;>*GitqT0lmnb26 z5?_uCK87!g;mcwWJ%KNa;jhQ=B{Fqa z#)@7^mj+#JKE3MqzCn#$C9ZchpFH}j?z2Y!m_JjhbI9g7Ef3%NRLYgh8Yl%s?v=_Y zvzZfis#SsJ+sAl#>133|J};fHu;QQM&SB2*FY)vjg#{~ z`hO~xHw~Zs06gD`$~i*nz6sIdqbWgn-|asyctW31_)gn zmG#;|32ie7q7HB@!~}czo^C2L@P3@9y#NR{bkpeVU&Esu9ag13%ZVKZmaX*cSZKta zhPLg_A1(fVG@m~Bs@wl}clkfMPX2cu`~R^QwB)IlEObINR$$;vLDK<_9oJSmOzD9k zXiF-P65IBl`Nx_OMnC2DFd2vizwT9xm?EhlymXSekJTymb7$25v5)S5D+qmAT*Bj_ zBb4mtQt%kVIyb=lpvtR4tQ#;IfW5tQSqU$qCqTDpMR7rSSeOsQKhB=>MEDhi$gMaJ zMlaKL`p_s+A3l}XzCCzj

)dJu-6v2ZG4&7TUXYRAqEbqf*W^E2_hLY!ZD;suSjq zR6I_C1TV2^1R&5rrV98iM9>ky61(D43;}QFOjo2ZX4mYFVZH*X4*y+NHH45iCKCEg31B_13aEK0}Gf;rSJ{kI}dKmPCV+7^d;Roxr6sXJj#7_uX>fTj&ljTv?ORlGIQ5~XraEO~n zlq_KiFgKhU4jHwLML7V8Q16g#5)_37D6ho2I8{~{ZC$^;&;!qK6wfG+F@&zsIfz<^ zwy_P%bXwQIBTdqTu1E^t_AE@f;)a4%0d+A=A0$dAyyqTg{TZuGfcm7cwu6 z$&kcjU2+Pz$K>MV!+IE$)j?qQ9_CH6>(wxvr%jL&%v85z7oIT1^+{jGUo(v3$(?lpI>AXa z8bu-^;cx|Sepg&w3SkF}iI7Oyeq_qH?*b0 zBW)s`5=aJGl7WY6s4=V+J&!Au8;vzwqA`4yv?NTc~ z6n@$tn`)ak{Kf@2zUbrr_@g(?T+y|#@O18a{6dvD}79GO93g9842Yp6Y87es96-zzq zSXHh^(JiiFrM4Ft6S4tpm`aa}VFg%bg0wy1BVi8J#%6&2bAy+V)j&~4sNH&1W`Dfu zE9cU%Hsu>(e@bKzsTjpH8x1*W)}etsx&*4}hbWPa^`%?QRRm?|D%i&b==EO=Q zpm*-If4xO;mIp*Vwixh}iHfzrvyrUu1o3QR0SFqE1lQ9%9Z`C-Q5rNEiy^$}4jt;a z4Wg6bjWsY8$v_P0!keM9xg21z`<9zzxLNl+{0+Ns$*E7?o+EWSTXTZ6e6LZ`SH7vX zXcX)|mIfnr-as8lO2*13PR3K*bN?QG@1>q&w;u(S5ilv7)$yUIQ!%`Z_T(3C-@dI@ z3#eYi1Jld^*l7~^uU5+)^~RjEH2{f*kV8c!Q6NVK6@93&E;)aA#*W<&=Q3(uvG+#q z{EqNBfZw`>!*~5Q;<(g}BMsq<%4VQ?P0X$;N>m1aMZG)&xY8E?p^mz76{XX0Nux)E#y91XQnm-8#yKHbXSiP` z2bAFqQw)Vv?|a&RVXLM+up^4tE76Rw{?G;mZ0#jS?fsAzcAQ3?<-Aeev3)OTf37k` zt=Ul()tgGeEEz`bpKcml0SA|smNwRp#CNJV9J|2BaV85y0RTGfb<^l?m_7MBoI@%l zC*AmPJw>50bJ@)Jf!LD@Z|E7;UaHfvJw8DWdZfTDCNIqZGW!FWC-DhP30A3#&hpVu zalm=*O+fH?4t4O5+EaKmXZ&%YO7~GBs!S*6&9$7`r$GJP(k=oZSY*)YDzm<^J3hz5 z<}P*nXV*x6WQJBh;zo{&EI!+mkXX4reF!2`HKq^;D0cd5=CLgP+BVj;S+PA;J_rq&#N_lOdVZ0Ja_oXX&YV+?palCM_SviU?s@C-6>j zjGTlE#W?>Vg9bgT(B?rKz8o7=@M3Mf>N`MST+1mo|GEued@OH#0&iT0zMNjmuEQz8D5T~j7H+>Y zezH4$!u`7~(@)&^l`y(bJUqGAXVVH&qWYYCv-*{lf-@Y%fLk3>jGafsdJ4E7<^}x) z4^_NG6(ww375Nd$j`P3)_Sbld<^4W4Ct*WSTPZ^Q<#M;3$FYO|U~lH^K`>O$>=nUq zfjM4m$Cm>D_k{4vfl6HjrE5UQl5a-4vZ{hu*_>)Yuu(xW`)Vrg;o?1{c0)mJULJe~ zp1vS?Ui<6uMgPEqjM?g{1%L(qJkJy>VngfI3ctYCuY|d02z_UQPexMcrY^#;xqK+K zxPFgKaG!REI{5f(Y2)l^RFK}7IEF7{x@5!R(EB*r<3(ZTF~sjrh?ei@QD7e`P@X;o zCyseRPvNoi{nhvlUTQRi(MOUkh-xJ%h9>f0b?x}z&de-qXPTrDkK8>wyek2u8s?2{ zHQql817+DoR$Yqo-|1WdwzoGC?7A{CzE{|Qtl&EIE(s5XV2CB-Ww4b zl!C*wYol&D@vzJN=S4s0W2tr-RMZJ8{f8sJI6UgZYt<)km6+0*4pwxrLQ#uaNFiR0 zEY|~Le5w;^kih4uqHfYHfThAvl6?J&P*bXucvjn#c;axqb5FD;R;~X<4Vj8)p~0fl z;8Gu9bc4tc9XMKFt6ZZ-D+7cET`bi)*bgiOx-=*lOzaJD$Tu6Cl!V7~Q?YP%dSVMX z(&APRZ!{c-R8kC}%*j9{SCpm!Yzk4*gQ26ft+YmXu)q8rzMN;SFC6Eygi zhL?+Wp%-uRSkS+3a>XsB=W@3142x|p?;DRomWJ$1Q^3J;waidz+eriQWt+PQEu!5j ziSK%q0;;PnyqfD$Bu&RL9YUI%r<2;18Eco!|xdm%zF`Ty{7H2}8XKO>^?ceVAk>z+*% z?o34Smi+3z=Ky0G%!9p^x<(bHJ!`0sUr<6z3xey{XMbQp9p?0*QsT{j_1TXnU-3P@ zHvvq};CG?}w}FA}>LYkWX>U)X_2&V#&)3d$ZFZ$;XOn3O=^8g`D1ShYVTsBGyzHsd z8y3%CU@Q1|*+5PY$mlal$+xbLH6;X8-G?s?=9XF|$xRGXvvD|ABPJ|E9o)+gAD(K! zjUqDe?f7$4$GHbFG)*Qt{YVo7ar=qOHe*jQ2i+yg0(-j5C=N8*tt?0mYvK23t+fDFDB*c7g0*bjR>8^tGUWU6O#OSk*VAw2RNi?N$ z7rZ0h1F;@(z?~m&nmPBMA3vRd_Bwme6(t-J1KWZsu(g*WXyHi>pX+f+>|s}AWH@y+ zkcEq~d0aL$Jtkv4dR+?bIK`E?z#A)(k+7?4>>r&wM}zsK00ab^SG9yt=_dVm4Z1{u&}*K>8vr^{ndD z(ZMnP_`1xmpWdjpoAHz`!qtiE9j-^944<<9d@eLXG^keZD#JEV1!=gh<%s(C*Gxou z;DNlpWjSKHWdwFA-3fx)L(D;XK16Z~$^mcOhZCCuw}(B5JGP89#7t2R_9I3Wlcr3O zf760ItT-z1gURATN7$H@fc-F0aVDf1EYjsBGM{z(qZ1|dIR5~I+o_?ww|Nl7(_F)dhaC<_sfm^cnk3CbT{ao8W&6 zzlH*`vM~)4nPgCQ{4}I+1lu|c5Dc}-(*1n)7Gj&zY~f@KBGduybS4T{qv^?o3)92- z(-sP#DNnNfOQ=~{ktUi}iVibAvtbJ3~wD!Mrb{;;+--wB4k zyJFs4MhU!EHw{74Uli)mKN0F(`E_Mrw77jYVkh(28$U4Z?xCtasUd{`hiZ6{Utt#^^8&JJmJ?o4)NJ7udRd~0 z;fj3H;2g$sqnNucXBKZu{SVPY2TxLWGsI{}iaLZU3RfX2?gQ-4$Rb#(Y!{szPw1Dz zOhfW@K7vYrrYYazku14_68Rn$oru&EtN;lOJw6hUHgGYrd?ZKlNdCT< z)o9ig^Q6;V0mB550~z#zh828(Dn-(wA)5yxEG-Le`?HVJP|7|$DZmm!sXu*JLQ5Ib zYg32HO?BW=Kg%niFb#Ju-4WG;9P!wmpzN`=8--QGU3eMWee`BLzag-Wb00Ky!?>Z>*(9qD;*YVM!EY4R*J%^L~X~GQc|SdI?}Q5@XHbt6_vrcDz+q=bVrB)h({mu!Atv}GUsq}myT35?nO@u#vLZpO1u4YBw6$FuiDhf>r|LsRfs zAkP~be94B+-on`$7;uT~(kvzW z^{Y!Ado&4_7nSx$vB5Jho%=X{2teOE8NuJ8Am!Tx^Z`;}QC?9x1MlnAhJ-Y}ud}l| zhDZo!{aKg}o}o1~0A5ubc(2a}-Duv)nL65)&1Co^1S(~r8V^R6h@5{-$cqbe$QXX# zlHpXdV1#hCkQMtFaAR8P*>JZ#A3J*yYj(6_P# z+_p#We?!7qB8|?u#;u*2G-t{Q5d=49JQ2fGF6CcwO@_~z|AwlZl^m|a57nU^dBF>Phrynp>`+_1k6}eNiRq7N!2J8r(kX_BtMW|w&)T&azf&7;>^!W+=16ih$ z9*1@)6J1D7&HWQ>+kDT;rrEo&uaUB@dz07+bw#t#ylx+V*Zgm|nOsA)sgnYXq}ATH zK&WCEb*FmEKM3U%5~u2_H!slVml$RLcK%6)PwdjnJ17Z0{>V{QY{E#WHT|4HEha-m zkCO@y+!$<_iVSc}K-2wp^{qT}0MA4}9>#xd;M5od@nl3}jW?PMH}tABSB-v(fay7- z6$5Ws3gu0+{v_!2${Pvg$DbQD9DC|QY{ARF05VpTLn?JQuS9C+4)QVZZcu8tjgAiO z(|VxaBl?N{3wJlVJCR?Qj(T-Spim9X3sOhN!VQJMmCOkCGI?ZAvp!*m4D3i^M`dE@ zyI=%i-ss<#!&!>x$9cE{;2sbgY`Rzu_H4SY>={|)FwY@GbIAZ4XuFfKOOHY$OG)0c zV%^6F%AT0H>c?MK3H=K{lo}2pr>P>`M}z%Fp@Uwe$he&@8PIo83t5t8%_K!43MiU( z$v|?>P8X*SIZk+N|HWrPcP5D+lYj#nDjs;=Gpxa><^+~4p8^j-I>$`X~{!&Y9+vUOG& z-M4@J<~>!-4&&`q9~K(Vyjv?3`(WAU>6iqg z3pJ-x*n@>Lb`Nmf*1SPtzwKB{gP2uM*d(nE5GY$Jt z*qm_c<(xNjpf5m4fZRugkdNC7wZ;LTCGM7Zf8HD_{X)=-^7i(=Q8wa|Fb}l_y_jyOv)&r9cn`!&yL><=urW!f+&8H_@4#crQ&_t5OUp-%vYw6yfN+n>&P zkBgbQc;cd;-Pd;*8M)%dgKbnN39{1CNz~7iVXikIzpOJa!eC`wOPNnNph3^EoU(Fq zRQ2@qIKm||3Dwk5+~rW@=EH$Od4gcDuvr1Pqw|O);mD^PZV5VR$eXdCHL_gye ze9kY*jQgRbn`3rp{R8gm)7^oX7J!eh|1Ybmt2ga)!5J;7l zk#RUzWQEIMGKCquJyA4nYt`h&LmY7wHo>Il2_T+}DlRJ7%xQq|tjg!FmA|SMf}dpV zPf_yh*tXyMIQDgV|Hr8Qel6%NCjtI2!0*LLf?!az73o`HRF#4H^NyG+66bt@X<3~w}atNU)mo$?UAPds0#wEm zfi$2{sh!c0k2N&HPu_Bel(C748*29<+h%XyeeVFvY|ZXIo7L5aP#T5Opii>0)?JqiFy6ImMrt&%w}7&2PYb{_Z{H)% zd+~E9=)F_%r`vk`OFa5^eESOx%BCEdFj-x$k>V8t)aITWZ2@()>bWIHq;#>Zy2~jW zp#lEDJ08pJ$@Ax@U(WgXaVq@>qWdEH>1l}RsA~qH7y|-Y0yb{ir1$&2?wSp(@=>eS zD_J+!6mTHH5qx3BjFVd3U*b_|U~2wXq*yv>`d{9VBQ)VUTP*c-cemXzHbyPpnd-gr z^pChQQ(X4dkPwsRc%G+xj(n%oQ+1asJ54|m(Ala+Mn)8vsi>^HkdUB+<#_(`u^7%Ue(>asZ&|WDV^s zE}T}KwBe9SaB7UTw?*KyC_6A|a!yXpJrqmk321l(oF--rDvL)E8GLISAszI?57eEM z(tq^c`WAZB?;%7pjItmwYHgnuumBxB7;(=goOVtFHu50*PeKW!HUC}`(r9U&o@-XD zlmUgOfJRwN8E9h4en8LYjq@q_XQ1uU^(_lm$`WVWV=97|vNCD4>WD}ki`i$EZ<~FF z$2j4GBJ))AIh!jVH60lyGsU>e?U)#OZy%ovH?ulF3tx;_^!NIoJ2XTqdbaT#%t5-v zv`Zd~74j1yJq>B$LIa2nd1^**UJU8f=GgYO0PgWVitkntbQD(JaYgIE8@_XhT+RP1 z{CI!OUomaXo-DefbDUQTFKP5C#US-PXvr*w+erzOy1sXue@Ia$FoI3J3v*h9-+EB-F&98u~Du84fS#d z{o}c9`Zx=B{e<#T^s{u;=Q~=W5!!V(T3o{shQ8h9>6AQ4h`M#F?2(U;PlJ-wQZFyB z)oYG_IQl-Xt?c8k-uY$G=e0L_D-IoWn9?=h&Fg#9TGC`p&pX&X_s^)StMgkS&vOAl zPE8BhPgsAId*)j@ug&`OL0u@-qZxro--O#sx5gn^k!wJy{mMZfWj!?aelT{V=P`QN z4N9`S63qz2v4sm3Eck0T9{B43^f=367tz~SW)y%y`|<`Zc5rY=j{^v!`x(3X`x6b) z5CsPlSTw(E!X>1K28D&zpB8WL;eRdOZ?VuHoU#5@(%HJ|`7x7lz~)AO0_j`&vu;jrn*n|)XDY$}=|L#PWl51T$5!~K2Lt=qj$o-BLRT=l~9 z@q~}xpmJ{VXF|ugS3uT1(42&U;!eB=H9Og7HMx;NTOzPsMlhBD_1d1;>VOkx-TL*( z1=jl=lyI8&GbR?GXaooK5R_*>zXaoAO=5#H@*L%GvdcAK=l(k9b2wk|*FqcvYh$?v z_cg+og{5W`hTa(up%oPBmbWW*IyJ}ULJFzaU7^MWvcTn~RWmQd*Jk6S z{4YQC8>MNRhA#lDTkpWn0fixb5Rhx_6Qp7--!5LC|T z>nz~k*d{GZPy1{0^&a{6D+Ma@EyTe4=U=@3_4h+Pq&k5^?w|Wg$F`|Tf^tyj5ipSx zl(0-9`Wwk`Op!rOR#p;9KktZqznReqo6wYghiCFq;o}7h_y2Ly_1F*JW@#v3#Rs=w zXg?tT@^vIj$E7+U3f@0=o6ec#6A-kio92RaF&SMi-TTMKhhzF68ulk7bSw+d)X@=1 zlQT?GkiP5A5BS6e$tfRy`?Va z^8qq$w0f7@EN37bJ^`uYrIxQ>YN7qb6p1=>8aRRNab(oth9NlbTX(>*ljv+jdo2$H z0{v>Q(2vW~x!d8tDuJ%%gPd1F6`8gN*a`ouy(Hxxw;#kLNJ0iAPQ_p%rC&dFu zMW8K*D2LaGClim6$vgVNsL#~kH!AjyEyYzYFK>v}4r z&ju_%uWw>@E2U2YPOSvuHWyKSa0!JDQ+H=4Ct&c>9_WW*?R zLgHD^9PF>hz(w)9CeR$r@nxf?8)1Gnw^*r90~q^_K~@NA?003d%;kRuE`di$_OuxV+xym%v!1t9fNbMGPeLS%Od`pa0^OAz6Bro-&M|1j(GPZ0!SxU8;1Hi)|<7@<~QmItbK1NGm5?=8v zp{kra_`dHkW^~3%MR2BM-$fF6H7ATTF8Hsv{yKR-OE;dD{yCP4EaiFJT|?lGN7oMd zsC;eY@jkTP1B5SD#EXjsH(|gT5{ZPnLPG<@B3gHzb;bg3DTf$r=ogX58xhPBQYh7e zyd{=f>Mk{FrSVcB=+0xQh?WsQpc2%>FHV*%WDyCsob6@Tal+;2=DTOmYnKeb#}$n9@~f150S~^d%2#{i!N95oUqz)PX5u~nIx2@bs2jXw zjnt(uv||A@3Q{M8xBmTY&?jOjcfv@XgbnOEzyaP%B>aSnHF6rsxVh$s=&aV|&Avlx zDU7#iC_V5F(h89oIE#qSfgN&zY}=bGa^2^rMK@0my*!%$;`irL3Qe>LXMoNiSe`Q1 zB{>N(o-1gsG-&lo)N?Zckf#z86KO*EG>k_6=|Q1)J@BO3J6hx-F0dYq*zPiorsPc+ ze2o<-3`GdC#Q|VK8Rk~zy6!e)leSZ}FT87y6G0L5&Xlt%3VzS-OMT5(9#}vg&$@!X zV~%^o+=C{Wbx8JbUhawt^liX(IdompPVXrROOt?KReg4$vkP?e)Lw*_$j#C4*@DqM$HFjajjXgz>ZKgsi8uhCB4 zqUIH}7j%#kYvQDbqQ<_ay)MKpm1QWVlc5E#n$-lR zQ!@`3ugTyMwv<%JmSRN!b;^i(@2!cz2!8Xxn>BsyS<9<|yKxiwf~P~?aIcC(N`c0f`Jz_?SxDb4eJ__vhVF=# zC+uv38W4EjbA2MS4xAb@8qtcHPIq$#?s$k}K+6tn;fkpDhFM*eS5{`V*uo+Jc2*Mz zMlvzx>cHszzErJ~j$@A@_~Rwf#uQ9+ma=1LGYdl0iA#iedGnChUV!n{gpr9mZE3qh|FsuPAq3E{w_Hk~S=es@!u<*yVDjg)K3=_P@j-kQ`g3QcY zM9s(H*kg#UcCuj`j)NaqMgKojeBrK&DX7{*hruHCb}nA8gJ01H6L( zz^@uR=AuQ%5S~zr+@vafvYPsII4CqRixz(=tW=92AKH?0ROm*DwzU{bjF2sC9MF|S z4jxIOo}Hm%RU2SmT5Hj+;37@xq;Z=_n#{Ksc3vS+6~?kv!A03J0Ju3VJeacGLifv@ zscpl4-?5XJ7O)u_JM2B+v_;+baBlhaGGUECvV*c(F_gAYt5?GD(}vSGleOlQKWWij zfoq_8fzmfEQQCC$x8nhzkP_1|?i}SORM)~ob8ev?FdPd%8F7wURJ%|_h!iN`L#)vE zF(+grgP7l0T^&gY4^I~vt~}HDt7Vj<`^L2H+{?xo>qz2%PY63*gtvqGKsI`NE7LrX zr3G8*(Z**jt54MEE^cBnz6329%ZPT1ct^fKgEcnCOV^bXm4@c}x`P2N=*Gm>m`T}3s?PV(+Mb6GWxoqubEcly%<;Ww-{^V3@dp4mdXd6&}GJGZ#>L`q7kIt>CZ zxkR6sos++^*k9l(dDy)1w{7E!$hHD4UItvj|LecAd)7~kZTf$G0e`)>K~387zrJ)< zdTZ(b`U2@0^`?{m`zwcKNIU=cSGLpq_htUGBL7{Re=Fm^b@T5^{C7|NyAq`THj00j z;=hgJ-<9}pqxg3v{@W=2U5WoTivP0`|7{fiF2#Qv#lI`@-$wE8O8mD`{GXNhZ=?8k zDgJ+L6r~r##GGtsX=#}ktUJu}jKn!2>2mM^)M~gnzHEj&!K@{*#bo`? z_|L4PV|=%^4mC!(bjEzjFswEfKS(+o931RAG&Vd~_rgS+gZP*+y<@r?&QWa+*K_ae zFTDG=)>(#RYS-A{{6E*Qe&h1x%f77Q9~%EM=s4>8G70ep?A_!i%lqP~cH!O1)|4BD zW34F}x7$+RCnoxAA>SpVrluBY+bHtojqFoX{2whn{rQ#ozi$nz{jGl*y{O#Ap!IBS zkwl7r_vX#P)-+wVv9`2;s51`djf{*`)z#1Ah0Dv!O@C$@Wt(@L{$TfekM;*U@0lh^ z$+5sDO7h*TzEn)7D?*RoFlbBF&Tv^6C*C(AB4Tl|Kj7`HZ*gCeuVv*=mhX6b`Q>Tr z&qrR!3^zu-#Ya`TdKK>*ADf$d8XubBMxKSAc}H&L%0vkpKCzOvHp}IRQ{H%M&SS@X z@BVFhMsIy4UOu@R7?h+9#duDZQs9t?^Rn{`#vQ_ zeBQMq?($2+w3+KUW+8Jm&l0@%9z8$N^-6Eq^q%P_iM;&BLSkTT6F+ z`bGcC?p5R9(9rWS5^is7ha2a_j+4%=IgO>{88k+U@L6^hX%^TR4cHXy6-|Bh>c9tw z30B-tU-om4Wdc~m86Cf7$)OnPVFs$IhnT=aa#aJLgJw?AM1I6B+@rfxtKnbRWb{It{zmSd&);OIZWA{E z_pha637@|YfAceLh>-mjcR4_u*lZ~`@+9W-7yF*}_dPw4nrGj8(^2P$TFUhtpWTwH zlld#IlV#-Nn-x8sR{rL_&CeG$Gc%L0cX_gl#h|~+@5{T3LC)7K$2$x7Oq*Y+h|Y)J zu<%Cpx70Du4Yrl6+pqpHkvtP?$mTZtWuJhtg1F+=Tg%mw>ofw!^-5(&y z`jq~7;tN|Hx49PUHf@K>=GW(%7A<4VIg>Qf{HxhK#B|)3233lG)=v?)=)4~z-61)D zU;5+MzppGQR)2Xb*T36i@m%nW7u9&{YnH&-)NlA$)2kf;mx4+*88NYc9tT3v` z%F2o@blMU-his`}RktBR@ag!kLb)`Zk8eCS)|IYbXGA@jKg)@Bo&KDUjl?w2Np-8I z^gf@%cxQ68sU7_>P3pnHL873dCmXc=r6J=u$nN4;Wt zu+DI4dN9LnWxh!)RrV>pHC{(d!LjekfcU3lvQtgd&W|<3r|=1F){R42L$wfdQ!bO)sKS9FKgRI zT0C{THQBqvvP7KzgpO9)uy*Fni^r~I9xk5pv#dZ3zCi@McB8)?p8UmjyRR$R}}7Ivj!eQl*b zP>$8Rdv!<%>k*h|f7{H=0Bs|~?)O*6KN;0;oMwis|K_w+-P^RK?@ag76}vw__$;%| z%2dq%?RcA$KFSagC{)pdy?<=f6DuT6ED_(RC4KJeS{!SVq#(@>s}J$BgwVj zibN+C&084xa;SJ?ZDQE^O@C5qs{aceXRa|m|7$sBYDIIcH?9S2y6B8H*`Jt{>Qm-P zK73?-?HyWiReiX?TND`Ioge8x3T#bu+Q>?OO= zub_0}2Gee_$+LE2t;f^4-Se@~M8nXsuB1ba))u9#lwgANW2*R%r52`2^>r(@XWvrU zx$oow_eoDS8GCzs&s5p#cgH*TH%V@|c3OR+nu*c<-T=^rzus`;N&Yq2ESytzf*QTw> z*P=QmN;cL-Emb#@zMp_?&^!_)Uteg|TmB={=+YL2Px0aZA1FnNRI@42O4corh<2O* zx$pEH&1{QbqQwgzCn|v_`q1I71(1_WV%yu>^D+Gc3Y&;cf+4B6H!7@qeLnA6fR%!L z)>&?%GZ5Xb*loply>}4xoMqhLgG;LjQk2+_d(dFVN)o0a-^ILGzmU*~9i3eLZWjS- zFi!d0*Jom?(Lpj0XY&n3i@Us0jFFh?@!V}pUvsB3pU-*z&;BN{ z8HKJkox;23v#1uL!irMQn73z-VC3HU^+7Og?D=E#rOFELz5Ua5CjzYdt19nrAf{s2WZM;NBHFzi z3N_tlNzGo{?`^tw9stNZL$B~xiAhQQgD-Ub^*=q9MKd=nf4F@L zUCdaV9=8U~g&tM$-qr>0x^qAO;Q*|9`kdTg@y6W`66XO2^q3^T>R3R#BDucVYzRDu?Ava$hA^M@jC z8vw6f3)u5yH=BRV`fU7E^SRxF<_$+Kh05Hzb<5b}5XOh7{H05VfCJ&lit_+@v?Ulq zeLg&?UPg7HM&gYZZT)^{{r!<~D7AQbG)&y(ZtL5#ai}a`MnUe{x;ngb`J)|gbxYhc z&|`|yq8_y*X;k~}7cc-UFz7x%674eX4e%V___s-7<<6b%VsW7Dv;BujWF*EME|s{* z=|>3(D)Hyd&CM~=NzaOZ6*^R(aG!dbKl}AkKhToDkB?8X+~#`%UFhWfW#nvP;}R%X zOPlWX6-$-)D-F&M9S1`+44R_F(Lp|kow}tw`?o`=%VpwYvRuM9qLewgxV+Vp)Q!X` zNmii=DJg!$Ou!Txt~b_9*OPKxDC};i6WSfG*In#pjSf_e+mp#USkmdSu{Kq)SMk)M z=%p9De&`mwXtQlSw^^D>*5}ejzQqSvZnhZcavF~MXR(Ls!>>%2)Mw(9b z$NL9P(W6r}&OUY^1`mo;4k*}I;H(7Ex*zXm(;1%M>twluBsVl0wC3wSw_oyHLEnSYp$aw8e|`#31VwpI<)jJhH2m}Fz;mx>zR5pd z$Un}E<;tYZl;LS#7+hTsBbO9->mrfo(o_(#Ff*0EVb?u8;~vwY-MADvv*bFTw5nNJ zT`d>8v_0X1aZ|J(fXr*4f2|IoJ3pv#(?2yvouS#Y=fR5;x_!8p7}PR4I;_gd%98`1 z_eM&3u)Y+stf~n-q;F<+Jyi<@D2=O96%~F$Elt6$)|6>fXEi-=u^{)>&&(ree4af$ zdWR1mK5*j1ZYL+F3l}b&wX!-%d|f@|`sbFR0^8wq$0>t?+yq}?|4(??sl_S7g1nsc z^imA-bdx65&W|n(Cv=L=o$h)8T3WuHom%)rJGPYHa3&rUNx%slLCb3FX!HnHg?6Bq722^XE@aPR_H+%3rIyJFY~Deiqzh z;^-*Mp%8Y!a_OO}sB6%-@$Qn6^2?iLDA*sW3jX;h{qUc~SJ2Ztpi}IcaFxkr{*M$k zLx?I3JHB;cFgP;O7p=Cpr_6J5X2#Ro+dJ{nL41ch1dEZZ^YOZIJ?0;Kh`em#1$W|} z;wCY(u&6zk6cO1!+!Uj6(L$O#0^Bj=_MBp=)S_3ML# z1TMz^3`#w0q#og2LY7?*U%X&gU0WMuTz&TPQ+`(BvO&f!mcw8 z;}u|Sfsv8*!AaTKw1Am%D36^xcMc>5DN0Fgij0aHyng(9RTWvu>hun>UCb1MIUA|H zZ&FgI(B}Yn$yv_at-u_9799K#>|YN90=KNEVXCKWi$Xa6HjK~U+a6xie#|0!AO+M< z#m2@Gbpe=vGz1BVaVy5FyjM$VMP-eQm>$zizqjPl13>&E*PIFXi+m`8BH<4H z>lqk$C}7g)I=}S%`JQ9iA86Ot*AHr($31fuF(sWOs;XGCtE-DL&l)(2Sk$VjD*5+b zL>)ftt_|Ut`lcw!S8dDuWOdaQ*9v4p+P{DQ1qB5e1A~KIMNYt+tf)qE$HmFl(+~J>3UBkn}vjYWXcwJoiV4xl*FT{r<-&H&mU-Myx7(AVBC$AN&FW8|K5e;v z{d&Dfgpj2_#2fu;f0i)8+w|z0PI=)%maNP3e|c=B#g%hn? zfiz}qseT}b1f{UDwk|7jnn`z<(CI98W5P|ycbefqi9bSb4K3)~9J9FS28s@65Qlxy!Nnjj8~0$V5d&52~r2E)Fs9XOr{?{0~fAipNg;?26jfc_&Yy#B$=q zi97At7gNo_4E!)$`aCvPVw5%Z3-R&YFDyKB@X(IHY*U(<)6j6FoSi?E7f9wq1)JF_rkp_RNt9$kr>BQxOY${=hmRk> z!35j3nv;Fyzu?47CA!7&qu~M*r z0mju8E+HWyW=Z$Rgpy=z^emGmUXAEPc@>qt-L5lK#T)A`f7)|)c&yDaKvRqz&Gg#* z!G4U4hbM_YW?1;jc=0V_!P4JuDkbjq(m@t6N9t|cw(%RD5)}NBWun-X3wZoCITJrb zEvNf|mk;3>4$!v?_;y7GgU3)O9 z&z(D0Hfq+M&1LcH!!}&zkoniIUr(Ag9~c-IpipNZK2l=bj~|*{+e0NZp`rnM##uEI zTfWkVP9cMpmDS7NUtQQlR{8pMN=r-2IL!oAA8f_Xf>Jx53f^wj!+I)YVCDOQFZnyPe9{k8M*&T7( zocp@Pw2{-sy7eO-tsj#D8J#N`bC-tm@wTBN<4Ps6(IQY zSB{O1^`qI>dmg5ZO-R_jd-v{D@Xz`V89BLrNbU^j+{9;8l?4EiQc|L^)Pe*PB6?sN z{a6~^%Bf#oUOwHpfiZS4g+lt=IT|*$CfYN%TaO8gic%^+!EUZ^Xb3mhSnS^&J5Xdh zyo*=2xSkf$ye5d2JeQMX^OrC8)6!1Z+1WW7I{f(|<;j=04;mXWT48b+bj7`Tb!`uvDYa38Aw!6>Ki{CJfqdZA@-eB3`f`&3sxIw2bIxm!-! z+S=jd>uFjA%D0?&xKU$ha)#3bpC@N$Wq=+tGc&1C?s#bfd@(&I$LP99xT*x^-MJjI zmRi^1^mJ;l;Jq0Ku?_=uQd{nA$C^)9di(lT=z6SGG7XQ8`gDDCd5i8^l#xyO4+Kag z-iPQKkWj-!Y&pJv|4|r({@>fz_W%HmLi3;d=A>O_T^4A|ig%xv| zSBNy2T$m#39=&WpWph|Y4RoZzRiFfh2(M02&8f4pKY@z5+Zt+$i;IOF#v||1(cr_q z;|8mz+QlkX!*n!6KErnSO2M+o68dV{w{I##4U=q(D=Ymdd-=K)v*f*J85tP~7X6^* zb!=>9(Vm%xmqLLrUnW^yad2>m69z%J^D|Sn*EQx_y8gL1x?MXcDbua{&r6vdNECEm zbtDjy$a?AhEj_|lN_~Fd?vy}aWQUM1bVX57F<}cU9edyfJ#+JvQT_{bK`&p{iM?;e zVEpjmgM35Dt#2Irn3!g&Fw1&DH{=_%X&_(jL|K&n?Z^v^it_XFqHuI_(g!It{T4^{ zjqhXvqk@9MNxPA&;e652(efg#97HdZ{PI70$Qm2l$8@|yym=BFmp?{BMa45IDamw>`d}`|v;M~VnnDH?f6U}ZA3uI9RSPkn z>Z>I7z3u8kw?_bG=O!M4Qe05$9UpJZUQT=Yl8I5sB6)Vzk5RCE_V+iZe&~zan06*o z=2>6B9X4x9t<}a$s`pom+TG%pm1|o0bx+ zlAht=Y9=AG@0{R?B)ykq0^;H<)d6f8`4Yr}Kl4e&0ujI?IXO8jui)-qMuNO-O8SRj z5eTF!l>&F{>sc&?NG2xfy>ku1_lpk4xQ%=ei|TiunZ{B zu|G2_E1djzP;D&Qs%DWRpY3W0kH*&I$1HPvQ-#iR+$x=zjayS6Qn&Q2xVooX^-7nS z5e4v#yA%+i5*>YOk|(v=7zo+KyS=F1gKFpSN&hcl;5@1r9V}uvOdhjq*&Ol!OsCI< z4S*1|iGBnGf0vn_oh<|EIpaHB+MUFFn1h2-la6Tp1D8{UBzHP6`JYotZ%*@uOP^F>w1zI)dL6Xih*dmOsh$x8db?P^%V zp`M;nS_U?@w5!n=VJ9muhn?Jnxk@=`&^tOxDK0MFC4Aj4Wt36UT`W60JIny0IhU2- zpZ5V5b3t|{t3doewYI81G^0@R!-DmqK^Ixyy?Ym8r>CC%$jHcKsw*W4F2m%)0z>jH zX;pZeROcS=4BT%Eh9Dy=>-`U%pEhc~YQG5=K*4S>JwHF>mywYnm871sK9vVkoiI-M z^LFgoRaN)mgi?vS+aoj8SZw`@swz+o2FIo8BYXDl4GaqM1oMY)Bc-Ugn~aRCxvlL9 zur)U9&fB+dhlPc`|6r$l5k}SlUfx{+Y?4(l#ff>3?RV4I_~6l_AK(`>>OHJhk*&$wzjEeCUtkMTv2j1U7U3htWOW|jq2L(+*j2Rdld<}ex zHb#tN%o&Vh&}mO78m}PSzlYjRT#TS##F_L=`HL5q7Q5WBV3?i6JAuiX-oAZKLxVxk z?E6_yGAccN{Y^|vOiC6qhaax)?H*NKUS1w)NqPaSNwnDXjEpiEFLl14d{V#=+fw>5 zNFZi%%{T#7b}=b&M+^+y6mwtQ2l4Zqv-5KG%nc`(L=+1Xd^T< z^f6jh|I*B`<5b@^EGi+yfWn!YnMupZk)t6lE{~;sc_p$y9zJ}y zF?(rbbo32Sb9#FES(sURw{9i$`Oq!&inHJ+0L(o)ho3)x9T4JWIs9c`jvn&S&edHb1QRoFQzcX_U&ar>V&8y=C(`= z6k(GG4U+uEjT^IYb*@~wqL5^>w-*{v54>djw3MkSC#$&gLy*vL2Dv(en>V+j31aq= z<7ct9dtMo|T)1+j3e`Z+L3UBm<^G0DY&wEnx3oMWI>0GY5`>T+9UTP0wn<4&ln2?% zN9yIxn>Uk_z30%B4?-weT3TW|>JLu%C?`h{Jc4kP2&H9obTpASic<|Ur_1%;i^0S7JQ{*&^N!b(7K zgQ`tFq~>v9aByr48&BtCEhZ*5IX!r(OB2v@b@rR$d!@IJDMH+S zVr{Ia`eY$`l3`y}!>=f{W}cY`^fhfsq;sAfxsR({HOXwK&7elQ%-`X(ycH1tX*C!u8 ziep@8^^$Kp%E8fxuDvm$xN`DK&y)4+-9e0k7M+WR9*kqJPN+G9UHY?%FHfx=7Zg-W z{Y&^L{w!zSKuU)UMQ?sK>L8#84K?*WjMW}U6!l4u+^>Fg{zqR2tuM#@P>R38a-aK1 z$j?VR7#t0;^_vSFEX!{HMyL#UnGo8;t+8TTtF7tQ&s?K#9g{M+!eMS^R!e(y?1N;C zukTI_!09TuX5P-1vtYOsZMi4n{|WYk=~ZRAmXsSpahpof^AO8PIk{j*sQn*Z7W{v^ zw1V0b6FUm9X{HJ+Lm%SWgEj+mb3aHo)2Vly`>UvK-n>}~U3xNtLWxkGrlV(=Az@%- z#=Cf;Sx_H&eP*8cbGq_Jp~DFnc1Bh2ladT!k!~!xAYemWOr*Gr`p`T|W^rjahG+Fr zdqsr|>^2ri%b)N{bQUL|zd+}uz-SMUT&I8pJUiC58(OjS3tsK8b~K#Fs@%sNsGwXa z@Q7u>rFeqbVaa@{0eg~C`)sHN>;ZVRTmn@XJ?5~LDeW)bDtGUF&wdudbC_w`|jth~myhK8%Ex)m)Q%%>N*Cw>nP6mTG3 z0(}c~pAZt!kka$=s!@VdzZ|-`X4g0$Lfjyz5_mbkha54;0t4>@T+7JFxULp@dv7O$ zWet~EqvmC^w=2y4r-*VKIB?*eP-wsKosL{8C}=dVGdEs9`4xAWF9lib4gZT8^h4k2 z#lUI)_U#ki4_ODXI79N+#0Nn%MA&v{=fo6m5>hY~6%_|KIEMNuLony}30oaF@4N3l zL5YEvDTjZ;;o(q>J|@M$i5?p;e30%x9(uzP0sdYhGWpgByi`)Ng8gh5mJ{WVb zdmbEELKwpjZgj1$e$+deW0jSaL>a)Ndi3lWb(d66GE|aDVq7^+lEAypD7-CYSOvvXnO3r1%M>3U|HRA7OP+62RXjqE zm9&5wo=7!OXkA_cW-%D74N;hQ4FCgQj*w#6Y*(NTKs8FJ-v@<>=IHU#asvZy>fJi7jFvVxaQZ{0Ky z^z2zFNZWmoCB|>Xoc+iw?zKQ&Xh})kuW!c!%OrVE5X#=HbLRJCsG+_dELosYGpz$7 zBk#XQ!e59C2-w{gugG=<0RH<%NO<`E;lFo5ITX?%g{p z+`eH^hw=K0hxaILRHGJ$aP!zl*RgX0^HR|c-R^dvh%7)3A^`@!>UaXTS`#p1PLT5w z)+NvM%fTxuDk@wn9Dx_|L1S&Kt*v7k7GNNDord`;>rVIZ)AZWrdp8PfViPZ|1;C)- z-yqw!Z=V%nU~j&wsj60(cjgBIqQ|}JR#Q$0ekti8@ggefc&)pe)yBG8V_BKh_ld#X zyKz0d2M(O=b)#N!XsNIF71F&{{Qv_o^6As3($!~@tHWJkbrhi8?O6A)0IG1n+>8C5 z>;-Pw`0ZPe07iRz@z3`5&?T2fYi5%>cj`ONo0%ngr9J2aC#xt_gz%f$UT}!Jz941MpWP&R9=tS-BZ}H(0XOOa5s=fe>EoM8?X@?%LW0g?H4} zjjC8evY3!))vf=28hOz7f3iOg^>~zD_;>8g9tCIiao3fu(HMsUw$? zl8TIoU{ujYzj*Wgox*N5iJR_h`2__DAGE?TfC@mH`2SvlEj3`a0!eGwTm|~tC3*Qh zrV~F>vI<-X4NXl>Gjlb%IzH+HI+6#+R@g{H*-4qblHeFzi_VH( z$-DDY`L$RG;exT8b9)WxFl>DRP=Y=MV)lW!2yW+?NbdAii_myoSyQ#Ch}Zm)qV_%u z_9$T``*3X73n5B;aW?-$qO7dyAE)AR1pj$1z{zMyk47dTY!v<&CXCudjkLy&D#C3_ zyu1?$V8TL$+(raMy3}HVf5VRqJLA9$O+cpZVg)w(J&Zep&V1{9tKJ9ilUTNtqHmwH z?vt4vZP|hN!<(UXWx_H*w`a8 ze}+M_ki6KNdw?Wl(RnW=C55w^9a0bBN`qe17Cy+&gw42}@XH|F9+WTksH>?dg#n=Y z{01EyWkQx=7PY%D+aIMkI541xd%K7Tq!pTM*^DeYGf)gDLYy>@D%U}1HlRs_xEUA` zk(hn=(7}Vvv6mQ#C=7U;{O!DhhD*`@{{B^PaUPvG{}?bTZX(wwH#14hqN~UoyQkLo zR$D5IoxQzm;``Ob_1y#zK{W?Q=RrU5Se<%OALcX7ihA75%*@;~IQR$(fp_i*p0ou1B4xER;gKuPDLjd7Y{KH z`em0R$BylUninSNQT)E`YP@$%yd#kEnznJt*WQ=zps$f(_B(!iz2i5+`2AQ8Cg%Lub?$*$keaN@Kw|vDP z1NMu|@FB+z5$nFKa5D!I6)$YxzTL{st^za;P%>rI<^r9Hrsn(X`}ce(cJ7n`5T@C` zKVeikF%kI|_j>UV2ExMW}hYKB4@?y1F_dD#qtBe z(@+Ky^iWSIt^J6#J;-jtcj1#lBk95WJQ#R?Au=*j4>XYpH7`Mv$khSa#fh8}`kVeh zP2fSbcdlTJnW{=y&O34H6fI~&uOE}7d(l@Lj-y9Ep?)ug9+T41iT>JdM7$5d z%2C2^hC+^jCt}SPA%@AEX>I)cS*pZ+EgjjC6Z6JvKr?RCsQqsk#ZbDE!_twW`cfp!0FY8Eon@9Vq?U-2u% z-Vf*d{rh*mb^qfF|9FUMH!4M+9{oqXJL~K$3RG6cBm{QQ#YAV6LcJ>G?q1B9)Si(K zBNycE5!x^^fYMuEK$pUT5z2ic?<0!Cr%%(vouR#X*F<)8s+x_^emS>1If!nXXQ}(e zqNiVY7t;4-kg>MuW^5thgccS2XvVEt7XgZi15XMWVDvSgKPx#?VHgl`7W68$c?lw< zg0VCOVVv^oIuH$E$4j+yYy?BSC8`&sB9V6+cmvWM=j`mVYt1OAsAM4oY<;=2uiMql zjqhd+wGvt5BV)(_Nzbd&^5WDK{m$-^%R!GJ-_2?v7a9m#!@|PAs}iQ zhl6I}-Qz^4oGCsw_7N6e!zUzn<2Wy`|E+Y+Ne2%TqpNuq+Hv;}k&t=cR?u#IE#Wt| z8aIpUr-djo5;!I%!4u_atU_69D?M`D@yhKy0f54mc%EqHU2y|0sYQ`k^Loe#M`MFyNgi;6w5jQ{=xC|I=1 z+9v`)(k83mxFpPeU}ZPZD+sk8?-ZfoCYVd21S3g-P?foxnwkQBA7rjej=}&}$U2vm zEPN~*_#pmaD5!wQ^)|Cd+g`ur#$oY zkRVyU}fdi@Q4oz+6$ZfGgCD`g$4!gIZU--KU;fywOUGTgb_x% zJ{Fn=eW-aJ8M%{?T{r!eCIXs3#54>HN6os>FF%WiedHzz2N6xq(J6OL&3#Z**d3$6 zK!}rtbbTBXH8mGNkX0t#zk~V{hyj`g&8gi_A>|XW(ax=B$6h+R%2WFk=#p54Znye! zrDmqJ!|SWbZlA)Dy{)=)*zA;ie0)XL0G>*myT>fURJqkS6`j(D-fb#XQ!!#C?Ih&L zQ+Iwmt;Bn%P1OK!%#yUMMsO31};+-I_p`n40 ziK?-JjLcR@_ymZFJ00>DwK39>cVgzxr^lY09)jqauc5mDbHOrW zM+O-1fKV5ZI}QMrL1^Y_rs&~>NH7&os5GxpgXy`s=TYicar6V3hjW)M?SMmAQ(G&I z{z_zC`zm)pi6F|iD_lZ!*yopa)Eld%jzN@!qNADCwJt_t&VqndkEDjGhWc-T8Q*he}mkiSgBDnj44K@n&*Bhx! z(f~n($P)JQ-??+FufN}^qsV@bV#e;2O~5##jFSp9W3kM zr6PoN%Y|&8UWUVoaH|w{4e>FE>V~B%4aJ=ZQ6rB5&gLo>1E;qPOvrk;k%e&PBqVfF zUD14`K+U%nhyV%gfLd6TlrHYE&J6Tw%(z%{@c3~mID87jCPakBT=@ul`mXd$YysT# zZK>y-a8$XG7V{GM$yzZz&2#6rzya;ke!UE#`A5F>+Y!%GgpLP0y(=HCJ$K|7B2>84 zV3(7xASyxI^CTQ6?5jnv1U(peEG#Stvbq1Md+OyyoT0!5uI@Y$6%pY>w-OI`n0FpSYsk?+DAOq0@m$^gUpxt61b^R!dtgdQU!FlOu#|z3WM>YjhHh5na0Mb`0+$(8bwEk_`~u};!%mw=NIMZJjy_es@Z+}|;R4;~VNWdOC$TOTvZ=v; z>oFTZ&~n4b#H8BJH5@w{ig^!CalKbhiJ%CfIariv6DfB=trhYWyq>yMaX%j)&?M>D z(Ig_$#eLYHAZG6@TmVvr2L~&2EW345*We8e<9y6kCo19|-7+<;QBwqfD?rfE`pcIu{2lIS>3QyJ z&RuPay1Fq)vkW!d##xD)+pj2(b)O*R<1;0GPz^^92%moo94%j0K%64#O2aXa$R|(8 zp<;14q@qKm;+ypaI3-X3l*dyP01d;q@h6UpTA-k{K%b;Vkoe1o17Zcox*sOkLW~$B z49bZYKT48di54vZOgjZE5Kp22ikM;@#xArWv_$0F;7uHAA1=%9p95$*A zVcwPG;j@}J{{;gKS!eXpuM0h1w1N~<8PLlzjoye3$&8yyHh%cNZTiM?1|7yt=m z&&O1(wSe1@KeNd6&%Z+E?T2m8;QsUS@Lb}`IeqJ^jBzT4ll$F53qs**lhf2|xsXompR3r^Y;*$+vf6ESIFM8OJdj%(##edgBn!9GdL9>$do((=!eBt?!M zebND|#{|)TjZ^?YZhPHpB{x(Xe*KF2J$I`$IXv-_S_D1{|KAy?YqDv7K_0o+e0{hi zB%;5ywhsN$0J1A6UKp@mU9^sC>j2{J)xt;6ug!6uGduDp+;w2d&v9iwWn@lG@L2WP zdyZ>f$J&H9SrJ4vnQYW>dE*KHav08oRIG-Rl~OSar)#wpbBnebG8-+7sU1#^N%65# zNIXUq;!3jbSje=Gx3_+xIRv9OZR&v;s}|}N3n#|}KOsKG%gO15#bO!m>nq2`j!wFf z#~YuP)|8NxWDD@8g|jh)sBVLUJ)M9x1^WeztzLFPC>rodu>Kv7VVHqd$3X<+>Vc%t{`|IC052qV=}z)M2b(J&~xGeArA&m@F8MGyF zoTPW?&|ChPv96D28~`wF29fSDW)0T9di6ltz)@@)700i1sB09s4RDP~Z31-6=B?5( z0>G(5Zt5Bu!$_;t8Qr{D6Ls|D$*V(^Bbdy5EVk;cn@ZvE8i{t{M19bEd#uf~-yUpC zOgv`VwN*B*{eS-+ch>gliVT1LeER3-QVBNfx5fOj$XVI$MAtJ(6m6eYir1LV1h>YkkJcO!K1@Dmt8}9E{>3VTC4ki+> zuy7a?Kzj8;jOLbmMsx8ZqM|k!vLR6zxueFc<2D98~-Yd zuQrwH4v~6d+?Ty?#Xv^nayEz8sF0Im-l0C*&YhVkM#{%7R;YfP$qH1~3D8ymQ(86g zGqdLM1~U1Gw&N_oGkHZSf?cw!sX{IwhGIXO>sF#0wcoY3AM|rt7-xY8G+?Ho1X@vr zHXUY=ghL}BbiL5Bh?rr>^(QzbimecUq=%!6%Uk%o^5!wBVklr(=!^(o@i|T3R87;- zekKOlsuCTQpif;tpdJ4stBMw%LVA-h5Wr=rnVEf&DuWX(_uJ{zsZ*0UbI2|x7Wvx+ z-I5jbTg{o}7zB!q86o7ykoVU@=nR9*CXXxdLJ!U}5P=lH6orob!a_WPLS|em6InfG z94RsKF~`#iP`Q(zc1xbc5KR@s`x0qq;=mU;N>ddw4rfzOU#!%-eY=hpmg?HirsrZ9 z1Oa%`Lo`<|p1VSv)Ph_-;9lb1h-X4rgRaIkjX^$xR_GCYrVY_Gm~mxHc{syx>_+a+ zJ>Ks+3vOoQ6X~W3|q3+Rjrugt#nAjcmM3e zVY|zxs^Rr%!KIKj;e%Bv6TCmAW>0;s~8|g%RheVM~wa){POt+vCSW_P_nl z(*t;dt2;WF2$k8C!3u-Otyu4axIoysb7SEOZ=taRwns%jb=*PFVj zcJ8F6rY1o|)x3T^G|Bv$TQA%&@`LNNxXqhht?k|A{&4Q-)w?lBumVd+@C-UUmFeYm88jL%wHyz!k4`V zc=`%gJlJ>*A}UC?0U|~UQwWLTrm}e!J}gms&@De@kBDG{`J)vMIuoKI3@qt1!wq)e_(z_+YNf1JUZ@CHsUB<5T^+7+&3HvIQgpvNAA3#=g}l4 zet>sD4StE(lGkbKGMorU{>&2$-SQ90P4>N43?v<#R`OzVUzF<2g(ZzMiRE@>BSf6k zX3(cxMA8wDMS&$%OMBbWG5`+QBl1YlYIaUe3b1a>NA)v$^tOCV{2p?j^)0xF*62}@W6;xG&wYD_SPT^SzsKe>1jGbMHHE5HL9y=gx zH6uzD$gRvGcwdZQ1plgFoYLt;PG!h zs6z_%ItWk1Nx&|9?oEgP%>v|Oq`nw)IL*Ve0}r9n`%w1t^XCM4*Ws)yuinPRJqG{T zq2)I%Xx<*og~ZTyEUrxsFo3CQlKN$11?1%sY30-?^wA4nHNeS&!HCHLPh^O2T>J&s zU7Wks%rf><=1^Gv4nj3qccNsn>Ier1M$x&1f>vi2oG85HW#_8_abY zDJm4Hs=SV}b%sLMYaqMl-ha%#zb~8ZVzAx3haEa#FE)|Fa5g>yo_DwnF5lJh&)Wf= zh}nvV)jYhFzJWuezIcXIu2#Xi-=G*d2|PSD*fn{eK|`&}Wor%0KYX`}_O_|17j%Lh zT7d?{DRPv&M(Rv9#29^OZ^Utl_FVI)&6$7$IK3N(q( zWI@LX;HlNX-fCM4WuLqtVID!0fUp+u+KreqZ|e(z7`JpcUu zc%E}!opZSF@AosV>%A`1Q-9sM&>iWU5$s?5i##g7AixDe?pr3Z;S(XLCjD)9)hjLrFFfCU4NA2O1Pu8yUVvfe45M2WlsXxpd8lK7E^co772JEZV-Fqu8 zoy*38o?3HN2+q>HDGk0PsWXA3auqZ-U2p`5S$q8~1Sbi*yKVST!a;X}Yf-!s9>BX^ zc85$&j{iCbr#6wWPuZkFH7b_6VXUhpdgb$DuENoW@%;qtzWR9m^<+LCRki~`;7_DV zv{KL#Z{R~jga3MO`Mf_a&~BO^6xc-Hi9^RPAbt6-D<(32$X>k^(Hpp+YcX(w)J_l zeqel!G9EDxX{+1*mgQ{g=m@Z=9y^77V*x9q^f?Gswe~#qS^wd|FzQGDZuQy2sGufm z%+XyipJiC4bYluPrKIHpMR?DDR&G2@R0ISE3p1Qv@T{5kPlF)t>9@vRD1&t$v3?P!H9x&0uU4kOR zhO;+|c)B6F8>fEnDtTh@T@g0m{z(|B^oF%tdY9k^G;ciobm=1WvDi>|r0eVIw0~Y( z1_Fo>cwDzUAzDN&nbGA%4B1|j_E{z}RL6>X=qphA=)n0Qo3l>REKl_k1lakdISMOj2^s@z2L1;fN#v&~AHK z2yfy3qQ9R3c~$M6F?cb;ycjBRq)DbQAtCH7=vv3GDt52s28#=?vZ8AFu+9ALg*9<3 z$)rEQdb{*_!kXhWa*_^W!@cT~#W9?CZtW=G=}9{3M3g!&@o1U6WF9%+18S64x1m4ym{18C9>0GQxxNTd<)7#m1?h#VO` z;SEp=oTQWhm4JW0VV?=%VNkM@B9QsZLtl8vtnSEcphFuIbH|+ZV_T;pn$%;&I0K@k zf_YD@=AKI1bf|<+q9${YtGClPGP?1fRT}vNr_q`L(mjQG3XqZ&kX%^Ra%1kt)kDUO zCQ3=(g#Y2L!toU46}}rf+Oe)GrUvKnJK@<5!^ zJoL1+OMyZGFXz!astoj3-m)GrejxB``Tj#k^bcL`{Cz#%CHPHpXG-GPflHQGJ-0X1 z`|N-5qqgfp>Yr@~^Yr#}pF!&0{QSJF>{B>B9Hj@)(9lpdn??Kvn-I-f>;3!7B?_0k zlzyfri`#%rR!^@e-Br-IILbuW2L=Xq=Y=Hf$I-m&`I)Q4IwtSAW3EGqiDQpZ&W^bR ztpsrBCHEtZ1OnJ_JHCZBjOBg5kD7~SyR0VL=t~raH(M9l!JDE0Z}Ci?XBIZmyZ_rN zMuC+@JYw|*K~~qHfqiNhumBS6Yk#C`QIteq6M~kr3FuWMV&;Dm1)z_G!d@*P< zA5nu=$Ykb!P*|G3;62+HUl^e*s3#eFFj z_6>hp@1Mt!g(y&ks{nXb zLGS>V$6F8Q~3>rCmTn79I@&H&uuV769N68$Q zQ3Ann)J)9&)TwLujUVDx*_7(tJG2a~n!mwJK1yvr+y+>04;E1o%snE0e%^UxHsax6EZvlU4 zs>=QZgAtzY9`@|I^hx}Y0na3~6MDG@d|_3a&OogQDcA?;en1YCB?W`XKXQ{R(yX0d zyZ`u3QZ&vqA>?I2qpJO)!grit0ED8fEK1z^#Ly@`q^1*h&sY1z*MHV|?i2Z{j+hyg zd-OC$ID_8HdLmB`pIis%{0*UryPIhrzYVRdT-11sF+q0`P6e# z1XMn)P1LwKkf2};S1_cc3GQ{f0|2t_fO(QE0TM%lJH~2pem2TktB#$aPrkC#;y~F7~X+O@TMkOU3HER{e`BKR}hg4A5 zKT`g1d^iae(?8$8KO9Uz!jpexHw?1xj-T|&)KeWhmS?mEoI|yAKXwqOr3;$TZ%9h> zcSV_~0&ri2`=qe48QpFc%~MUN^GVE)DV6MYlv?z(qVIk=8zdwpiQc9{MtO{G?P}kA z;uIqSZMm$*lAh0>&6~8huGIizNY9ob=-ObBeq;@r`KbMRW@rVTy7Vkom!m)=W@Qo2 zwYc6VJOgh?tXe(z^iR;!oc5osORP&$Kp-j-u%Qsla43UjsQ1GG_@W-t+QX_~MBZdU z4+$;F|8|rQ|=@M)~m< zts&(W+TfO%&US$Ajqr555){jp|NQOm!q+-Loo-DcJ7MjVwYk&yxvSVhs%8%g0X86+ z!SP^sw%$eaReosXswEU`NB}^K_uxPRg`{-Nd9e<#i&#JKi}Z*qK#dG`7Xjc8Qh3Ub zPW~pKE#BrY^=;nzqZ49USFdD&gWrba6vhpzUI4H~&B&;=e6buoVe?D; zxHr(0t8?94w{CjQG)PIZM32qvj2RutD}WM9Pb|Fo;PEX0b!0#|S#8VIlU0m4^8vD* zs1RccZ+mejf6Sc$x*KC7bi{vt`N?@hQR==_RY9X?h+CVwvL8bln!lZ@8Eeee3z^If zcyE9&wy8^IUE};g$pzIEn-;rMt39^gG^=&afk+<;ZdP(#g0p~(Etpb897bUJ{Q*sW z1uzn|{lH!<^WNEDEP|Z^0_t({q(neanXQ9E$W;+GUO@*mPV5r4t7jX4tT#f}i?)do zg?a$2@OSn(E(faJ^!q0R6Dvu_B#!IE?i6p&@Szs6W?}3h$x(8$Rek;akZjW9xe@CR zv?UKb*VoSAPow%{|?Z&n$3|5n>0`4k=cE1+PGVpJR~8h`oF2?Adj= z65y4&hohgEMgWBPqif%RYy^P0q~HYMz$+I4k+{lO`Q%$JKMvF(v;QkcG*MmQXyai& zUVhc5di#03?W2eq+$ket5;eXkxNFx6^ru@wQ3Ec+?&h1F2_3o)K?9ShbKBFT6)hrY zL@U@c6>VZQ0|0*sO0f2MvuxRt(Z(JVPz?RErlE zwWnMK2e@&dqRrNsDv*-G%c-O`uUfx;J>?9iX10>HK+`h)li1rgm>t$Kyynx4IfQWC z3D^%(HU~dM)-&FclEPiV&869wA*g|ri@Dkkv z8}#e`uDH_$^wV!pX}69&vXBLQWh4g0;04ZwaD(8}DJdz)%MqIExFclpcn1+>v$L_V zOgHuKto^AUBIsU__-R#EH-{)xrx@?Bq*q|A0;-TiTzgLThxO8I?d<*mmd6e}IvGC- z7!a06b=7Qse%YMn&(i+ufKi;V@rLRaZ=y-3Z~g(ei{ z3<#9f+h`U*^@q}mn1tma5QNrH86p8Rr}@Ywj}r+Y`DnPO3EdUUDk3yIjT;~1bsL3N z3F^twRlR$6{;)h&bryptojod+1pPIPj61c3j&>e=kE{Bz&E`X6TEbMIM(Sh7lNfA5 zhYrMQ@^uIrg|8acl8srvUelL~)8Ei}e7oI>RcBd8b|c#un7F^Irf4vOAIebyx$V)c z9!+KZA;tnB+7Muf&OJA9?0#8d71~ibil(1Abj{ke?~qn`ge%_X4!Vc*kl1Bk0pa*> zkcT3U5&ckr#N0EKU8_&HI2uq$?^cljqWU(Qfo2*&a5;0~%snxWSb=5lvfO)X)7Gs= zhj-Yowv-k?9I-}l%f*6QWgF+ZK(lEuutSj10glVqMtq?(TS8j83eQ;Mw;|FS-r-jQ zPFjY@O%l^omWBF(*r}LvhxyXpG;N5HzoZ#fdfqU4y#qJVe*C=42TlM8$44w>Jvk;Y zmRnJjHhG5P&!YO*#FRBGkxUYxOYf!o@l1NhUSuJoIA_Ky-pvI?rTpmUXS&y%W7=`& z!OeurrEAg=5Clb~OOr)@X^Wi>FHRAt;n+O7kU9<7GZS@ahr!+I%16JH? z`Qtt8!7=@cJqkx@8YyBW>=rV^*=P4a#kg2(bs?Qkr zPA`2$x5RKq0t7l%DQ}ZP!JV%vy1F`X%)$tB+s8L|QTJGu z76&;X+{-M%r@>vPerLrKh+^SD*E!((KI~JcG`vs!TD{6&c-517jzX7&9K&N`I>Q%w z@H~imxI#wr=C^shMS3(>Zl{E=v2&!>zc@KH5x8WDAgr#tj8sX%48=zia35C zG;a0KG^5G#-$8}?6|_GQWn=bL1lYjft1Gh~f{e&Ow}Vo+D4ixjd)MxzmAaN&VH>aw zL)!-+%D#b7XFqUJcvcG9MU&^}(?U(xWYo8DezssEhZ*mGhglO@vcMh%*xO+*sOEOp zJHUAK3qwNTOaY8QE6eZikz9}Xrss&4Bfp-6(UVx13m253bN@OxxEfAN6LWLrOoO1s zU9Da_fUL{U*6)i)_6O=}^2y)ge<64{Y52G~7~&Glws$@Gk4#O27QF>G93lAp>jU#i zQ2~cz&RKpE{!!*J5@!_(4$LP-vuw z&jLM)4xXg@3RCz^h?9{VtlTXexL^*M7YlbZiokZ2T&14xqodCHT$s{Ps$zDp15D_I zcxHNtxJOXwa}kKFnk)Ck1b88qph=^hQ8vMB*<(QRU;EDhIM_VTg(6$I%(n+j7Od>5 z&X+Hb0RO@*w~AHN;uhQt$hO>qC@3|QRs{A$Yw!ke$<)C%u!=1x2fxbrrdg-z-zl{?ar%N0eS=6%=De?D#A z=-a~^C;I3QZbywf12qV{z&DP-yr*F7*p*Eb{s3M`6o}(#P_w~>}xq*QBQ(>s-cC+v9bCGM=5U9tl#AQCTQ=|l`pKIZBq@n{l^6C)^ zBO-6#2#f=r5aB>jgCM$?AC=Adf7STbpuNfPkg`g@C0uiR;I`R<&CK%WBC&3Y`7V09 z&4W!MY91gCj_#tsm|3BzBPy4N!M@8r+3VMe0hru~`r$2b$GdOHQ)B$VbIRPCV-7 zqPS2Cxjx6J964fzo{^Ym5ZObhc;xSF#&fMCc_Wb5lTa2gWmNo!wtLaiw~$x|rGnLR87^;ru;zS|xHpyv%u zTki}M&IrL@i7bXAxY)+w2qpTBm6og1DX6#w5ft#^;fVGo%Hlc0dPS%}0lM>Z8wzE4 zE^9>FWxJKRN9BqCzzU3uvUG}KW66W=t&vM{wsuH@;H zr%(C6s2#jIZ_?^2I97rcB5<CoG7YZSYC)y+6 zRdgsxo+Dor*)B|=B#4crzP=vk)^%hHppnu?Ru(8V5=oB%OS_?X+r-Sw>$GJQ^c4wq zxl{Jan}k)OW8D!79NBf(raAQCLlM|p!XX3a*|~E$pxg?0R|;SQC5o@7b*U}Q&5ba= zm;JIf%Q$y0b5E9gN|n0}ZVn8}*ip&P#~0aNUvo|F_|Y%I@dTIPrfF{ci_j6F89hDy zYHH`d>2pyLgoDRD&qRIYJ-ZoN@pxwoO*VSVz5Ui%Y7dQZal8A-8y*s*kBl;Vs0z%~stayQ_g}A!bB#dv`B{Zqmwk@$ZNRGOrD;?% zHz-0e!t1dz&Ha1ky=_&Uou(t}Z_V8(%&F*L?f!^8`S_kf`I}ObAM@gL+rJQV6j43C~ADKQ;6;spxk@QY) zu5^j)uQO8%aQg`nULPO{A+$jWzQetA9(~aDp}W?oYhsprSbk}sD=LvMQ27-zgZuXM ztDtLHy`Fz7ocLk4NZD!WPmN5;gkjIPZ>HR zlE+w~orV)qz1@sX@A>&t`m+)Xn4=H?@EZHha^S*R0~AJ%pkSc^T0u;xKtskc%?gtS zR$|3L5IXNi3Jx4NQK94n!0E#|+OMLesP|}kMh=`LJ~!eau6aM)ihX!N)hpxCAF&u& zVJvbj?*D-oZve0pMI1Y9F)CNtg;_mZKY}CRXkm;N>kdAHr9rBH`yg~ zBuB3cz3Wri?Iq+iYj0;GbTD*0hr9QwtSK#ZxCkc2>CprA$eoyf7Er2j|tj-CBA>Ba0hQ z2Y_bIZ}ZRr9z+IRU?0B52@0hz6tK(C_uWL3`xU~+&Gy1vhDo|D$0B7toQJ!@5a4*i_Im(I4vnY!N~F*4t6?GP24+Rf zC&6%{<52}mxh4hHNMyT5O=(2pHi=>+^A1R#kFY*e7bGyOBE4q=5}P)$v#WQzXV_Lp zarV_rea2%Z>vf`BL%HID)&y87a`Bff{Q7$wBhZ1I``~Yafqgo9j6#p}4fSrcfT4Y` zK>KCyl&VmKtM`f7)i4{3;tP6w^hvqAy|15(015ri=@Q8Ks(K1XIz>iMPM|jvJtYap zw(3Hb)RDapaD&G%H~Y)vUL3R)RzxAeF6+iiG+nqBM&wd-o3pKLm5H8&lwCMtkX_m8 zA;+yhHz_48ecWAMR-ZL6UO->zn%0zqMb^RLVjX;%BV6rzOdN|xTLMM__H`6FZo&8F zt5$w!Ohf5{2?Jb#(5RxUOh+q3B-QYfTNMuIoPALpWGCEn=1|wAqz1*gY)CWwHw*$| z!x%UFhty6uJ*_qs7;$Z!UX%H?l09S-8s*z#UVEU3L%XsxxU^y2x=Qe{69@Nap4UwU zrI8MG5Kcwjz1_x9q78pgTD?Y1Ep-`%`xyd@NhBK9i7c%@`Z%i}a&niF>@jgYPm!PM@CtjKq(h$Z&GAoH<7yz7p zo{=DN>0-T9q5)20^=t{7t)OdLme6bS>eN)}bT zRMWx0$lU1EqG)*l421C`3yokPQUbX3_jskH;F1H{yBug;MaR^XJG|!V_jP`HWr!g3x(E+3(-+_SvjS%41w-fq8u19cZ4{1~>^5>%6ZzD# z3SBjB12V+{H0=Em_o1a?U^9?3plO3ZAjOl;4^nxp1LaQ@>#(+1^3@`nDYd|%t}+nvQ{T4ASuD9-iYcO z7eFQ0kFeoCX=h@>%wxJOG)FtEU;NPfMphBktM2TuK#Gos7ncr4(x->VPSz#MM!R>P zLqr>yRn$2l0C@yd1?mmdy_Tgn5dKmfr3M6hBP(klZn0{&d0oL1FJ(}N&n(&CGsR5F ziPC-4#lNAHYmiBDTS(S$kMGh!EVJvFKmE7#KhsGZ9G5S1*3Bz4hz|u~b%K5j#6KqU zE{u5OewNKx22bnP?$ghYboY3u#?{`KKb`Oc0dd63OTqM!hMMHMZ2hs~bzZbxZTB%eQ14jl=(C>)TmdQI1?G_JTbZ#Ytrvt{?(_E^OF82m2T-X{-YC%ht+Z`IER&rcpf^P9CeM|MqYyungiP$H zP;SM$U9xW)(M}z(bIR*E=i3hj}EJtZ|KX&0H5 z1#%-=nu7xYWJ%1&(M`E!tMOpjv&oM+AY2{X4NY7i=_JbOc=tyet@GOBtOb4QQsco* z?gBM}R~YM&4A482>i{c@kkMB?kxqE>XO+NlIL2-J^`>&;q>4knROqx)?yB_C^Hs}g-6&Ar&O z!6+nuttIr8vL8{ww-$sI2xuBY;t$>8&D2zG0_32?-gV%Bd0YYE^Dw~zaN{P$`JXF@ zc>jY;R*g}4d(7{LBbBr)PoGW{!~_d^9Q_9d*~du1Z>su@!2t6Q3z7E^Eujjxd5=Du z6eTm0vawl#kxWbF*_+d~|0y#d`2;vnBWduByG{=uLx)+N5WARrJb%0F zFTCCyy)^&OPW3SqkCf-&2GosTJ7SrDaIivsI!is<@pu^+{7pXdC?9D6`TboXqGa(I z)fI0$b5yw>BT0|}#e|5TO0dSRn5NlD)l^r1O=eX=g-?b$v5elMDujJXF^doAZyivw zmOE=`9rpd8Hz;h@pjA4`6}Oc1qewJeY^=6kIF~l;=pFd5s&V-?{q_Lh|sa zYvjicD?Z0w{@5@QK*B138Bs|gkLgJar~sq5K37+-!J;80p5ojK88-uoCc$kzolBsHa0p*oQ1XbklXYP z+uh$4>vM5Q<7x>EqS4;~k>|)_03cI0)ITFG5bO;$1=@{ctA2*hPVsRFrX{J zFtP_8m!6>>x?_7SunRK5^9VZ7&lj|KE(WPaBaB*zE=z}k6M=cnPRCmSUy9Pj1!-pb zYi4d9HA}xA;7TprRgzl*HMd|r7=IGp>fzkYGiyW2I@r+CGcpP=XMpg$`1*yRu?Y#c zU}^q_oB&ewDc*~|m3uW`km;>QiP&eOhQr*fuhw|%LEPJGyl@p4nM~VNM|^f=(REOtcdn@^$;a}EVtJA@T%0M6X-YRR?1^N| zpdGiyVS!kjNMRdTZ88A0A>xtDC7a6HRhV|~+{c|+FCMk#BrUtu=^42B%<3`I&kmck zmh`0ALxY0!AJ9#&81B!rmey$9jY^Zh64bIrzt*BLdQx1Xj0EKj{emGe4;Wt4k#s!} z^Ca|_WU>PaJP-eObN_=SJEY{`>a_;9K8W+>?xaMFw%mspK^ynU4O#E-+F%1AL0FC} z60tT(C=rmVwB?=ERYn5|Q`)Gy9zzKNMmk(Rev-_HyPsbcB`ay~{LW%PkOX*5ZL7Ww zWy)1S;|J`Tu|j;$tM!zWmIHV@h2l-meoX%W9h;DmdcPJqm}!;&ft{z(LF}%?E(O_Z@2wj%WV=;bJ5DqvK)WY#@_hWH3B2>3>H%Fp9n(lGf+M;RT@WNfn zW>@0f_o*1Iq<;EjcK*p~OOb9`y-MH^k-0s`;tl$7UcF>-{MRp4J-ypGG|uY)#EHI_ z46lQWG7vAA2l08RIbyxDdx$gwNFbn_-sLOS=;e=KE3ZWXkoZJ@ec$DZjjRz{GjMjS zW~D3txBe${z28^8!cCXE;u`|f-dFA8#gR#Q4)&0}@6B5*p#B#!l8A6ZWQz86@;nbYZ5}CsREUypqJ?vspMy9en$Ira4o?DBKIhm zTPu_ah1z0nX)mUTlDdP1l@4P@2q>L=@CqxCE8CJDHv_j6=@Q6u-<>g zJxA#P-gQes!A{L2m+i>bbeuXgTzxmn%N1cW9!Cf%A#!0Fgsef@ z9tS2Oh-}J!^WZ>G0pFFWqw5BA^feZv090uF1t+Sy9t@F#K%a@TfY&1a(G`PUkzgQ{&A>syenL+@?s3N)!qkNID zVE0$Y_Oew_pw(^0Pf$Yt3V`IDK>YmHE& zOn6=Y7vcU-gZcnK6ubASjm6i;voZ4Kw%qDUD%DATrKCL8b72Iw(=~WJ)=*8&&1ryO z;d2ko(OG^6VPLV-Gg=cIpj1BBPXPv_+_?0T0IC zNW8;e^P5wwZ0xB*s;}pk%-<>dZb0`JUz8zzFA2zWmiO!gC172Q%H}}LoclG{FAM`3 z06!q;5;;%wUm1&H9%x~#w|7m+UVLG4HF8H6&ISOa5HiX+q>!}{V)5oNN`a;M9Y!`b zHbReqK3%b0!TT0?q#ZIc?2vah4qw>^yW@%5dkxUW(%ZPp=CdH!k6rmc_=Q|qsFiY4b0#hC0Sh`Juou5xjJQS1?0dza_f8jYIfb5!!6xU$dI{RSBga!A=!#~Y z!)VC}BB&Uh<>lueww-8BK+6->+Qg3$7cZZyZtaRyJpq)TH8f55Ui9@xRJ%Kqzklzp zgl!TzfErWdf=qWZ($m-GwIqs?!xnqY1TqI`e8W)dLRfetLn#>740)1u$hEPqww8=Sbqf!qBGU_xge6q6-~R!^A$wm~ zjo|X~XL>KlaJe)NK2Y?JtEu>+oM;D*@7T5QGFwwi>jqjwG*Cqf#<%yo0g)BR{2A(2)BSfyfix!=?6o$?L z_sAM5$LHeATp>UoFJHd=2_5=3AgxHfl>?5-clj`iCQ2gZZi(#GT8;Ptbl1s_9JD{W{*FPTuQ+du1^XbaXi#)^GFarp)N*Xe%upo%MU|*{ZRs z$w+eC9IjpxyENuQNQ~F zO41=Y_4RHq9qeTU0$51WK~bZmxOn8gd}2zk{J}&~T^Q34c^7*}kd+Q)BZ-{zcO{Zg zj7nj7e@n0uzaK(_U6tf4mHSep%$OxnWxHCSGLc)LAn~B20@(kJq1CmuM)OyH;S}^2 z$3hQ4gT1^{%w}*?DP5Ux9|RRp@s0m3fX2_o0sR z7cVt?obw?dO6w(FC(3lCOeQKe0)w(KB&Er3BXy!XZ-F9S%D45SaUR1$>=_3uxU7@Z2RzsjgV z-_PpnKN5l56^Z&bfohosX~4&cbe~M6o*039d#{Z#H4`7rUmQ4qf674bPjGz(n;s=t zuk-tLcNzLdi&oc6jKEU;v{q;Iihba9vv(eg^Im|aKBGIoXMCT5wzh3XV!R^SxrKhbWTIy^(?7!a=&_QV7{@DL-YDq@dju$l|x2_rj!zfl|Uq+8r zOCZJ_-M#rA9J;pLUtE)w4muX|U*ZBxH!I!Ox3bzfXsePWYh0GSTW!vrTaVzs0Eur6 zCg(_pA6kNJa2>|SkatpM60{_dCqQ}#!H;MWK&iH#PKLCjqP|`S^7rcGz6OwckTC76 z+%D^eD=+jUz*`0zAOm4}k|KTc(Fl`|uB72t8F_2@^bQSa4BzH6`pV4Cp7R8iL}2s7 zLqS*MEYYw008UVX4@UHRXW^= z&UO$CxatX80Fj!#{rxq`k^P9TyM~C)C~F^YZ+a&8Vv_HSrUhkj${)yJNUYN8?KcZM z1NjBo<8T5KgS{|Ka^aM{eIRZ>Ya*uhEPIxbajrKl#MhxUV9Z*2SJS|6R6KSDhl32Z zJ{IfKPd&cv;AJDU>Z%Lc$0kfeT65a%u)?BnA7q@nxN~4Svsqwk8$z>*mW|Q&ZHzs7 zbTnSk)^M1uyZWe;xj$j;VO$i|1#ZrMm7(0I4}Nu{VP5t zVt6-_oCU%z|Em?YVCXr(_X-(QsyS^=DT`h+KY4}@I(|x_fV~ov+)_qCahs}IE{1YtDYqmBEi_ z5m}(ck}0XDsv7t$paVxcN!o-)&hZB(V(+v}T{iY&3B7=RhASFH$7j8y&&H3>5bx+g z7;ZBb1gR09`1Hz%-Omh%a>@-8_KiY z4^2%>NaQg*^GZv8i(Xb~xWhgN0W74eYsx=^sehXBq9V$w%^6*W`j09y({+E>qNl<* z@|~9`oM88smc}r6os9PS>4A0IE50@n3K{fRM}l9$@OZ){OU8z})@>93m0fM`LCxJc z0Di#XN|Rp>%G~uZ4sR7(RfpjAIALE&``SYQ(imtlqoIz2knw6j&Y!2?JtKx2f4c$^ z8#?NABy>wkZUgK_S$8G&<^HUBb27u06p6a3{H+5=N`>gcgMxS}Sp*G^^lQZ+4mAL~ zXf+khXBs9?Gupm$PlM=<62^AH%}orFWCn?-2*Fx$4u8P(2FZ}(B2&h;K9FM5aOV;oxKCj(mmnT!&VzZd(E!N$F4E9IyF< zo>~_O?Fh6~H=G+oK#XY~qaFHU{0O#!46e~>+pliKe5<=!JkC!6lJ$m4RTU$%h#<_y zwp1O~$)1`W0Mo z@#foQyP)bVMkGKbb+ZK8KkpEJMFP>_&{&*af`hA~rzdr)M-(EaE&N)IGP=q{`d85t zvjM5ZIzRlfD8w-+4ZBEQ?9Kpl3^XP*l9j~?l`@@215UFT!gCm=u5&@=;7pmZ6Ha^>h zqGSz~l;*%Z;lpTX$Ym$i*&J`N= zatoN>{)N7K(vV+aaLqa4QI3&NEvP`|7r0A1+gab&bqwItL5(9A9`Y!0zd%3{-gdC_ zuc(9s^-q2|IN?Zi?dYsn%i)qS20uKdn&j##f!_+iT!J6+*#aL4Wl7Z_JdC{_%v^`f z=zf5408u1(J5ucA$&(cc=%&LCxVjHDtBCO*Jh+e%5FL1 z@9F7zTFM^Bk-97L5y{%wK0W!(U*kJYHImVQYTBjeqlPqJ3Ftv4Dh3WQLZGI#H>m~f5Gye`dmMMBv$CE{&LhYkUyE6(!_($ zm8omh3;uuzg@vZEL&nCejum0K9$)SWyNUf;Zgr?@01<$`1{DEijoDZ7;8_rm2)_;G zA{q8c=>Q@_1PWe@K8V90Nj#C^QV4%c@z`ouLp+FE2bR6YvnK`{uPvKT0qyS%cmom{ zi?_k9e$XYRCkL|wbkEgB9e4QZJ25pC^Q!R%@*ELyfp27<1Z;X<~Kg2qN4qpUw`9f$Kn#c5T@)dvDcIYIT*i^*P2Kn!_ z{W^x|2w;IFOy~9VHbU~V`-19(M87P*@_FEw1{UZrZR>AvJi+yqPA(W%+ybxha_s8t zpu?xgXg=9U%|RiiTz1#kZT<9$e`VA$75^~{0{TJX z0S(;Q{r5fu9MVWJW?~lb0|@DK@UDX5eQQ5hj=&`IvZL17eI|Ywhb^?*K#ef>8LUfT zU)l`>UPkR-UyG4B^W8T}vkv9WI$2@}8_(Ih$05Cf;@tp;mI8@?C+=f*hqab|VP4@H zJxFjQDWnt=nAsAaoTAo3{7NJjp%}Ba!(}5S2!{UVE+4E-s7_XNPFQ8ZcfS%I6W&T3 zt!()8v9cMyM-hwwIF5k^<|*^genJ_z{x4r36q1&xi`6 z+0o2!hNT^iS@jhq)87+KsT7D7Kyb^a+W>zNvqES1k}edBl*(E>#W<-5{J%Bvorj;w zgDZY7J7!`F|4A=K!uOu$wmYwmrztV~HC7_JmK_yZlvF(Eoo^_z;yu=8rC?kqk?o+@ ziodahgH;c>FN zW`P|x?;HhL_P(1z=D>li=v-qx)+*a!00SV1HPnS?S0pl%+_28{Ay^H&AbA9~*_(-` zixKvuI-C10WlL1IV1KZ|7?z-0S8pE*Rw~Jk`g7M5G#C=Ha1+FNYzqc>7PVh^58%4_ zg$0eRTTlq>KtLj9;P@Bd22N1$krOPO zj$&K?&J#&-Hi)~Rbl@Y^l%`qZfX9wL63hjq$=B)ASBVcGI7z{$baY@V#6HdT`sh3S z;A#Cx8=8C~^lQ6E%WG_bsM5^fSPWqO+x0;-yk~Ys6IcDNOYG*4t*!|#)hY4;qqn$i zKNzsOAyu&o9f?K(R@)J1QEcmP4Kd+ghG_jd^O?cF3wVuZxsK*Z5tGM$MQKkoGbLtv z%(JeL_4TES3<57aJEiH<@4OZ^Ek$&~*1*Gi2UHLnEa5O!fR$Y_8xFD{1J8`n?i~On zj=lf+vnuYf`s=e<2;_p8qj24Z_fzWf43w5GkhrReK~A&+?Brtmn|;c}DpV2F1x;NF z^I;;WMgg=r^bg`b?99JP!iNKMxpJJ1FQeVFL$a5C>tfIc=8h4_`!jo1ZAHbkqDI~N z1{tJ>0n_PPW_$`DJ)p3fz;1OAsl5iDuulT<+kcm z`8Z)yf3lb_dMm398G(ZI>MHl;rXxYSWZ+d4jdLrU0Tp2sj3&T%i99`3EvJ|({Qy(e zTzvoWZ~t=Qr)W0n^iyaH{axWnL=YO0*Ufeyz?cYI1uqh^%zbd*X<}i;b@C=34rAj5w2m*~hpZPu2Gjyx;dcxwmg3P;J{P`EYwtB;A z^p8a+LKP54(>(8LWW^xFx%1O13pv&EY zzwn1@i4u0$2^=qQSN<#1tgfyu?7E35nL$%ykBmhunHhb!QORWR>WCz6&32OXPs0w0ib%oW4``~#cXB2I zYXy0!9k(+Pnrfn#hEXYYzC+j-Guwrp;;njt`MC3_gh~jJ{zheXrC$3W^)Wjqm zT0cJp{sw63_!=Cs`!Ql=Q>fwnHY8%^^{Htj(~_KPJ(qMd=t zlb)u)tiZ5xCF8|IMR2>KwW6pueAO$Pj8WO5rKtZS8)vupnUBJz)D4V`%^^KSc*ca( z-%+WPD8T>@ishgxz%P;`R3TGr7Dl?Y{riol*aOpnG7zaw_4sa`X06^4SJgIHdzhj2gEvw#}QBt}5&U`Who* zZhU_n0?tsVN&=Z*U|a&sMyI8^v!Nslu=v^zYN@((;TXcl#Z-?sB{OeDL}+0;CQ?e2legLcI~_Ji7&lE*h^>T5rB1#s06GB;D^D9sk#4GHtP96dEGY5 ze?i0e;ZB4Fdgf~wHF3Lt_~C;GKd}eSv@N9g`}$5rKzNB_8N3>5qdgZ?wG45Us{)E@ z$~D~ms$<_zJX5lHT>M;ulMdDJ@bcc6I&h};OLs1pC#HN%<*)l(#KOT51o$t~8bXgV zru~I8lgGR9i98Cg?fiN5LO6noz7pWB+#Vicigs4!MfgcT3wO@n0=n2D_1|@H7G=c*$8&?#hSe%y^aQ3R91HO+p4NnKq=!#6GmGEQeAP& z;$jtcY-)n)2f}Ly4Yn_0n1i|p`twNZ-6*MN{kwqG5pi*|jl_2{G#z_J8J9tUbEia; zN)DFz8|*5(>N-fCKsE7*#C^c$?ux+%t@e)4H#t3_3;`oEAL|Eaw`0=811c z%FyobM7qb_ZN9{f0{jcVH&*=qZ-x#s6%^>BMo-WN(#m`P>U5B>=MQZz=z~g_$SrdJ zxZw7xZuc^91fW_X*#pp@hyl^+sP#Ws6v34b6j2SGm^emAqWl(+D>Fc|^mjZQ;xF*l z)Gl6pYHb5}`fh7v)Y$iZk~kg=#?8?jV=6)rUQ;zy0b}z@X3}Bs>D{@52U>vLmt40h zc*{U5u)F#>V#YqA&c6YOv%&;0m@sCg6cz|Jkf}0(XqJ!e=iic#bp$VKqLl@HE=ECw zpdfZSXb;gg>Bi>Hy1;LV zp(+cD6$w+|cliOY2PIy6Tf!+P1TTVE{+k&@Qud0rPojCoOu++~0ZVTK`~OYsxYGyu zTQ(qOO9{(V{L&ALca@cb`_F;?MJXVZH-q8s=}}+CLdIdfw7_lL!%l<^3j|=J-uNGC zyS!K+&dl~c6Y*|}+>-H{;6>*p#Yuy3O9g0^Mgc~{DM8UgQrN?&n*m&0ClEL&TOwu! z@@8Cx2fQV;1QP(r%|ByZkDfKE^b{X2?>%&vW^BuRO=LO&dZjQ6xeqp8D@vFJ5ere% zb>1y$xDAx>G~TDYPP|ASyHL&n?0>vv!Rklx7;E8H9a1uDe0EBh$>JIG0F)mEpP;McRa6HSQ2_*@ z2?s#)8;7$Lg!zbxZ3MWE@d4tr^5Ut$n*g?)W{d_(VA*~ zw9pE}VG3|equrd249CVTy$ZXlkj>k&{3;h2uZ?bM11k6GU`d4hX$(JJMc3o=n~Uh0 zs-L5rA)&nB9(GobhjL{azJR)y8UO-9Da=Zd4}sy^7%{GK;^iKa{L(nL)bXNWMyO_LiPjT+`z~D?Z!7)g)i?B% z^8J|wgX!6Zv;&SE30AZ?%wWO7#&THS#6-U_^MPNCK(jv26n$XR;w6`z-o;^?I z=HV44F~)tRcQe9$z>Fa3t*_SXH~RcM^Jk9~7N!i7Ht;JV2n*jh1ARMk!S20gu7$iQ z4+UYKNkKZ6h(pVTCSb(txa5rRBi?&h0#=$HY7B42|r*eMhXNyR@PC7gb@Mc2eG z>I2%Rk=*RN1^}o`N6LS9U$I|e?WHy}=t97rYdV6{AO}L0J8~XQWi&_u%|y(K#IAg6 zI)1{7un^Ukx~||TzcaFB9}bg;DB(W$K4+Xv(Bj9@-S!|m1)>5dFp8V;PbRk^*tmPN zx>LCN`>Ba%6;HjYp~wR+N0#^V^yyzVVb7zrUlTaf+S!?LF0` z#<+gHF*ZvP<<i69b?s`e zC#XuX4Ygt3Yd3d!l?i+*sp=&L6?c12Y6EwzP5-letnAMtNVc65I2i9BrY*5;Lqb$k zI*!sLsU}w)Oz_A>S&`tQi#t8YzAx}*6@J)s{edw7I7$AGz4r{NYTLR+mw~Nf+HS=F zh#3SVD3X(zBp_Kbih$${l2Ny!BA_53*+7nxGpHyz$dVkDoRPGUeB1P#{e9=$vv1Y= z@#jbbrN=TZtO!KzC{Iz^}q zGy%_5Mn6@{2{zzBZge}JE_6d#DN*uFoZ*t1nsK+Ap(rEKHjNOltsGlHpZe#g5ycaO z))u;$tRbDK7@N<(8gzzeVluPG08af1T)CAAa=MkdrRFF&DVn!OIIBNtj=|JkP#X*~ z*J6iw*>`ik;8Xrf3*gd>EMR5o3Yt8R;t{doixT`OChiF?=N9GsH7I#9LgA5b3;w zwh&$@6vv$S`MrJ>x1iw^(C*%f3Zz^6u>`3n#gKw0hM|^1t&tc|20Zl?pkhC49WQjm z6Li_YQ+uSkxjEsyTKSC#cssQP4qn4zfzY9!(7t(Em z=+N1kB5Fzy*11I-ZUuV_y8mEcm>ANuYfCE@hi&80gaUTaD#A%(lqc_{{r9!i z$+ha$BJjiqP=}ZrD~j${RUk!zQJ7+C7m6UE-NNVK(t_KM51aO`Fo>VQRxnJ&Ot!ky zX!~L2JYB(bMMvk=Wy{XaPGX?Rb<4>~*sawFKEPToxVBpe7(eEKFAHynTT8*%ok#Rb zq1I|(Qq7v3`l;sT%R;RWSEQ~y!dAK>F8)Z>fdZ{e_tcQ?;^a-Qq5#p=tiB9j>aQ5~ z5K17D1TBRKLHkTgpw%O^l#^=X#{G4|^P#CaAJ+FG&ROur z6F#7e4j5Mew%As~{BH@(RCDbZm2&z1V4qcuIV6=kDz=l{#de{Zg7kivaCC_~yZ|@_ z1R6D46H&w1vPC(DUCM8f#J1u0MTg|pTKqh(@ghT`fgxCpjNBw_SRp}~C$Xd(J; z9CdK}k!N<%`JQqd=b{>Piea*4k{rny5t`?3+~W4;XJtcp*qZN}pe%+Hr&bTsNWPrZ z$oa9M-Nw@LG|cXpTD8J8YWLoro>L65?MRdAg44|1aT{GT(o$`P<)PWTdCqX-ECKdD1q9xYaDmt9 zFw~vVgr-avHoTP1yx@iqrA1eNdvvzlx*wB)F!cuz(VbmgsB@!50LYW9k$Y2l39R-R zI5~r>p?vkX(XQ_DWCR@1u0w~+r$kiq+^8~1Eu5!9ZVk*!VOLM}cyiDJ3uMNA>4Whq z1={ce5Z(`VmJ{hs17#uOgZpX@ezG=4d%ZK56=d3xXInM4ADSPv4EZTxz_Tp8^6+l`#-fhs5x%qmYlQ%dX>)!i2ML3bRsumC{vKtRhwHsIK1ji})Vxk{tDS zMqawwXd*{n$XaUO?P4G|)lnFQnBoe8UShaQ)0_2hlqt0E3_x2iZwSqISYH8aTm3}k z3$^=N&Yuq+9N;MUagQhlCt9iK%l?jbFZ$4t(M}f3c<(xJz_8u`&4C{~ud(l)U9VG; z({5l^L9!g4*r*3!&y5Q8h4<@*v9U|B!d_S+I`qNa`x(tU$`xLx@`EtYZ;Fg8)`o-i zf`EYzvFU02FhIARc(f>HGcQ=4uG(2JZ&Uoas;UY#!9LQI)(+QT(N%A_&K81ctS@x3 zPhXtDX9dM9QyZ=8S|OY!g01YK^ms&VQ?MKd;EtZb`muX8lLYUarHv4Ji_l@0X(1CQ>X0m$4(aV428mj%E&wk>!p)#3Nx&3YisJyNxQeeL0jw&u6E2~! zmV-A=l6bbwEX^V}`4ql8J_xxuC{1EL5+W$S^XVA|AxyS^HTg`V>L- zV9Nlag{LquszSL6KFT*9 zwD7v!D3P#^baIG#3+(G-XeZQRl203VqNcosFJze*(g@;#=Fp+F_j3eh1@90KF5Te? zmr=t>MCQs7E|j3l?c<>0u^Sta6+lbbXcSMMgrt+`HJ+WFja=D_@bF}WmP0r|0+v00 zZYwEQ@OB^~!WG!$y{6W%ns~+^-^<<;h`Toxc{$^fXtyu zSa4wtmNgUTUqT+0Yb+T2;O6Frakj%yFyz5*Ba-)j@!}T6ybR67lF=tZXneyorrQ{{ zp?N0WUcYG(fua#A0#IZS5A^zL%FNE4D!>mA(j)nljKuN?E)%cubN%_%iv4R*p-ezP!-G}#DL_jx(Y7qUkBqaJ-(9(qv z@IkkTv2w$(2pGIBhtQ4~9e{KJdN%bl4}fM%ME7aq@%0l#f-n!zsLN$u(=!XqLjla# zYjk%J_eD8&GI1R!kVc#~{o}_qcol}?`yt;UF3ftH~@aZWar z?=|>HL-fnXAX#~k8;a zdQFSqP0;hj54~iMJ2*PVgRf^nO+C>Y7HMxNTZVAv1kfoRIg4r|_|f2CH0MW#D+b-hBW3X>MCL1&3QXsrj8G!u8+r8dlUQ^|Wl_&c1aAi^a2%)r6v7eQ5fNBpKNw`YR*KbtezHaHZ!nNj zzPHWkc+T)#zAypEj-b#i4mlQF;z?#^XoMv45LbMjLMTd1E5#fURVNkdP$UA3 zVb+bhiwdDwGHl|38Y>u6n~5qtbR8v5Kce6lxMjQ$^Q@9#Ku3wa9-*)tjt@dB)kGAN zsud*h6Nej~0)0t45|{RqJC|HBrTht!_UAdy#X}oD+iqU08Y+d1bp}wf!<{?V3&u-6Vo(weyfPvq zHW6O1xiP3rVjiAYsfB(YH+q#guedE>t2b~oqp)kpL0&JKkhVt`Q=ri58H$5{KtMD? zc|$-39v>Qd`a}Q-D7~zBd>(j+0nE;=E=>+D(%GRmVU^M4-`QyGcrcFt}CO6;? z($@w?M-xB*5swT(+cbqzJ7JDf>`2M%Ac|uT7NhZ}TCP z0|<2dg-hd*rhfA1(KEuT(y+YfEVk_{-{o1yg(sg0xK9I&#*u$l>^-{sRWqpQO2h5e zBSq6cIA}26;+uift+BL@$bwyXa8hYK>Af0X{CW~8CJU|1(#`%@Tv)(m$k>&iTyvbC zNJ6~H)jWqo=0CVzMK2K%ny>Dz5~ze#Mk1V|BWVB;p%AF3 zt3bG1P9cCwkhtCPS%U~* zaX7PCt7>Wv(B23k&|c}YRD&2KpA6Gw2%>qfIqGqx$5ErMJp}({aM zpGCpY2g8!<`i*W|4!W_wbvLEuBk{CQnA{RMelHf4vuenDBOo}%-cpE;vV_tZ5KsNY zK9noDpocPI$OCLp$8$W3L@4oNH2dM75-~<~#_SuRvHq%QL(D zz$JnW7y>Zi@j{29SD@452y)14!yYy@MI@6H;NJ->QlHh7S88W%{T02F8sNd4v#GAX z!CxYw>kk{%|BfCuGjvn{r8nsp8A+r)^z7a;;1R!_uRa*s6eYDUfBWs~6vPQ3bH_d5 zoV3ubq*f(yr^wH9+Nk0@#{G7d=&cBQB^LAiEnFHwqS$#3LO%u`H4cW!&eOpMHkW8_ zuM{W$c_J0kQ!JxCf2YC?25xw8P#!^G|Hm1Y{8hB-F&}4)Vc!}-c*1<6g0Y?33^hSS z_6+l4+PT?Jfm?Zvx{ndu{0@%Q!Wh7mMWC};=q&{W{KeW(@(-2OS+N+oSEy0G4#R0* ze!8`ba0ozztbBYe6RGF`l!9uR7U78!#$s7cn}0r{)!kTHymc)1&HjnIupS&E{5v&ER;j*rZ>63CLVfHae5jvZ7!lH zv;k(S_l4|yBE~L)WSeOCTukniSi`}XE^t9Pb6C7v7S1I+I`i)j#LI&`Jw1tJ4_33W zK2FFAI>{8cfb#C{?i>6s(60@fLLTAk*dHmtUc?RW*|XRIpy3e5Du`kAe83o?C z^Nwgagcq}@WyEUsbcQs%*Sf#^20y4>hz||nexD$0*vbJ729y^ubE0^9XxVa#4arZC zy*4%iYj2S+^_DrJ4gAiHLKW$tGY=&A=!q;^8~8Z*pS~f*RWa<~L=n|Xu%wwV^Z7Er zokjpvI8{n#=Q+=5+?p1JGU;bArl>Uvn-ClmM~pJkkvp@YSvB?M1Jp;|hShtL2abI2g16JIpevLo|l)y6Ol5}?#1-0$ri z+V6vUkjKmE!=6Ou4~`KT8Dtit5jpb-glQ}+E)E#`{%#Pu{00sH?l}-N{5Qox3LFNU zgttuZ^L?;20OfMv;O%W#d=jxKfMJ`GR|e*Z{>$hqZdCu~foAWOD_2<9*=67gb2NJ; z<-t25Dj~3RE875~z&V88t!xa_F>q#Wsk$DTn_i)x|3$oL%p0A-y-*Zo1a+=0K%H#}$iq{+d4OP_zOK0< zscZ-$3@wvwM=F-5ZUY1>p{oyCznW&hBmzVr*|}=2x)wG@#KW<$S%z@Xb`hV}e2C6H zIH1B7VYtdxW;zmydIz=pI+FX>V2r#%iMh3A3d(_u@bnIzNn^0y8c^f1-pUL;-V-1v z89B7})1y=HE`TbbNPr(uPpW~FI0?uP; z-iVmD0X#}bDds#hAkl(?tmC;k7RyeG2Ie0J$PLWR_Ny8R6656DCR9jDcnV~|MH;0D6 zumVJr@>5+!a1&sX!%H^xXPdSwqc*Zpdu>t0V?gc;*xVuLVVZ$*ln{-14E%B6Kpb3~ zBDj3zFag`duGK>8Y6QJ%h2!1Uz}0Z_1V(E+Tl@AC0+NL|HJBr-N@G5;%JB|V-ZZlK z-Tz>T<%+%<^ahTkJwvt>quQ|3RIXlqsu}TX;Ij{?YeaqzLW))P;SEMvbm9d*^a5vIN(-KwipmutR_c@rlP&LKHM+(@o}rZCM(^;*WetR zcN{pvi#%Eru<9)O-l;?1JUumKX(QPRUZ4SEF9^H}S6_tuC4JZ*)Ukwt1%_Gtc7Lad z2xBrda*LogmC(QmTdtRXv1?g)eo-OJ(5ei9q|lE!M05O~7nn&TpJ0!{WEK+Xqy?cA zO>aWy=D~~H*RSTOKf77$?t_E{cABR0<6)qM>@G(sc;#laWLHeQemWr|#19QTpzW3f z{%eFWN)l-)L4(>uF0;>(v6=01n&dAa_4pvd;C7;z5b%x2SU0w@q3P7>T#B0^9+V8X z#d~C)!P++#NnNg3V?4tm53>tCV$b2W(W$WkND109RiZc!k7y507&tT` z8`+yI@{x})#r_ph--}2A%+)(74QLsNdOAoO2$D4h(Ru=qg@b^BDLL{nSY#WFlO$qk zv_na)I;=K4;Z+05XE;#XwI1g!$@QsN7xeYYX!;NTno+|v^s^8@AH`E?28aPm$6kmn z&9hPr5B(B6(k5J6D`WQ(NE*U5C(8~vD`FapsOq(ER~f(*lctSK0KkObC-{(~PIY92U3+bad8)nDx5g?i1NdW##8NRkLxGhf!(KHBeD=R|! z!Wd~~!reE3G7Zs~@0P_;o2_I`xeaX z^QE8mU{66SU<6I_;(YO1(jO-zTTZY~h-^27SYE*S=Q~2Y2Hc-ehAcE0V>gJ1wQyko zX&aNX9)S9oxAo%X%UGbeuZ+!BP+iJ{H3Aiyf)I#*c32G0Mh@W_sJ|E(4#Ab(i_`*` zf+HQuCx^RL205Q35Zit0OdJ6P5ZYta#uTa4yc?idBrX?5DqZSz5z-?FT;jFeR+NZT z$Y}0o0#65OIZD6_WE#=~>IfqV05}*y^bOCKA^H1(gh{7%SI@Y8qq*qna!`JLeyi*{ zt&H2xF{#)zbXT=pr1&m47FjSJ2nm}2^k!k;;t?_LV7|5${sfeX?d*`;%An|)WxOTp z$sBC#IV5?85P^+!=4UsicoLoj`06&aS!l@-snq_^8r;K6ya&X@J!4EtH(GI9x2;+}zsZc{w?;0K!N} zhru`y^1ODvR}#o7fptp&%>dF{fq;&H4sYQ@Mn65?orfYbf=WS5%fiK_0Cbw_AXD57 zje+n&pC3Vt5L_h=Vg=_m&o<7WtAy**a-O;jpV%B1@p3M(c=@C93W5?V+6766K76r|@RKUO&-E5bO0gzi}V~2jbXZtzm=+2c$q` zvRW2KdwSl0L>p{lFhN>H3dv%0slA`(b7WyfItdX(*PY(&EBzd9sqz6okKxr|ke2J@ z@tom@Z*dTuHh>M>JSZxF2kzl`84C_k11A&nqf5_$qlfmk<~?cJu7HkLe^ne z3{HRmj|4mfI^NU5r2h~#jbK-3As#2{+xG1XbkPLx;z`hq$;;1AK-7$|ARUt&%(Azn zTDYA*e|`~1IL^MyL5%Qmh)EBbb{BQ_I8n_*F~yDfoOo*TFo9udvH8ee(Tchj5IYG4 zPS**L1UoxpTd0QNi16=H#NQ$TmH5(hbq|Z;Nx>9k&Jn;%V|@vWi>*ZLpA$?>tlZr2 z{+(%U+=A06#l8TO{1uy*DBB>`2>tge71UwAl#t}(zE%Egy)C=p78RA|v9;&u>Nv)< z0mC25SmsU9@L?8t7J}OYY7Rky!0bUHoBbqx8Rs@|OBWGzH^IKb)n#c+-WVvw!GKr% z%2g-y7H+QH^q#mi@n^`fm)jNsu(ckc>(fUi5OJI6$+z-;ZbF#qCn0oE(C75<@DQWC zq$fzSCY%hsDG$~P*{pFg9A+ZzSCFyL3pg%Mm7%hj33$8jwUhV;YHtvuHDQ7(1n>YT zk0ugKNDw&~C7}KO2-2Ne4*fKZDcaqYK_6QQD7w^Da2(jd7z<3;eNeiD3&3o{5~C>~ ztUbWVc-+M4A#_A)?M<_gCl4W#;xC#Q7%2TzMIyC4swf{lNCk^2bO!meG*5AYs{+~0 z3R{a@gq)gMFp^(=6BF!!639SR0OP_4#H(e-6R9OsR}mEU4PM1VjKJefD64scvp51b zw}{-%i_p+S=y(r2Jc3sfT@IjQjMpm6gE9RT7c>bc-8c1Y~+$x86L2-Oay&KJQ_%I8}Kdhfgsp}u11g5q13kr z2{;9S07Xn{#sR4`)Q`Q?MK5S~m7q-s`V{d~aG@rm#&Fj~L*b>dbb^`N&b86X9@VJO zY#RbL{<@JDFCy`pljvdr4O^bW43T?0Zf`$7)}4l)o-E)gz@aE&9va>t4y)oJdSej5 zlmPmVdou_J7eeSJk6CfepeA2{Q$vOVNygm#{Hn4tF$DOE@FzfbikQWYsWS1Xijm=U z-xeStE!~KSB3QVE56^>0-5`<#4gyf88UO- zBu37^0W!Y=?@Z(cTd9~aH1dm|tVkSIb`+4u?&sR6A5JKWS0*qI5(oV`wf{^(wsA1G z5KZdAm^%W=T_$i9>MGLfE+e)+L45GyVm!!tLfeSD2GcW#%Fscz*{ywzFhS`N<-x!- zNZb(#H|V=sJweS8sh!^5W7rE+R8-8++Cv#fYzIJqkC#k*&=YqXT!<8Q0m}%sAg^&0~IX3`zsMOj2(?1xG;z_9(sLtNsmPf^THsCWzb`Vo8cHjzO|j z$yDC^o#-tE*Q$k5U?PwLnDAd|XJuYuFhm85Qj!`s9@!9jLJ?WO`&@2!Fk(&>>D$)H z1xVa%fzUMz?#Mw&QCVL8g;)YSdGJO!jBzmR2qhHl)`-@LiinfILhw7sXvjB(2aTOes3IU zM&dNW*rrdq;Pzw))he<1kUGX=!ife^MeN_ID%K^2mckh%p*e9cN-%K)ZR>Yt;sF>T z-2^zPZP#5|xD5wJTK6$Tv&CfaJ2J`UM10of*M(D;%15G-6K#8<^e9Fd}@v;6b1ydtKLjm>k>^ahgz4bC=e_h>##?xy&`vYtPTkHG&vE8N1=vr^xg_W(xm;@)3rdT7ta9 z&@(~3jrf(ZI%bH&aWA~LCBhtV9Ied9!0zlN*qwiV(GS7#fVKC99|`LffNZ_NIHgd( zEb$+|x3U8mp#jy7XUCsB)8{8kWJ&C*sqyQkCb$ofFsI6z^U*~Op?&M=|9JZ`L_>jy z-TUdaIRMo#ahx4bPEen)`6QBs8<7ryCUX^+IM(tSH_^s)1i!eh>FiuU*s{<{Z(w$` zZWSR|aegj>oZ2VG^y}5c|6Th6M0ySfnZL*t34S8!<$d5Ech@%t9P03G6x%2I=RQ#V zN9Kv#+4W^s3G|zIP5g+icgy?#dMgAdQ=hp`g(4i$wz(;Uu8z%*}yj3 z>23ztC6<#QU-?<_tLs&;Ou(bjsAgOuTw64x$x4aW>uZD7k*>Ytyg)pQUtjOHVEB&| z%HD9Xh{B)+kG90(sP>xV6bFf9_kQ<( zKfBOR$RjrbuFz|zAiIyq`2+;Ke?7WYf-E*_&l-2pwzjma#|A}ZEVrNmvGT^4-|!S+ zjV*llQju1U#SP^7Fm_Acu67&tuLl$9A6pB5%J(=1jQ3rt_Xxtl-OY@>1h|VlUv)bkDG{_W zK{K06K*N<&bC^U`uAv)NMn!w_11$B zK>=zQ0SW(f(dGch0B%hwr0PDFKv++oBVwZ^H7!T>ta3AEA*ps81{B zLeyyzg#SS1O!A@BE zdff9{(*D2x?BD*iIQoyY*1!GmAK$!plOt{Wo1fzm@A?;m@Na*?bYUImzy08^Z@yhR zN&3eU{PmN+{tews_5QE_{$Bt#_1f zCh3?nmT+zpV_HW#cm5lcMSw42G5_U%|9Xo%;$S)mU+gWjfuytP|JEs{<`=-FP!nUc zA$M9Ho&?zmhQ;>W6^jf+#hp+{$-3EFT0Zyj@!5dl8!}j#9fL#Pu1>plQ-RUM zbVWtQ6IHhdJy?*UHhDDn7@FY({j>5vRll9Od14-=xNU@&Ra$mpno zX4A6u$Ooz z?}u(XTagiBFZgjGGb4i!{eb@S>(l9||9nrkgN6I!zWjj>N?r&9cnZ z$mdF>q&=I(aNZaP!T~EjEN|+Okp;@ zXe2j_Z8_RuT_G&)_m!|H#xVf1C&MInM8= zMb;MTMg!E%>N#AeJl~lTCu!w}hiC)%*^nQ9w=XzDe<%I+jDl6wS5j6sf-XBgG4ZM` z|HV@1zSyeLK2AhH**B3lnjBfSP$BF326ZVKID}hryVFi}y3BVjmK<7rHhcYV9yBL? zj)EqMbjccLav0*Y6U%fS$mQNfA=j?<_0KB)@p{z% z9GfVnv>BtnjA{EFtrQjQrM70@_`f^JI#?R_ZPwr3uOqZbyV^Bu8TT4s*qAL=w^mI_m{m0iCDp;Fx&O^>W&VO1l2(^5us|y9<@UHn3 zjTsjiuz`n35|_>^=8{uW|HiZ&R`_*`Ju?d#$iqA`l@Xe{R8|@Ro#>|(GzSRmp0qb{ z{*TWjk;*p`XZSvbdmp*^zNvTWHo9GSdx=6fmfQK=E%T?dh?0^LKaa@Yy!6(3;{MJ< zOHXgP2Jv*?oZ~^d?$J3TFjBkPq5b=uI`wx~y8G9arh)%@w1i~n$er!=rH_>VBQVA% zZnOV&abq31Ts^B`ECsYmAb>tP!SuH*&U3vexE^;GBO{}u6NiKyGkUo%(H&Fs!pfDX z24pOpFzij2UtyA0Q5dpQ<(FTmC;zDs<=}bT{KL1V$3Lkyki~o?+Pj~P@Jb4gzixM! ziF#fpsZbj*puy(A$NikLtVtf(6gg5XF&7fmHSuNKN-9#WOrlKV)Iq1meOB9zf_^R0 zpN&P@YAXhDc1aEIE>lw;nyCmW$A_M%$-5BD>1JVk>B4lLQPkSXYsKvIMqPTfq6`)N zzLJdM{#;RhdnITTHWgp{WIpLZ&J&AVp^IwbY<}6vVEAc|VYP|jYID?^$`47q9=9&W zXG|T4OO_lF`aRF9%s6@1(+G~5Vwp;2+78-X#X8s2*8a>eeUMQsIbyiAlU-1omR~d2 z=Hc0SR`~#Xi_uHVj!u!>QjwaIxRc{<219napULIDk%s%kxkQ+9RYMrZZL=j4R^g}E zxJ~@m7kwG0W~t6BRNWf&w)Q|Z_4C*!wV944*W=vdoXwUOnHh|e$7>3&&~h1A7;ijo zIKM<@stYM@RHs}q8?}E+dy! zMcPmLC;t@Q_u^|Sr8z35m@QMWtf^?=qTzT69&IG++HwD<))_*-p357xnP;=)oskm* zL#A}u5`x{ns}xc4mS*vY6%OW@FAKE0M61ZDnXt{^@vI>qD+81YhlNo+t&Zm0Nx8Cxc+Uj=0QP$MVl3DO%QEuS}k#&mFO(3-=8#mL4&A)Rko!5_FtWA}Xc8!P!iimJCbT_1Iz3)$p^= z2{*CXERWUIg>Uxc4i2fnj*?H?_R|ZGlUeP>S=|nGTW-n<2F+HVOYLh^C*@R{O>2AXz!VE>&Dpk?jiw-l#i=w+d|fg?GcA0Zt_KyQij#> zgd6FzUufie?UqI_OdBiR%L&zjjje~-@|D{t!NgAwZYN*d`s=3|7ae~}rpKQm*R9G%Mrl74UT#;Zp`Ed= z*D`n06z|HSA@{EBSN}OLuC5)xu;S~WEw-pS$21%@`FZc^c-fiVOu{p!>2CzT9j`j$ z=UGOFEBbP*aCwp(V&ATU6c6cH>GgH{NoT|f^t-ar{o+z%ifa@Uz1>rm(1h=`auO5s zKuP8IpFhP#4<39in=`|;?(pt|g)4Qziu0B|2WRaPX6i@hR+pEK@8ime_G=w=d-EhK z_>jLDPgS5t2V=9_kIhP~uHEJVCc{F}6E)#G@#QO(8|LU?+*hdECN# z1L>K!l_RZ9WxSirMD(NWRhjjo%9(HXwJ7cVqhWsLieZ`E!R*P3J^|;!K($5@wWJee zjH(C56m!?4YnE@R%DZfg$d{gM+E+1n@P>lYyOI}SK1Pyr-G59T9#W~(^_-okD1P2w zo0YGV`ENCiO^;z*j4amOuY;l zPpG<4@_qTC;Lz9MNo|f48u0=@&B@#CCE13}pIFCOw@FkDCpQ}&T9&d(xZpDTQiLKa zzf%5njAiToS7{U5YdU5N*j%W(e+DUMdMi2|VXf62+P@=$SEtxQl$YfG{XXG(pG{1Z zr?UiGA!Oa!%-HDWr(>#g~u3uUzkn75lqtbNpV=$O4Qkj$c z+?~+u7ifcgj?U0``c0(6{wyQi*OXsz4ZB`xDtJ>v71MHU*VviVDQWe^xQ>-XiVTB+ zl=i!_DW}z7n?q&^Dl~!-_0gxdn#OL?*0oTcJ6hsy5BUq`k*Pj+}e(@_4)7gh9h*?RW1bf^1xMHF}+< zDU5682h!)MOiv1H@7>KCyQB{6HTHtqG%!x_1abuCSS?bNp$k`0su zEuWjZtdH}RAXZd|bD?{R+Z1{9?j2|KGx3LMs9vN&`7-VqgvC-nSXr$>yw58Y^SdmX3cU(JJ78AcJ@q`gFoBK zom0gu>Z0Le#6}K;=pE?&GQfeO9eaOn<15GrwjPRSIOaH0|>>7#z(?)ZLBs zxH)RwUi6q`5&UDLlVV3Nt?hft*tu+(PD=OmZvuZz3VwNApEUX=E2MDn zyzLz^!;%(`Sf>2rx9Eyv&V}(Gqp=t~u2FY{h9{}*umpdhDa&X}d_citk8G+=)ijM| zhY)JJt`{mzsShmdgDp0#unf29sk`-?M&KTBH6&7MrA&`d`}1j+?M5tzNufK&gba=Z zS!`JMZC1zNaK#BJy@TqTlOwkX)*Tz9WS#8J)(+$MClG_|bK=Yubb{>VhW$4ySXHix)r^))I>cPp{bI!GxCB+v zih#r5nr92+&~$9{t)eVNt@x(p$4A<8?z__1HJ|KmJ}mo%*P@u_nnbgix{*lVWY%&{ z_k4iH$gJ{h?TW{3JR@(;Yj)n@v)<&wGSX$N?$&iK=1JasJe&DFQGl(|I7BSgH+t5S=H~gPo%mHdHi7PZZt1Rrh_(CHt1n%;IkqiC zLf&DCX`>4H&#)tM6@PBoLW)_(dVAC#=3?Thle_a2IijZxNeOK@)e zOswXMmeqVaF2AMdE$wd2cE5LQ!iTxrd<+W!NGs4XuiWtdd1>HPuVH;O7zjp#u-;yx zjij)!@P@4XPBR)B8h#NGvMeUam;2-UY-(z1`D?pKOfR^T>#Jp5lTGN%`RGrXvA&wB znKX8uS@OMlxW&q0F?$Q8GV1Q6-hDi0sv^gOnrpt^$!-$94cF{^?@2t|dOuuauJ1)f zpeBn{@-cmBk(=Q27g{<+qbJS;|~;$9x_p_q-3+?XS3bpvi}m(G2!UoQX^-u-%fR% z9+g1<78~RD)~%qd9E|q_Cp{#?Z?WPEi62S|u!ry3gAGmc=%-anj8jHh3 z^Tkach*fkC8tf*KX3O|@kj~{z&Dyo(tyg~B_%SndkKn9B$pq;~themh!d`Qa;_N+{(d7iAvN2#waSNCIjWzZyG1pzJml3g&@*YfjX7x5 zVMDD&evkzf>7n4SVDn8<^61QV4gWf`i>FD>U!{4$4w_jxheFsCA0Kb@o^tQrdgw?T zFe`mF9p&+vncKH9PjRig^=!asxVc&KBIh#QlXhxM3ZNc|d{WvN$9}{?HCMj1o;=hW zRe3;u_|p%r+k<-~`W2)@KBQUYXEb%OZxytc3fo}b6PjU=yKu8~F!FgBrMtE9B)3U` zQIlk64P|fN{=l<0eb4H9pEY`@D5QMkO~RFmJBDLh+ zO2owE{Q>K}V-U2DVT@tSY_dzI7wb?XpKDB1!|OV_6JeBxm#m$o1Fe)!mexEQv2zq9qh+eW{QB*{i`Gcl&9d zZO_A{{Zt#|N44UFKRsy^P9leF&)PAVx;*_ec+s?KJg)gs0L#J5QMvRR0~eT=9+5n0 z&JI#`ns5)&u_e^;vo?Q7+39*{WV9qE`=%jXw03q`=stRfM1E1Bn`wPptiw9}*l2vX zd=$HWr{5-7c%+tlLX)jfck+_2gYc4nbGqAm%44SpZf$z&)U#6!cQ;WMBNx3kMYIR} zE9S@6tT8Jiugjme5>5R93AtiVE<$OGQOpCT%sF>2YSn*lqhzp;J<|SC&?7KsDv1MNPY{2A_*^Is9xb1+;k-fPm z$V08<*xqU1J)xXdS6ZxVA8>P(7C;ZY32p{WfY# zjQE1y^LBv~-*}77HyqjfIQGELuAsyo%J_yXFQIqx3U(Y^-Ju!cEc^L?ys!NYLB3JK zY3@TjKO7zxNT1Hyn#z{apy3(jT>4?uXIGcsR+dQLE%M4wCY?sdx2%L`Of6;Y=*?Qs zVy?!evvj@ijc)d8sq@6kZ1L$n`udN)YLu6QS%osx6bCb(WqLuKkLcAVc=Mu6sv^&2 zFa)`F48seR9K4gv{13ik1b5Y$wUjmrbK9Q{9{nmW>z-V+BtOn$sTfe_?_jswL3@$9 zS>f5{kKak8Uq=(F<;D(rk=frze6HkYW@TOJ(7w*MQ6_O6Nhffh*-q=-TYkUaWoE5V zvbsI>kb;PGuv^&K6|V0bKl}Y9azD$JPCQp$J>NF73G1Tr|wGzf6gB z%#Y-C70A&oP00T&l$|P4%g`y;M1z9I(p6x$QtemFdU#&-Xk%TWlcv)7NI!p+Yn}MC(OYVO@dUSHlZ~jc$^* zRL{W^xhw~^v^iQ;55``*J8)5h-CEjwSz=(`)XvOmPBp-R!*$KoaMDA*?6AvT?`YeU zjGnUlq7$pz!4zS>Y=1y$E%)v-mwf$=yNuJVjur3FWZ;UMd68ayX=lZVnSa-kf5ym8 zd9g=Ztlm`69XaSyWb@r8s^{cdX~rMA`yZV@~?_+XxokUEBj{fF}ghiL(Ve=5W>SrQt^AaK9 zygs*uwBoFy6|cv&Zr?sKKCYx%w%1|9!P@4asZ+z5hot;u{1_vGMs5C7Jc0M+lD z{c%ay?mh;2QYXwyLA1j9UJ=A)gal>==hrhn>MLv$U z$xIj#hd|JQv(+_>pUyhk4bj}5k(9O={#h3?Q!X}g`@bPsIBhpKi^lvMB!E5~lYt zPAtrr@!J7Tt(4iGadNyUqvFIn1FD*(nB78Jh9m0@d*Z11A78W!54vM8*6}6cd5B$5 zUHKf{?v&RF6$Nf43);ie-Qs0hp?46k!#Ohi3T^uPkI3ww+hu60lmAcZ_tw+Gglg*K za{@-KY=urK4u@wpI_vLslc13cK6<`xHQgrtA}`cP`0_QdC-HsbVjX8pPm`Ao2|CO9 zBFtREZ6!R2WD*;vY0SVn@uZ_x{kZgk;O@O5R#YV;J0tb9t+Ql~n^j4rQb}1$RX?%! z2ycH_^Jg`=GugiSSTOl9xi9@HN&3u@>FrfvN!u%i#{($Nzq_st6bJj~p4crTa8~Yi zuU(vF$PDN{ul8de51ZMz@18e*z9qVUPw;qw{#WhM@bcaIio&LhB#{hiQ)O?}gLdr+ z_f?MdG-oI*e&elg*W35ORJBj~XwPvP%{rd^xkZjZ(IS!GO0 znSAcHa8!%x=N0dEuG(1pHLU+V^?R9FB3lx9;FkesVL95}RcszH!@Iqqsp(3GEQFVw zCK+SWw#X^R(6_K;HZj`wLdS)~8Nb~o_Y>)9Hw)Z0@t8ch2hq zxeUoVH?h0{OM^1PP(M2}p@=B)T^;IWj!mQ_Bv=1b{YFU~jk_j;M8GYou;E`Z9Er4lB$SVL z{=;OXw3|Oaufg`^$=50B@lg|dm&%B^i*z_N%Ox)P@a4@k2-pwL>>|=uXHXpZXo-%N zwxOjZHZARpSgHB#+t(Bn`si2)*8E)QyBWq3udd00Z?Ynz_TM)&s7hqbvp#JBH%kiQ0uP`^pvJh~p= zKK_-;cXvT)Elq<-=i9@2*I#>M*k(!{&S8mZKKXk%_^#_V**Tk zq3%1v@(u5GJXao@%A%52L33T`w~FU7MMoNy-fwZxBR6a%esg9I9tXbu_(+X})s2DL zumt4vxW`r@%^XEdwEe9y{FhjVC?*<+l~R!ov)S^LHoG=#8%~^jnWD)McdOv+^nT`; zlM8CoRadY5?3k2-=IwtN_+!1LETIFXq=eKh|Z&JIT3SRU`adbqZ~Ow)K^*buH=h)(ID8#eg(-hJgmhzDh?DAb*6po8I(Ma=wU18tL=5avXD$y4LJ0tUs zw)DR+7vI-$g2v~0*RpwXnZEB=bDj??gXVrs!bchNYdA}|N!9TmaUuJEBl4~f`O$>< z*l+Hr$hLKv&+oRqHHK~sY(1+eJN)|Gave!rYO3qjbrGdt+Xq~k^gR^;l|DQ^7SZ7x zY|CL8E4Fd2ZySn49gA~MMAtnTKAqe#>ieWjvTON=G__bT-KJ>v&D{fIlai*k1B@xb z+~4olJl;%^G+oNsbwU-JEO7Ox!`8^42)}5}!%3Pfjmdtr*-{^V=LHfuYRkLRHR*Xy zdd(Ww-oXcjUtw{R>}?ajQs;Fa1`m{Au#gM4%*- zq;>Hr>9wbDiBWBtn0pXp$*4}wRQ?{thaG#DBs zIVnr6dY|W@u@o4%Im2Js?^|1-B=Eh8T;>xpTFU0MDJ%OPuwM>^YY+XJ!%S$N2DyLj zSeWD6j2pSRJai-B?pE{~ZtAo@_ zE-pWc$sfjd742v*+ckJ(r-|2iLF=_as}N2yl_)J=u3p9#juVF8%_Av}!${!?cAXuJ zeiIfrb4%*7ZuP>ujz1)tK3JdMRJTc0Y&m;!^;-LmY_A(`oQMAxRc`?m)%U#*kBK0H zii9Abf}kKJ-73=E-6{>z9To^kNJ@8i4h$tCAl)6Kk~2dyLktZ3&!C_0?|tuDES

z&pmhN^X#+Fy6ywo$(!{Z3S8S@p;Vg8g3_@|67zzlT`(BsSuKEk;;!WGryrHsc4dhZ z8>z8e&2ENjT^bq$*mZq@EIc{R=SI>hzU??TMP?$`0+U_VUf$$-VETV^0nCTi#fl!`HRYL+&Lr%F!wppy%zP&&zs_< z8kd<1nv|vw-Bx9vZ57-DP8Y~QuB_f_F`Oflrd*WF-tL3F-u3L2m6?3+e+TR@5 zwSumGaT}G_R8F7?w4O-ZOi_9A47Rv3jJ`5ZGzZLz1zgNyq5Zxv$Jkk%16linihOsX zq0Mz5$0SFlOzR=W^oyS#3DrpI+PJ^%PCT>~(sS`mo*`oj&hSyoW0$Jr%%9O6zI%C0 zpLC$D3cV9EWS%<8wHhMxA84K{#w}Ny3@SXCs53;`UxW7(C7MjnkNrM1Jh3le?suN< zaeLw?67aNe5@K?J8syVYkGT@{m zwewOXdf{1CIrBmNDCokGQ+>{j=swp-L2V4FZYP8A#0OdB6WAz9*uzhx`@?6!_GMAA zp)}?O^xlUwh}M&VnQ;Ezml<|78D%$k)?@Zcor-@%O3`zq_(&Y!Qf&)-5KKIN&fvbdu>b zg$HxIb>tk?N$Qh2;sxS+LodUxh?Cn>>yFDX{cjFpBh~AnBC-zhHPtBE0!L|d zaK^iHWQptcgubF;lQaI6TdkE_`^!yx_5NR`twiikr24paX;*DMWndC&P_>u${1>--wU({Th65bNT&vE#IXJIEQpXm%qRf)f&zXIU!cdrtx$B(ORdn(PrGAlbYLreQ0(oF_K@S1!PNlJ3r;`xUSpY`oAs&3VluO{x9tphJ#4m0}C`&dn% z-~E(Z(qCLxzsW!*L`+_61$1{9;=0vgRp}tns5E6Z*w|qAmOfm{+M-%${|ybtXH*MmgHJ-G(~L9q}nEnB_imDVeo$5WoKpI1smM}2f&E@67yh%)5nGOW8U z(e~P^Q(vtu_duJ1J%ur4*C9yz3VJD~pp$>=_!EELL*Amz*M-4(UxQxuKald8pGIY` zJA73!?MYo7a5PE~gbSdE3Oqjh@-py|De*;Ep7$$2T9G|0!9A=6+ui3R{M^Zw9Ok05 z&`NiB_^>dh{~&L2dPDbt?{OVrOovO@FH0-5t@B2`rOQsueKGUpuhKl{TF_m)!yOjA zL^&r{ScBxFdd#)Zcf}=*OzZ7t_xXV(sJy|fdpl&HLpN9X5fbx_D^~_s#-{X$=FBKuZk}f zYiOU(PIzWigU|UOzmhX-LB$q~%>F zeTNJH8dE!;FKWw8oMCwM-C5;{QDP6{;O)+6TDQt)F9WuBdoLukN3-=ECwtzldg+;S z`_zQ)=VS9_nfMctG0nR-fWow41V2`ksND%o{&O%*8cZILV1mca{Vf^Y1xUa>{IfVa zBB_IulajUtyHf1@*`%p`8_}^#ZLG&<)uo?|nJx#gfqHfD&6}a$<_=lnak} zx*C)oMEpJv2x|c2s7pZ5{2M=M7&!##>Iqgs7D(`z%=Ij(O zp@rA)KkBz}!k-ji`jENbn;k@1CXp?Ic&|YWJOJd$WElT^J{-5Bi**23`gYOq5u)idAfEY!nveLGLA@lY@oz17fP6jGYsdlX1cZ)mI)-H>+A8(&iF9~xJ1iDLi74ggz&Gj?*LVzx?I|F;-#srjgl6} zs*cuzwGnz?s^U0|Q@1<-Tbfr2X6!=*0mS4d%KCGeDF5yAPeZsEc+P&HiQoUV|AF?O z**o}`cX5ojAokD}5@D{EC*XDDb$2}YMH~(~XQJR>hd5gLm2lyWL0b3O-v@xN%&zg! zhV*kd=aS&h2IrHF+C|Pc&LlJw{#}qWtoZ!gFRddK{=-NoAk!vPx{V$cblz)RpgY3! zyt}Ds2B-zk72a$d*=s%rp>q0j4YCp|q)q@(ND6fgd|}JC^r_=0Jj#~zR}b&b;Rgw9 zoW7uoZ!D@7eC6jG{7-*9{7%`N4obI?A*`k4B?GKwjcQ;u=_qKeY^9$DZo|rvAfUeM zIz+8|2~ZpOF$KuDwX7Jx4`1~I%>&2N`;7@y|Cb?f5`&iBMxf(D9ezg!U>l@Br*Fso zFY)ntWj;%+Sb&$+fc;$YeZSv=1v6Cd-aRWQ5^OgAR~iKPgPJwh(#>~7E7-G@@po_B zu0M}ACIK&A;>(#owO=3=NhhH5xI6ZW(Qaq4tMW1H*sD8kz+qd1t%tDd4*o@;0(}*z z>mcY?h3}txw(6%Z`8o>=i<+)(0_d+?}dAI!1c@O02RDuO%!pO%A@ zk(Ex#h<_uiH+W6{Yh!sbVp|Xmt+KlUR&)FZT!Q~lsfl^E&Tp0BE!x>}B@Zf1gk9g< z|6r3%)?)47a`x`zy*z>DJyE;(I3GFc0YqEOZ;pF;+SpfrSnTP~d4CxT<-{I`o|IL!xqZ5p_7otlkUFTM3me(30l z*uTk8i2Ql2S2~5YPtVey?Q9Ulamn8griC5F!8AewVw~~ou)sm}#uv@vJB2bx+T<_I(!fTS$5QKUtD6 zXgp`qb$l%)*8K0}so__8fa3?tuh7%4jW>p4su=6DZ$#&CRpk_1&7Qs4P=vQL;CKRT z|8ZyenTkS8^5q#JjeDkuRp*=#^X$iEINk^C8H8~Ob@(XecKClkx*Bo%wJ1(5S}9`k zK_ONca&Z{(-?hYJbd`!~% zc;AZR$i(T!L(i&N!u<=7Pn6uUe~sp z5ZLYzyu)@9XcZQ4zkTXR;5$bk%VhR5c%O;%IxUo*T(*Yzp;3)e+ChOe}SH#XWjF< zd@_ak5#(+6kg2*MwTP%;v$ud8hIxk&vKqe9*+CF+uj_w4<&BTy<$xyOk?@1P{jDFe z)er5v*l9p{W@7K0xm3K&GXQadU~D}(ol8e+mKfv zA4W@fG1zXHrW!pEQ96WeVtWL(y*fKSC2-6`IR9zxlYkipMUk=Q6TQN96#mz~rGw>+ z`0rH^?SV@7xsW#2v0bJRZUcWG@SoW0e_uVxle4zYV4nO z!ku~TX$F{3_Qm&$>L_eNZ{_7wt60kG>mAg>9m1x|h%|a)iBkBxK$sa zIv!pD&ym2psJfxJxuxOXZMv}iif;^C4$t_f*5zNFt2Evu^4ej%FPTv2;EnM2->aTy zMlgV}Ym>|OXYI~wUIJX_NwbrGO{^#~w#t9E)Lz_IA#di%&Dq4n_~J+PT_LVu_fiY| z1c7JC7}14niCX-dbU>&WZQT$%Ei&?DQQfuZ(voNT=f0lV(aZe*o={=H0Qw#!&NTLX zrDQty_yKOGY0iE?#s$?ZpNC9-G!+Ln|IA?UGF>oTFSAuKl;0OuZ|EDW>%FMhBR_s= z#5v~HLUl1cWRUgQ;xR&Od@GI5W>;P9^?>Ecr< z!`~gMaaMMb)+Dn2x{nV5?&m!iL$6T>=gGpY@%A-_x%RcYYC#{Dzaoj@GVXrM0aN`?qHBzXK!| zf*%0oKR59HtMIe##K&Rc6SI!IAHN`!{j)0ZZs4*Y%bBlwntxtQy}|p{CgzdFVxCM? ze^O#e&+BDGJ*K_Mp8L+*beGMlBn)zbqU*IyQH<`)+8A71Bz=WHX4OP9tMR1ywnqI* zLZ24~6&iB~wHCd5PN08<^e5%&N&QCk%uA@M>X|^9oKtQ(G@t!v3?!a9y{*S36+KYS zS`3L$@b`M5g8$YPg8$D0aX03;@Xe9Eq2m>kToiHJpl`gQrlVq&*7_#wrUTWp%&h90ChF{ELQ zPw}VH=-Q0}*uv)u>bPGUS*d$c0&ibk&j0_34;2r|1fPw&?t2!be#6`VXZE{l0mW`v zwZ^0Z6);e$`)WIV^y=ylUnx~L<9#&beqh5q{@?3`0rikK4y+L6K6!g>N$&ooL2(B` zN#!!u;WYSEk#B4m(VpW;ab2#iyf!UzCfe=KTj*YX=@e_;+<1|jnW39vzw9vj_|{U+ z553Wbj7L<&$fmhiFK>&FdzyUt1!M5_6Z<^Hg{qspz8;nA$#D$Q9A!D0?^@FnMNa6l zQXG|zDy%2pPYr7Zp%*Bj1w$h^jL4Tx`oZNtdUoukV=er*P(|buh2?)&%mj38uceR>rFRoK|)bX+D!Bes! zt{8ifYhT9JwowIRLDgmsu_PLNg=3VfZl?nAhGbP_yf!ZiOOum0pzl#MC2}_U=$}VN z)qB5g&=%UqaSY;W6hj=Xos^=KXoMBC2Uu4z0&Ms5+EEjsNhCJ%jwK=CJgk##+3(O7 zp-d}GR=?|9!um~~<(zvU_!;uXPW*Dfk=HxCJ?E5pqkRj1=g(hNo-c>S8`mp!DS_ySXy}liNt@uLa$(gQbnRj zSur)0^)7R}5HBCYvlWG|@kUiEEmvM-%y{i8t8(c`;(KWY+Wq+rIoaW~`Ki1#Lor2e zp~DnX>ClNXu$h_VTn4o!e{CR7_$r2=x~lk@H!Jlb!gMEuv0cE9Iw>K&=QYVhP2Mfy zZo!pLD1A7~oMVV-AclNpT6^Dq4#o288{SsTtv6Jq-GOH9vLECPn5LGQTg$Bu+ zus`58^BSKK6j3)68*HG*5tVfMXQ38ako24h+SbCV$t`BQpf0z*^XTc6ELUQ3Qnq6P zp=#A#+G%eK?T_}jBkCFt?`G+J+17OQpWHStckPd zcC4~md|u-9Ouv$Mek-vvJCoP$)WKaQAvz~HI(t#X=4d?c3IzxjP2Mp4_4FA}ZbSAi zdGkMX>t5X;Xfp>|*=c#4;>Sk?ULd{VAbhdWaX|+a0aWBUt_O#eM-Ae^?bkP)>!;`%i z!+I1xVNv?d-e7>1wFIz74E!HyDf`mD{O>+D=-wCcO76 z{|518OdBN>Q9(}dU1)xRboGSa9aU43$9s&~-5$7?&)vd#b?yJy#2 zDq~-BbbN(QiRYsoPdPP!FPJqLZe!njy*Z>?FS8zfuRZV?yR9H2_lVQKw?BUR#Ao<( zQO>R(OS_x+GCpxi-*k*W%SoP-uQm{U1Dc@6!`_B=3^ZNc8|g%b=b+le`0p>MxJH+H zztogDVydIXj()x~2ebSvl`Fmf;Zs^mWn0uYyXelcnKYd|fB#p0LDn$faa=oxF{-q- z{%(d9sfOBjhMT!})LjM+$y~cvO>b;y9;E6S=C{?b#nnI?8lSm~)EmY3_loZ6I4Xwv zq5ssD&!7q3nJSxr5rSa}1cLc^bDSHuBNk8Hc5ARpE&Stng{zY;5xOc9R7A0PsoIg zha8kWo8mU}2V0R+yx!+K{q~rR_}c`w4__s}xhC9F3U(^oo?qV=|Lra*b+ir)Em2^* zP1lF$8aEJs|E&cee$Xz!cDOH{ZDQE3Nj3SNoG(>AHJjMKzp{_5c=l zyt;9b~#4({if&l-MvZYg9SI@+tdkkWd)wHdIIbcT@~+lMMrOPJ&Iyg-O=F; zZ+0xG-n2u+L9??#kq#-Tc>@r?rvm>ljQn0Lh}HpFMYG?YfZ+E#9*ve>;V1RjNUgPs z=0rBE6mW_1+T_UguprF0mDf^syzei>hI!fhT4qeBtUWB5aE&M)=4Ga*S1|HT*E>B} zjeNE8=`zh#8<+JqR?J9G9-@juk@K2niL_VMWNyyIvGF!Iw zs$I!x4r6$Mf8%x{vFxR`KfJvBvhf4mBWpJ_NY4CQ&({*jn%wGR&ERLbQ_P~(BkaoQ z`x9920f(XL#+M+FLzc6F$ZCl#$IH|_*e!0nC^MsGrdF@%oTm`siC&jIH;)*rsN=4RQSjX$kIliXk3l<*y<3QzhTy1pwq%0#HHjhCj{H$7AviUY@D>xQk+dU~1oLO0Cb;=4JSl;8b77fk{^zhx)ivD#gqQkF|Y)W(V4!Z>4= zn8%UpDdWZY5hto}*yVF;!qT70|BRzdrU8{U(=#j zw5P2lXlVkma7Yx zS~e^9eCzE4&E4&z?_YAM?H(5oMHi7E0@bCF!Yj&mM#ntxmiw+5AZNW=7I6Zc+WIdy zJlx-5e4mecu9RmmrSV1&>HD5D++HEYlyRhZHGVIeK5qzYX6x|vkL1U1(`)HVM<`F5 zwbY%W(V+th+P3`rcMV9AoTANNp>n59jUSac3~f|ijvcRcf%#4)KKHy|t}}PiE!8vg zIa?bVhZrk)CFE~i+wtmwTfK2(PbuM4aH5!qq}6t**jk3C!{%e{SET2>s`x0zkd@*- zCRRyb-11?v;@+OpKaV1mA|@g@QVK^pa;3|)o2q=IKa#j_CzDKEiztoiu@~05C3>^$ z>X)tG%`Cpl%Jh46#!kiR7D~ONO_WN={q&Yj%GGMKCPvYd)^j}r{MRW7!KOMIla}#| zv9)#^j;E3f+~@`Q+`XQ!bE+p#RUYv6r5MemXP@pPm3jv1Z56-7m2e%_H__V(8{}Qx z@K+uQVn%US1-aL!nNm>;K30l$io)U!r^)>9=I2f5`ClvbTV?2(;VEit)-*ntp_Uyk z36+K(^=_2k?v@W5oBd)%og~QFa+R+dTMcb|1}=9mVm7zEfk%*ER+fuiTS}>x6Y^Nr zd*1Shd&3qrEfSKBZ+CN@;y}(NqC{Z9L|%o}e-w8Uu`{D8bS!Nm8>DR>#+I+p?b4x8?3!$9HO+ z1u&`c{Q0no-N?dYF#V%>nNl8cx)D1HGV6gJWQ5Ybrd98E(_M*iz>7gvsEax?Yp zh$@CLIm}DQ`KwHixF0cnZ$jp0jOD#5x>^I~AgGXLX>&2SVM9eRZNEtT_%OxS&|aTM zOk&@NQF$;trC-?92_?p$xA;2gcXR+Q=R`@ zrh+zP!^=dh!)he0EQz7OF6YECAy_WF$}N3@lQ@NoOWs1E7wOjW^lm=4AEuT>gICwf zuje1jw~!?v&2sM8L^iiucisb;zSXcHyjP89L;tuE6` z!;J*VDZfDl#Vc49l^zmq+Xr=6Jh1%wk$gjoK7Sk&QLI)4T{!PiE>*;lZrs!?-{R#P z&;B*8Qrf@#x@m1vRXbauDd6d_TX&+&+9Aw%IZxJolPA`%Bv&*S<##F1P}Q z#cGr7iBsFhL;R;TU*1^Kd-yBo%)`~EmfVu=`ED$ppL5;&V5IFxdig!}#J?6adG5JBtTlglCz%ck&o-3FxU|Hzh9 zTOT>EQ~vRq6*_}+zW`XV+HN30svLmDZBX7dpy_5+^9Fnj8jo238R=hp0xhn;=9_C)KEs1{LAeu_quvj8pEP6iQGkvx0H=}H#CqyGaP)&p>n`f zHJ>=m*`^2<97&pbtAUVrCRL|sj38WRRQLnKb=#uzxGa!>;-MyVoVpkJFMoh&Y^L6u7t}M1p!=MeET6lXl}!UYz-5l1$cy$wv>QY?86|wU zRwU0;o2K?_bmRrbmZ=ZHBc_`D&nTQ;KeNvH4Y47ipa)MT>oDJ{y@2reA=eftK8sFDFvNgKLsv=&o zbN4s=q4vlq1~vGFsSF=Efc(N`!HOY5^SzO=IfAIZa;+>sdS4brH6sPDxD{WKhQ-blaAY zf9PU#%WMUU=^M)xgKYF+Q>?I!0un7@koPW_7r7oG%<(cCIM<)GxvA~TtSK?%Pp#*R zJ!BPjNv~8DKSEcRvre%YdVbn+xCNLnm@~pl)c?pQtcPe5R}LG>DmvN80NKCZtT4I* zC_LE1ug2?7T=bHgi|F2DEU=dJO?6@5T$Uo6G0Kx#J!O9cPrE>$@eEQb;$&+t^$ME! zH__!Bi*a(Rv9~Ou?lV3)LAPhi>~@eFdHgp{!fpZ(32#^&>^Vl7C>4e&DZ)t_N`M>C zG#Ifp-OP6Pjb3sUSd96Y*7RN@6kp1dN%%hnCHgk!vs7tqmK?j$V4L`7jzqMg(*4{Z z2Rn61?~e@vZs#a--h0B&%*DBa2Z8d24)hKlws>o^8C{P3UQ=IJJG0J#ET_|HmNqsJ z&~r}_HR4OkV2V&~@pg8n$6WuicR)aZ27fMN7xVbEq~WMO6&0PiVy!gsVnSUo5>U`{ z$HRDsM`vakQUF;ay$BNdXCT2$*}NVjw!hWgygth8fqMpmrwK$YFgWO5*nJ!#rRgj< z-}qT=l!E#gW;fRN^MPbMoC98T0~pWtWS@~v?D07Y>d$7%C67jbB)^#B@sB~6 zsDAEFSJ)h9_H2xf;!imZdpX+%yUq22(Nw2Uap%@2`XMNuZSOLGyS52~rW&_dWI`uK z8yWlPquGml3Y>n3G1nnyl#8$mR}tp$Sx=#r9A)K^87PICx@N( zYqihpsb6TcXqr+&hY~KgTh;pq_E(hEln%*U3OMY?Ke`Ve|MJuyx?e)-0LWvgX|b*h z+!p@nfpd#a?Zt}w+G|)uhIf%w00E*-i_N!Del*zoZq#VsT*Ir8uEh#$X;~J=LiGFi zN(Ash?|b%t0$>XS5eSUkt3ul?v^&(K!heHjA9l&+@c3DM{Sls1gQU!ymSXH+nZgjC zx>{XvAJe4ydEJcHo8Qs~{mTnw`NeDXP8%_|6uT5jio$lV6u!I0H26tuNSn|0_i<54 z2IF4># z*j+AeL(Czw<7KrkyO*=KZg#`vtB>{7M;F9KcA_xv<#R2^I~OW?++(C+`l}ynz+>)h zI@NrpXOK6O;wF(byub?}poui0=fPZ^@Mz;{gJJEt7gQStFr$HDHZ?c3m9#HsXsYZe za8zMELd|!*hQ2VZhY!9ZhGXW7A8ZpWSr=62KKn~eseXL)2|t5?RBU}7}=5A$0ZhFM$L3r$@*ub2i~r=?Bx;IA;412aR-DEzE$Rt#;dC{Zx>wti3j z7}iP7hSc|kZJq49PE0M3uONM%y?~CC4k5Pj?l?8i<3>8t%VqX#BLv=s)#%VXOKYRb z`I)|5xAIBwgl*`J3YeSURCc^%0*pf9$;Qp+Z}MRUJ$4{w!gTC8i5}03;nqe*TsLBD zHTk`&YqCp8y+6JAfc4x*dLCl?J)>jptc*4^+~4;yDAgztIef-8dtg_vY_du7SqCEU z+&u4D$4d~QaMt~c4O9|}A#3Zo=gV0`E_@rhKfgYx-A_eXv3Ip72@Qser<(eQy*wq7 zC(WqT-pyoqKqcJtI|qL~O_sTV*m6kjDfNeo8B>aFHH+YQGDcoOABnb(t&4FfHSDOF z^9nM{A_zA~X83Q7t>!2OF^sjJTRAS667qeX3y8q5ys*&)`a7$e?2@z&0fcAefP*<5 zS7s%;#HX-)Y$|Fa#bq2cK7bnqdutksZbXAv0_5*_heWHtzC7rzv0Gzqg4tqS8 zb6;Rj%p{rjk^DmCO$<(1aj0p)uC@`!b$k2C=RH$fXj?8oPg4XR$pd;&)s~XnvKNaX z_Y>V7x+hu#Q#oRxS)|P*H`-M*!+;Ex?x@~>5yDlo#NiM_@IWC!1V+K-!y!)U}m*ISRg1DDqxDrKsb$1kD0v;MQ_VI!>Z$Wu)2$Kqh zxE$~U=m_5MrqVjG(Q9L&@b@YWRJ4LUbKTfk?rkoq@(^ua#2C(DJ$SW#a9&(2WOjG_ z6%^53e@LB5oj1@+SDH6LA-QHC(2pWTc64g7&S!G<^-mHbc62@Ef}N4;hU7vzW3H}d zIyQZ+3^&99H^?Dqo+AmjK61{?NsD%CzU5_JjKojC3-W((1WQXjxo#5(K{C&8{fdjf zS(N7g8n)5&CTcH+AJA;Nt@f9@0EghF$ydE+N_sR-DNdqiEXrYg#6peUIyz#r+LsUQ zT-|VH{z=g)Ymv6-HtD+iP8H_a`p^@1juv5>vkY&p&{r<~ytY`-?1pJPKj+>0;z5T% zgeb*AH42F2>PN*OOdfRK+TF7W@x~={Cc`sp*k#}n8809A5YpZq<-k7>>u0_3RmBhW zyyWp&`YEB7)vn1na9Y0@0qO9cd1gd<)`SAR5``tdDa`o zjN9tmPQ3oMF!sh%(J>xR1}}DW7|5|U1k8&WyFgTxhkA{QFWVRe)a)SY^K)QmSeF-B z=jSM3gqL&D-*rx3OWm3rBABMTnp%FkUHk$hn?THIt#($Up`YHhn*4Y_{N+#RuaJ0r z02bvkzW8{~b6H^SblF~hW(UcbcUax-nIVPwxJVo8=EoQCo6N``mi7>wn6AO z{D650KMWw{*3OP4VCvCbp1==+u)y=7YXp{!;8s`hMa8D39?-4wPk`TCHer+ zD={#a9qs}%hW(%*JDdW_Oj?mlIB$vISL-Wz?JR8bYy~*n0U1Z0;~H01o4NG_i3wBz6Mub!RRB~s38whB(vQ0xRsgbBWzeugzSlGB`4lTu|T5%6M zpncq=%i=R?R}d9F7S;YI)Ykg87n?@b)|cIxf9!uZzpr^tz^v8mJl=i&Us7|te3`Hb z>E&t^p90xZiM)ftms%u>-mjU#;e#x^vovn3R8M_ILDlG_)SSEgK;D|>8*W1~+V!N` z7Kf}coCer*pqBHP!yP_}yztw(_<;K3!jt<$OOb->e6N@~Tp9+H*^_bw8PqUU@$UJJ zVpxfJ3&rly#o0xYhz43v-yt_z4N`VFaRFv6YF8!rVyai-5cX6E>3( zMm8)ixY<-Cd|)W&wSC=Yed9yD)mzE)StywvKdtb6PB$ zfbBmdi}-j;yo+<10$n`}tf1GCzC5~U!VMu#BOmB8>Fwgx=;yp7+qr=dUgN`U6ehqH zvkgQ+&TPk8z>RB0Rnq{@R07IQmj&#={h@VxVA)rXl$*0iCcR zhjo3L;O|d(v$i=B$czeWpg=L7&dnE1RO9_>ICm!^`#8pE-%(q)sky>7i;r?*4_1>Ms(>bsRGjQH;kgj4NARDnCzD16lK0h zWpWPNV{vUla>N;rTdkK^s%SEgrP6y1Bo_W`QjMg@3o1=Bm%TEvUT$Nc1=rdRlM-Wc zz>`)_R}u?f$$m_&9vZF}|H70EKdSv+zWlVN)YIcZEF^2NChxO~wU2(fbJqujrW1gV zo?O+h@v-ond|S1f_ZkHVhqc{b-Qc>_wu%{kC*4Z&tku_U>B`yz34P;h+PZ2!fsV#k z#yHul(eD?#+ww^m>xoDK=yBAXb6kc0Z`2g`w8Afj7t}nOP237y*>O z1|ar?NhS)!ezY^L2WI>(sOVM>jjl@Dc+e@Z4zoIWh))&u8vQiUC52koWL1|QeH$h;aFbvFOz-$7jWD^*nTbDH zU?MR+1O0=fU^V4?O~t~sMZeQvqj|MLAj}xm&HDrP+%8kSB6$9`TgJtG(y!ykV?2y1 z=Ku7gbfQGFG~Gh={?UQ5mfB}A;rW7HC%sW*yq*#jEF?mC@ZF`|nf245W|p}c+pOdF zFYgV0egU?r;L+nx<*RISqUO+G;nPp_`G4lZ#f(4vei7Pfv078c zHtqnQ&57941O;NaNP|XKfY)H>G`V9_2TwecfE06x3rmPM_#}dot-^BHqeVXTKL*q( zbnvB>syCkp^8esK za`J#1rniIb=W1Wt#?Pb~c*^XHLF-AqUmBTxmQZ(&#=o9??Vj z;h!JvPB%m1EAwQx5#xJ39{?`rds1d|igvOwXG+*;mNh$$7!$^LEW*XXkE$k%xCM$34DY$r+7&v#{NwK>Qm^HIGl7UYS- zb8*z0YtS@ri;QU`<*h;H3rY^;J(3*2NbQy*`c zul-jG(ED319Cbp?Tt}P8UAbBGR_{TFmA0SWil%i05Y3SghqR1WHbj^o-4fHfTH?Ph zC;_6;_w>&rn2DZJ-VBINV?o%ooBMj-aiI9drrU?=t#6>35MLLFh5I`UB?*5w{*YOg z%>Mwi4|6I0V+Eb!xzDDgz8e*ra%aR`7(hkv=hIqmW@b+A#8R0*WG%q897RR%xQu5% z#zzoMHCYBA{kqjxKU|h7sFcMmWJDG}m-_{=O`URsUTw@asbpc`{`7-RL5zP|;{Ae> z=icU|AbADchJ$!h!4c=HTM3$xnI7()1;0Qogp>v2>gV8u#F@6E{5Ja$z;A>_yleMO zaZ9pK7MJ7i->eh(sR|T8xmYCIxVcsx!?sM}NdFM92-en^gu=SH*|}zovy~Q?dHyek zL=w&0H#^nexfozNKeoG51FG#rt4i~YkG8ufC|I~F7JfC)amL(2-F-oQIcP2yZonnM z5Y&$NvcF%{^~0o;+yGo&#O`HUDmU!wX$tRios4NplQ(B;sD#EetWLgiS;#C5)HHLL zdi}|IUuee%HAx=>byDcLtIV=d)S_beYQk~KapEqP3h6!;nW41Oq`6lQDnY(jMI=PZ zC?(v+sloYJ=~5ev^rqaf<}MK$SXB@wq)cn6QI5rK^e2D4J={WQmr=yQaXTwCcV%^m z{0L9ufIxTJ5N@J^JDGMF1=@_K;js-g7eLFB)k4opFl(c?jVA%1%24Qoq<@P~M5>

dTeUNwtcwoBb47(d4v^lOImzlNq=6vY8UT_UJ z+OXH`)S&|kG&VNviK+0AQoTtO{tsVAXk~qR`|(3Wh`4Y5pTy;UnpFl6L>L=A30%pZ zrg*iASb4Mk*&s#qkvwS=R2d%!NLw`_^`={(Qu1HnOXYYsbK7ZR+!Trk9Fal}NAKXR z`~0L)?ssHvB!xwx%{IxWOFonl1A{ZdtO}O`^dFZ%M80(hWG%_!n_j)R@(-|-{KoO| z`kv4ij!DeZB(Q+&y9rewfW8Wc$qc>FI2`VYK)s1AjOq1$W1(oT^Q0ZNLy*j+&58k^ zCgD?x(xfggJaX3@A|>DN+morDQ;=IuHo%elpQFoX+}wG>EHP2+9E+ zv^q7j%=-I-wQ+pkol-z_g3>olm+Te7tr^k@1gXPjn2R=B^eQpS23eJXEnkvT-~$_g zUG=9#m2fk?t`wN-qyV?|XZyA_=Fm00vOt1&NR%9d#j4XB6}We@rA7|H4XNJjjQk1L ze6rTNQR!uP{42z-%%IN17Tsu1%A?d!GE&$oUhk9Gjnc37v7p+_qQGvYa@VEZ3B=2n zbhg#rr|_BO&kAEXEyfw$fhYPu%yk;&qn)Wv3AKxRN_Dh5SK3F6#WdqZ>Yf8^6*pMK zw=0!%tvkZ&~5`;|>KvY0xjRFXcgjfgt zl|qo_5)@KvP7SianLBofB6v`sCQg4&a|C~z-8jwM@Y~nVnY_a%~x1ldiwkh zz8+%79ebk)lyCeJtrtbkO^b>EW=Zz6zcQy?fx9Q|W=YUpr~M&GfVClF!vKjTmE_@yawRm$=}rWFb_R*NKoXc z8w@-rGh*Docpdurqp3_@*gc3XFR1ayX%CDV_V6JAw2B)Jnqp7`km$FqQ32c%RuGit zkE8Xkcz_z;Dci@HrZs@46!ls#@WmBen>L&u(NGV!Xj6|AVJBa~e_C#;nW(xn%ElCyU)v zFY~keLg(d>cG7V8<|o;Ev$f$h)ixJ^LM41+uIZEE@s_!Aba1}d>}>5;3Q^wqHwI`Q ze?#YAGA+scTpbxjE99%;+#M`j9ag#xKwPc&K8>s+Vql;J=y=pZv3JUM$6zic zJcrl>ZFqhs!_{8u(1pqe|!Eq1&pV{8J^44{{|KoYW95?`;qHz?{KTx~aJ zy>{ZFK|yFOqQ*}rrj;|>IqxOr&@<@W)x4Gb4A(>eRqU~+6@76TYxDsgQBm97e$S0; znwJ(5K1y@lJP$9b|5czpJikof<};@OaTD&nHV*ks9sMOe$l+@iie7gNSJ)!@RW~wI z+>l>iit3r{3oSprWIvBC4ct~#L7~HTVFl*E)u_VkBQ^DO*+U1YtY875&~C3f7FHw? z9#8ZQTn92JSar@s``scE_FUaq-??1q{`v`K+0)6r;*AOTHBftlU7GLhyDC+XJ5>Zw zr#T1B^4G7XA2k0zuD%1F%J=>MJ`^P*O_3C7$tZjKd`LrRNs^ov*&?H?)1;6}qO2l> ztRyl|A(g$iBYThR{lD(#===Tt{-4*YKE2L4&;8u@b-%CcdSByy9;3r~ezt3FLXK6~ zKqA{H!P(-OQj>lJ7QS3X)wPaq zMQwNArd|7ey|Cfm?oCe$%f8)E)OFqe!LkBdsF?39hBRn4kh3~wpV0VE?Yb*LxJ-!u zn2yfs)K*Niv5H!WR4*+U#|m~US`>*D_Zl5oJ01djp<7F&tovWbVJGN!8#)E&yR;k@T)91_PiHaYdF}F%!oRyyHPV@`X7ru6yH z;?M)%Pma!||HLoaK-S)_<%K!Ksg}^4b@Hf1cl9pNi=TSG9w(g6lKgV|Ccj`w1WnAx9M3pnI#<-6DVqf?@ zn3bi}jkD3;Zj_%+ad}?|tkcjcBr29~cF#cfhn+b06E0okSNuJzGkab8CxD3V0I2ky>>QLkB{L#Ke4d+wu6P0g2lV+Oqowp4&x<9XZFhNRgNfF zsNt0h!)g9q+S8s=8c<5{TAT{|nPtkTr~!Q#f!$iGOlaU^p~^E+>7VMp;3_XDeUyVH zb{LfJ`MYyMj8y0!=J-TJ!T(L;uP9=sWW=HYe&nU}(r-gJ&LX-__L}UAwm5l>BX(^g ztLm-jq+^~A6DK+D+{s^cNzlZQ^7RJZgq|1Bq~JV!Hwj4Yc+cEiN(7LuUpyWCVd>F3 zS8g2mXsY|Jh{rE7u*;{f()QsMs9r5P4w@ge*kNKNO>=Tvs@b+M)9jL^WDG$JO~K*r zpnLcZjQ~LOt(9*@p5>%_t;^Rk{=Qae^P>H$yR;} zJF-O@EgnL~x5mKOrxp^~ncEJ(g0B4A9S^_Ee*egJN%TE#hv0Cvj09e?e~9-syxtl& zoCHhCo?esT(M?jz)V(U3f}VE`-R&%2hlYO3 zWB*JkxuHv>PXGNq6`+*I^Nv9*%;yrVPadeb27QEUw!1=B-bQ{9_my4>6_Blo zF0gzZJF53+Ujw(jxX06?cU(B$baPPuHB*4klJsYMlaqShcEKJiaFkI; zUxV*qIDj(`#{uG#3;LV(>dodhI;A8fsvkOhn|)n6FVQBX=X-GC!GrMVBdf;m4Rk=m zUsu}V5EFl%80)p&1$*RWBXcqs*3_Fn1YoTC&2h>;@GXRb3(aij_Ix*~wTtp9gFijP z@!KEgrxyW_&uqSLAHE9})$N4|u4P{i*&eG*#a?sxUTc8rw4lk1N#5$kS$~{8qPTXN z`N5M=c-O11Y=w?%+){j;&sZ||Y0F~Qy8H|u?b0Kjwrs!3tc)SK*gq8-C>TBH^ijEN z;l7oBv(!~r;@PNWeq6pADf$m>h;j@0>EH7(BTmQpD&U?LHi=AV?LX==>ph(=zHO+@ zeP;ysMqJNd#}x75J44UuulD|>qlN1~u9LjXwXt#MPm|O~jbZp#W#Y-CRwH5|)HjEI z;&q`_4`{}-Yqh1#L~xmkNtus+Xz@+>cb2h&`zJ|``7L61zjKN?Ts`mRfHM_HjGFhF z70ogJb1Q>8Py+Zt8GpeuQ+#@mtK9B`tiM0*g~O!o;DSu&Z=E$yPmb(t$Xzh#0-g8IoQ=wCDR0H1L!61I7YkKVvun6p zuUPDz?_sw7VN3W4oWBg%;A0r|eLOp5j2H06CxG`T{4 z=~t&s03RGtWL2QgL~LhDjfPvs8M%+NbSX_H3M5YY&d(|%=dQft0Jm`mY2qG?$BzeW zq{ttlZ>P$Y8d?1DeSWe9d_ryQrtdF#&+UneX1O`fHyFo1wuFS|SJ%a3U7vVn|2$7x zXvAS8qEa^WALK)pqxPIlyaS}xMR-OD{HMm1jNf&Swr{v}1`Wv}bJsV34+GW-g{K2+ zSQD2Wg|Jofr%TZ(7T@0;v5$&YHGQpEGr5B`XMTXSc-ylES~DIAv8p89OJWfF#{dtv z|H`oC!K$67%n`N0Vx|{%=#}9tNdKcgKwPXy79}5`^-W+HFkaEvRcxC*{sc zwO4BLovOU5gq+LAw{}M69eW;RuiCrX^4iYy&cp|wub(ju(tuN#e%!+cUFiF%wLuG| z2{s5Jp;Ml_llO?j{Qq;znI&iD=)G(a$g~6l7b5Q&S;=M21V0eVa}4}oCEmTW(!C1M zJ`FWFT-fhzCl;T0-rS9eBDk09g;&|8Jgntw^@`+hGYjR!iXv_9ai(YhJmbBYuVw=G z{oZ9QL!-)3|AUq7z^h1(Xf^>9w60sig=qFd&(^O0{_RikOD2kdSjm>FqgP?1?OXqj z2=}jR1f=-iOSp{0HcZd6UdFbO>+*+q6eOv`o$_P+Qi|rb%7S-!Uyk$PuaL^ly!0aI zZIwe?)dgus=rr&C1HEqi<=V$$3{)jMrS0vzV3w+PrKwaI_?WWeyYZ!!P{bXtFA#KZ z9DfVCG1OUa@vtp7-~tf|!KiY@Zig*K?GH$8(OTK6viVZmb+v1k;9^#rzq4KOEgCh= zP*?#9+kf3p>a*K(_yhn1+wvjRnm{#P#p>$%mww_r}0%-7&*W%-0)V1vvQf@^r3L6*A z9FD$PkB<+Y^c2*e_Ux$+U`4wNWOJ41w&Sd=y!k;^+kA^a#qwt7~&Bo zk;P4nY}pRKCsajFte@~~|8j~+o0Rc<(l{vB+=b8IGlp<}Q~Bsak7*uqLri0Au9kkX z(%kYu&hn$8DSOuU_c@o(#D7wATGoyLJ9aFCwOL7h%^u9^GZ33SZ1Q@6wg+L+?>RYJumXK&YE(57=_&e=?t1+3IoM4@?53=j#We zX=K%dpDfUV$v_oh#!HO3f1t;LOOa!z)AIb@k4n92q-`;~wb?YVxVgah-HYW%-oOd} zD+f{2KyM6#HJ9xfeonOOJw96eU+7axtA;MhrZ;uj2k^j?Ay|(u>t=_ee$n8tM^fe* zNlm)CAjZ&o7HVVI+#S4i7>xE`MgQ zra#VreB$!5tiD;r+jt~^q~K25e{nsWQT?~Bpx>B`@d8*D=Rr?WGS{ROcL@P@)AtW! z%YslAXFosM%Dw3tz?RzjeOXk8sK%xaq3PQ^ZeVM<%bgl3Hy<64O?`Lk2NMO0{Hyn}QDE`)-JI3Df`Ub?dao2eeIJi<`SWbThF2_9 z&EIDbHW%=phlr67l6DGHKwGa4-~-#MnEyH(SKIZ>SvEJn6kqF(n}@^{WV$eL>-W%=n_VVWN*FQByi+Wfk!pH@%==nwN@`Vw#aj<91-)=VEC9O{R5 zrpAu#Y=}($^VdG#cMK$m4H-_gr`o?TgDS1PzvPe2*Om9)GS^*t1z=jcUx10h@t$zczkh$#{O|vVZWI2%DrY`Dv?ecqrFh^L^U7FYy}B)4eKO z#~8xbY`_0KU7(oi6(KAB+BV%OK||@tb*jMMqH4G$lDmtsT zkXjXC7}7EMncFqL@AqX(N5DR@HZbu}thVWn>bm`L;ki|sZhr`)hw@vtuGkD^=bm7o z4n`V98GS^^E08`~mFK&{%{OMZ!{fHd+?%|8li($QtM!_W=NNY%iz-~~v{K~cbLsms zJ|SO*K}TIXIPA3_|LbZJwyJMDXJvZ-^m(C?c;KBoKgDe#<5g{P@11%v7c4U8?c*lp zGWbLSYp$4@EU8t$KifVwU9Q7$>H5SpKUeJnrdAGx#pAOLyv?!LlTk==KUSfoI#D;7?8RsOoSdU06GEfa z9ERS^#>pkg#i9*IP~F#`@PHmwEQU9px1Zgd39AMor51s&4|u$9H*zlP{it7H;yxBJ z{fBwDzODi0^i(K{G(9-%rqHsuSfD*WAgVa+G+KLlb3-Ik>wVP_c#{!NJ@x`+hkQ4o zczBxx#UrLA?6(Za=hjt8JDz`>38g;jmd!*i6tYWH%fzUN%S#c%BIN8HSslWXZ>ZvwzmDcsfvl8R<%pG_7 z6%VYG7Pl?USafkx->`8G=h4gDvp$A0weB)zZ?J6J9hdsfRN=R5wRSoCvCy`XidMJPCTg_xjc1E!P#9{F*f`W@0!mOfhq zHX-MwW~b5Ctlha;4ugK9eeOfvhYf8Mvj-(P@|}mCD#73n`^ixW$ojj|MiLna7%Tpp zV%PU+lIG!YC}Y;nEOo$Gg;Ax{DB0uw#}>T;&scRvP(m@zYKX2p)4ioetNTh9n0@jZ zvpfAvq+uVZlneF3ZL@yC(*wohibAPo?iDC#)&|U$np(%!UJPH}!#cdmGebT*X}Tte zX*+@G^&j6dwdTfXxxUEarG15Q5}S>Z^%Q2G&y{3pRkFiV!S>$G2W<< zaTlN9rsOt(mA9$81<*_Ub~t4If^#WtDaCPsLwU3ONkLkUhfQax!%7N?X`jVN^F&`v zeOM*vGb#~~L>Gn}(g*fLk?I_*VN@?_=;CYlcKw_`cWmRzJMvb3j>Zb1UQz{4ntZhR z(`fA?Z7Tow=7vMRj?k{2123_ba}9m#cS<9^o9P25ut3pz$-v?^w*~P8Z>!s#3-x9l zD=Eb?pdWh%6u?)W`?E-MlWQ4!6qPeglTRK;Bm8Hr4pu2Khza{)qbRmf#}rM2ouS)@ zYocjRqKm%`9aWu|9I`}O#{X>2%bJVjc&DtnK6#v@S&ebz`@i{JNicu?27+#`$Q<_7 zF4+G%P1!O}p~10y;Ae+qjJ+K?$0$aXDUxG*hYH{nzx<|N2J%WcU9%)pcFH!ck zTCC=KG&SfVHWVyqc|Nna?L}?eJ>G;%=$=F&m$SnOGX(ZKl3x}z#gV41pOvG`_O%$Z z-%X?f^HYQ}I5}?szReP>1loCT36RLPr{NKIm%6e3s^$F_=Tu(s7jT^l%`fEV??zRP z!k6s|f0%8{o^oEpn5gqt{g@~kcsIZj_H8m@X#sx9JObI~j1evuNH7Lq619oHjItuD(<%Fx4E;cq` zpl-Qw2Y8(11h#mDnsUq^AJ*6=x{@;7Al$~hG|(>>oXtXYBxbYgtZys6OO1ucKj zF;MDi3=Qh^tJ|sK`QMML_xkCNgLgiwy(yS}L+W%VSZmUg`+IRVn zSl+A;vAk7IPh_+RSgl)Jxt*UshHe-sBuP|i#F_DczB{zDk|>p33ryYxe(HIV-t zE291&g!T#CM)$S6R5!Q0g@hhsMI=&YB;_tjDCOxBohv9)@&@*2BC>P`{SM70!!XoM z`{Z_#UI(R7)fuR`9Q!mpa{zPWw3{vxNO?TnLwRC~f7|WBnOX+2L`=hWP}Tqnn-sXk z3LeaM$t;g&W*u60b#L#mFok`lJR=@D8X0H8Kk=e`cSHYZZguEP+fw%MHJ|Ssi}_2| zj2z6=&-xNrnW;ajbn;H~J$9UT;VgBX9aEm8YDXm`+kzvnVrpIBB^2Yh>H&SeAzn9B zcc%ydO*{}*%);XK+^}+dw&3FMY_Z||u<{oNw@~dB)N4IrTa|CzD(EMc9R4TCZT+bD z(zQHeC7Z>RUw}nk;R-2ULb1vFU6FsuMZo7>is(YY&rQ!h7OJhJ z9F6I-kmH4Ax3Uh;D)TRPx;4{o%j?P+*q@7Vaf>3@OLWgiL%{^nxpT1h55I}nfmj+2 za#Q*vbfYha9N14HuiHfT-VECF_IafX-mbMxgl3`c^3KfJ58(eU&Gx?v1kGaig-2|W z8$NPVw6l--0lgAsGa(j^( z(vtV;KV>2WufXm&o(*beQg|I%zGS50BSEpkuZ6kc{qyKUMHOeLvu=)ANf&3nWt0ZT zdLGJDA%FKHjI90*yzG!vX=4DntReUf)^>8k?dwRS>tY-_7gvEb#5^NPX~T{AFRr!w zIr!y1Z8${eJ*D#IYUGnm_dy+N04<-lfyTJsfwyNI^tAliatwQ$#6fne@tm#+|C`z4 z?~gepG!U9cRm0~6snZ0MD{Cg#A`!6HpDz}4MW3O&tk1DeW(~*ktp=QXfAd>Zj%H(> zM7u7xT>4%Qz7Jb>vKW2YFd~&nCk2zH#Lm9<#oGCpVYuw1-{e9taaCkkp({Z;>L4lx zEPlEsfkZhDKmMXCgwDot6BhAhe+FrqZRt>+M$VV9&ciwlk?mO(4zRx<@AADU=*D}O zj5}Mpch#%_t}Qmh0PaFKij)S#R7}Yvr!eDU7Qwa6Gx`#9QZ6oKaazsr$r-jtSZs}A zqBzifC0la+ej_s`|68P1;nz1<;NeVSHl5dSl7SlWYc&!LjyQwQ<$pL^%~S%Py^QrK zby!L{3`%K{7Y=s4(@HCSLZgfRs*Gj&Q z#Y7R-<&B_?eWrP(&4zgd9D0#a&*$=q$iz~Ti-3B{nC+7Fj110qekqpP1niq2EW~-v z${JNh>jSCLYsvk^73{VFc3V&AZn4mT3Ez8Oi839m)V??j`6zv;$jNA=?X59f0pAFm zyeac3`;lJJX@)dzVwVO^ftiUE4kx8O^3C-P{uf{otCQmU0Z+}p5;;Gqp*7MSN3tCo z+Fh@P(weK9suVUM$_;Ts(s9wxt-d6a&H-t!-sFw>5iF`3Y@E|fPq-ITt0G+>NBk9q zEKIMeVBE11PlXk;*z)y5C$ioP+a#O(WcN|R9(=xN7v!p4uFW`dNu6c~-* zd3P%NRnW&K`jX>*!lp{1%^-$z7Uf(rppNg$7`2PWml2H~*DP zkTa?yb|YDX7pwW?Jc$fr2Su8GHo+oE{MU~Q4J83{dW)xvN)8ThKw8eaEl1Ef`~*as z0B7(Y1ep9Q&ycv%KhZjqpD^|vYF2OLHo{W*prni57Ly;XeRKf|3U6}MmB_);rm>2M;Eoq8@pjNYMEVqas}%SG*EUG zXd3a<&g1$VY*b>ITDpYMY5Z`^0u716;l(2~>kou&-`l&1m~|u*`Rip&tm(TEc`W;y zEP|go4`+RhdCLC(s5RI5s*^#} z!>1q)n=7tx^)C&ZJ6d75KwG*nupxO*SF$6#9W)Q9qV(c?;6-l3#cxihLgB&Gt!)-3 z0h*JBFzT+z!Vo`uXrj{00(j<*ufcn;EAG(Fwh|_C96$Py{Jv4Z^7qk5WI!qd60@|Ah9yYxJZ|u(ZZt&M z`3EyHT<8jX928iy@1|`mVK|xy>t$jV)1i-9>v)HCd0x)+V1eiyWLA)te*?NOFfmz< ze~Vhp54p3nVjM6 zLYGR0{FTSAR&YDXAF46N2>iTHZa~lE`&RTnG)a>KoQ`@r>uJQ5R^PcGlE58x3VzF2 zEx}pLKNyn7)EZ;i#y1}b1RQd8U5@O2Ev|tj^RGN2yr0rsBysYo8A%}nsDjy)%St7x6SkGpCVQQt#Pa9X(UR1^MK&MX^rAr`=?XY;& zXS|>PL%%C)-mRqc+iyzRibBjbk?L;qGPUn^zVy_&_Tm;R$6lAwhyE>7`EIiV#fRqe zGL*}2?ZvpHl64OEPTe#|u6bW@4qmRk>%-~uI-W7PH}yZ6F^O1ZNC>Enr$#snEf%)Qo929-;O{l4MyvLN0?g@ zmb{_i6L^x-CmkN^6`j%-AaSMej}G6R2ihriPDfqCs$Lk)kH@+4Pz;@EevT9VEsg!J zVKQPj54oT2Z|p#cq+K|LN#_-s4bc%g8+I>d6mDNhIUwiKqo_UKSat+x98&eGL`{;Y z33#gWrcqVe!ff4M^E)sS`Mew`)}!G<9uw5EA^9u>)Wvl3Wh;gJZ4-1*dl~HxJ9xL0 z^`8L3ZviwS=_@H#;~P-6Q-W8{LQQQx#IRZZ6L_@17rgAdEuZsHq}L*;^(+6!%$im( zP$y2|6ap$dwIo%Ap#`Ivq800jJvczbZW zlQ0ZjXJlaHdynub%g)rSLW*02nc~0#lGJ*=n~A~`Wq_Beb8Q7hUINk5{8|?0bZLKL zrnOt9kEp2)3~#uRsJ}A-WA94kHK}@beq_Fj1tHmGfLC%;cmMLzUiWEmXdt z@8+z`LWqqEn(htkCAGT84;4&g)TFM#R^$a%ly0*G*-L@k6gv0>7jtgGRzEYTc(|#$ z!t9Lf)cKXvqlYdBoLdCL%k|*{Q|rWzW}eiFd-=8Tt8l)Z`tg=~{Z(;H2*ErD6Tk{i zCZ+8M(_&qr5YC(Zi~$t(;dK=@YHj?$JK_}tUKh%vNsfp_Za?u~YlHKqjlKyd4Vd;K z^Ltga?kMf|r+Fv>{Czd>Y7@luhD{OyDN9&`F+t@`AJ8{BEx@Q>jm%3}5H*d?^5pev`Np_;U^R@2n?-InhuBau!lV&J$#pL`)(gjRe@J#k&}&U2p#zuSFiqPz{R-kScn)F_~=zB{c^B;Crza5vRQdZP@pC{ZiIx zh+hKUi8Ex#c8(B8`R5oLDlPP2XYO*DG&;{XVvuoY;N@p&m<9Etw*;OnsBXYh*xSmN zGM~~2CQ9BQ7v$Akt#Czn2AnkcX;*cxP*@iA}`=K{qz4JPA0ML)v{ zl~NhxMaYVua7wK>$ zkwi+f^k<}Aj792~UdoLtErfPOn;lZS@(?D-deVk*WHz#eCw0?LpBsZJI3D z;x|a6&wg|jNO?qR1zCgvp$7d?Uuj*5Z-JPuGqO>&X~!>!^T!+N@$H9?D0}zGZPikM za>>K4w_P6~F|izJY5LjU+D||kz=+bM0`N8v*BeV9!>lljJ$&nTq=u>=6s&*rq&K$NcSYBK2!9a8VQR}%l78IC_sU+d2Kc#f9LH=8WeIVsq68g|6(5MF#>E=!;v{d14 zm3QUv!b3L!{`hT#5>WSbI=iH$Y67uRdw-UQ7ItpKEMDv&$ajX9L3dnm zk0VH$XG<7-8+6((;O0zm`jYsMDTl74oYUjkA|P$AfBY?kG;L5_Z$6B$!9E6lT3HhW z=8o9sF?eRSFx}$#)gb4s3(S-R-hs*NUHH;N<-gywcjgY&HmD)T(_<&DfV)!1?P$QZ z^WGlf-QB2ebAB6%D^)~w@|xzAgKPk{6D}`q&YT<=UtCoiKb}J$#@|JVU^Y(62Co4% ziAdt@_EPH`9;;-`kabtBA_P_T$wJL#hK;JrfqevOl>jFchk;-Y-4L)n4Gno{q~gT8 zAg4Hn)_1qm8LgYaQ~+i4G{tcp1}9pREX4V@YZ zC$9m8qxjnV`px5h9j;Y9%_~T=*#Ilg8TFf*T3)(;?j!%H^baXIY*czmdfDfj0*9)7 zFS0wDLF`{+iOH^ci|Yg+F=)_@{0ed_jAobQBs5R0NC4A%h z$-`hSZ~^s3&uHz8Lc5i!MJpDbCd6|$USzq&{q zO9rpTL?~{+XS&iPekgqEqF2fF1`Fb}F}wram79|DJ7OxoG;`1=zc9OF=wc0gM@j0l zk-1T6q{bvw&Hx5!XaDfD0eoyx6(Wi*Y$(wIk@833oC4_O>pq#8m+@>=j;7?zR<~!? zXw92P1r)??%iMi&Y^2(;y>Q4=@B8m#AZ9U1SfdqikoGmCR{n+T%FP2e;u`%WjaNe0 zPj~ei=ExGHXmfO-xlI!WHJ7w} zHQcb*R2*j>PRh$lf|)q~jCPW%e0xV%-sPbb7V_3v`LeeGo$$lSQMjyM=P;+c^lih*=tlACaw+0upi+0><2 zN2|HVpY%2KH-ePki1v5+4$>1^FaLZ5bfVS@3Fx!1k0zzzg}Gyv%53kcr^RUfM;N}I zvEioBru_x7+ZvUZauQti@=`V*E;1Tz8di9g`GSs@()5|Dl}20hQosr`3*#g$U3spt z3IX@THN5?=jEhPM_qcf`P)*r?uk#Jcla8aY9D z>im!b{UU${QdlUyT|jY&VOPemR}SyB*Ik?*ky()cya1UZxO(>E(7>V4q977nl@z56V%k1w_R(9ny9wTAMeppI!rbkxx_knBUV4_g_rx}l!p*9@(9 zR{XDDx(Q7s4~jjUx*#u9K^)qgRd+@^0k^HQby5BlXJ+fX3J3%tiUQU9Hr6kKZ^ zbGg|3CBIG_Ff&5LrOay=eUBru7+)yM2l1jg3ZFk9GG|1<>KEH%R%M98Jq); zJ<5S}2Y<3XhQ+J%A4tp?y5D!Jjpj}?IsnvxV?v(5-SZRMSG*_ajbT3{b<49mk;91a zsU3i67)A(i1f3P8QW_kNBr&#rFkv`BhNy>Po&c7#RwG>#S`uVOB4HZH<#mGWKpL+d zW1_4OPTqWkA&%>QH;G6MeVi^nb!;Wo6pzqn@hTMX(f+gnDToSa&4>)t+&GV>$%p9% zD0+X5B=V8P`rB@lDu<0P*7`w6Dh)nCUO(%1AKm;K{FR>y64s6%=U+4#Hn|&@JJw>nL7Z0y#x6kW=`R1hY+8BZ(#OMj04}aH5OvTnauL z&T0W=L9?GMrSwv_47cI!A+KG=P=))(;zu}hN+~~LK49SR{H7^Nd$|Ot6FCJ83ha@7 z0kNO02jc=YrBtt@8r-u%&ouPP88cd&rmdm$9$8pVq}$R?KtPqhg^jA?yxkTGd-Ps_ zhKEolU0%m58VTT`6zf4v{D0h9BO_$Efw;vA5W&}sSwQ>(t`I8!UcaIjfru{IXS5wTGNU%S7?;fYNja0$xK>A9Tw zXQDU;c?|J@OXG>FQJ4*Uki6Gn7iBIQTO0w~@A-loDW#BP6j5f*6)4w2bCgN5`A1%Y zi~hJw$n6_smfYrQ`Q%2E4^~L;sewKIZc;NmJYFTv|C$Kq(^Tw~*{FJ?)>F$`bWXe< z(-^#3u~qnQ>dyI=^`+l`w{=)w4yi`-^Gx|RLw+oj>Qfw#-eaFj@jQcpILU=t2zo_P z@-s8?E#Cf@>^Jw}L7ZDhjfbZ7o^3>~i;|{M&@4kW9m`Yyoh~^7DkE|NU8Tb!F)HmVWOJ{HSJO?^_y zL*bwgLnw5r>MA6^b_+suyXbo&Vb$5-RMPZ>q5a^6(iK!kxKNs@1)Ha15ak)nwCC>o zU#Yqv|>JNGN2`H_@+j$^t?)Cpd{ zduVpb>@UeX{Y45XP?%aZInOXbL7dR+qvtlFklk?i!ToJ(RG;OH864RG8ecoNj<)xEE1T0rykuTzsj(LhCA7 zpRgSr%bk>-i7|QyQb>*$UyRz)rV85o?sOTVlFybuvOnlm?g49C76|FBZbqs_qwDC} zaAS_xj)+Nz;M0)mKrZ_{C85xQmZ9KD1Z}G)9)D4TY>M8CZ#l^MYds^~HIQ}Of2Qsa z^Wt+UxH1~c=ekd6q}LeoqT{VrYI)|HlJp6urV?7itJRc;7^pl~{+qOeEtNU?$xF`S z*)4d9HWE|VqB<;22bQ5a9b$c(roX%bWvkS6l*3;L#y7hbY zt|82RrM{J?W2jaY2k-VRfi{FIT^m^_mR*n7s4N)gYfkg+ru~UFo~s|v$Z4l2!Vo?B z2b7(ZHNb0=8BYT5y)=a#53#~$+$h9+UQmGh0mtXAyQ)0`V1SiSlI`HiW_D z$VJG=m}58CsAV42OTer6@mDoS5?xSTO}!pbl3B}|30X`+)zMdv19>~rqz(A_D4(YDoCBe;()zA6D!!=7oE= z-sKPKkL`f2=3Hq32u5%hTimHC$6yu0=)*pD;b;9g(+XPrV3OWSUk+a@jT{?mOq#gcKmKZC!I#qL5}8a*mYQ_XhNj;{5~4*QK>+o~r0H>d-Qq z-r)e;7m>5{SQIR zcD?mSBTYgZP;=3GMyfaAHc$2yL$x5;@H_5WmDMH`BNzPlT5JURZp6;+W~LBw z{e2Yb1H5&bMN1DEVAZYP&J_Gig-)Aczt1?npPrxu@H0YMb-fHoY29rT z6aopSGR*@TJYfm5@<2WkIYG5NKYK*x*4%CWHi`EnjTHzbr(GZyL(A*ssJ?gwKqBD& z?feU20nmj(7VnDQNaZYFMS|aN-T`GMnO|D9gG6$aqEX&y-6rDh6kO(n>h|Nl)&MF9 z*Y||91N*MW?<+UGy7hp8D=zPQ%k|Q2C%~8RN5 z%)i*orxZAM#Npr?TuItxjcwBhQ=Q|Mgdj%_mux#>+~KB5f;n36kg7tN`gN`_1LXfU z02=b5*u+A=*lo3%do=a^hF@ALhM(WxmH4W8O8$~~plh(?k7RWMVC1r}G5$iCP-34~zUv6=?XmeNvNxk_d+W0R~*|FDB2c)c>P+F*L zq#h19#O}aNcl`svGuB`m2vK}f@?%LZ2#}S=6=;e?%$4DCO5q>r>~^8{5b^UA;5wmv z7v+9Hm?5H_8jd?!Mb6u87|pXftgsm3VXTxj`})?F8%wd!q~!vgm@>9sZXb%-CyNwP zA8}GFAAiAHO@4EVhoVn#Qn8yH28teh)A6qR-%P$o zsH=XSxAx7PZlP>}w#IDbwifrZi?+#^xejQvBc}%pZ?H>afstGJ&12{(Oe9hrIvun5 zd#Ni;x_~y{OMB#?Gl(~Q_mgbvGzvF5g;R#p^6Be%Ll`f|C zPPvSP9(EoG=3JT)J=8Q+A;0*=pQ%;v+2RFsyu$hAHgwVM9GDc9VOWX0r4V86D1}pD z{kqVyFq7Z|1&4ygR@>1$?_3WL$FGf30wMj`B?F%oB{9lc{}B6^JIc)G;aEWXm9sRW zo~ONF%sJ8a#Le{VRTn4|*+L{=evEA(UiK}$72#au%?lqUk{nt%QM{80s=3UdBE4lLwg1=yz(soO69LywW&ziU;X_-Mo#G>&G(yV- zB;~Q;Ni#AT9vo|&tYU@Z#6SM}AL>$ROO|_~PW7#COTjU|Yrc?HuUNHiX!E1(kKU|p z*cNtov%1Bq=CJo~{%ySbUc9uDO;k~?Ps7LFEcNrML9sZt_jRA{&OTO|GVXK4?f?jF0fEi@`F%QVhAE=9ZA%B9xF#E%?H9baDWAYJJDCJU%^H9yaDV^m*Y+nn;3 z?M&O*n%Z9%bA(-(4iIE{dyvgbS((|t?1)N7YZYu z=$#Qh;|&Sh#TvZ`aB^?17w1`K4w}2lg_V1}pQp9uf8X8a)s@=T={w}@BE*sZ?tMPl zbc(i$mqMD=GbKB`u*|C7&r2bwp=Gm!!O&?-6Rp1MLF~lRFaIR9Di6focnaM}qpy24MJ?H|TAnw@{i*eWOP`Xw? zA0EBQT-Wc(tYW=&4ooacPkhiR6TD#jmgBFm0j zo4`zq9Z*c(HMLh)+SoyY?pu%T|H3%JH#u5$6TAZ@L`9UPK~GLIGel zhy^_L3HIWk#%=NG{Ff_zXG-*7nmvZmkD4bRbR2uQ!rI^l*wUV}iZnD*%9B9sZrxrv zZ0S{Q*_D&hLI41Gc^^*@^V%_mMjXb1MgL_cBe}D@M>vrGY==4Mi}Up=+rYlwE~(Ml z+~Hxz`Kxq@BtSt-WeER!yXV)7G(e4tS_dC;wKvEfJEV3zBxETFjYpWiWT&z~q^Oe0 zJ#!PaD41kS_lQU3=O$e#7^Wx0*J%u)d3P6u2_ts9B84tc_ti(Rs_$_(a&11!l3Xa{ zxHA0$7#QJ_9C-@gR3n?a9$*3+1)77Z3cNUJ*B@KMA`4W69Zlblww1GY<3 zpLqF=6lzDOdi#gGJs{^o$Jj*(+V70w(}k2pqVoSjwVsihu%xDDcPe3+fpUXibx{{& zhu%2BFM~O_N6RvVQ^sk1k*sHZX&`mv_3X|khAx#MUP|@9P#auxc!UA;^F&u!3tl%KR?C|W z*v8Cfe7u zjWLl5u<5yhrae>EU)Hhpp)Jkj1Ue*+h@w|I2Z1JPWx+Di%il-jL>>I|@{aJtI3awM zM;QOGULrwqTYV##kUj3(ph6*GoYg}!UTsMdd&0KUb;xI3OT6YFN}g z$HHGOhGfbid1yC;&584bink9t)$}cdpO5wt`l~qq)=ks4=4^tF5KM5rMqjt^N<_HhM8-wwt1)2lUtNv^UZ-`J_d6vY2Kg$Ax2=mRh*gZEcuju3gVo?|XD z3yQbwmYJyyp=C6tb)~C$^yQ$XsjU0VZ-Bnd^(v>&7S2k4F~zb(FV082mYQG5OX>GkSVv#PgXKjG;7%2lclNG)f*%4Se4V4UOE4Nm zHJDpti2W1WvC|%HbG(G={`n5$|DE_jv{j#(f>(a??epKd(qQZnCB6f&J(!xlm%d|` z;MI=J|4zMgf&HM!hfOiSm{isto?*3%%WMyr@)YH(M(M(bN+X*zz~qkcu#(#BH^|n5agz1Y+qt-l}s8u zn}7qri*t#Vg1NS8%w(9D&@FoeeL>n=K13#fQ9@q9dB|EVulL>(&336kfO9l%jQ~>& z=V4cgw)e>bOi?>aA~!)Wt|#*l>h1t`d&LWlL0_uPu(X6G^uln!R_3Sv1UBRmFNN6x zCuu0Bcz#^sJD$94G-qi?TWolz4qoW8U@Pe<0Wb&-W2%`>lVf<>~P3gHm8Qoo`qOa^k~4 z)s{--9ks*Tc~%gjQkWemp}H0?1&pU#R3#k@mgN52(TvZxuPxewB^3>$U!A}}Jz$ns z3(jNL>#EX)^4xU4JmW_gyDGW|S5i`kkir>_rC`g)L{RghF(_*+)b{$7|1(B%i|@5i z^OCKj6ERjA=;q!DvDI`ySGiZxPB+V;OhHw24r2lB`EtwiPpEijqFc%dU|?#?_RJ1l zYz`7{>-Qt!MQHUUziSCRyaPlk%Dshw>UUH>>yu!vzwb}2O4u%nO<=0nS&wO3TQ$ zrMW%kdfz2&TybfMFi(Fqy9Z^y{i4}a#x-;EGz0~!ccqLuF*EC)S>J6g6O8GFx+2)B zgK5lh=e`0(|;16574(sxfz zkQ2bF9+%j%h>x`FQ3+Qv(x?t(ym4_ME$!nCwZa3-nBwrgE{Z!~f6F(?L3-J_08KOHQ`CF1%5yctX* zVKfK2kvIa$I4y6P(ZJH+wdudhJ%md?ZM{A7*u8D6aGO{40eLw#$6hd~si#Vxmk}U7 z7Kuh`^qC&^^^#im-m4x@0fS5ldH<d%IN3ut0vef`6db>EDG}CxhFiCw}A(V9N97i zw_$ll-@F=R&CI>Ub%3t(3r)kV^%Z>`184glSHi-ixxqmGddF#4vJQpNJNnzzW95v( zU!51%Tw;T9j)Y@_b%K2*6UA(c+`dSAixm|AV=gZx=#*Zf?`UqSMC^^eTFb{NrL0*! z6LzILnH~vTw$Z_45PkPNYgYthV6~G=6(&#Xi6v}(Jb;3BprD2ns15G>!f5@l8+s9_ z!_}2{GfHa&7Tbq*+vuGqRE|rTNgoJCG^zCj4bF{)MSp`yb)F!Dr){{QSNT5AbNp*Z=bWwTQ)b4(h?IB`Gw#?#F}({RadldK8Dg>0nhxSkGN|8 zC>N){mbv!w3C3@Ze;p}pQ+3lzdS+-ey!!2QK7LdQWk22i?MZ}M zi8__>6B{5c z=|0%UAUW)%)C5Q8FmEZ7k7NI?J%oa`Z7B)mhUL4Ie747ChGl@Tv6O8`;LGVuu%?dB z)P+r^t+hz4E60pF58|uEr2h1ypg-)yBnV=%$GrntcfXCPQt^8th&pym+&ZN@hFRY; zSW@=}bWy@>?m`!=0DV{QN7k1=ZMVak{*-v-=^l3mSm1N5t=?QvfDWLXQl2~P_W8{E zD09M?-3(U>lE{3iiX6Yc_$qU2belmbY$v!{*g)x1W|5EP{vTWK0Tor!ybs?2g*5=H zh$3+n1r-qx1thx$R3s=WNrIrFWK?pP*>x3Ef}%)H1`x?P!zc)%^^vB{Q(GbGVZU$N z=Ih$A^opJQzowgQ9$kr(eCY1b~(eBVKP*8AFjiS z>OcCmpPLYiE#8D-XYhSy-}Znh51sL9@_UMi87m$}B%1*({nO(Y=UJ;f>PrN9Tc!t`@A+mZ3+Q0-1s6xoB4t9{TWB5~%+$#o_tH z8w)&8-(#iLJY&x)JAL&kIOe_Qu92q=(PrzPXH8kDKOFyMAhz@9&)CoVAHmpEPC#xV zPnT;vr*I~-`FtEUm(f(aULPeE4;}U3Q_-Tnne60w>CTP9I@bH)<|NOnckLxS;a=qzr1%q0t@H)&;YuV!aF6+%N&XDQCJ)p_@~#ccnU>YzgnHdY$2fmK67vK+$q|HM~4C~vU#%!0=PFp;V#)SPeUfxLJl<9|m zRx)mXr>U`ABJ{z3KtEX4FXMo1cQ~=+jtg)Nw)XKVmRo-q zV4}B&AN0i&4~tMwJd*dhd*BnE4XT)jN zOxM7tiy>9aHT)Ivei}6I^b+#_&W>*_ojZZg9pC1yn9O!&@>SS8f3NPNUC+12G5Uoo z2{L}p);-zUeWz5%`9+FuJF#AcK?!}A#1!z_8K@TUJ$;ghM0kMS@zdbcsZ;ig-A)y! zI23pAN?UoWhe?0QyxV9xSQRpz9#nLAfkLDQE9kMl57N)Lt-diXn2Mo+$r{Hk}i=;ZYKk$8g1r$b;h=30v{ z=EM5>D8^jMg&q#>^Zli!v>nPQQxU%;sKKLzvLWCH=aLq_>~q5WUaiT>;XM=_H#2z* zJm$6Wp7fY>o9+{&%U(;;=bCpd8fde~;@PtEuy;=3fY|gxPKhGB^6HdiVdIQ$mc`Z8 zDKBLo%akJNYl*ts{FT?8RVTybooo*4XC8QcSZ{lUfSc7}-PC9*8tridm5%kY2Cw_v9zu?>d=R3weOgeE=GU#2_J=CHGYps%dEG zJ2aZve{Kmfbkr*xxtj7+$WM0f`hqQ8+H*d^IE#&b_H@(e{8Dp@Cs)+kn0cSKke@e9 z`>`VhW9gFleLWrNx76I>lfI|ePwX?AeyUTZXCA?&W9V?T0x5kJf<%Sn{E?5cqlp>4 zTq(|H`0jn(Go6*Xz= zFBDDULaV*ciVcg6Gm-JsNrld1b*aJ%T$OX7Z=XOxFN?_O3wqlSMs|e^vghzOdPU>m5bwLo6ZMs90m^f!q zElr?)OxgfeP?z#iY~c&;qXTa(SbYq1uG^pCb8Nd|-|f&kAU9d-xsV|{S9hwffU;(j zJiE|Q?#tWPJ?ZIm*f9T?fHU>4&n%z z`rzk_z0w`|!NISf|I|G^akX3fi#kAukFxKN{+uS$)Pds&$FXQ4TIC|+*eN6z;Qe{X%ksCsN?;<7-l;~K%az{8iYT-Xk^6hlwRcI_1YYU*2xRe#vgYYe^n=F zEheBuNS)Aso-Qb2Jqbgc;=3wu(v`Q=`>d}@s@CVWsYuC{>f2IEt3Nm@_6J?R{8R2s zXX=epeD|v))7+P5B#l?fd2M}UN|vjq$1-aDmOC(?QdoTXwhnJwz2p^15Lw-CncX=>u zHg_%3nX=NeE2rDhK-DZxGfH66rPi(Y^A>R*1KXnG0-j4hoEO^7%^G9Xr|V8}e3=>e z-uL&GBi>HMvk{UG7UmI&Hu=M`OH@|nwrXW2jPuM0$IK=I^=xlfl7`&I=qL!9{_9pQ z%SWWlCaMm$+nDe0Eh`lRfK>|GgDLPm6iWfh4iC4MASZFpI`ajO*tvFpA%+eQ=3m~Z zsmwp=Tp@4j?3_EE>#^7^<4J3bDz7E3&&u}sNSXfl{3va0p|gTYHL(KwpZ=&*bf`vQ zwrXiWoVZ)Z*u!D0XtBq7s1qE!u#bPzJ1)vou9g@sY2SV;=*vKmvC>FxymnkUWwn}8 zh5$I|`n~hvjvaUHzwYrWD|DGP9chYBtCsF8OD>q;dA3vRDTl|;Q})B}gUTm87Ymk_ zDwG9Y3aj%ttfvsyM(qazbq1&XH>fCsY}DnVl@JS%q$qJKl_$#3Rcp`vRvvw%Ba3U< z8Y}aj7t?oIX6%Q;gJ)_eL}1*oWt66$XqLgVwmMev_DnrS3)MHDLiA9*F95b=|6MGn zEMUJ{hhM>D@k;N@sMVWsIr^Kk^u^X`DRkE+`<1Z_%`WFYU;CO9LuHPg)~(a4@?)u| z++pJUqUftblEn4ZOBGQb3+?r(C;3T^fLVbpygQ5!WvQ9sp3pqX-ga<(w0`AGkGa|% zv_6IBgg_79!3fX>NlawlbB8Tn!;9N?xUQ7NT>eOYB3B4`WVV@~Y_Ipy`eKP71S9K) zu1@P5H~@rI*;}WC)@)q?faWqiYD|~AJ7JVR^G&p`$8FMD{`N#y-ZVVQK6a%gYSk!0 z8T`lFwUOP9T_3L|^oCj{R~E8koGKZS(w@f;u%N%BL^I*mzmYU*}xU%$<2Iku{ z%qwmM8SVsI|9*@KIx*RPnNCcY}i}B zWm;>AfZIf#d8_4k34PtZ{>-i~ojnWLmnMgOZQadUM+tRtmo+!4|Axg$$D{z90)z2f z5D_?H|JA1ROAg)Cerqf5bXbKn_G;;%Kx{T`>(i2x-I zr!I9d*E&skUR=vKe1_G;K^xV4KJsf>%)2VWW7@)O7_WaPKC#G}#kAxfK72S`@9&v8 z9;_x_bd1M$`|6$ga=?qu1sa*G!sjtppO@lRC0S9X^6cf0$VCVw!ix@spPccvI!I}X zci&POPoO?VdKY=iaecwq&I@=U920)`Y3C;Dpffakg&la>FbUS}>9^8c=SN<*#%V zkOw|Ov!J~6iKD|vd7;hB4A^B}a^84$XL(r9Tx_=4*@6@!ULGC`w<7PU$yvuP`-<#V z1QDNGSWLpz*fA%g2j|8EbkC1{{tfHC;IYs&x)~@sc?&AAWDS~pxBSIrK4!Mvf7wIG z-Fp1{Q9MYgHnShdLWX6XBIq`j_9#)lqpyZdV_& zvc}5uP`d5l6%ce`Jm3SgRNL^1)*f|V(f~as=)q3EwE5!Wy1SR%h;Q{ws;?lu>?kre z%lVOJgf98x!7_zE*d8UqBC6&T6af*#{h$E6Fd9q_ zod-<^cw4-PBbJQx9&Us9+Q=qz-~n|*JUEIJRXhI05ZCK+^!tf#Uvv>-8ot?o^3Fe-D&eEu?V%Jr`uF0xb-vuU*Y;s^Lk;&X?v>cJ29 zC-a6PA0@J>2%Zz$ykj@k0x6c{Yuead**$P)=NMO4R;vEi>_X|hj(mAU%q5DiiVC#~ zhdp8;HOru47{Meu6S#H#0`1M2XPXV_5TmW#)>;f~#U8BLR7EPvvnx!IU$;iNj>P9e zoV;)BH1I7j&2x?Rx)rdZHWs!4Ci(F@eJ(jH`T#t6=r5aYU?!K=%k|6O3i!nc zS!Oq5L3^4;sW*RlmOf$*oujOR?shSwB{P93R&GUA1gf{UnZIK8_`KlSPu0AX~f zUhUn5h)Z5l4sgSzhM?jm$0{$SxtOjN=4g)NPlvJVwRL+gfmxO7CunDPR?eV%)2;{& zVN=n+o>zbT*at)mG7D32>*9(E$C^U zp}qB2;u(r`v#}ZV=;e$;Nkiel{98Y{Lp#OvUv;`7{>x5|;NlUfk5_MX{-CFnpNP=95dblDY*x3Aqi3L<4sq06J5Qs5&U3$$4EunrcZ z@6;{EOMi}KHfo5a5C^5Ao~RwkdpGJ(469MLt9a@W19Wy>w>#N73ib>|UZjt_W#@Rk zR22TKT`y7*cis{m*tNvLD4B6yPUyIq@s*u?>58>>^$sZBqEOQyAoMPidp| znIMr`4)TVVJXmsOPxR8CAxz}>JrdZ@%dgG-5xJjo^L2%37-u5?yYvG)v7N(hetwDC4HW+hs^|LuGyOgQ*vePK)xMfRl zS4E;;2FgyvQv4mGZsFN+a?wJE?C`sny`NYG`RuDudM60%2+ttSJlpx@h8O?N`$ILp z<2e+i(CXWX25@pKz-I1rId2~T3vZU$6mZ>e;2ZWWdgfd>+q?id@(oaAW7@O==^KMd zu5O_Yuc0xMIg~={;_x(PCxLptnZVi)<5v;1yc)(xH)%Vrc3zR%h(*^z-R*s*O?Q5F zYsFD)6~a+wp^_03dD}MPoGNh#$|e1Yt9{cY>#g*sF)=aQDj=Zkx5@qS82;lunv!Mm z>F=c>i0!hgQ>9Y1lCKdHL}7ii@envC|Ma|hq>C^xk84Y`SG7{L3XL-k^azu^u7>c= zL-C5B_ln#Sn2_o?9@m*C`js=m0?wx9ABpzraASxS%_tCx$JfQ zEH)f_lTo@9rIXOyt1P$bqhQrn9vpJa&3vM8G}-y)!`i#$tVG-AXA$WIn7)i@P59(@)11t7RroIWGo zSGzt|`{wfbl|3JVP#Oveu)J%w=i7R3HeTsDE01p#M3La^3Oa;geXb#nsC_(IC%B7 zfz7aMO`xbw`3qHn-Ne-jBHu1!cl&!ohq12>gxvNU7iCJDLjKf6WmDybTex4Y#Rq^C z?prr74(bI*iO`R_`dvglLH8 zz^r_BD!BSn9VRm*M=Ub(A5AGy(l{~js?CYw(PwGAqMtm=Tt_+TfK5nXU9f}Dgzsl+ z+S;?5jQih>4snznwaZNY>sL;j)T~24>*Z!2Df9gI;w&zpW$BmlnJ?VUtSK;SzTueZ zAgmsGOn9+A3Ec-JKDj^NJS*Rq=}uo;tYB4|`pbFLfWo7xFn#*RC_!SK?dFM7527H}=0P;dZv&lghNk+h+fROin^nNs(S_H4=&Zwzm8XM~Y$k8ww<_??2lYE?_Z2eNkLBLhkKdu) z8ZPJXaV^M)cfIG2XK$303EawKcUaL1es9x*#u=<;8f2P7uw!- z65st9ZeP9|{xjcET=VzFExj;fZ6ou;jd8d_^|>|99iVb2h{0_m2qypRC{*g*b=S7t ziLz!&5jsn!d`r<$=AV8x`f|{7;3VspQTC4g$L z6NEgo_6{q02`r2_FCWRcSHOyW{YK%#_NV@M>fIc{VY>_Kxv{V?o!`p;qE!8)=V}oF z+fhy7C7+hc9jmyMQY7o$c5w_-_#I)%Wazf(iw$%9?ZgrfGrG=7_-%K99lhVYn5hST zi+**xDj2BfIb+YKQ*(`)IYmkx9t#a9g?sl>gXj3F+hB-!xmZrub`gL@?;n(Fv5*WA zr*{#zp$PL{Ehw9Rh5C@Ayy3l?D%%xiiNB8LD7D*NVUF;Kh?lusE8>xyAcXn6|E5CA z5cw_z65LO1U;T!uYV453@!-W^Up@m4pBz3$L$@{${jpOr+}u)Ap<)EM0Bi$U>qb*nadvOyY-mJ`~oy_ z^b%Cahc3eVV}NgvRw1Oz^PeAWWlYew^jqJ1KPDtw$PWTfwsY?n5`?r|+;jSw{a9K> zHveo$t-G**OaF_mmJQMV$3})H4?=Y#>kzyl*Y<4(c5NR3OQepV25(O+^VCg-S~}_5 zMv#R%RP}Z+|9AI*x}mDT0&G6dNR<0g@c9PEi+aptB7KoaS)hT~)q6i`<$AK^ zwL^iqQ=hk(g;{6cJ#pLFSr!HJ>#ZB3H6OV0{M^FzZ=SLr>%!~o&PEoD+BgE+yXywd+c`r={%z7L`hL4iyJ&VOT zVX z?;}SHa5r5m4-(K?#YHQ(wMe&#gAdl~2L;F1T?c5RDYkBF$5UL?tsp^sltioppJn8R zcNTvmZ)i%4D~W5!SF7A|>#jly$QWkU5^9)i>7HG{)}k!lIbt?NS559^W#C6Lk)|!* zl}<}R5ITlk|HaOgV6Wz@7J!ltqY@|yKq3f&57>O>%4i^EeIds>1+=%6BdY>n1*woK z0e$&ANg&zBg1ICVA0$YW<7K@3%bH_YR};SFM>zeHg%RwzJPZNk+#x5GyJGs8AI9fF z70#-g*TGZH&yTijF;q?fYf2xV=XdH#n{o?=>Q3kA+ioF@Q|kqRx>bynz-1hW35Rdf z$h8q2`qS~a!J3KkwCZ#!!ci;~rtVW9OgTs27^l*!@0AVI8A5W}^sKB4I z3Dackoh{bc9iyaYg?1@?{c`}4NmK&@E9{t|K?%bQLLBG@jp{OAAidHzijs4%K*gj( zH^*(RCcu9E)2Fwxv2meWOa5_XBUz0LcHSxSy@ztHnHX#iMs`769Jx!Nx)!jLuPXZ? z&RxRG7o*hv70wUL%&>*ynvNqz5(eO;uN|l13u#sQc(7%1UhMNMBFMDaMe9hAvzE;Z ziq(wjS)g%hDqLDp^vN!V!rQwk=8*GR&UH^wqtC6p>>~|uY~Q6@=1C-ckI}y!UCC2Jm7FPC>6#Ji_0zX2fE8sPUtk!OQfBgl3vr`hO95+UpB{Xh9g93fq z%kFz1S1*6~=^}y3WU~RnO$w{$w&_42A`4BB3D9=CTGv5M-O*}H z^yrjS6>zy}1=>(v3LAvWfn#;-%w)aKm(U8foIR9U^u|OLq%-XN>62Idg})=DBg6&f+P7j_Sd@6L77ObB9~U{7t03UaFhufStmk;nLZ&b_s+xPGs4|1?w_a}pei z*T!ut-Uk_VI963CEuWQj#}*(DbVjToOIRc90eWU52&kdiKmCo zXki^FzPx~8GaveTmTQ~_vxPB_eE=n7eD^cRGmnjjEs#J$E}N>W-sZo4sP&+wWZMkd ziwBNYg5u8z)-`+TnOl((IG5T0JNGUag8!G*H2+=NMGsn z3qeuwWPiHs+FYY5+o2TwtV6&7b9HlU3|mLnpo;E`%IRsht3$Kv=i z-=}$Q#GF|CsQ=T}P1M7Nu-gpUQpFhDi%M^~ok0Foqj58%K*wfKMNv>He{{Do_6vo+ zM#iSKTd&Tpn?e-40zK z)bnoHb;QRQ#G8;-8jO!0)xto7b8AW)3cs&$F-%%)Rv(*7L$CzllNAh++W>?my-0hs zvU6pId78^snM&sz?`4IqxWdG#iNoA8vu;xkub~9=YCj>A-H% zrjHO0MRAlldJOYB3yp38Xa1pSO=u@ujMdL{{L8Mco|TQxt*@F1QvvtMQinKl6YXbu z-b-AsrSBHKmUxGE!df~EFBF1N@}S8>;{jT*Tk3Wd(g9F`Z|7XI;xB!M$64N*G7nb#Du$`P{h5>Dp8~Mi;Ivy;zF;4WRt3L z;qhi`Uk`mFd@B`cT}IXvFvYc-pbNb$NlGG5Hu{L7ktd`S%Neb7w3a{QP?8;4LPcVm zqWPAp(dsB=IOBje5-e$UcJPGjU8v03FAoG&OjigBo;no~!CnGJsGDu2ci15NaFAQ@ zam#DhT?PWvT8-QWjtYXRR>w{r*4A<3V`4Vp`7J<*ULEgE=&>ZR)PY`y4A8s*> zyJPF}-JrKZdEFirR?LbQK*!nn{k7OLm}GxcjF+l*rMVqy_IupSJG=?)Z|AnuV~@In zYF*^A=VsVaPx+DQkPdlp-|JZn95=jGhS@=~!Ou!+mPUF!KUncybl))B;u8o?%3;wW zR#t6Y8^d}V)WmUJZ!yp9MrFW$v?%~3jeSts-2L)+&=Er(`kW?x2LM4|a3U*Nw)GY( zwYqdZcPP!*zG7s4x+(U@F1CW{;;c$-*d;E}0z!mis5ETX**gEDzTyGZ*i!Wi{X@i# z+VZCCzSxWSkzSCA$eMZ_MRYPU>Uw+#y!Apsu4cJ1p5vd8oPX#@@lx+nLJ2Lwd3Cy? zAo4yc#OBp{9O+rUeo*KSs$uBqcYi}Dh`#XZ`)0H zKAg^I_YsAy8cOpIjLgII3=DYr7`KY`gA$bhS3zP(L zKW}gI(9W`tg92%9(rmlh!zuM{_!c|Ty3X#e@yvE{4%%KI=%BsD+Ma}ztC#dwFzNu_& zl^1tM`}4^gE~V^equ*L1FSSj1Nr^!vit#?_CX;t5^lJNd#Gq-=TC8pt@HYWe>O&UiH(r=zW zte3uTeL0GL0!%m?DX@q|`9rcQg3?51$Qn&y20(e)!OYBz>lEOWs6HTR+f&#EL9s9T zA^TGVE&!BmqeMQeyx^?jvKW1($HBf{d}frkQuuM91e^PMKh8>I14(VF8}dkQ<|j~L zd>iT#5BpTle3>)@6t7$S7?{LK4w1tW^iTo@rd6Cl@m%@hxia25+Q}`$!oq@Y(g1

~y$9etlqJB|Ylua7{$^x3K2^@L1O+Tl6BuyC{1IUSb{I^QDy0Z7>!rnIs~ zD7I*Hbxln-iR~{DY5sP%yqsiaEy4204y*ZO-)#~{QgPx9D=tIE>L+rPe8S-&jfNXT zKnPmzNfqw6t|ALzBE5w^FW&uPgpJanTs$M4Z7xM>!c5i2EUcl<0rfD5vm{>J+I;5c)Hv)tdcnH!kKeb8CK!P8 zx=AfV>d{mZ)u|zfK1h4e9?It@;88`{32Os`WlMC2Zk&+O<|T;*3^MXZ3}F-zVb3uY z5tugU1H@tdVAqr?IMdGMJpeNR$+Ds7wabzphY2$NZ5acrxZb47iDwzGF|$(&ZB;cq zkpeIv9wOsB>j9~)n1(YA=qF~N;}|~9iVu-)zy1QC4?&ER6)6LwkR>EL@23<3UX7;`GuaZL0gYX@PeN6g*Pzpl%F8`oira|Z64 zUE^Zy+uu|ZJQ;Flhsth=0uv7+?}m&{obqiv4aCn#w-2W#Cr_MEY{z*Rh2W~()takLH%^9Il!Jw=07BCu-)0hn(>QKa#4Y|}tTn3vqZ`Q1l z=+VKfE?R1ur5XDnhRt=g-Q?`174MI5zR%#s>2{)4(IrXaxSt<|)FHQ21@L2TwwP6+ z>IukS&5AuOUst-Zxpd@!K7tWJ%z7Jjf*~(DlQD2T=X?1`Dm9)rF2EJA)L42h4&%!b zYuSb>K+3N2#&8@KUFgIdDNyecEqPSkt7&t7ePQ^I;F<^i`henGm>Nl-R(-QPFx7@6 zkbcG9hQXS=Rc@t1gY8MKNY1?kKC^@Zq(l3Zr)B77!LQIswZwPm;`i1Bs%=Shn#MV^ zxA0YQK};uAiV+3vp84YZWQwX!=@^AQ7E^I7>rOO~eC@^^KnHP<8J~^f64`f)YrQ^{ zDo5%s?qqlV$Q`)sT@VSl2IewzF64^L>NPLfY$y09mDRp`eDm=2clHO3vjNqw`{O)w{8Tb{ zIg)<3HHvBLR^B?XuC1&Y+#cw1_)T?9 zO*YDLY~;I-AN9`LR;HUgpL#Gk3o z71!-0z@j99Klj%vp-2!t$6!OehAIa9W2K@N3!`I>X0YZmR9cSmUy`U5=3L%!o1{&@ zRC+Fx!hyDMJnYlXK~DC|!p3{uBeqr$ycpY*lp{h5hHRHzL)T5u9$HO24f|x&DK))F zDr`ssPSg^;HZH8Ljs_n`tRt5}Ll@r4imeoq>mUu1rF`dph-;)j(od}$3%->i-d}%a zBGztMf@apHPn#rz0i~>wcnY|zq+jv=m6KEr-uV`^4R%m%58@$m2@WM-jBc4bLVQ}x+E*e#A6qw9tg!p)vD z;_drxiS}0-(kt^%(Y#uJ?jAo2v?kYABUtlNU?81&(=jcrT>*(XFAc@I?JpWJ1_C~e zK(D)oW>z!qO1LCo$5nP*d8XDZE!B<~8O$n9HNEjYSr0qo-4^!N$oJdezqV2-)8?A^DqJxQ5nXgIGG!^$-)}%T=rt}!)c@t% zw{Op_oq*)LorKu|;WuAGnwG=s?Lli7aRQ|=^v*;-SOBOVeqPa&G8 zl7=q736=UCq)Huk<07wKT@3(#cIlyck>!-l48YT%KJ^f(aYqjiGQLroV+D~E*sH$* z#o?cJ=f<8DuNC6$4G)k!8R7&-2XpZL$#mLj2Sb0{h9pt9qtJ{WyDqpf{ghMpSs%Jl zJaW{Vmd`8`9_)4dGagj=ho|fm>I9<%ofBG!q$7F;1|&?Bew37PpfqN*T;|OM`T2xV z$)^6Sh6F85$x~D63-ZPJyieMYHZYesG*_$k3g4y|Q($mMqSQ=v>q=kM69haeAw zxIf8H%|hUeQ9^WdAbOE!vCqM{>kaP!uLBRo!i8nV@BmgP9Y^^&<>S*QX5z0sQM2Y{ zd(-!r_|&!jnxdua!D!%Sk=w>E2|sU8DupCQ0;bs-g@T4){$mYFw&{oN9q-V*qk3Ox zJaMwTq9Xpp$?>jpXfZ7~;0_Lg>Y+J4W(g+EmuLd5X|dei7R+``9H zmay{>t5J#^6IC_fPpwX7PCQ>fdRpWcSbwIt-Q0a?ImvpULMLJNfS-p#^>0R7sppA4 zRemz^Dv!F~Zd^<&6{nWQ-gwlLbsGY0VP?T0A&9vFBTwI|i-0d55qDFwG#{Eh<~0KE|e$2&c-nWzXa{`uu>2?#wSBLgze z^4w9gFiUT1I`=~EKzKdA!b8JRevEXzjBIqW=nD)b5mB06p;gB|7@+ZOW=6Bl@7K!F z!t~G{Ph_2T&h|Jpuu~R{vrN~VW$3x56g$D1clq+bZBO*6j)!V>Uq9ND+PHwqiN8C< zE-fwGe%V*eO)GS5D@=CU&2u@H6-lt|B{nH3ox#RW!2H>$uhH(o-Ivwt`T9D`P8-YK z#+FA-gA>6ghw!MffEUX+&Y2MHl-h7-uHGn~Wso$%b;UO^5fi8$_g%wgJWzVJd&_t{ z27Urpnj->(^7q@8~K?YIu|mVIG&D=QO}w)n2`7GBH9$j@Sz3*Q+y zTAPT*xv7*EFvBQw{I({99RU8f8!7-a=a*4i*Qn=%OC_rKr+QYBW;HigM1Ox^;ojZo z+ATpj+6msN!7UMPKN6ZZDm|k)v8o5+2WBx#y-{i0zS=3m(Tgg7w}8X#F0r<7Y(>cA zvuPhAd8nFxOxw0p4x&>*3&*FWFyjVeAUJIYj(wBADuB#&KDMf6$k5PD-qQT+*(1<4 zJt|*tMKE!4?qDyt-OfP=g}Xr86=|nWa17i5USwX9#{KqvVtRT6VCGSf;<@txB)0;* zFMet*?cay75!Pty-WS{Qw##i~K`0H{lITdmGyWgnzjr*v>6aj3yA|!bE?!auP>WQp zjkQEt(=wozWH1&Ul@%($u=5VeCS9NpOk7+gQ)dhfaP0sI7#NwDf}o$rrPkH@E!W`rMk`$=O+$eG3oI?Qh>;kJncpx7QjZ4eUpI zrirbERgvw3du?I9%nbAf@gi9=AE1zS9jr1!&?B(dm7`;S{)pPvRM_na6J7ZIbC_t& z8>)aS64ez_^jIgVNSg0~qyBj(&ab*u^EC%GWV18hM*Lp_eTG3^tmVr4|7%X(|GEHH z9nq5}Ib24eb+#7dssH)&CwKY{Di^W3tVQCl*YpOzF$IC zb_$0ORmM~Jl&b{&@JB|8u@RSq;YngcA}OAyurIU;n#zdVT`H? zy!?Y??nZRGVc5?7CG5y4YEBK28SMfaNT>x=sl6EVz0)Im$+cI1(LX^NoffNF8_8vX z7(78bq;|r#+UxzDGZW@Sf{k!L6eirqiSk#0H^ZEA49dRp$mg%daha{gjgz1;G&DrK zJVf)3y63j!@g9^0j4Et|m9XZ$nf2|*kNv;ykxt)oa7{&$<&an|NVm#ALN;v za?hTLJH;=YLi@8z*T>vdRrCJx>eYuK96)J?(T8zupSW#qI+zRLqF3#qVV^5W)>faV8b%M8RMMgVl=D8V6M zKEBc$A`spkJNET9@3n|WJ`;MZcaX-A@EeE`uHbImj*$Ts6CzS8WuVvYDv&L<~?TQgQh z{=!C#8xGB}xsTI;dapn|yNnJB5|!5ROIwlZ6Zwf^UNb&fBT{*=%w8grZSqtJ-K>=YEyhcnpia~IjDQ)r$S zW@v5Dl=PvCAf@bam|bBf!K2Q{@Pk-f#)iiF?$U@%(+t_KWzTd^Vo=?K%t`w3L*4#u zROufcKs&cLuE!^G=KQ690*v-6=p#k%;k_rJ&^XA#p8E}l;p3nnF_B%yVU25dVb;`{ zy^82=5j)4*K8$&if*BQUooR-&X5UpHvM-x`6JQ=Md5MUKFdCf+bt zmN}v)fOmT@kXTF~g-$e@Bb+m?8Xv%{pi_`RA-)6qz1qd4q@`Dw(H;XR){W$1`YwBT zm@%-3Qv5)zFIQ8Xea) zr9<*sV#ko3!@@LVzSuOt0YRV{&^Wo{FX>QQX;>n11)UX1(ITl={|grr*Z(#xOez@n zoA^N}a)1_J0hh+WCb14jlqC0)wF0>3NK&Vo-#mfsbH+<2CQLF?)PaZxgNAqqc8fTeFcX9V34xkupZOBw#}6sLAZOnT zv~RC+FUEfF@@R{b-Ps4UGFHSC)4duTOt0_^tqGT#jYSoLfNBj5a*~)DO0j(yrn#4m zzV%4muo<=`6%1Y?a<9o9|IHYu{{LElmvo@uci~*XI>c`qyICgxR|N@|Nx})A8XIV9 zX$d>S{T;^R%E*1bZP+anUvcUvi@~Mpn)YOAnmQWB^&n0CvnWJPUV+uBD0Dqb-YJZn*DJo2 zGtZULC8_wd4weIeNaiaQA&qpBF_hoO@H+%~l0F^-+{e*FHa6KP<3XPIe~s8JwU_gH z=Pu*E@am)qGqHqMaBGqm0S}xwc~SB@e?2W%V61tiL4FkOo_Q?jA-1d5j9r}ISmH~n zu4{hjyN@M3ZR5;s-$yGf=^v2mc zEaB!wd)?hj>;?ewo%vCR>6FNH>>?*??~DG;fHufLJtJv;QP{(t`4#wPJ3tNP8731e zTKJZGE7D&2plxLnFFas%aD00DwpT+K7)~2TkGW=Oc!^9P9=#7tn6J=rfN{v_N;~8E z!W}9ioYY5cZN|l;sL7%C_FSs7=-Ku0w3p8r)-Ccrlf!(H$Tt25&!bl<7GdlK3KIp* zaDp^L@N%$RHc{Hj?KWlh!N%=7MY#{kRi8A!Ixzk_lenjIetO^nL3ex=Gu90}O_Du_ zV|fjo9Eaik&6E_A9OlBQ$@8mjym()9$iXD^HtvevRQBTrVdJgrl+2uyIz!;P(@&a; zCg6S}`(ttsf<6UJnGF)v3YwY9<+@t3|@}QkI7MuCIYY524`nySYt=P z_^Z6J{krdrb(*Uo;_6HR0KoFa4wrd{w@N_V;&=J{5h^D4wX~0}Wnt11vC=H@KUuz( zozmrwe_^ujl2EEWkgrXEyR-q<%5PKLwTqiTx2Qtz-o3j7UN8rxk6fIPKT#nJaP@Pi zj35_y>KtAuZ6~Mv5{iL#`cH*`zwD)u&>sJ;NW90e!U!GFTou$AY}?kj(Tizv|7I?( zwDHHPU~LnkzR%3Wx<~4YA=LxNM;oujor}NEKeRbhSnT!zz`mROf&GQ1yesMHIR-B5 zvFHwJM0(7=v`{&`63x?%!0g?2ZOfB=gYTE925vQFpV^E%Rj|mdU{gz48E^D?**(?m ziyERw>(rq1tQ3ni1SW)@gWz#hH8qdHRFMlBNf(y^{nh#}?te;cq`1zy)QHIxL>i?( zFcUs9oOv43rHR@!Y1*Hicq(KzZNyxAaKwG=K0Ypy_%aupirhiIA_imKk&>h=ay6h? z+q7+4>6GPOLAh}jy$v6kPA#YTfG;8TM z-=R(f_h)M3K{n!%3$_^6n=u@rma#W9HLb=^crp7Bf`}l*R{s@GS%;1daxlwnspeG$ zCS*Mb8lUicQ}wUT_`VnbX@-c5ttg%5i)Cb3DH_czyOE*6Ir%GCCH+q0tGPQk_r!>d z*)CUx_%jeH5l0&(0k@8@#8m6*4Ak_ zzojhOb##{FD%Qt6D}OYI1wW|Q*ZsKihf(abY7%$YRES`^i-eZW3;}WoD^ceJY@ynW zbq{AMK#ClAeR5xc(FGb$Qi@TZn{XA7l_aQEgaA21l71oZU4|i=kd+nswjRhOcr-Mm z-mXKBApj#Wwt5U{{P~Oam2|%eO$rstl0`5xFDJ^~cHiIX!NKb17m7%kHKn^5xU zu|0G>40dZ}91XVtZP7u4Kx)GL^zI@{d%$T3tO74*EeMM5C#5j%j2_LH0 zTg-5Id@04t_-Q~XmKCXRTz8p9yMpVSF%a?}Iepz}xX4|XUO{m)0u2B(l!>{;U6_lB z>6D0Afzm#PpIi!BmN*-(9X_k~{CAMQ<0QAWZNQ~DM(>_q2n84sV#CB|aM2KqTg8{N z&d)@+2O{$9rcVF(@dMzeX?4s?+>w7R=7hS}zPISe;58LXK-SJbXwkMHyAP(vAhaL+ zfNYkM5R`?rW(OXZ%x(O>^b0R7{_v`w$;EB8muvbq`*KLx1==k;MXs08QNkuf(8zX( zx4znt>Vg6&>iDMNd=p@9=hf18c$>8GnaCn7|?dK&<_4s;sWBuWt!D57j9VRCXVZ(8nSblEXvVJdM9g zvKJAgg4s8gClf6>rnYZt+_LBJS3beKN}#NU=?U;X1fE168zZVZN|OI!;mpP-twL_1 z-4gD`N(s9BHvLK0S+mKil(t*0LFYf4RQog$bd6KiR`?MCH@e*oAOu8C$Y<8R_H);Olq?i+E$b4oO)d86<3fw@SAJX&W@Dh<FN`qwoH=+J`mhj_R7> z{oZpcKoXduu+MuLop^iBJade4O!>ZMho=_O_arc$9t+LuaQ3E87o*z-({`s2f*z-(BShT0+B$G0uN?aA=) zQK@|N9NElHDU;QCHDl`I?csnyfYuNPvwl-(SlDAsNoJ*om5F*hn~f_q1>>|i+f)1+ z&CxHeo0U2v#k@x>@rGaB$HmjD=1<2;=hu;e=VW>&yT$k$e1ls6PK~XfA%hu&VFqa| zUBWODCn=v6f>v7Zi(fj}51>5kFKF7D>E|i-_K3Rv@iSmYf&nIwLO&{&fVLZL0YpCHRUJ0Q~VK0Sf0l|fZ%1{i|K@G1*Av5}CFM0YpDRDVH0|~RweZdyRqhTz@yg#_+ z*bJU)$sUE@rt(~r$0<%B z?~`^#7c7R@!?Wey1K)zS6yH1(QEK8l6n-5Pj9UY$VN(A|`$3ACK26#xf1xg4&BIo5 z+xYDBTGa0bm<(>U`2ls)#q1=|YEW;+#spZOV^BF7Y#=_z%%{V*EybXT`aNuOax(ctFImdl0 zsUhz6&!a~X(2corGj4DtV@DLckP_S)5F(PsIubvY4EeDUEZBiKUAMTQ9-*SJDKY{> zZl=jNb)UAgWlgb|W-L0bZW1bgj|?MpcRWXRI%yk$RG3cr*=BM>z=-BwXi#H$Aogm! zy~=YjT4_iAZD87$Fjo*L>R`23p4}2AUn$6*bE z^J52pLX%vs(exZq*pu@D1T#)i6K=Cz@FpX-Ma=UoReu`W#{t!Gu2kG#b^f~;ajgNd zeIB3u%?;82D3!tZyBKJzR<0y#*tSMl-E+4#AHX#zw@r&Pe)(IR>}UPUlFmn6XAJx| zQU7EsMZ|Jen_70dO`N z+4<+1ilAj$$#(mr>oG3xyNvlqp_ADYb{DV(NT_a=dkUF?v=-3P1cO7&7q0m`r^k&G z!i_4>m|erC9);e2&6+iDIqmtRdw$A09;=dIbDH&uc17=P^&sghb{7Z2-boTm&Gs)C zr7yPw!g!xsi@7>3SLgMf0mb$*aY}l-8~hx`IS=38dJ^ZB z_UOfn^$6=AcpU`yWhe*@BXmYkO=aU{A^K5P$s;9-+%fCvz3;Mm*Gz>))Nllo+Q|lWmj1SxhIHbWdSVy^l=&=kf^>G}j?clTPN+h#0ImF6a9DhUUF#8! zg?8 zE4_90s#eRdC|nw_t(NwBM(iQ|1ckPah{W16HAql9>8sIw@Is!`U4|C@^8d6_*BICB z-M#B}09H1%T$hyeRG7(1lVpE9;%QLN-JL-H2$D4*&{~jf(6c>ZHxQ18j3ZXj@h;qGIN}6WL$ZtZNb4MsqAM^}>4e7- zGY#-AvMpt^Lw+VO36#nx7?K(edMlpjszi1N=C3H`9cP!F!V6@YZ^!{!=qB||t?$3) zXvPz0ihiFEfSfT3LsrHiWN|D^OIRA#lRzM{DE8vQgfQ9AMSwc=_oz*}Hl{_9s9e0t z${fTG_q~eN1_LEDJwdii-qp%G9NqDFMVJ|8q(%EqE&NGaM#@alIDQAR7}V}CK^Bo@ zr=`=Wf-G5t!x&_+kz5C)G4J%;-x>`I(FPdGXqZ&#DHz)hVKZpwTgAt-z#0J=&!{P) z-`4@C36B6_MrRI&$c*PjArU>CJh8qzri$Ast(%ajlWs}Jg|)PZGi!;CnIIc>ApJ(# z{|%WhD4dvqJI+NM4`yJ|^E5vpP|yNiQExo5dwe@Oo68myoHt9rsX3?CC;!7 z!?3vW!QWEQ2c)rkchV{JoZd&V!d7NtQifUe-1kWq==}pR zVqy==Mqqucj#Ow8jzLY7&GkIql=X8Rq=_MhbyTmTdV|4Dw6AH)zGo^@S}RVxx^s!S z4@v+yV)W7?DsW$tsc+_c4q^a$Zy&wg>$JIb9`3+nD1BoWl=1Q=@a}M7kvxKMv;1gp!l7?*kLKk9pt}NQgRB0T++(Sq}C(JEOy&)H(@`aMGW#p z_d;Gpa-q4X;{?IvV=VOnuz`$2w#KN;3ph|>{=R_e$nx{3#aTP~-p8UR@ZPLK3*U&} zgA5g9gAKkB;vWViC9nPkTrW}DGRevtb*BeMe11sgirUc5>yA!NFqtyq2D9NFN5_W2 zG(^vuV*}=X5N?b#Ggd)%u`CH8e2GD`0sxq?duX%t4j1ABB=G=B#3l&AP@Ei(|HFI) zJ3m6oO@(?JKu!I@U}`Whe^CjCOEp<^wk^MG^O8GWQLOVno);HC8MTJn$lZa{j39?`mp(-FyRY^yCYe*Nxf0X{K zs~FHOJF3KZC5Bsmb}e7f@KcMYB@W)X;gA|HL!-6>sUjNRFtm1ep1#(@_KMS(&$k~{ zMV;S*COO+(u9<3r(f^t4!9Eb2U`zDUV&<-Vs73d18M1I|M?+F&@$s4N%Iwk(W9Ds7 zCX!l@@#pLo*P-H?$Vin?beC~LX%lXAnf)ngp1a0nXdE0fR9B*tNjUNeN^t?%t^QzI z5J|-<NRZM~V{7aZ%0-{7h506q{$?mCAKy4;bc)--rt$b%$}?I)O$}W`;ALUYX&{ zoOEw|`jp+WK-L!W?>*@G??7aYhq0PeA56sZV!33!X>@Apjy;L_Ik=UcU6;(X8$jFZ z_)JHA={MyZk`qF3PhayY!A(K*Sa^$J;yoCBcC+G#AaQU=aAbe@wTNq-1Z2OL7NI|1 zL-aKG8H_YI!x&IG;&}Og*XA358G>$Egu6lGgej`oY9^Vk0DRB7Ks5BoO0QTYPESnv z3Ms{~%#&0Cc5opkDno!5^wS>&vxXJ#%QC&;{<=KKlXmu`%T3a&N!+Ny;8w~Qy zXEHHePc0P5aD$573$)zsFjN{OxPe0^mIeZiM4Tq1>udC(E)n%txL}e2np43+4-%b- zSJUB{o((BRiqi+g5`y~dh@5gwA^jt|;njAu#-X7jQdlW^X?nsSaOVE%K=jsb@@){n zfJ={#-oEJV3zkK+4T`!E!#|N-gcG;bYumQyv-TwIzQirB>cc5t)=-8`PoAfK+tlC8hUKD z6aB}RemF*ltyM(=MdSN{d{JdfY(qHhe^iu-f5Rfd*E{0G0WsdGf*YghX z)0`C5`wl#KQ#TS?mS8Zz|A@VHtO@YZ^2)Wnt6z2fO!)*6}E~C%G#=sD5Va7vBdZ%{v)~8K!z#=S>(x0AjO> zPkLnuSPWxGZB~4aDp=CNj>;w2m=5h)&gk7J?)T6zk?nt8Y*&%j5PDbUV*Jm0We;zQ z4r`#x%{AU(KRTTma2||C^$LRWdm^d^lkr*_4U<$;Q&aBQG(rX1wF379*WgnzaYpp) zb;Bal(gIK~4u`(RCMSnN4)siiwFhT41Q&Qi6&ynR5IhkMC;d862^L5ESQiSTg(zA5 zi7_})frE*-q?w)F+=_d2mTQt^0RWK+(zteEw7&YbOe8%Bz>Lumfx-s~K)p;yw=u9{@lrK=cUM~6izBaf&0J5rKTH|E~q`_HG1=V&~{6 z=;_o-bXzfsoasmh#6xmNa=;Sur|L0B@QpB6e1Gv#42 z$Ys@LBp(|Wr=QwPOf{geuk+^o)wR~puXg?iU-JJq|GT4IMA${)l-%BbcP*?RIZft1 zUo|{OuIMy5KNi_y>BUM1cdG7;v$$3JSf2DqT=e;{$q^pIZVcSRPe$8x{%-5D}<@jI?hIytxAb>y9&04YP|WufD!0i6@gRtcfD`EA92;i1Nv>PBRnH>>!| zo{)%$^-#tMu?t%cT)@`}r?%EtrGD{E2ZFs$CL^^KEvLSWdKV9XJ92MIVIhpU+R-;1 zW{NW}8|!5!?T>mZ@^_4n`yu?peA(3j?yKySknkD~Btm{R!^jqTmuVQEk@&;Gyqo(W z;(-WRFT7hN>(~9_I6ljXuRpyp|1bh&iP+{Qk~+k(9H_Wg2{Wgcbp8$;QJ?_8!P|Pi%CQSr$ke)Q44LrL62bi!wwEMMSn=AsS<;5S7=$BnL_V{1WPJ z!#Ks!F&J}^K}yp&GJ?e39Lx{wOdz4ZM4QOVN%m(7n`Fd0id$$;tb>e?_X6(^GI}6p z$-2oQWf5tD`s2=zn!eOStMl?WSFq-u{=pyU2FMV1eBF<~An*x#*H8uIFlYLpXeB|= zMnncTuh&MyrpLH`?1);arI`Mps!=1xF|fB1?08yN(Ki1b%(@HYg{Y8RsCY~G#l;Pa z)z;I$SN#MdSZ?Hrke2^dWmk>1!9i{yL$TZWznPU5iHyIs?eZ?zQfHI(52vw*hGDR{QGsU*;l)IUX=*D37e>9n8p3w zdHD3X%Eu_@p_c24$3{PBI->vch>kn}e~iePXFqQvUJtwBmPy1@wz`1xoY=O4t~Fit zz=(Tpfj+MXd_>P|xs#<_g^lUTZ~536x}xWYQD_Tw$C28qb+41QP4=6f`1^-odY!qU zb^}CTJ*7~g{qT{x_7uIss!zidzqRYv z3mVaWA1bqN)Qe-nIHPB1Xt_AQ@R%4kbq=H(q9x;HKaEy_LuMK5uEvvcx$6xSN6~f0 zF?2P8N7tGxeEd=5c9{_O13577LT*eCMQRdz>JNgIh}pY)^m++P!6xRk6czjs00;vyM!w%Vq0 zt^)i!ez|b9KG> zl%r@G_QA0TMyOOo_q|I5e#ynnO+Pv#HuIvThGNG3Y- zAPhFPE&%bCzOp;B;n9o@yNP^H;&9T^;epyI=0i6Dx_4YRt%nTeryXT4dw6j)_;tO78gQ$d> z+Q3`I;2&VVyq%ZQcwhK(1c4li86oRX(laTB20%Y^$?A8#v``o5zcz~+Q|klJysyNg z%M(xi^Zvt!SXxB(430xi+a0SWjnq;yJ`_u#73S6}7WWLX^+u#6Bpo$CpkB9F)_Y^#k8vA6ZZ`qe2S6r>Km!v=U9%Yk7(HSm5Db&d0)bY&!wYAOyva#kE>(m~ zXP91&O0}UFp^3P9>(=LhiwDXb^r42*gkNOaI5O507rx{J$rT7VOQX>yZ58uCxj_Sw z!gaeXU#lO-TZ`<-KJPz%*Y34g>kr(mzaXH>q%Fn=G%!{pkQf;t&k}Ki78djs24?t^E zv2EWo9LlcHinXdI5iIklAlGjgm>H?Q?;0SlY7PV|7x>N!27d?_?N+|7~^8+L- z21O~z6RTN}G}m)p&B7VM_)tx(p$Q5JwM0jF=4A9ew_4&`-SX1}Bc^+>D3sQ@BXX1i zOR)|-Ui14`fZLl^ebY9Rq`msyC z2SwG9L-!fJUm^i8{{$5M?Z`;%`1Bk2pD+u?Mv|!tIZ#)a-3qaz#OR9zpja6!6S3*P z(k+FMsF}wDctPH#dep@zp|$))4U35QJwg-r^~u`_A}chG3#GN@|E2Hx(a!*5)$bEL;g~30bvktc2j}$d$11^0tKEBhNj2WwH}k9+DA=@iKgg9fr_^ zMy^SsU=%%xIehHPQ$tm+=>az?0o=t_DkF&wjw4>6@TbAs>>9^+z$+}QJL3n0`s>1X zx8|k}9}@fE(sa(%^R{Ws*KvaBkg?l-J^t*im6XC%H+C5yIm{A=*^zA*q=9nM?Oo%V zb=U&Q>xMIG7?ZE=JakV_Ju(_)h_p!1%m$SaWf$`QR*qhrf492R*Ac==3}Vsv9$I=f z0s7ql>yU6G6g1>T$z8uK_bj>=@uPKV%x+i>ctQFC6dWBDE*1?{0g^L0XBXmgru=al z$k+DIC`5rIJ$C%by47g0VfBt>C`O}16g2xX+HpQkVeMr@6`)z18><{?bfqCEKWk|y z&nAgey%_(Fq3;gz#G9-OZmD9MN#?W_>ewFJ@R#^oFNOM5@%KrfO7t6q>N zf|MTNs0+S$57vTgG!)>z>>`X&58pr8^MWOH!(i0z_QCd>bH3iyNcjU!8X0~48cJaYZk#m#QH2lE;m_fBRRqTFLIx({T4k7 zR~&gkMbCn$`Z)CPfgRcDho5{IpEWwt?Ha;nk2&QpB({Le)ysSsQUWgy5wV{?U-Q-k z{fl>csf|dVrTI}=h(*?MDy%~}jg8cj#_Gb(5Jy3S_}z$Da-s0So&v~@tn~iJ;1UCx z=m9Nxq<>&%LNYUnvLQRW;9}V9oNyodd!&%WD6*!4m<2g5*fv=&lDZM7_B79+`TY}b zgbtoMNug*h7&AWs;GmDZ^cQipJJxjVa_uldPb|>(^c-OICy3f*R>eorSF~(JzX!*T zei^3bEowYgjqUAG%!;VJ&GjCz4(j!bqx(Gxptj?@nt$DaM)s~FU?xD5>y@FfCjuJ< z<44RT|J=l6vcRAv;6EgtFX4J@8hQ<~f&p}RBlBCtu$!DDAR(1Bt%FYmviS zplIIVdnB2WH(46{3FSYuCToRxW6e7TA%V7M6%bQjs+bU@Gt-#Hw;KiUbS(|9xKX)$ zHcXEKw&5GORV+_!IaY?doDt>+3l0n1@edCjf~bPp9QwafDx~bn%kJF}oJPC>|E|5y z*hC3P!jzXee%woqfdeEve~LaaO((qbcywS=+mG_d(7{N4@0{Hx&t`9imYWd5(EL7HQa zl{v9>3IILdN8URB30(Yfn7>_g`^a@flDOhwC9fb7Z?X>0{1cE)^1pV_6y(8@3O1UB z(pQpTjDh-vNb+^TX$r0A6!M7(->dU&IWw}KpT?%_=&E+4*aK9+S0 z=oi`k1e7BzGG6lN5veawv?4^V%BD#{0HuRvK#%OG#L^2H$EQzqs-4uaVjhn{;Q2AY zAZs>my#8t45;d$5JtqAq2w{?fo4t4KOc_AcD2TVC?XN>m2qH5s>cnvdW|2VXfiBPa zGti;+_=tVo#tMfZeG@{M%I+gv2l5P95WHy8pF2Z*QVqt1cz)<_78dLO4l>Q}BXwIN z;NpoceoVU?F9HdJBBHA02 z=FQX{#HSA)OiQPqtPjRs$;HiV$=u(e~>fGTxC+g|ZTF zrYH7H+ZN1hgjwqeKA>J1n#k=Z=Gv3gLBa-tZ?MZ66$Ta^t-!nGE^714!U~vk5h-!B zq73WBq~NG%r~=eY@>u68cj5cU{caEH{t4n`w7FA>B^@H)i1Q>mgF+h)LcwN_vxKq{ zTif)*dYb;JacaN>A%z~7751+sf?^rmJthZinKOdUFNWn{M?I>94*`K4RjYN1%y4|70w`tsog zAHuQBQDl3dchP551z;3`d)6TK2@tSvwF=gi3EcHDC7P=5qJXYZgl=r9J>axSJyFN|4K^NZ#M zENZ~Jq*b8(2*(BmIC#IR9*DCoa3OA@UceWIi#P9^(oO8k^!$0$@6!>ji8U6m=~UJ{ z3a|$_gEE4kIZY`Nt1iJrj#^Ty;onxw9z})_?KmUZ2BB0#F2moZ5XDj3maJuF6oCBOPrd^A+ ziUxMBV(auitX?pXa5#%z6}OZ&$9+7aAnBSKlkd&{Q}LF6$xwNkTK6Bcz$I6 z#QZQO2rA?#arTmjtLU&_+gjy=kbr<4t|uEw5%=!G7(1#^_{+wZSRP?M05pYZ%NG9r zD&nEWCFEG2rMYuttBk|7LPmX{2Qb)@ec>IE&2`k7tXrrGn+fE z1I_qG^m+n~#u;kXbM(~!HQ1%?uM{>p^j|=XyHi_QC=h5n3}LQpS&{70n&s*JaPO8O zy|vS50YE+MJO=w~OIz@RI*=_)b{b(sbJh5R^GjSZ7zv2g#5#NzzB^-^G{e{Hf;-kj zH-rQY-o|apUMmT;`@Z(iX@GNNuPabBDn#J?NChk&eUT)6nfbo|;#u({wFisK{(MI7 z2d_eEvri^gSjfA)yMmH}_FnD?*K2gLt(h8`|5g;^x6{q>oa26fI<8#r(nJA{Toy5O zdXk`bo$*ySiQfvIQmj!Coaw$sWVtz)U53N}&PSJ^67lLPF~ zB7j&;Jn;!KZlZh+^7K1VkPK#*WD!bX*$pRpeO*K$AE#uhcr!q>kUM=J4FxgfWm8ol zTA0xsg7;;+fWY2(&r4B^FVN^-Lj%!p5TaJHuq`{nsM^FEQSvYq?5>dJpv;_`{jk0| zRnR+!-xhl(cB2XrzSGB)6ygn4n1QiB)nJP6 ztqG&>gEJG^ahk!X?QyKKm_Tv>wBZ3q^inR?cxruK*;awX9euIFe-F@SIubqq@m<7N zP1XVEtLVzs;Lg1PS4og3+Ir#MU&y7 zQdPRxjYya!ya+-e$7Vr9MR;pt+wRl71;KrqN*0=_51Ip)ZU!>51o3t5p=S~upm{%@TK?3JMD&Uga3t&+8V9Ei$s_=Z>Gi z&HLso`n_&Yv_>!1WpJS5_Md&Bn9pzd*%iB&f9$j`)4k z?vkDDA0Z$aa`{T2d9cDvkbnQe`-B7CXhQYU9qL5|{|uAfkKZu_%%0MRm1 zyHelab+SS_l>gU;)d~-tl|4Vbl8(TJH`Lt8u7Y-d3n?}PmH>S%f}m(CLIt(jwLQ@L zAjX+=>96m7|M~L(kXWw7=MTl@oG*+rT$D z-%sYg927Lyu$m{yH8nOi8|Wjl{9LLdv2SPVuDO?5`8;YWXrMsH3io+VW2`7E=`Fdc zJ6Pv`2qnqq*|Zp4(=Y5PGqT;My?1XRCKBUkBF@mIltPH+hF&$lAIJDG7>EPtHM!F` zz8-aAya06C^}6~Nr6K5udT^~Ih?r?&_Upy%$h}QgUfv24_fm8XlrF6j$j9@cj#ZVC z9oX2}*(rw!#tN!Z1ci2xFK5>c5k=$}l#mEDJQuvy*C#&1k}d}zaJAD1KOh63Qgeun z0&?Cr?|#m&d-4+hRE!?+I69jA`*#nD!)$JIuP<6z9$|h7;?^>6&f*hx%C@WJAQ@Gt zsSG@-eb@XAd^xEtFNWX;D@Ir4`1-@8)!R&=z(|W{qN6+6LPtk;DjIJVXKcAG<_uzD zJ5Z3Chi8(kl8FCyT#1I)X?=L3y;xg%9v~?lOH0ersA-%6@-HGFw`E6Z4+w{&t?2OQ zMbx7Fs409ma>&qdJB$mlugReoqqWiBhx_71j-jRAuIq_G!9i{Q?d9Yz4^Tf|(>#y? zQyTRX_6P<4TFhVakXxtaDB%pq51pUd2^L?n>-Tk03mVCmxaT|eL-t$~I_iuQB>$D9YzMH0+nN%~A7A38+WGP!A zv`mChC`%-feapUNnQ2B-Q?ydn$`-O@U$QhpC6pU?2$f_D*|WdLNi)+tzvuny{r&eo z_vbTB;l6#p*Y~>4A9<$KD=l&NLz!}de z#C-zX%WacQP*LOnA$=Rnm;@mHU8@RcP(Exc_MRM%ZrNHTY-+J5KiVvgjLY)N-OVIX|T0R;+dF!UG? z29zz;HWq`$M@vd0XatZkZ2QGyA33*gZaZ*DLdQ*}+yze3TDM3JK?MGt)T5g(#-RC=k zy>}6LT3xqmuWSDk9_yzONUlo2<+bt~Kz(y1Qr)fhj>LCpBaZD{wj%_55gi&)&Qdy-IHs_>5^mQeoZbzs3#a9Dmy@#vs8!2d%c0U_P$u+ONcQbb9+S4B&>Xq7?cwdUY zAvu!H>V33#iHtG-5fHO4fV#a3HPHKAljlJvT#5Rq2y)`%W8*y)>QGMKi0v!nc4N}- zRA#e@hsbyVcjM|2^&VcmtdIKs+qQ0fPWO5d)a+NkU%Z&Ed=I13sL8nmTD`X5JU2|- z9O>^D0S;~$s5kXwS+DnzNq*e?_NLPVDn?)+I*-fAo&J=(4O4?Shf5~=2;7;H zf+|R`{VMcYo&sef_yowV6}(!BAss8hTuf>3I3ACv;bd?#7WTuHSFmF|?2Ne###y(a z8Z8y4bvyeWElpGvKZ^3Fh?4+lMG|P`32oUiJvCC`P(7-N44B%7qNN|97se2ZKC7`r zKV!g;Il9`6b8J1>)zSF%=X;~?7J+t`W@d=yzlQ{ZzCeU*6^O{DA>^pK`W2D~3bwaI zwVrz7TVVEedd9IiOMt$o2uxfzhG_a~s5$Froa#Qr01{^Eu)qO#a6wIWbW_96R!GvQ z8Jz2yR`$I&ps`lB8`= znlJ`n+lZO;63c`I19wOlaUc{ z*l61(jJ#cipjWiXqgRG`#->LA{-Xp=)mnD*QU6{q@YdNHxI_k6+?zH%Li!p`rln5P zte*}LEQ%P~d@bm*c@M{3!}RGfeKF~SqZL1{T4jO!vvj|Tiujrqa8~3|mrC7PdG5l6 zXO7>O8U%V6K3Bq*R3;PP2T3FAN#cFv(w1YV9Y9WSzSzAOJ~FubR6}aJlr%eI+T}jW zrxI{M{b1-3tc4N6trEn_sT0RQ_Q<%8_NW#J`$`-xlta&m#=N%S9X+5RaUd;<_H%(E zQ?}oT8h9#pbuK}S7#+xE?1xcsVOr$p7N-v zs0_6sALmyXJ;eAB_UxE#w!0go(e>?LB?=XS;}sFR6H|0j@?yG_+*%#p-y4xjIz9D4 zFo~U!1amNGYK#&^_W6BtK642?HZaY|)0ZGz4eEA{{SY9W|LIRd?*%UWjHx!XBpX3C z<+*EL@rsKmurvcu$o^r?8tX^J#T?jwqTmi*#KiH9;^H-+>4*`}48_GV2ut1U1CMPL zLe|XK*F!eSC);Co>v|W+U4~43 zf3M(ar(x|CHe1_XkEwh_dM2*lF&Kq&U z4~$EMZKHzZ`$tfRjl-PgC(+h`(Ai-CnGz^lWk9gYj41*5%N@R~8mw(*0|8nHbFLJh zID~G7Wk3FS2XGMv&GPf{DWX78gTf+Cew5Y7vhTmYg~|!PtZY;C1BW<#5ux!lHW~%^8bBT@-Y%!H;Fxb*`C{9;Hrdg4OOb^g z#>a23k(H9tMOju8b`t{d9)J}N0Lc1o@!|mV(^E?eB5fe-2XVVq_{7vn!Fv$3n;J^; zhQHPs-Vy2X6!QPjr54hP>67E~o;Za_K?OX2C-)C{_U0sWR+kb5o}Y!gbkSB3FMsYQ zOr{2uZ4P0D&}6nFU}BN9w@{xA^(JDU9<|Lo$#ljM zc@F4R3~hXh>M*B=L8zq9gmdce>%)M+AcUNbP~--GMHQ!>31pn})XHc$sr?v``~uUF zj>mcG>4m^2MNtBZI*CQogKVI&(I8myW4wF|=Kv^wX#S~1t!N10nXwy}I(Wq@;j;QL zgqbYE>;#0?RnUx*4}ncA5-l?f;i}8H^e_MbU^KhV;EF zeilK^{qgLk$-6kih_Wu@G)ACbMWZ1yGSUp~x+IBD4aA7(@eEYKxJl6#0H~9r8nWXy zDiA@kF`u@8ZjV{R+T6+kX>LbFahzfh@5Nz6Lv)YPe($Ccnuv_iY5d@>qHl{2)Kl#I zK;(ucreg>da-c#{F6rj#+Kz3di6K!|O|=&Q*mYjq-jv*t*^6c6n0#*nm#Bgi{=T>j zL-P1A*H4Hn**Q5syteWg-wP5zHDEECbJ~!BjHA3SizDkSAOuUqbh>ESD6xd4;|B;2 z7E%;Q`?N4PuP94lV%)(!dwzkV7(%?&=6>J`3S&rsPa6!57J2GDa6Ke9@$pQ@xc>04 z_w7_hgd~pw07IO*!OhK0lDi4JjvXWYV0dm=p!N5p3Lr0F>6&yT z5y>wT($j{62RS7Org#uy&vn%2EyylJ}O;vAR$XQGufJ|#%h)K8^>!}s#GT2cb6xIv^N(N__A@F7@2(QeG#(>5&Es# z>1yXUe^40_b09V}HxOkedWNVswK`I9DHfq}Py&n=mT9EAr6G42?@D}@*!3ZZPoyP`Qa8?E#yp804`MTZ2*N~5K60$ zSu9qMBq|UV&@QuhnS2|kJjE*a^r*cj9Gv@TYhZWS*<9X3cYYbxA!i6*=c}W%^GunQX4Cvqbq=wLk zi6h2oANuq3$(8aYb3HiUK!}*e(XUDA9e;uBG!p(s6^=k+#Rm*ECC)KmJs*AhzM-KS z^we`Y3whH}jX_Xi;s6>+3~f~MUOu<&ebZw(9f9Sbb00-4lTtR-Q&L*0fEXhT5>GwJ zD;Xg?>(}q5m^wBCGm1{xNfb`DVhuDAV5L}tJ|dBDEH7w*(JLdkX>-;<;WH$JW>}YK zS*FD$mF3%?K%-S%MhAe~r6O|}g_An^p@__~w%=S6Qj45DW|7&m1QaHMgPxoK*qwtX zka&Vlak%I3O$bTar>}Jp0i1YU*r2J#+}Hveo*ozTt(%93C0Z_pvJDaZ-$s0O1WRM@ z{sH^m3{?o5?OUGZZQi=|AX+Z+Fup5<3j@7>CN!4W^0oljV;aPaVUwiA6Jugxpt}_b zs(ehzZ{2WpWJqavh=W^S?;0$04ML=QZDAf2HLxcOO9;lq%nDa?%Y~Z$cHb)i<5)7H0 z;oZoB;a~M6HZFK|rpBTM9fN~UwM~rY$XveTrv9>HcRNlkGa2Xf zDWI^DPLs?GP%+Q$JaT1oT)$p?mJcEr1hY}_@RI4DM*I+Gv?Kl1#C{IpYQPReimd^T zaR}FVQc7;%5r}cgK!QQ_>3jxbM1Iaz1|vBa4eS=Mv(fd#?JtTR*1c3iSO^1~YSjQG zQZsCoY(K}#>H!7lS@rNC(e?cAAO39=-?tJsKI=@0$4DwuerK# zS-igY@LY1}Y*8Z}tJ>XMU_hBKoPd64Z8IG&4>~x&k>^(J+sJdPY${gYd zFjYdOuAjBb+C>iq-P8pA*2GR+#I|i*yPVJ%x~149XI#6}Sz^$Hi79r70t6QnbUz6? zDPxFljMJqu#^q3IAf&6t8R3{NII?>OPDLYSa02JPOak6c6HfW6$S)f)(M$zS)?OFA z;hlV&Ht;9+WepyN@)vwk*=< zCV38oJd!(B-*}O1xHphJv+mCm_wNEft_LWMMyRe%N5<&qWG1 zj=LZ(MB1R6(XA99aI;M+`Pp)T;Ltge(pbeBv{4LINcZmW+^m4r0Y-ycJnh_I3WK=} zr6vTgH3=q_S)^HCpKN#rbheJ=j6nkyZqy8)-4s{ri8%p}mDIEB)Y` zIo`y^Ld>m?RMy2T1mlt?QHlns?C#!{LJ7o%Rrr0JQ?Gx+nKVQCpt|Pn0tb})*)i)7 zaW^v3W5AaV!;R^O9?5`xh(wTTfet<)83PFD97Oz*4yF?kj3qGSTWJ|`m&(>N{lN93 zu!%Z7Lmdt%$b~k;7NEFMQ!qVg zd$#1%3LN@clweY=P48=q0hfqb^vh|0vnq?e-^#WZN)uJM#E?tZ9gJOiJitoH-O0(8 zXoMeywkz_e#@n7E=#VDD1}tHS#6Z#}N=l?W#~d@dQH?U|94|daULN6%X+sY{&Q63t zOGWJSK<+}i=7#a-xu|BfT^T4th`VU5tRA8!ca#zPHK$co|8RwejRS$cVLOL3y11)x zE9oFoV3gL&sBFNbmcV1B&<=@er+&~M5j#H?&W+Q{PEmG9)=fYR9!OXRPh!_V4)`Bt zh>upGmZLGojgg?@a4`E66yni!zS!SoJ0daN0V^BTTMBV9=>B^b99o*S|Br2tpP0k zQatnVb7Ah3g}Zwf{~TWXEs6+~00u*J}vPH;pP zU#tN3tx*3y&demB8jn zol7T7(9zeJi_lRh_Yp-X;DaP0DKGns1Q}V z5QDt?xWULc5$rT@!a`-oKZqhWc$PR$x)4+bARhqMLULEW;aY^R=g*yc0pUl^{%hkf zlNKoXxb^(ZHL?Mo1#v|@E;UHxS*&FZM_zzoEIT1_9T%JI{dNy)4PSeY@baXKo> zxzi;Z+kluxf%QSZYO(jOQUgi_Q8i`364AQm^*`ORc(Q;VbbzoyA`+n;?;H$JVX&@C zDUKC&$f-gBDiH{Oki~eC_oOnymQ!}}-rIpFfI7RS!5N#0AOZx`p_i_=P+#s6*-ys< ztbriBiL`pXAD9*k&k(y;I=43$Z4|UZh)~|OwV94gnwn5in9B~i2^D`!V&@7&iSI6M zHaN)15a)6X`8{X&wP3U7w|=Gz1g6+UhUV$(LYl{bV@E?k#KEli?bly-?2OKnftsKs z|6PaDI`8RNh_%3%UnP+u__2rPsSSXac2ge$OraxWgQ?mN;OUf-l@>|6LfZE(`Y0%K zp#93^I?{^C3P7_gP+K2E;r%dTsF+8;y=!fa0)?aUetMICp^+ zJ2p+$1rp;DVq6xO$Fev(U|?`ilgua>n!sb~I+o;5#)AaFk0cEtr3OynJE-TT=rLZF zeE3iRkGXa7j@xtComB8C_RNFPF8j7_-4+wmIT)=#XwsUHMbADC3@{PiBtV@@myR}S z(G)yjuuUO%Y7|m71L3^ED~KFp@a%7P8qK%2KwUTof)51B05S%ZV28|EKy!e-k5$3N zr6F7xe=pjMsGhbrk7~$sg|(iMASOvpjv=(&iw*xAhLe5u>i8AMTpw~bd(@$z=#Q@c zdw6^Oq!$fuPD5UdK&&dUWxWGGXl@Pplb{UTbl2uZsJD>Sv>VyONC<*6v=XUC*Gt(4 z99DP&;0CrY5jcxUg9M_G#QW$F5J$Z_4>Lc<5ErD`z1ahYqC|msjaR~vc%nN3?~KRB zr+h+Veh?~(W{~7sC2Dd3m~;Z%p(Pew%KqK&gyLdq4UQf!#ts77QC+(UQ;9rehF==d z`NyUu$;&5O*@A}+?`sp@hNxQ&=f|;3$G_LLGd2b@^`r&CylQcE=--~HEdZP^0N_$I z%K669D`BYfk+oX{SoiC`2$BZi1Hr9uWN(RZU!5o`vT$S_(u4u$$iPRCYk-fx*}9HG zPeez?xpF%KU_wzTibG+^bi()Duyi`M@hb2L2~(3kdCt2Z{T}}QmCXS_v0y0T&o&`! zUdK@UX}9JMBNXKhVVo^O^n1|x%A5*)5=(gp4hpRYL=5AR;CBM9VF88ykm8L79l8<= zs44@(i$zlOa&jjxm~E9ZBOzfPJ(7^)Gso_)hYu(@@%}*-8?KbXNf8ls2vD4gU*Pw; z7nNanzGVm`$QGlCN*A!zornlR_i`VBQFbqAyKN#|)?FlFLVUF-vy-a^niH4V3xztBYX%N z>oaYWux06vbTX__ZzjC>WH6p+J^M8Air`>O;<|xOg~)CR-vpYc2^M|wZcqm_H=T7A4f)r-XFs1q?Pu|xif>Pd4 z?a}DWK9~h)adF*+Zfb}76_3|LnKMla#jVX6?_g~%+wAJtz`3oy=BUPdt9Wm+N#6&HGcClEeSUd!@ z>|R@wTE0e2t@6SHl%sE>s)tNN9s@LLK|FPW?iY56B2Mc;G%hzL*3EgR3S4pMeXy-b z0|n`-kLM3N0^l>=h6^)Bq1lw`tS` zz+>Y!=}9ACYY}3BTDpUF0BQKa+6G2=f}9+STcl7E&&#~+fCB~kb@^?8^PDL5dADf! z#u%5)Fodt|QG|NRyFn5-5#hryfSs`KN=o$WuOPu(#?BszYzkez{5YHdl#if31Hq8n zC?DNLq?IVkp6LQ5#Yw1e;;hCKY6!$cpYlC?0$b5R0Pg*5l}YGqyNjS84pX+!ixv;# zkR>(5nGJW~HPNSl?2Bd^VU95q&)f-GU{NtKTY#Zs1|S6q`0o}RZ!8V~wjuYKs{Y?0 zB1nlwJ*u_jKk?6*CvMwxt@y+fSAT$?WQiaau84qx{M=#GKD1)|^@#QhnaHTMUY~ZO z@-LpJkDWn*f(+7m^va!^EBbYc3t&3BDCDf<>4~yJ@Gu<4kKcngIhYMwoD|8YaZQJST!n|2of zlP1p8%+*@dRLxzo^K}}B?;GeUzj_V_8?^1^Cs4wW99<(C9FYDC16$EciArA_5JP_T z$lqzaDlk5NK=pX`hvBPU^-oOUSyCuNSQQFwHIBQLz+@YIY2+V^y?`7zv~1e+=Yky6 z=V^sWU4$ut3T_P`nw|%dui3#ZrGyau19vC{f{rCe+Xj5Ge`x6N@#D7$v%-VrMGGE+ zP|(L$T`)Br6Eog+w@1(a8Fp`!|1)cFokjUU2)JHTzu1d z`LF{n=)&9Ik$-lgU&ebp|N6B){iC2_0X#egl+Yc7%^DOfVxGOWv4zLunA_6JUK$47 z=N5-hG{yn~!VMY^YSB<30C05V2i~#uGZ<~-$VF<9t_n1uK~D!AX>D_ge3pjDc^|{y zStx0Vlx(0425!4TiS|wDC5o7DR*~g$=KPPGN6n(Nj@GBaVm*3nshOLZyZ> z$6H+z<$8DSl3BNIU5l;3ouAHK=ncl{&MFqj9JYr7OM-sx5u6iJG>S$KEG0@DBO6gf zTLy6+WZj74csFd=L%9L&w{dv)LTtV&{FJDEGwdCJ4asdA8H`tJp&Ul9S202;P9V5x zhrkrayoG2|-uo-uveo?(8>A{tbF(lJi&47p2Gry6cW3JZnKZ?)k;O&KB$Gk>Q0(}!_4k3otK<2bm^eepMc<0xDeYg)N z8Z2svnrAhD$+ufTYEa~u{nhUTao;-2r&%T-Y*1BG8pkx7Eh1$d zCv)=gsYGs`xxn6AjFo>~;JUM5xr!lk6lj2cy&_7p6^frfa>+x#LDs4N!szDDMvT27C@K1Oy zi0iu$rru2S{&2sP3WYo-Uo&nf0C|Nbm$%jqHrduIeJNw-U zZx9Y~Xk4SaQ1nSatS(L4kns|u6s~}l3hzIfn>Yfb18(>*!YCfo`S=YF*$QXhk3X{q z;b2U47!T05fH0@>+~+5gl?hXBnv)2l#XgPOcz25ElF`KlSHw_>f}jWE@qAID*3G_N zKE(DojN}$%h-N2Gl$9t49R2iZhotE2PmC~8qw)mx+(mx`ITf}2t5(n|5C4b<4rl<> zu2)W;0N%*1A^w)8clIwgVF16LeI=iPG44VUu*`9iU>gSX$?|U0v~% zX)=e;G9ld|_<<^_}f|s50?iUjMt9|2>)G|7Bmmr2pUDW;Hl(*rq3Xpqh6Uz$CvUtB}sn&RSOK0(25?_o*&zfAV4B>=3h zU%B$OQ|ybk&HmNx8p>NRJNlvX8HL~8OH}acDoTTygpVm3WIAmzd{n$A>vd%%pvE+fkpU^ zS%~dA9;ih0N=>~gD=V7^_XBhBIs3#;kgPYsdvY$|Ws8 zGy`)l^cd#;mF13R+-F6hV3K1$u_>>eC4=E{~CuS@lMy;6ZrfAmyU2kN@Oh^G( zSSW&caAZ}*b~`!L;QEonX@fC@s)NFzf4lN^Y7rD4zkEj*xPSk1fE3rRU3-TLFN}o;e$P&%76Z6pGQN*p-2fF2clsPUJ`}qi-fF;^WXUL-hw_ zK>N{XQNuSI1OD~iOM)}+C6=QjKoXNlCm$alhE@!|-*YO&mfXl*HG` z>|Y|YKCiOZf5P!(xuk}@$>wjHE1k-VTX*)lHA%0R4qoq85f5R?lcuIyq@|Cdoba@~ z+$pCNcp!0Bk@_y#Jdf`5?^mG=8!g0^m)*|Difd!j!7?V=3bLSgy}i9}jHA?`S@>p` zs-0c(k{|Irs(gF5+lk+A=zjY6@j-A<;h95qy`fNr7SYm$9e;oD%wOyl%`Jon{0^|t z(`U~dvq1H?Cz$W6uRb}`KJ)3VvywoWjL>~htg29V;SBpG1V|6$w?NCSRsN4HW#<>3 zgk$LQw)p1N6hg+J4)05O3xi#G{rdHB;GJvq>V&v0`S&64$=pW4ftP7!!*x)Qb4pB7 zV*$hV541GQB&@|+fFdE%wkA%XP1Ye#^lw3vla zcJ8xZ_~%^}Mq~me(E1N~Kme@(Q-q`FK7H z!kU>&+kd6MzyDfzxNQ!YaL<*^>1PV1{O0=%3=FKvU;7_cBzPqQC+y0*YT?`kUw`fT z`S#0hj)?pp*R=HSYm(M$X)Dddx-%F`T&7KBTmK`#<5j)!7E7Xkhp@DMbxPf$MFcAs#AdgBh~_kCV>m{pO?7%%^U(M`Lk} z>Z&!+vO>+Yw{IuopdL7=yHPOMk|sf|;^=%RJ9lpYWq9hoha<~*JBnsTORzyg_9OQH z@}) zs?zlsIx~Ccu=4o$yqIt=T|^gC%mL?Ied^bOar3G&&|&tZ92B4`H$olN1QkRj z$oXVK?hc|&^?JF9=xGqp@Z=agq^5w`Y2X0|CZbN64RE~uHm$v0 zmfdc`>29ZYCFZIE6z6K3CMxQ&V_}AkopWA;$4;Ek-)g}MA=;$!$iEFKyLRU8F*a8MOLEy4u?Gbw{QPHUZZ(keJ=>d4JKRpEl066^4$`Qm8TF^;^p&iZ2{Q!YB04EOjFS<- z8UEG3y#(W6)l7WAxb>1+1>YPD-UM3yE|hh0upii1)Hj0Oi71}8b9^f6x}8;SiWDc? zNUXGs0ulX2t&9v~f>khe7-2AP+At~&W@yCbYFzst7tj3b;?W-+T#G*Z#81pdS;j$i zs-n=`ptR+yR>gVrWS4G{d^X<)ig1zO0Ju3$L%lK^D;tG{)ljkUb+TQ=!0gDq$XA5Z0?-+UimnGY5RETiK0IH4lA8I# z{&{l?P0+3FT3ct8u2($hjQ2;2JJ^Lngzuid&=`rw^LuWbe_g=RQY z<>8cu?itz>WWN$HCJ47^(su?!!OYZ0!eb5sj@nRc;NcplS8UWYr%MX!>~hdC6N^^6SGSa1ioBe{5}7X?LxBIAG2XX zneGr?xm_u}YO6yvYc+B4hCbA3fW*N>C4J4}X{jsMu0>*NcG-H52NN9}MOfsZ6+y|# zk5DWcdgV|_Y?GYsj0S3JFatwHbCAgvBsJOJ_S^48OS)Un(jW`gX-vC)Z@?Wh8x z!O7IR?-F2nJP`;S`RO0$ zitaR`Z861(d5PS8(E{yhYCCyaRwjDysFVGW?FZ*vmaWk9dpe?lY8glpQ%EC1n@FFB zjQ$D5cl9}sMvCRdi%rY&+2lJ;Ea-T&yyI+a6;EU2vP#9e{Lx7cdg}X%X5t4%INdVr z(4sDIuBa#by9A)5WrNja7=M8l$E?R3`a@Jw!vPDDbcm*l7&+VP>ah|6`Pp>BNeZRL zQ#lCC)Ob`!qb-lQcW{>tABBE3trT;55|2y;;h<>Vxrb|SE=nP{3$~tu{wlVS+ojsob{f+@GKC z0)4F#2{3=lVteiu)DYz#UcLjy?pWgrtt4<;$kYRt$oEsf2LjQP!AL?ebnSINphG@s z_nG+=5!tE0>XAX7w_t&E4bvtwIBZiBPJE2&56;DiNvzD}OvP-QUL|zF^N5Owq`@?} zZ2WTRGi)9>zPZ)nbZQ_9Fs}}IF1V@5T^)4 z#&-1Sit16U9*?-+W(gA$B)|h75|ufXfnq00me;9z(P`=Y)B(LXdQUqpz|iY7F@JDT zW8~wgALt?;6*WK{`6B4y%@DZ~nKiE>sd?yT_32A(U~~W+9-$De;M;vFhB!r6bB9^r)axgTlG>tE@wyD^=q# zsVrcdZU>KA%h>qcvdT3(>~@hN(Hrpy`HSi>iJ_g-1*p=u);dM$;A}au^j%^>{Up*b zBL9}bbOi2XRAnazHP-Aj^D1pZF4T2ZO_sU?HLD*-QK6LxvY5HCOc$e*{%Twc^nl8> zrc0As41ldgEE;o2jTC@u^g8oSmMv%Izx|8aT1Tb82f$bQ9A?z+%ip~yJR)NIY9Gn)C)?9&O? zuJ%mi7kKfUj8b}7(VR?pgpciP#8$|Ilm&tS0!(p?uTmWXHBn^EWYpWr2fW{s9q`cuEl7VJvwR2*ki6)2BySLp?g z2&l5wtD)&S8G45Z^((TE?Yy9+>+{!;-( zw7rNXc${ElfsBkt$P5o_F7PgRBaV>fIeKw-4(nP*gS_fHw-C+K>NYlsK-EmYK$2yh z%@Wcq(j57kCb@oIuimyI>QO|Zeqi`U?kU}^KT!mH>!*(cv$?KT4A!t6-p_XkeB1Vn z1{;SsEfCX)Z(KBn(tR4deW0jR7r3g36k-mrz#dhhzRxDF@$L;vOu>Xd276OLyd1QS z--S)x*SVmJekv({ERIex`t|mMQ<-eMvI@lX%AErjz+j9<#JDOk7hFF|XEyX|1z`ni z2Y;;xf7Aj^5~?FWgM#M{SC5Cll6~`=6Oel1upgy z^qdwpFN*x7G_f-B*ByLvNoJ$8J+*yjlSf%Y=MzbrAV~eJZhmef<=D5qtG zV~WIYo4y9fBAy6fa!}P1Y-}(|HHUhJJDTSNx)+X+s2{c2fC$=od5YSfaB4Ksj9(;9 zY_P{oQTw1(fM7`YW+DfEE+r*}bNDGjRM2j%rP#s!)WNJwJ;bo~l3lhQPzWeZ?m`WLs(`zXpFDr$*x%D6;nolMpC=}S$vn?08w+PeRN z*Pe$)brDtGQcBF+{X7?KH3_#U^q4j6yRMW7PVe(j;~AIo)k41a#AbRxuD#w$0`0Bi z>wdWRJkohyUTsork`cQHj5ZMp53sUC7y^nojYQQooFs}l;(f6B-m4oZ046cg9YKEp zx;WAIxKVkexQ4W+sCzaH?Nxia$cRG;26Eo7TaCF(VWDEN;oy#qeyddj50$nNa=m+o z{(v?XaftkcQ|fC8&RIG_ai4Z$Zy?_VqDK-yteQ%pm5{iDt(Ko8OprT(zlsT^T9wxig%ATA%fl{Or1)JmQ$* zH8FH0$%ygs3h47eVTo=H)|nm15*=dOAaHOOdA<%PiAJ}F0AN!aF2VrE*rb~P7bsAc z&>#47p)eh==UeUwzCrwT?6phY(or*MaG<&;@x?SlwIeMyR8}=}vY|I{V?DL*i>kJ=f^BnHgwJw#iLzOW2Nl30^AI5m!p>qQ?sv zMPt~p4{k&olauN=mrmXHFd7RJNX3SFz|5!VS>=!SY*CkweaFTKgvzHa%1HCY^#{->AM}3C`8yzW`KHr!Tj$)yKg^Z5g3F`f z;cq6o;bcNmr+7rflie7NtNXBoHGG=1qK$LA}pK^}IX%capN5Z!(4M|$D1<1xViHliY= z<4Er`dM4aKe&VRbR3@`09pOHgVeUC<5ui%;Rewt)cOVptx-fMk2;{2XX&E>**odcT zZKOj96RaE12kL3`5GQ`>@`N(&{d0kj@Ff4?yMp=`0{aIx1*^nW?fNcPUL^Ysu@!yp z%%U?stQpYfEE~riAD=sUD%7zFimNz!MVXxY)-akNTWUUu76c)6?`yJjtgwBCkbql4 z!-JF>L_|b(W;7!wm8s255ypgtPR%yk8`? z7Y8`+N)g*^I7%xF6md!bum$kIeHw8Ay^OgES($YUEsP)pBv#Ngxd@*0p2Yd}^cilq|D1zuVoUyejwbE-?{+I?I7xMbzKRQ1}E=96D{$gPPQRL)nW zwD_9RY(eScd8FKw`6NTfWhot#D|zUwv2|Z{5}tvyH=U<}RNSbAep4=MBlACYV9)Dlqi2q@UZ+?3*>cXgTMYg zV(B{!HTYb3!{xw}9_AL-svkQyXk*k7x;nD`nEHW&UrP6ExAAQ@dN9~;9^0kemFoWI zZ)d9BF8EG%3B5(2csBJ*x`C|JyfKczIm`uTx})W~ArDrIX(e1Z%X^ zR{>`53@Cc>nm17sjd|2XshU*qKFBf+eV2h}ef3-0H5;BiJK*0VyzIey9EFv&2{~?i z4@pW5<>+PqXm{3%e)a5&TUphYovAg}*{lB4+|vDst?tJ*>&pF3HYw3DF>B6Ue_Jr* zL`8yI)w5u)Pw6B;VJvUBVIx92L`DHUNObw+ z{@{shk<)HSb#M7aZgOsvM?@6=cI}2{jbVWyC(5vIRew8M$x*aW&;2E7qpLpP{149K z;bEC|R{bL*BfB?fzpKHtX$%ADE|7dQe-xijn`N5~g7%fk2{ z-$u&(k|_jR;wHz9gW>H&v*YJcTD`7QBtuaSrL*A>CcM?jaqjaZg3E~9sKCnt@5;% z2#%UOC~{$yxDpJdgGB;#HAoi|UUhV%$am6V3isRv$k z@`i4mmwf$pm7tchFI#rF{i5V|OCje3jfNx0j|c2TV&Ukchmc*n?mScXZ6W%I`#w!o zh>Yt&x+e}DMaK^OgR|YL9v_nK@~GuCW_H@EX7?M{AF}>2E_KM5=0q`^}~VetCcVKt^la%DcSw)5c<}cX zzY4mQm(O~0cfjlI>zQK?PzkE^moPXuB!4r|bIkSaJ03Sp1PAj;WMC*zVR?vFWS9r2 zn5(gQnMwE`I5<5|}gzVUP#?V@CibGjrmT3=&18C$;!xc^C%hyn|)%by7G}O}}vV z_4evg}5iCpz+)SAXdGN%?;Q|sn~wwg^) zmLToVH7}QZ`|Y;wK6I#gOo&&oco@Np7@ujESW+E7*(HASzwkwc+@^2u^}2O;t7~U@ zu$)(QH+4MBzjj@qd$Nkfhb#3tad9?RvP==kHsf*a9i_GuE~cdnDgDA5WqzAvs{J z+l&b`hc;Yyhctw5I>1!_?k=u;^dN1ck=>u8rc`%^L zoI?$SmN0Wy;(5Z7>G}?#7s}nrR*}4hVZzMjZdgXJjCtOU zlmCE52fy2-?fO-+fsfOoZ{rT&-sNa->j#MIsLfVCHB?%mGD$Q6>2(Wf@Kp2iZF z6GD(B%7;o$^K=gZ#(6*mkk=l(-G%vncV-e{CGce z3=+-P1Kv+8F?AnoH`EOW)Q?Ctq^C^<41?$)jGOW|#nihT!)_>!an*@}lm=)b{ei8$ zeTrcM+HwMVc@(Ju5{d>pt8&wxK6&!OXU^OMXA9>dp+{AVz~KV96)==2%moj7O%Ab~ zK+r2onMxY&zS!Fz5*XNaU&CkQL*2&QMjLHgG$JbuJDsg#*a7sXY~jmv=-}J#N%b+U zE#^$)j!!0hlP4ZN@3mc`CEhK(Xu7k&UtznlF!%nwE8J|fYfP?w^~*wU&Fm&okDQGi zpRP|^XDXj7jZ9BcvaJcsIL)iS!%P-UGEZV6^U5OqrPT^MX=K?42%mnl3S-G| z#Nwa7nF7d;uHgEQ^`u_~&CUR0!3z;g%W_pQq3;xmK85XkQ@<=bJ9{>8v-0_Z=QZ_? zb+PKof~W%vZNF~36|6ZeJndO+#y{@{%Fqfm7JN_M=T1(ypIs8=xh1lDTh*O6RpWw@ ze1eg^FCd$f9O_6kS z4WSI^5YQWV`SNY_h8=Cn6!Um{jwcPnIhf+4Lq2~Am!4UE~Fj5n>NAM5m*^jR=UQZ<-)Q`rEHzrL5fIEf98(` zkmwWjHZ#Q$D<4yu)zqpj81IorAzQl97Co5JL!^-c)n?U^fdHV)H)~-t-uAH}P!>t3 z43}%Jnxs!4O}whGf^FlcQIM?ZpDcmWAwnAMrp&ZeDB_Y-I8z*X4b#Y9#v~^iIX;rM ztA;WgH|~XpK7W*B4SEzcQ14*t3LC4>2M%jk{-W#m?WpWFr8Qv^l`!`|so24{YjlLU zr!1`13U!LKmQ2wPR8PX6C*PT&n85?h&w#hNUhz?TnVah*!;?r2 zrNb+6>uN?uLpPV?yd9VbkqiKbZ-x#cqYtskBvQanuIMPhk{xGa5zj}ClF%{s?a=AZt z)Xu?XhqTYBQQxmI)orWiA{_|R@CTQN@I_N^0Gge1$Ied^+n`)}ke=l;SYHX~kkX z>Wo=#Evg5b5&ow&-PyMg0rfN3IxXO!%&Vr{rE5#4-Jx7Y<9?XpxK_Fa5)XzlO?lMR zH2QrH2d>nP>+8W$C*#ubZ3$>*q@Y1lhM)t~=-P78*RtC= z*K2CjloYg4%-Q0|7$n9DGPTgBZ8RyA6eQ3(f9*{W$`+(#2K|kj^8Q>i0;OR)G15L3 zd$I$)+b_UKTBtvOozMw`By2xbWelBy96X2XH*cC}MdR{Fc#-|bAKwn+1hvW07^>EH z?^eFQvE4STXt$vj2?oNS3Z_v{IKVbZ&U&YP=!#$mksMfPkvIv)P=9yhsnRtlyWd1w zNeU6G5|^Nz&DA1jOMrmR3GLMo#6e9lM)#A#i8CgN8eY0VFrcE3%wgb<8SdD59E_B^aD|^eBPUCCdUjR384viQ8S@kzG^oOiRq4IX6NGS3EjGw6fD4-V8R5m5v-jn zhP7o|4q54gxHk!zZ3F%gChxHORHH%B2+2&LR4H3$z`yb*6y^`X8^h`J+D(EXLb_vt zBOQ?8#-P(XNOrQ9GH;{Tfdq$xCg|;>`;8B6^v>_9JD70 z=6@3ekec#J>Mh~+$OraGgq}CIhDrJi7&|F127DL^#PjkOo3)=KCz>~K(MU4beo4L?_`D1*01K^*j-=qM)A=;999=Il&`+~=HmyM zWSi{P;PZ}8hll!Sb~iIex&~Z`f= z*_i)Bt%7EmMAS?v9tY3IaKk=*#Ppq6>7!N zL(q^hgSzrDrIrxDk3zjFaB2SXNphBGoxHq6j2bd{}&ySL)z=+V!3D>myWf%#vpk#4l+)|&G zw{O#69`;z`h`P7mJ}Xf7k3-zWclk1JIfv%fLCfp4m#adTVy*hGR9pFI-cNM$VCUK0 z8flY+z~b8ca^98m^E=*bS(_;*yl6u6$^x4(F1_8IJCt$~Q!QDok%}=c6CV$#zcqMW;WbQ2VaHtB`VGVn;(}lEVBAe{6ti^+=OPQU}h*dtPLZ2~)@| zS+Kbz&q$$~&5)gmKaNdT-bm9H^>9eL@(Ky5!lh{d!V*ww%OM605rAL<{&*D+b}`ZH zXj}(`pq9&o{6B16XFycf)*Ur!EJzYHDu~1e(v>P8ph+x?>%Rqz1LoA?JXlYefx-^Q0l3-;NTLw zZNxy}IvL#k>P+Bm_XC<1-n-WC5cr3rLyp8|=G<+RT*eSO#F$9Vb*`(c`@L-(B+EUG z#2^(-3z=D;sC^PnhA^*mf+b+9@ zbUvrij=kDkm3xlpMPH^7EceAl4*j$i`7!87;Y-}&~S%@^d= z7!g9uVJw1-c0e5m3gKyF8)eniS=Xyy+kkCIfG|SJMB?=ssu^A_%!<(>`2-WDM`Je2 zXy7Bc?5^9)Sbr)>06>X<89bUkT0KO2!wVCBAD)=FgMRL%&rE6ib?rR`Wq$pGM*$RC zKuZMXAZ^yw68kDA>J{aUP%A_3cqBax3kfY~T&cSMa1$)qN#?MCe&vc1Iw#)5r4%Je z`OKm$T4TgO){9k28?7~xc410QED$jcp!e|eIWHq4;NoQn01yP%yCDZrh+@a;z-2TZCC}MJBk3b3t4$@C zaCNrn1^q?^Q$4@ZeI5Pa9={SIDj<}|c6$zXubxIP6JmpoztiTOv6J`#pH0?Q@9 zhxPC-1&>LF5Nu6_gHs|`rSYQ}HkyJ`ZV>1hvB!j96r#?!OjZus|lCDisYD}(5n>iO`lhz!>Z`$ve?U33?aoERBmmYfTLXa3})Uaqs z%4#1NJW>)?sm~=8o&e6-bL2WCRJyRNkNz1wPU6xF3%zCe3{;2%M2v&<#`RIfq~y~3 zxnv|qOR2kj{#+>7n%~MT8M;;vQq?-r1mhaYmQ5@^n`@`EMqIff!dJd5v7)N&Z)4+Q zqsutxL{9bZ|75;_b1*{qHi?K-HTR_R`p}sq(~7nvG3-5l5fAde6k;XqzlSFd_wD*2 z!?~zAEV^>KEy{yGS%(&p0H)$R(<&vd*=wYS-`XvFS_0w7fT1#ah815IhMVs=An zhGuXWyZi9rtkr>P0VdNKaG{{jk>~q|u4 zr*IBKeAVog`R(<+onw2Jox&XV<@Y&P&tA{|O5U7t8;tth(U4 zd-3~~E!c$m*_H3u@K{`YVM9A$)aa$~>a?}7-dch}<$c3Y^yOPga-(4dxP#+mjXi`U zPH+PzmXC}|`eB$IAtxL>9RCS@c0!`t$oY5D+9^~!dyY%z(TtmsTtSS8^!_e|hBpeu zgUKh>uB|B5(pHXh@2Odko3v^)+}{>($aTio#@M-O@)+IlN&C)*D_=gHRRjSY2D|3~ zM$a{jzkdBAq4pxaO4yt8?=fK{+NaM@9oP-O{2KY^if#w3_G6dAji;jX zA1!=t^Bra1mAH#`$;lxpebKuAKPnuqDN0I~hy7p5i@Cp>*9@pSUvgUE%A>>4f0-kC zlk;3g^ONB1VcXU3o@oye=%q_NeNRQi{*RCdzgT4S);s$332W=d{v+!>gYZj=@tcbJ z|M-8}6$A4p_E$5(p@y-tIk_>CB+N3zL zZ;l-PbF=^XOZc;(Ye<_zsxCxRcH_B+Zd?t9SLGxf0^X_78U?}Gvb=64K+fkHNon6`J zhg-`0eC&BTN{J?e)>zLa3Rfb8rpXuOefBT6$q_$L`>9uWwQ-cU!B|&Ya&DU{JEi4r zRF;^`nnEMWwiNCLQy!rK9wF8v>%V%UydQ6L<*&U--uBDOqi=Zia`QN!we=fYei2re zvq}uK>e3IY6XPh(x@VIG*K{nr@%x>`IggUHEPQ`w%YVE<(Y0WM;P5o_U6aA=R>kiLjI+i}(NFvi$KoV~MX_IL!R!9Rn$vZl_hU*hWzg-j!1KATj9Xql%8RQ1o6tsO&#Cu<-Dbw%DdW>-`GP| z_0Rv`3a+T`0b6hY*VSx6hnOAj-u9H|2W@KXsgl&yGRH5RRCw_(d(Br@+$ZWDdzpWv z3Ui#?#<<~p1G^ErX^&%U?biHhs^@0SOwc;@NLM?d8Cc6j{2arKF4PUmWJ z&MBtAL&|2?&9&LcYA?EW;r|B$wNF;b>2thz3gqzMP`)F`$GW8RNwQX#Im%T>%joCo z4}48`-Sd0v?fNx?CPl5Q&It$a_~wdv623r@`@gKD7jLSfxV*ge<6D|qU5>E+_&VzQ zEGke=0ef%l%w)x)!wf;0~P7r2j*YGc>nuS@Nb>5nS95j4E8bbw!vt;lD4f{g*g789nO1nKvjn ztzTB5q`9~Et3w?8jeo^J+kg9z(a&twlj}WY^1}o~*vHbI4$hBFN#)TcmvHWwH?EOThmA z-}Wb!!9rSRIs7^oKYK?T>-kD^e)e4#nI6APPO6Tfukl74DMvg}2?0#?g{%}No1jDx za(yKDBEw+>I)$3#9nUn(ZU!*~$g*5JdK_4f6ZNZDGE;OEDKMIq`?Xe`8m; z9*``37apfy3&|1vBo-LVXsL_^(`XR>*i@L~hoT@S{J_OzY+B!Sn8i465jjdsy&Wg@ zwX!W=)#)|a!taL62MXgY=GCDef%NzM;~y`6zKRAhYh|T+#>*Y*m8~Hj37Vl4%_m&T z`3H<~n!>-nbNpB8;5zPAA|kcZW+4Ofb)r$#$; zP|Ee$>IS<>-j0bJ2W^^E-;> zdziz^2mJFo@%K*kvm$}Pe8)A7k9}wjIcfBB&j_1Ip$RL&2^2diTq2eU))FkJ9;&vC1RI1*%@v=<_;PFFfvf9-AGWNNQ zo%(+_!9`l`cKVF6wbgp%N7NGsv}Qwg>@}8?i%9%2GP?6<+|laRygf!=cA_5s=(zy8 zE&yA0(hLR2t%UBo62yO`5df{(xQ*jJ0s9fn;$9tTv^s1Qh5o)U`rov>Ti5ibNuAr+ z=*uHNY^Tb$(rCn2V(ZV@a4h;nk>Hv&3Q3u@HLMkt!PakDUGOVMb|Ew^sX?;q)-VL? z`m^ZVRo3Y_vOpIB7;ty8QA=hLNFbvzcmL<3P9$clQ7zRjPkX0Z8#P%m1ntkD{e|9E*= zz0&uwbLUNRIVBdLGUH-)_T2CpUkS!eUbB(M!WECKssjTA*xT|n@jFLE$OUZmiccmM zC|BWfsC4km*gf`tydC~}aa&^8A=gE!<(B?c{8FdXoYCf!Ib<#rnd4?z3BVB3o;&~l zbMAg`-`i(eTa6$fawl=5c_GBcWB~8rp%b}g_sJY0uq<{!OBir(PuMm5k1Ii_w>W&}-@HpZM!iuEa!= zQep>Z2Fq1*xgw398!XM1dt?;cGKDhmLq!&dz7d+BGQNkj#3H-*HnTaIozbd9cNZ<9 zNlaD<022GC{FcmqKsoLd@hmj~Ld!6RkH3GXi;n+$bn)6W=|4{YRPIZf+$=3P@!Q>f z55%J|8v7onRJf1zn>@8gYzafv1Zvkm?tT%CICOwR#d~aq^ym5cYb$pK z_JP8ihTgkN!#EIX(m>w#oNgvY|F9VG+_PoXf_yr(x6%9DkMgm0nxT$xlS3v)6qiLQ z>&baO_8aIad)|Py9fN8zCyoiRi438I33L~K&)1-l8ybFgX9YiXaUCI z*8m~WglL+PV3qpBZ=@8xL|wi-VqeI0tP%KZc;PE0z!=jYln%D!(bzGt_Ca(lisd22+GIVw>OCsb@pY#Lrq9M{2c-6`%iHs%9^8P?b;O>K zPr&|VO5Ovw8G`|^mQIWkwGF|nq0U2ldFRfZ9A8}jNoy3d?Gn)UcA#FMoD{`Uc#f}$ zX7$qS2jGx0n#?eYC$n-0F$n+}x-Ur|J}4}`Mux;rdg&OMa^#pWdb&`3<>VZgBtkO+ zY2mZR6Fz}NQ@GeRO7a8ZZKsS=?~hmP&hO846z)%2_4Ex_o^i=4JSg;;cfE2p|F=Rv zL=1_p(fLOGZuLREI(lwQLp~bO3h${0m@>gYn_IA9Gspv1^D>0~#2>q1W44S!j+GvK zLbTEGtph``9;3=6TNx;0sP9Vt@O~s?fo zSDyOB)fTe)RSgNUcT9RljdAvNuXT~7C%n>M65cr>u`G%&7w!(AbsKNgmic6b@Jn^`zB!v=&k=aqW(Pzj^R`Lvq`GfP! z(725{(2-+$WjoNfN&e4=@Rcd{^4UW40J;iI(Blv=OCdjr6NcxQFkmCdK7;<@@N~h> z;ih1p{$!B*pndH8t{x4;(;P?YGpwJ`pTjQto(FBq!Un9KVxgX^3n_cZs)Bki4kA%9 z9Fa)EF|wPUHZXAe;h~BoQx%@ou7Y7FUHyB%m+kx7(!t`D3`p=sPkX|Ka51 zOl1~HTXP&EaNuC>5Z?Fwn?2d5na!Q9QlU1H~W}Hc23x205L$oI=yQm*OUW2Na16P32_C(T0`cB|MnxILK*lX!Him*4p=stIo zkhw^^j!+dUkp>>|BtN=GK;L)wJ*e#=NN-i}ytK{|3_Hv;y3oc4o)M;H0PD}URR-9l zOF(HMn5HSt5?V3+b#hO)-gyqzC*dLwkg4`;Dgtt)%B1a@ca0@ZpDPa4d)-QJJ*n3V zPp&)aVWkV?99%geO`j)EKF1g@;kMS{0?FLuT-M)a&k$OR#(=Dh4A-~=R9;xyX7ei# zFa%XosFaJJe?oONJTx>3V4l5y4-H#=cwco{nU%E=+zw@F!{9|?wW!2Mz*vIt63AG| z%W3*v=y^pV!pByxcKgVKzPFJa5x9LkiacX^2ytRdlYNWahnhlL7t-Lp8D6O3kbgB4 zi1CL|J7+A=goua;C6QQ5Wps_&)Uc^}=B*0=+ny)+`yX;y>+&gGRZTdtg1S>E=I`S( znXn3zm{FDj^EDLTp{x!?cgI#{x6$>$#aUBCa4&{Dag>$QL-&=*aM&=^0yj7AQoR;N6d?tYX}~$fO(k!5B0^$r{GMbEUf#@> zpVwNCpC}GLZXETp$yBeP7p!kG2niz!AWHI5fMAP^*n^o4VcN*`oRg8MLo193p%d)P z0^Ecci_YeJTJ#Z_>`SRMMx(VhMAUld&1mkZWY&p7Y%e(8J#2Fz_dG5VUJ1n1McAU< zMR^EvYC^yQHQ02aK<`rR7ymP7(Jc z`iLvIjDR3dEa-?rkMwNO6MBxc3X=_t;lX2zXd>(Ixj(kGr zmA(;{ap>Cn;WL&#$F+_UaUG@zWOf-oD+WdHk04Xo4&)&{Gs4jF3ngDsc9T;C&c8a> z5^>CuF-95#b2w(U#%^VYBsO!F&}&76;cHhug9Y~G$M z>@?0ZVguQheMvX52`*P#KVi{jnvN1JAy(_*H$?6W!B|uKpBF)~^iEP!wyM1#nxOdrRoLSyibgTb%CPJ8t=lH%prRskDwo}v^A^J}$gJzn zh+@j9hC4=J&y`3fsS^uBmgIc2WI=Hr_Q`tAf7KI3+k$0}?Xr(A z?XUK=vTDoHIMz0M5jl0iDjK=QA~V>KT;jnZk$=@ut(Irmx|L8lz3vhnOnrXcdGPBJv<(oSg-ADysehT6LTc#4aFy6gNugS z9b1N?HK`n_o%i+T@m`(GiG$nLQTUEI&zKfFpq8|SO;~Om(<(oh;~-SZUj`Gdi;7rF zl#u4}Wwyi)1Z5d_2Ro>I5Q(X>FmBzd1mSGYqWE_xeJn5App1#z9$lV`voH5pn8BQn zhX=*;hQ0PAx>_|zUY={1=bUzQoEf!pMy^4&DWUGQsRT=9yUeFzZf*pK8J|I!fu*q$ zA{2O{Wa=5{6_^`!32nH$US75it`wDt%u#uj>7Z0IV{w<8#M}AO zwtx2>cS;YK=c@RE=-KGG+=0~qKR>5dlJHPV}1&WDB52 zl#_w;XywbInz(rC)GvyCw{P7dqgV;Knv8seCg3^xzBsi~vyH1UD6JluK)P`QCo)3lX0&EH{i_EcZhI zoXDCK2+0Ff4N@Ku_Hfs9_h&Zlu(_4%!rB&32qOcQR|>zs#5y8u4)etv1H^q?KnC+D z+`}|h?!zO}(4KRG3_gWpMa2YD$YYTAkzMGpEDlfBfiU6LzQ#iV+z;E|MSdIe?{LNz z>UcW{K>Lc2wnY&aizd74tbPCWc$?CdzR3$azl*ENYUNu$9(caUXphLbTyJjawwN0{ zaT2TB=C^2DL&`dB|IUfA)_%N8l=VvP+^Gk1o3@`qO{Ex=>P~$G!&@Bh>?(% z2+0=i0Exg1E)l*G-E8SXLmM=v+V0D?WEw6uAGh)YP?tcSJWC!C9`hk-C=!YL7@l4X zITgUIxgk1=FIE4dtHJ)@N)yrpX!xHiG;m9!G$O;bhTkw^5Fh%vnzk+gi-ROxslCa4|C>m)5pnk^}-M;0PZWIa0Ly(kE81%5i=d zPZ5tmBuwVX&8~#RhRJ@p;|MeaNg$`z^;Og}Mibqow@q*Z6EN4a&3n1c2vN*V7evsk zZrOkiRP#=QNm-hbL=S{i;dU|m$Wh-6N3#!R6m8_EVDdl1iu8*oy$<@z!zwQO z+~t|yd=(~~kNU^gh4tzbDYu3B+PSms+!Yiq-glqgPU=*AvYxTX0-f#3P;pqq5!MZo zuh|{lZ}&NU-tWn3vx-uzl|WEc#IORSn<2|KGTrp`k6YYM@%7_BC}E8@WLfB-H0XFC zT6ga1)u&_~0L_R4o0p`|Ik#4R#OfeEDd)!?(>D4pmFaJ zKHg#~j2K?(ogXV3-1}nQ9)v=oh&jBNTSpcbveevh?0WUoQ8-U=mzu~!JppW@dujmz zt2zIeN2UJaD8s%#ZzH8MDuvxCW?t2Mz;33Zz=QAJ;E}d5Z=syDx};Ll6$w8@&e#kX z_YgsnrB{tF_i;Y#cA~H73IZ23n;<$NG)!D3${x!~h`mw&iz&`ZxGtm*FpD8$A^~hAWM_Ziab6ghp4I?A zO%deXX_#gD&gZ}kop7It=^Yd-K}t_&aafSich|CsR41m8%^gu)2t=e}A+U{e+g)e1 z9$t7L+ya-!=x5IkmrO<07FjvUc@M{`LyJDA@@Mn(!j0E_x!b+79O zSFE@Z4wQqtB<4DAZlk#%b&44#>1YBDgaw>4vgPXD#FdRWI66^9?bpHpC;}FIrG@>x zYFJ!kjxj8jvd!dm@(bJu06`25eEt3PjoZl}GKftVFkM!*a*%=Kbzoo8EWH91Jup~| z3^gy;PixYuOVN=6{Gx^-7%{_x(r3I9iR=bK(thWC$1RJ7eGUOmD%7w17b^^SIy@=p#wV(avI;Ouo<+JrtGXu8-A zfTM^HO{7zF{Mi~NeH;f4yq4WLUkK3$^Bd@#Y|#c1QN~Dy$=i&q$wV?P6z)0`$l*+6 zFVK<_VHL;x-X@qWF3b#T^s-eF@h6kuIS3*Jwtf`a0)`#3N-z>KU9WrcRAF4P*Q zo-V||~=178^%t2y<{tO0UcF1igZHd{N>a#ijo_U0_F zasP(tuuzWn!1%^~e-2eCW9pn6H@$1nqfG}cxVS+r0+{m$=^Mnn#C9LWg0vdA73FI{>} z-Ud9ZV~GGGMDsRCKUB zI-mbAs|jBlrI(&ady9)y@X62Oun1eL&`UgVmC7`O`0OxhS!`lTz857=e8&+@+qVz2~d@7o1N?#91H+BM68krD)zj!&?e@< z_#nmAm1Txly7dBakVHwu9b7q+@ByO=BM9CYr*A=`^=V@757DR0{a8${;o#_3bzh}> z6;GoP3umXS+!&leM8Tz$6y)BvX9*?8(fa{0MvZ$wsaHg#OBP#!ddmnzKf7vYlpX|h zQ5bGQ<1U~YrX@i@jm_-W&O=ozqx@GCKAB@>7p^qaDjP0KbBU-ozGE=6q0HyVE@ltw zYMmU>laIy?PGEC(7NX11X^%{r5X6gxF02ZL3vBNQ2|c$F<8VX;a&CZT8*NOf0$vS+ zDwg)IKly8z*TBoE0lPBRS_FV5p_G%!?{FtO4`?MVcP4ywDfad@mUtqR3)S%^(lRXg z8uJrCjUYnG0UZ8Wp}oTx{(HoGW_7V}RS{?ynJEv1)R!YR)@8mYK$RsI!^fwg4-k_$ zO~no%>1DBPft%}cEv8vd4QF*QC6ke=#2AnGj>Ux_sc%36HVylsLHu4L4p{e{?pXNe zwNkQ(sVurdn~L8o7p_dF5UrGqBe5?*S~(uyHx>ZdV+JY%GPx$YwcrY>jN3O7m^_@P z2ci+|v}|3lCG4u>;I)Jq?t6-R9k>o1I)tpN9h(Lq;m*AkDF^9O{XZ*=Z82LmrgNk95LbnrP6925NAxy`r_U4Zf_9;A1L`r)Tcd z?=TvUhOzdZCU(P|ZOmrXu!q1{Pg9Y7NQNN~lO-N|GL?aa^?-Ss z6&1*#W_*L{ZXwEBGTS+GhefUbFEz3$NJIu_dUZ;(H;IXes6ww}qx*M5Tk_q&hR!>? zgCA@!_>&93k-Fe_Hc43FwN~x(p4zeX3SWm0uWLP!x?_~bAp97e&oj4`gdIPedmyDk zDQA||7W3rEZV_cAw-DG;cad^aLea9QnM_tXtXR4(n<8~b36jnX zc%hznS>hN_=n05|A2X4d!Y<4>&U)@H#ugtB`C%C*;YZ*ob~X9SS^e%smmoT1Ub39*?R#E*MagEi&>GQoKT*wS|ep%f8O zRxB9mDD3D80_LAhmfiVS_y^n`uN9;`WR+^a+FC(lgEIoTIhYAOl#Ic&ckAY@ke)!- zm^)6Il}b8}ijbbrDA`RRZN8!*L zoYSLkj91>)OkSz~nGm(UyaJ`x9OqY|j`P(%vX74V#@c$_5tc8!snf3rQLI9c4j`d7 zVV*aBhFm=yTWgN)+rGW{t1G(~KR&FD8xBi;opj*t=EEABexXR8%DXVB4wlZkmEL~N zi<^;m@ZV>Za%+ut!8un07n|WXpD+ppAVq+c*g>>9`0}T`Ve#_Icb|}s*P*2oYW$5r z&^u0PzyVy!UOgqa2Rm3;%%siTvkTmWVGlwAq@}z-p+Ah`uTy>#>f5cKMha>k*9hvDT5tDY zkzhos@z3?5U7_z&t0IH;3i#=lUadaRu^eCa&6Wc@GDT8*|Bvy_YH0ax-o)ixNvYVb ze0M|V9|ydEm<(mk3u}7-hq$n&02)W@H}EgDZYELv>WTgPU&;Cv8H6_TvdoO03F-KF zYj>yCHC-?FSK1dZMj#q-9r{mB?#BX{+}|EYjjQ$QRig`gHWX;2(fA?sGEsKMG6|Yx zdXFfKNuef;j!!vZh~e`afOV+5k$aU1Ti4<_m{VgCfL?&HO*dRT#?*YG#EF=R^xc3X z{63B*1Ey&!^W}}bR(=WV=ZDDD{jaVdYafL7{IO^ii(VOqA~e#8+?hFHJ{%P#7sPPr z-X4C#BJuFgl|*qHtuXJOd|BHy-P>&hiA33Pe8k8t(T@pT9^nOgsVjpn4d z&Js&h!mcg>X=!n=(b2ytrM@P+9-Nyr7fM0Ndrc!KV2g+IR~xj9*4nNAQpgFBxV!#O z)=)oCeR8nJ+${^hxht+&hYXd(-IM)zkfNHOOxKN}c1r*XmOG9`F0Q3&G(FPRVs47h zC*$Cr90ZXEkXbr&_%YqvT?}evo*rDipRzY4PMu5m*XfYye2us3JmcWiV z1YIwlW3g}TQVL7`+?W*n>#x6_zfYtEQBlYJVzH_1bjbt|lBdQmEU6C(M+yXM~8OyLzI%eGsZzM6gHAoj?Y8pQ#a z)wJctogN>5Aho0G`BMo_&iH!UoB@De#I}JMF7f#-#vIb9bFQ{F1^?A~pv?LCv_ySU zE!0tF+xaZIY`UUyQ<228_}t8uPO<(Trd7v!Uws=Nf5`(ZO@^|BpfJYS^T{Wfvecfa zp0@Q9z_%KtY$GwoWe?GVAgaRK3~Rloz|rIcaY$Bq4dtR3uny!tw{MI2nS464Sa{{( z-Mb2D`jsKc3F%*eU0sm^ObLmd*e$!wkKQc>TyAfCSKsmK^jC7YFDNDScaNe`DPx=S z3?MLRZ|TkFOXJot1jkKIOxSd|&KhBy7Es;vTyvCuBr?bsWOhKnulyG0G#M4++1CpL zg*U~;#WGp}3FnQkuN;<_hu^E_aVNS}7(F~J)joJwS-ppuZ@zQUj&kU9gXMC_>%7$y zR?!0D(e;c`O(N&RA3WY1%1jr)bP$etxIJ13%kXDG>_owXeUTG)U~wCZSQN0p;=Iz_uB*$cY zbvsN-VzK6Y3s7y)Qfvav==vC0W+Eem8+i>77p?fZ4mHtV>cW%xux*iWl$z(^CZR*Y zqij}1^6}{T{8F^JwibF4nK)8WyHCK48c~!O+E1iqamB6q&{UX!)++z~+_W{>Q7NAS zY>x}nd^nFiK));ahi~WH!`{C8(?g3tQp$d)E!k9bCbPn?Anb~^B>t~M=oR^0xP%PY zZ+J3@V=R?NaQt{8uyjHc1e>#lkVuGgx3?>i%_39`!n$J{4W{w!FGK+kS#&*rC1aIb zI*9uPK@Pv>By4{~wN%x2%L++CjiV@vBxMQ)F{EVNMoUI38g+>xngaw6KvD7>@=v1A zM4zV1rmY|u*}Z?yOzhww3d!4*9wUZTX1En_pg&kXJH7#5tA-Snq{+t{P6(5(cn)&% zr)JL_maQ_w>7>}_RQJ`D$PJzNz7Bb(T57DjDhdg0?aRw8I$KT5&)BU!D5)kh-CqL#=h31nAq7$*mU-Eqwjo9G z6CDM3IsMRm=_mK)K^^6b7dtIoG5#wI!gc=9Eff#&5Da!YirKZvombvU{fO>J{n4;5 z17ZV=(|(O)tJMjD-8BKIfo_Oq6g+=^ZjhEjLra<@8eHhzBHzCRe-I?GjHK8lFpF8g zb_(kFFSiNYn%m=OcLXUvI6FJWCNDAV3y?eoyE?WSb!rZg%AY=aRzoc?gY=m{R^AH% z;aN%P`fhuJx};0%Uij6$4ej~dQHqoxHxB9MA1}TeD-ph{={PQ_wTQf)x(ao+j~y`SiyLyf3Yw5%(Ic*FY=VdPZIcv40I zcTI26ITu}G6*8M(pYzZ$A`M%&Ve3UWr4xxQ^rvEe;LKelc^qoU2;?I2ctg2RRiqc> z?&B=ho5xqQWIkJY2TS1wXEi(Sk8#G-4G}w-^REJQ z>^qeUtNFbf;-0Ox+c1wgUjpknFtcna1ov@lGq$UnA(k5ksD#CdV#EvR>x?-r?dXVb zn^D5(yjpJV3xw;ex43v0yVDhHD{`b9(wcv7i zBgV8`2t1l=-6sbdH$^fm0@F|835g8A$_sh&sMiP`bh+|dTBf>eM}wpsD`P1!Da^9fQw-OB#2 zHOODm>auh2Tvoo3xg2F=r*iR92=buQ0ntC)p25AFVADwOKDH92=-|4@p#mY2 zZj_%mr=)TGibVTkWe)@zgw+tk7t$1hosxNAjFBIR6y;Wnb<=(U0S3G6&;F$6Xi5nq z4nLso1%Z4=hQ!>yo2Xh_Edg-TdcozaY{JNbv(eO~2A&OE8M^$%?*B8p(-7SQodCx& zJBQSw`&)Z=^Y(oiEiyL^&eaH2mTxLrz7{0C^I6odrf*HO9$WkOcjDUJh|o-u3r2+K z^9cOGyZS*IzNC=BazLIaCZyp^U7N+l&FOo7;Nj*+zut5R>`g1{${1pV`gp`r7Uyti z87v!nQvE+QkRlI|9I+oDvuF^lBYk&RkEprelq4Q4#1D(uR2`9&Z1>Gu`A>Lq3cB>g z4(IMn+eh2J-Phg?OSDEzlo+jVCc%&igTG34=A4!GN&^~Uzu;oPM#;Td^HnFT#!|Aw z{-Mn1sp>h=zbFztT~}e$yXAM^c;TgvRnChI7a|}hYzjB>paF%wy zkax=CP)`V5)mX$>qrSEXliP&KkG5lC1xaBgN_?#e>jwB#nEQ%jcv#~`M&>aQdDTw4 zfYj9Urf!?JZsiWxzG;m-XosIL%DiwWtw zkyw0ibTW@-&8YsaBGEP_*ZMQ4ssL*XTVWWNT*B;^aXR;zpc!Xh+Z>?KKMH{>S^(tYBMr2 z<`-y%VE`s`Sh!3=1GJqu;NoP6(GP*Js?rCsXOEDvQu|{2tZ=j1!n=bHqY4V#yatnu zDDBsMWP>zeoGN!Ot+5eRb{K+#FtuG>lKW|#`}fRd>6gk}4@l4-)cerZ<y4XVP%xLM32`sIvYdp#26rL39#w$Qxz7?iAQ@J3&nJ!O1Br4P2U{>Fc}@0iLie(Qb(aAGcT&MD@a9sTm5G2M zd}hh6#vcK;U*^pnN?rQ6tMDCQ6sA^1b@f0PI2j;>Ht7XuwP!TGuWzjsZs7)X-uMOs z{3VTi1`&SEZ!|U=8!uSYin3Ao)LulCGCng-e*9(GN64sW9B}MR{b()n;pNq>T&>6{}bO0Wh2Dfr)eKCj1ckKwzJ=L!>yGHDN<0qfW8R=e0?+W(=j*~jt_Mr=f(wE1> zbQy{$ls4}TS3LGz`_G+k_Z++SGjX^WP@qI8&No%NH4cR}3Q{amOWDBFFq!&E3P4ZJ z_Xf6S(fF-6_I9t2?gLRava1cG7Mlq6DBErg^B`l&%BpQ_9}R+%C*WAuH#7)k!*udt zmNNsm?rOQ=mpE~6%1>=%@dYtHr$z$f=B}C-F3$`VuC90qTSy{t%0a?r{hx2ormM!8 zJi*qLoO$_B4-Ykono>|8xl7aX6gVHD07YW+^73B2X$rM#j#JLjFnxI%>r#K`m~=&@ zVf-2gboEAeu-4YM9_j{`mv{4zT<$YPV3bSJ`dzPd_`pZ&U#gN+JFfdkv^y;&oOSc# zc24RMl@X#Z&Yoyso0JG8Sb_Po1;=}5u_b55%-dk(R1>mLW-Y)fXFLV(*{&aT?pWkU zE<1!tMY1E<#VumbpH-!ZOB9loh#r^_RTB0RiRg4_nS4%WC<3vi0#z#@4)k`oPbcUsbHZ!%D(0vKVI3#FY;WGs$sqh8 zqV)F$)C)=pCZ>_np5HXUCj|jN#OBUaw?{#i2BH)Efx` z8UuLprm2C>W(8q0?_29fVpjHi5z5(cB&ZykZ0;()owaasJn$r~0XH-{B~u;{lrIbz z@Zir<$6jxl#Aza!6ANkpIR-C>x)!b3D464hNRcU)Cf;J4kYv^Q%SPcG1N0MFlw|v8 zpQ(Ux$!mZfYvOL8z^Y z4{oQc9h%chYDuf+;Hw25zj5v6YVt#75nl3y$#}=Tn59EbI<&Dv(dxa9=~$I8NDBcj z#|di7l=y6YeSP;mou!XV1jMQanA0(^5EP`Ot)bD9tmqMr5n%N+ng~@Ae&TlGxk5q4 z^b?XFR?XWIi4p*p%~I*i9jBpesy{k#z2)~3{k2*e?gXF&d67byI*F!D`RY>js$lM@ zjLt&sWg%`@`y506-YZ!?kpJ*QiNCYGzm32Zg zD4Sd;QJUim(LyNk!K#^#VS4_hwxfoqGwukV?_yS~z$Lrjsm^l}kU5vR|4L>ueZdK&u{ zo%8ywK_@24-6dBvI|pC-xq5Hvkj-2@cO&rR?0ffomG+CPD%)Y6({`7>L*Ak#voRH{ z(%xxW@T%VIY{6{4lB#OTv^smJje^f0ZWk*Y27NQCM$LnQ$HWcaM{J9aGWpC~or3SZ z*Y3kr*%9@YGfOcc)>WeFsn?~ua-t_HE!+f1iy^pmvSW3*gKWE?RspxAITXv1UdhBo zYpizyZmvCK{V~x%_@rst)SOPLYOyS4u!hN%FmTK59vc~$d?jW+MAl5_j!;dKtTdj* zt?DObX`ASbnX!^2%4bm4)$q$2I2k)to8EnQ+54XT1vhI4t53UD=GB<>cCNZ8&B)$< zC}%fsGg0E{-6qGKX&2#aIQ&)TA@zmx#t^OWRdUZia|KpO}E`6r`k`7Nuv z%LCEgC&HnQxJ&v7%(5e*AMYHT0CzE?KV;-tPJdvqS*H3%IWD) z`NgERL)WdP&W%z>xKrwRsh^*bdn7wDUtu8WQzs{$bQ)|Tdu^XVuy3ls5w7{T5H#5~ z>Lvnc(vg;dCi2qfvr^{~ts6NfZ?Z03i8L`0Uvu1u`uj9Ks2U8vMzLHDuxQL|%&;7X zt@KTnd-&XqY|QTQWWM`e!?fl`2|XTA(iZW z52LG;x6S^Ujgy2JEP!larHAJI7uK^p?UtAJ)9Y5B6!R%VecjvZ|`80rDc# zSutu*^2(A^%adcesQ{vca{7D~<&0{&M|$fU8+)ZNLop4cD`5lM4dgwn!EF)F=>r~9 ziEOOnV+GhB5~w~*ZSwJ1C6)iFBrETxq8sv)59A0p32jlcUIINMtv@C>+16Z zlG%O^Lna@K)i9QpOT|rV6YO&QlMAq*+5vCJV9jt*YyEAa-H*N(8W-sSeo%#ue`C!3 zs*gBi%QmrxJX%;-I5Ud|tt7sXJV?cj@k3aP>^(hRt7SyIQHef8dwj)hO~)QTN1Tl9 zwn-?B3_@<43AXZNFqu<))WW|k;yAeOfN-m2@fljnU`N_?qshYQHk|)2w5rVFaCq5x z6~1*x%lEgx4kE9Si(VRj|dd;WAlv!Wh_&8yYSpwQ;ZINjca${>UyW zIrBkxen7P_2;cko+r8EoFgCI#qbvsvLu*nsVNF(w6pVYFfFk-{(3&uYO!b!lXUE?OxmZONbG}>2*P-lIFhyw~sZ^6dx;EmsZLaoX%m7%#%U8 z1N*+kH~7%my*GZ2G|6hUk_nz<=EtN|HX7tfA6UN;joeiej-@mF!gAAv`~;17E+Ru-@05L6~D>Kh%gF zNlq)?oNn*ExU=MEQ}NER?yD<2l7momR>4CtKzt`#VN*Bl zMzzH3budhFkkDC!-7X>;J!6JjuUaq_&DVo?sH1C!eP(8?$$N`%nMA>t4PLT0Km}3F zlhx{tVzP(O0TQgMunaUoK~cx-lStd8UXenh%uCtFfH#}obY~||jK(>t10?gst3k6+ zO30z`rEc~~Btt2$GT^c(NnndKhTNnKEU#G9p{1);T9&WY&(}P3^If;?_z$Cw)z18; zA6@`Y$f{XJRwar)#pbwC5|(U+NiO<|^hgn2#q{N51_lvou6Rbp&&?j7NSr*K5;gkh z`uwl{9o8L(EhJXjBD}n(JA8&#Ze6d}E@}9hax!;v8)#|~QOS7|Wn{M=7Ins415v2! ztufOhb5In>kL${qr_}YOxp8$^@%cEL7#p|G8z=x10Ij4~V$@Oo_SQY#Ko_n<{}z{& zREe8Efke|_Wodp?@KklMNQzeB1NUik>HDC9t3owR3PDUr8K#wdE+@)Yt4tY>tIpXxO0&D={RB|a~aP?Q@kZZajA<<9Cr&evzAdd{x ztB&i6qlj}sBvZ!)nTbKxd`WctKif$$D@^UfWmG@)+!usrrP89tn<h-0oc-wet7v(MB0vQ%EwTuks=;O48)EStR=rtBg*9y(l+`g+ z`Q{+rOUkPBa6mUXr)_6|MW?;V(6Vbf45-G)wz1F|^h8=Vp!-78j0P36D!KNcwM%{} zF43Up#DKg7o0oy|OT2NPLtVPhmh`Tryyq>G(ZWxkJlju8(J7cK;p;_6 zFW;%ES#!0r(4qzTvH-r^5X_BOoXl0hy;#+B9?qD5?4Je*=2q1N(LsESY-nN- z3LC|TCRG`|yUCb5UpfRLkes9AvBC}Fy-##&bL~er&`2ASfGf8`CR51asfm`HiI7>& z{?iwJlJmyLW!7X61BzQAe=ME-Dk&FwB~&!E^*Xxm=&cp~VhWtom;RSsu z-+G#}P4q^}`-61jG8+@b7)-;~l*9w>d-T(`Qsg}{m#fK^z%eIIz!qScd9PzcGk?aq zM=j3?9mBKYD$^u9Mgfu$q{7P~fa=Q|Cw`(3sFoETrU9Z#PUo*%Hph>IR{_Bc!DZa) z%M5@U{PowrZNf%3U}~$w6}Do!Lz7W#=w_)^0(Z%~P55w=;5m(ftKC?7l?WdnK30G@ zNaBl$CSUvtG~LNJlAhnD9a2Y8WZnJvY;Sx*va#iItkklR8`k>{yY?19S&s;CKVKg! z=?52{bdCgUQbN?ZS=lJff2GJH#PanfGs!Pa_K4yN)VxU?YzZCI(yOY6BWHNo7(eH1 zNC%t8d&y>Xrab1M_%fB>GC|b8R6=4BoDS!rlO!rN9l#g85sM~BV zIUxz6gUspTL~loyvWiMCi6U6N0oAS}*8P|>pBt8ih285d!&{0m4OXaN;Fz3vdX~j` z=w%LgMb_{3dqz>IR4tReFco%#N0GiV`5cJs#vzz?W?%}R-V2ZEWVww ze5)Ke9*_w$uffwIXTz<^IJ}aV2_TH%zFA__Y$J=!MY0rKJ~4N^1Eku>`Du7nF0%p0 zcl+n&Sjp+QtxST?D-Fm7q)^g>7Z$EJOt?#G=OsL8O_F-zvf@@*c=Fgnis}HAut$y& zIKe|M1xX^hb8dad@Hi5YsF3H0QLHaa(`(K&L7SBZ(D`~oQs#M#CO)rab#E)H0cWhRYI{k#0ZVF) z(3&iZ4wnJN@G|(0VA!=*->sL;&CPoqyC3IZj!aOiJ+?vLLDuovD_-fcXYu`dICw=qIsXzX&^*f)k?GXkWGNvlJr0f0Dd~6_L_jySr6$P zsj|@8_s2@xy8Gx44Gj%@j$2-VML-Bo=7$3`P^k$+HdKae*_&WJpkW13 zfv{BwGei>h%I~^^*zoy1f0S3vGwylK_w~NvoN+2tQx$=!B#zBio`w@&-hik31lduj zgb^L~J_Mdr3jl=sGs_^s0+wMb6rU8fs!Z5{YfZkWN}p+crk?%|Ajs*N`T5dn^X{HX zXZ`nCeO&wy0XEDKujaz(S_nxw0^qm;+&vV=g-brb0Q@i}gfpat!5l)tXuHw26uv1} z#)yt3Qnz67Nc#$C_q+U+sOs-=9g95anfTHrh@6);lz_G17jrxWd7fRE`05W&`>gru zJSC;2DF6mSQBFVgjGy2XI(@K)9&PK~1+@Hb(0ie;d`en!rqwYkOJD40#h+wJE4Pg< z&6?h|#$s<(U_5)A%8blF?)<^=fkuBp))*W&fy8Q>RGK!>1ED+zM7)g0jhyb~F;`qb z7N0@sxe@T~F6!&+qdFbQF15* zhC2Tis*y1O1rS##C=0QehY-~Q0Ku1ot|%V@A*X_eht(^;c&pwOUL8IEC@%qoh0vAt z;Ir0__jx*bi@y}KkSv3L6sXp|g~jlh`-j;jJR&MNL{%bu^g3f`TUxdH+YDR8dlhrwU@BLnNsu=5x6AYFJ~AozA6s~{~8AoKr$3N`pu>jCvf*a@(yD;j1|{v(&^;_AwR zrK1R`PQJXd5r{9r?)E-d4T0M@M$m{VJ;3jLAXvZNAPp4C{U8Bj2jXI4Fm(NEu?0cb zWhd5d$Tdk2exNTO+*?;U`qR_o<7on~#4nP(%D8oPCy9)8+ zX7G|?02@&v!GQRB3&bb|ucEaI5XR2Rj;Jm$Gtiv(f=G7Fu>z|uM&8*7>gW3N6nr88 zjFbOz0#=6d=ZA7Cr4adn3m^4#_2zVp6(y*`jq>cdCzsq za?wGS{y+#(G}6yO*a$A6@#MR^ES~Y4($;`9#4woMjey{dZF!!bPw51|>}t?-{i7)q z?`!TH<5rz!c~@hQJVYv@sTH|I42xEow; z-xX!>Csj;jfPwAwN7fp-fj!;vOlDsVF|fAhmIB1O^VZEn3`V^P#11sSP$7>3kr*I8 zdjrGKF|-OMUNgX^y*}RKul3HY4r;OSrh~!lE?v5{w9l`HW9{9fhf3zXfv{!IPrk(& z5VSb~fh5e(wlw<8yx8dy;LnhqGlXI`;3LO@+bRnxbwYI>xy*cu z%Tr)q(dQIas?bh?grDnG8>nQ5z=o&K6(Ra{IEtbIEa`(+m%%|9_{lhG-JZ0_&6A2* zHN1tj4L8`OBJMnR*MmppQK&UJg)L2;ClRxF((<-p@QPW-eK`-zsG&d$@;tU>tV&&Z z@gqvnfQF21p@MVb4G01|(CU`9z^aRflVSfv8wt5^9akV|GT{ZbiajW3#*2VZBO9Bf z{9w8(UmhKtdSy_DD&-r)^*rAoeeK6g^WM3fMh)_B3^7&QUvzVfP>NYnnHUdaF2=6) z6*-$CqM)m5WfDIBcbIfKROc$>naxfmw48h7vP6?DVq=ms+Q05bI7;IRik$(msf=!P zUf+&K2%R7uG9A_&uUz!<;bS+p%?pk z)sZm%{Kc1hk!E*To-(@=ioxe0mJzr_Wk6-Qo!5X7=zFuV`;qI0TID1ex>Vh0E2 zmG3-s>PtciU^jAP9{E9#g>IpQo`zP>^(GOs!?njRA!07D-d2S0)xOF0yE}d!5pk+L-?Z^PM)K_1kgXa z3}u`6#Yn1o<+K42>P^QM68xKwM2OB-_?v8e6lz7mb%{rr!S`wCe)w{X`chn~gLXlT zAl=jrm7*74!e%1q&BoQ&k_PDhdYtQ=KAj{dlwI^VeSM`LNJ z(#5iBS%Cs$(EaeyUpIX;tz_lVkn{+DT*b@B+WEDRas(C0yRIs~z9XXJbEimlG~Dvm zqn-wXs>Qp$dB6S6^52_OF^$`sgp3ZMO$_9QDq!2fpgYV75!_~fU7wUKT<|sMisQ>2 zWE%QWz#_dTFaJSZZO;54>d^dC6;|y7+M_>oA9vKL+jV)zwloC{%kOAeNoSIX^sN$ z2bx>3FN~ntdhzgzvyn~bTs7Zov83{!#^j!ZpoAIVgwP2hkZf$3%FLD=jAp>U3gw7u zHbq27`)i4!S76$<I5BiXE?Y@&oBNgZLH?QZIc*Sf?GUFDo0p$Yhc$$6eO{4d4|X=nN1R?ay0msP zn@?!B5N^nwpR(ZWZXcAL!~0)0F;S?f1(49LEST5i1E7W1gPXC-=If-QS9IkV(i+~` z^ZcCklkg|(|3RUanz0&)-UD0DWU>o1u-gNWmgb-~iGg1iu$F3!LQPk-#)L=@uDA* zI=j9Stp@zQXdo880x&Ld_oidn7w)@7J?vGWE=!UtO@ zN+J|8DlVs-^ArT<5=`Bm)<}+c)>1OHNoroOWp;TIGdx`a`$sZL)X}P|{2rulT~!1y zCjrQS0%(-?ll|byBQ*pOax*YB*)vmps$k(}W@YIBLIGByO7f>XIJ(p%GdtVza{&As zfJV)c#-3`J7xXcM^##8)L4g(WuV9rQx2h~Yy9YNgH%CD=8$c*!VZqd4R(&Q$Pn{5B zs6W_CL~ZH&4QBruAIv_22NnVU?tXec7{B1)76OjMFE1w$BJS=!Ex*`flK)*hfN$Uv zQjrHNiG=U^rf*Zoy-HYF`b_RUAKG-N!txepuk%GjqgCMDeeEt^wE#$s(Ws?)MiThH z5tYatfq$q>UrX*nYSgLo1`GZnIShID^3P$JK{@v=2>`xYZHFCt9XIIY14U^$n@s@E(u3+ScC}O2@6^{VjmUX1ClH+yprC;9T@wKU;egIU5Gh8{ z@ZA^pVNn3`A)~TV1*$+!_$qT=)fW7|lV6pm+>A8zJe!!cR&S3qn-T&(J4HgGA_v?R zh|BpF0$>8!^X3gN*pq-&vf9`goI%0lM3M#)dxN}~ z4b7#F?xmhy?-jJuIy2DFD{Qh0w1b1amf0fn)|ao+o|w6!3C5RfGH(JZmzIV)^2K+r zq?V(lRI{`<8pX5JFKo8zblhmGn^e-_O$Ne@&piA2Lh~cP6P!g8@a-TW)ZjMahvWK* zi?-7h>ow07>#WA;C%Dw9@g%X?l6r?-{qh3xh3hKdGX|32j2dcUWiLqd-mneL3d!1{MGe34h-bGCTMP zlJ=BtJBr;rh0UVeJtuaiOebL0Jx~#z_;b^!`B)Vl)}yJ#S1TUL%yqtP5KK6aGw+Q7 z_r|T*m1F1C9o#e!W~?O^IoHM@F|NH}#PqW0EC0zZj)A-xTQ6EJ+k3K7?6RlfY9RP5_R@W*Grw7zb7kR-?ID7AOLrRDYh!@UStVHlrv z_Mxx$wh8q5UiTVNt{>*>DMbi+O!ApXq>a8^qtk~;=}7emlm-_dqebh%Cd)tVvRQO* zh{JTngr`{$vbx)T+O(*St$v=edz%BHFQ@}5gNz^CGJ0~;KtxzqS1mOAmgz}k1Hcb{ zS3!FA+jTSz8xGN+HNSdCWSI$ljYh5i9?@R?I+W7ulm7{=RQxUuwrS&09sB7OyD`an z2UyHKxKz&OPd>x#Sm2GE!^cR0!J=cTkh3 zFU%?DuD|HjrWef>-?-$(I7@zqyRg6d&-b1Ca1Cv_#8py)8|!6iPR;^ayZ`6gbFw4( zu6o_09zn2yVdyp{ z!Dy2_#e0n9?I5P*?~hXs@>!p>j7`2$Xlc-Oh<$`n`qm>DGymE&Ax`Y4fK$2@H1$OY zB5?426*%Dn{(QX*i>dFzD2Gm|37pJXAGCLymc-e(54-s41Z&C`king7yvY+hYhgu% z9ly{kbAH{H_tDw(?F-VHPvF~bv@bGb+VVb*)$L=k`Ie%?#})Gf>|jl6pS3TjfRAWp z43}**5B|1Uz_#}`CXg;(w8lzcy{9xgLxFY1H1VOjlz@LgJI+Za20azMX>=`Yhd&L) z8i-K_F6mh_PLp{C)<%*bV(VLW;l6wHj7`~7Id}*!wP~vrU#4db#oC6suIUpV`RV$p zr*M4i_tj!NC23z$Cg-0Pls5HOG^(1=j4khK zE@axhD&QDn7^_6?E#mZtIm}4!P_Q=R*ZL8(ORQqKe_vpCRk4n$PRLqy`J0GFVt@3$ zAaQ-?|4aXW|Gv{Ed*Fwyk>uZXb`(E<{^(OmfxFuFw{xFe3$}iI=ZCGd{IlZwGpfl! zKmWV<=$|Lg)cp?=^W#sftJ-NUNt!R*BT^-_YpVSCI!jDD{<}Qiv8r~@e4&u)U!!{C zlEC&l#)957XPh5oa3XooE_A8h_}F}d)o?iOVW3R`=l6_c?%z*1yIrsjEG(}scr7N( z4o^+DytRH;%BH)_nQnz8wX@15AILKN;<#Wlqn?aeEWBSUW9a;Sv@O=JI$@K@gK}>4 zB7ssbXD>>EcIH^iT}Kb+;M;wd$bq#_9%9c=6v3_di~8IXLfC1w9JI?i$av`kX^yso zWhroKDwzCYmH4YI;mHHBXS+OSAH!2xo!o8LidOQWvy{h&aTk3v3!c^`ZXpzTYG-AK zkvYE1UdGX{je{#_R70VB3#ezV3ohMD zTv4Lrrg4&oN0yO<;>@4Nw8Ph%KnNBW<8F#F!VkN7D&@wk|4n>9H?koW`dJ|Z#(eVjMF ziqBF>T+&ASV3~;Ih^T+Oncmb-j^YfqU%R)K3}<$uxfhexh>3)#cSvM&xvV)e$jHSl zn1+`j<1dlhR*6Si4bC0zUP3|$UuMYNXKxo5ovB4P=A?VQz4b|T@W*eVS7Uk%t;Uc7 z`g$cFPscs$VtSS(l7GJ&)`SMXYZv$6t0ejA5(ccz+-Oq|MEhLAP*@7nwQch)86G;Z zr67s}j5zxq)5E=twMJOXho9tLA2Q)6&pO4U>#-J23)(8=J@of$UIMKDPh<_^*Vk`u zL3A2LoKG;UMU82!U3Pd~IJiCFp1p*ozhdfXbesz_Pj~$lPUkky%sq=QPBO}U0iukR zo}qjx?JU<&GN&gzn`Y*4SmK4mq>ilLXVuRQMb@;EUozO2+dY3d9fmgBFP8X$! z=4%j+2Ogsq{)C;<^i$4?$U5FlAFVE5Hm6=z6+v`w9G_6)9M`tPKek^LBnL-}Qu;1k z=q0Q@aOggfz;&{fo@D`J)`~m9FEP#ufI%3;8k9 z?nOb_pb4X92WJO4o!HdW`?H=RlmT-$J4U4&y(6QIvtT-mxEGA=?T?A6nJH~=N>=A3 zB6z2c^!acdLmI)gj z{45pa+3|=hm(V6O{zrf3?k#=buh(Hs;~kQVgTCYthNKiSrINM!Bx>OA#^u&|=RDDz zov0QVD1#+RU053@q_U^#IfEDR>!#OH8Y0Q+NxHO^!ddgcq^CiHf#f=wTnf@2PFprL zZ}+S#@qBG`^GauGi0=eTEHQ3!zSgdntZia4!9ri|-qg^@vV}i}XvfG6!}UW#A^mX% zt7uP+;nm8Y|<^Jg9j)#(A@UwQGDkn;baXPc<=T>O_j`_WD zR98dU+YC<37}NbHcLyU`jjyyn({9L3^gp?5vM#pT?sLn>=kaId!YJ`y-g1n`|ND5+ zm+2cUzn&vh#_IaEDwg41HWIcIw4vFIu%?L;OJ;#8A$DqA>|MrlH^MzXMFab3DfO1F z3^tIYs?0Vcx7}Kwj?0FdcA*x3p}no_=fxG86IR{l25EyT6NirJoe z|E#H_n14*MXzC3oR)y(4#yxJKAIcT5OHmL+b|LhMuZLCJE*|3&dxkk6(`K{7S`K;p zv_JFYmb_h!TnVakiL1C9d7|+PYRt*t8;59j4ex)oXeMF}_d#t)AfAD@z)cB!cUZP39nB@d6K!cj@Mp|13HCz71&7oJ^k%bxizj1V2tzm$`*%%<4P3q|cz|514%Cw1yg z2MRb~d~R^d6)Q;nX}?ORC*=p8sQ7qSdv&~nqVh4De9Oioco*EQ#h=P$gto=x1}I>^ zG}^6s5*2oIdrXaLyDRO$s1z*SZ&+b2cCsd@x~y^LBkKFMuJLB0%*%BS+A_zqPfw&? zZaa66&UzgWXsZYv1y9xdtSke{>kOs1w>9Y!a#HFkPw#;@dzNeHl8XYE;;_@DoO^p4 z?q(A%Jt&*j!;GGajn%<^nfJ8o-V?@rpw!{`q2a!}b(zDvD0%t)CPit5S*6n!$1(@r zPn!AWQ#+tM!-`uCXgSJz1~7}lh(;4h|0#cW|B*q!oab@{ri~}3zg(2RZ|U-y>l9Nb zA22Ga>D)c1$}5O!F5j?kBxxHdWy*T!yc-bGlpxf(klZ62LAp{Nwt=ed@=umhvj z#JxyV;_iiuW%FP5SQ|YesU(Q$Hq5--7%q%e=0K$VKD-Rv*B1%UTKpzND%>vv_f+pgtKX_BfP$*$3WuvS&J>V`Smw$x(jJtjmM zil#_s&VV1{a~-u2vRs1(X9u93-yV*GLJ79C&cA+!yonbyZUitiPNg$7N8qfuKZT(p z4j{)N1b}_gpgt0T`cKCpb;P-gXl=F+R27yfM${ zLi*aw)?ph^bFEd!+sKfXk%xg^3K=SGmanz{F5}C0vsJx|3xTDXMF2aOTXbo>pLwPlRd!#pPLr5A~Bg7#}rGBTUr}VHg3acq~%K96+iFY|Mf9LM>VpkQmFyaZ10TI*0;G&*c3-!I+h@B?WT6 zlx||JvUcVy_SJ5^$19g7yrGWS!gAnG*4pZ{TE#WrG&AaT;n){}OEU|s%JU|K)4?us zDIV7zQynh^_~mCddrcC?-kI6;RknBr*4U7`<8OaT+1K@N%;>-O;(y&Wu|;@6OJm{X z?kL{|U;=E49oUb`u>qg1-eL_2nn(l{s(^%{+|9wdvV_hLAE1m;N_e4;*9$U;9Lz8j z6m+`Lpji?_Yr;62lqS;{yDeo?xdV3x%RU?T=uaA!me4a8H znGYT|mr+ziYFtg!A#IMi4|aT(1e6~boO^sI2DqHc+b1R?fWm@yXNT1DnS=ChD3$jH z?hb`OeJIICz+wczSB2pUn%Jv=!EciSo;@L8UbSZgv3Z)j(#=#u~)a zZ!cusXd-FLPS$~;m7MT&tzB@DUcE2U`iSq{fV4p0Sw+gW+02&yGs_N*sc&OWIg~-B zy=2-C{3tWn*YyZ`hOmOD4Cc_S|NWr6^5vBrfW1*oqj>zypVK;@T|;O+*x4`oSRjEA z#8CC>T5vYP@qvT|96fbP0f;jwY0=iPfV{$Hu)Z~q)CPv$r=?Hc55kd|*8MAPxkYkc zf{mqdf~98gmOKGde^ zdNl|*PBI@NaC`-TV-cd>Z9W!Yb_zDj-JOL1LS`@zZA{pYdO+tP|(mwTJ3?uFZOSI(#JV0>9|G_!yXMo;R=!Gk8`bmj*|s5El9yJ0LG%M99t;ZGq!3Zjl=;{` zCtf&1_6Z!rlty($_`g&*wk$XC15{(^C8(58H3OCUe2h^ucOD$l+`IApIw?!0+jPv4 z-N(>a*Ug4k6FmEtAtzr;oa;J~aky|fsYWr!Cj6n`Tj{`EQ^fJ{tkB7=7_AYAMznq3 z7qU!8#9@Av^N$WjqD_CVMHLXP%n$h?3ZPl3v_-&%qiW3|xuiwC>nPaHxssc(t1%G2 zz&(dx@6jUm(~6U3D{g-Ev~YpKk%_J1^{7&;sk<&|yN!v!!e*xZnmWJBxrz^m@*Oz>@vQ z<2}hlb2yI=K#Btjfh|x3V71U2B`XY2wHzR-`%Gvu@?hxhJpt! z&S?~s>tURZ%-6g~9S&<89K5uJ+462z<8PI}?u*$C!Ng}U8)P*ok7!ARlNl=9ir`?2 zc!WW&8i5mFNdNdiZWQl#gysAT9mkK0c@F)ST1jgm{k-NI>~;tMWMWAKz572Tm;@2<5DUDG{>F5 z09SmGThX_PJ`=bCx!yIaTTr_to|K4O>gew=_H(^|DPX-`W>pskohg-9tf8-rP^zOE z(v3cPvlm}IpbgzUw>J?C{am!p{(ywMD1wI+bpn>Nz>O6SlE;ApbjpkJ^75&H{+c}B zXlU2$UfPmtq9Jhh>HmRApz`pZq!NvpRQuG;6YiSaYA?>gaUxXIZ~fMUTBZlt-!bf zEv6Of(_?97X-E&fI&|5tN>UAXm;$OKB}k20Zx8Wo-t(K+89<0K?H&;(IM7B zQ*X|MQvQX%0|w#Mpq_W;)d9w5X(aaG56X;$KvO$NTo(Vrb71rZ;?_ZxAy|O4vOvYz z1L(EI+6J&eVCN41e&q2RATD8{(g-*>!u6SZPXio((>}QfWnRW}Lcq6{__x-weecUMSG701ivJTc7^7@=kNrSj-^t>R5@zFjOA7&IN(dZ$FTdCa|fu zf4_!I31cX=``u0+rvdPuV%C*?;B1zW`#c0Di9sI@Fz&IA1Le zMJ*u+f(+;qQoAIb0L0Dmff}F}3mI+g52O4x#1~%bS!Sl10Y+mo9)e2A`xM>!W22+p z-!z=CWY2VahjrRfD_iX2u)XCejev*saf03FISouIr%>r}$XrnpBGby7QBie=a*CG3 zva>9uN5;HVtq;|lOGlk2r z{fZa$z|tjrce2jrHZUf8zrS?e9_mj}4VGk0>qYaDtVN~sd+}v-1lLCedJ(~`Q1w>2 zxCAUJNW2wNGFGW@s+XV5JY-;x-dX0uB%dfB!C)F&R<~gi&W0}yk5%0Y3Fwg4*YT_^ zU2f-X&->oSlJsW`2*{yNqn#;&Y$d+Waso=Dq-qAeV7yp($K+TX)(6xRulU5`t zE4)Tn=JTtcTkFNN`9k1Bs2vedK?%7UxLh|;`3>4ZVB8~s9zbPKSu)Ty{TEKMIEVNE z)WC2-_~b%3i$|!@1`JeK2=V6+V@04Q%PfWz_X*MJ1ondth4})uAP0(Ncfo&9xf8WW za(>}1N*ROq@+R?Uoqy}dYJZ5MYZfk#$J`ro&z*W= zl(n`{mE|@mBkvmcxK;AZ0MR6P?xLcbgx#(wC5(k_M`4!U@)`ZJ4*uB^!w(A{QD4-i z{Fimzv3wv|88AeV);##_5S3E-4cw@BsAEwEug|;jSVk(4UQj21!9EcgCQ$393}s_1 zD7F;^)LI1`Z^KGp1UXh2+z8HwYR#c$IZ87E=_8`U=bmXfz{c7>i7oROX1@;6m9yyn z=JKk9g~aV2&Zn)}Rw{WM7x8p8ai3BjvN6hHP8(pl^V5yI7=Mq4Hc$2CMtILTHHFMknqZxs>uK~PVb+DGUS4atl=I0r%6+3Wvd6@ zKZ{u9l^^+IHz&Q!}#>#J-~n)NBZM&l;h4&MhI! z9qm)JUVffG`Tzuk0|n~i8*9(#${iFGY^wd{8D8!ljSNpUd)4@}oY^cjqfHG?bmlkP zXS0^8bBula7u%)Ml@(zKEy%0!9B}GvT>M`*DldSFs++KL-c9<#$yzO_ z#J#VwWKy+Q-u8TA_0Em%3iWmE+s&U?VFV`VuEDeq_5AqPbB~baV)a-Yv&E_#_)$3J zj^JSelxo#4e;HWoVu7HJQxp1%?uV=+P&}o9{rk5L(rDtIQ(gUVytO?OC|u5^Q^{Nr|70{qV<;$_yJ) z|Gkl)EpL%t<~`4w>phRpy9la)38nT=q2xS=nz5p&pfHRIT%ba!=VnntXZt(fGB>Kx zoRG>5o&{DCI|y+@MF+P6cjQwj9V5|ap)6tOe|rp$qo$*3&%R1u&%iziJSHE7U4$o4@J~5P=%Jr_iag3n)ex;OHNw_>UoDL4g3>$;cjH;1^pQ<(<6o>!3V z6b1H{5G3~NEZ=tkU_ao@nKOd!g|556KX9PHsc(r8?sI_BQ2Q7X@Hat~T^7}qOXPRw zmH_n9#sp=jkFmcqywud`+4{;G5Z~>y<`vgjN!B(6A-b_T!*PLY1%VOL;6AJHpdNGq z*LBed;FevW2Q5%N`UK*gsJyeMhKBfjs$dxwHsioHic=Scl?b+Pqbx98tY3{&nSw+k z+k%*9;``!wF{;lCG9!dFe<{oUzBnqI$H%?ZCH>4Q0;b>0}|+`EaO&Ey07 zp=w*P+pbdxxW`%&HG${DKCaKmPq%8rUe>Cbd$1fv$x$tY4e4|mLdW|wgMTvXn_pIx zW+!@mc@s1-bGO?^3{0zEK=XJ`KhRuBp|XJFvE;2-)f6yhxX%TF47ZP4g+hGA!2WiR zjdr(rxc3pN=YWbromV7~RMmxc{JdJtDJ2aRQVVT1Gnf1%aA#vUB`$)^uziqb`3R1- z#uTSoLblmS8Va2_#J{sjSA@$|~|@ zunWYrOrZam(dLz|LwL;qMDvFAW_h*=11Y0>aZ4WJmud&T4tk7e?t#V(vkNid|k@j^5I%g$~jEI(G~jTVK>WTgZwLlHO-1aT6_ z*3hgN0cK!nP|pdLw7v$e69)=#54BdqnFjY-ED=F3@N{s65a=DQ2I56=?4agds^i{d z>^$&nAgqb%*dL2X3-6jr_+g7m!-yO32R{39^c-FU1^mE5h^ujcLQD5z{R#aM zz&1ohwJ82o8rT9XbrQJt;Vl7-O0 z8{R;qnF<9&_DQ}_6*|OVuQ4pEr@WJvuWs9UpluurRP`>1LkgmE5LopFda2@o4xsoL z3!1PTK)lCg*#5S*KT!=NoZWN*jCOzL1|V2~e;AQpo*6(H6bOfQrG4|ro%UqY#FY}G za%?QF(#F_?$;G@+Oic1tef_lF)%TxPR;Zn_j$=#5ElG>+oe-k?dn9Bycsawvkny)S zOk{R;9;h(f7|^n5&jA@RqGJHB<&3!la{dv$10qV1hu}aU{maK!{?A2v`w=ZPaOAqr z#X@dl7^2sn(~Or8#ZaU{&svNP6xe$V5D9TQuve-kfHYpe+-Y!ViQ8gXmI^ia2IN@V z?xeX+cz5qUOcwQ5Bl6-%$HUA#8>4ddJ(oYUUAf9rUYf1~>byK?$tsXP3hIbfcEd1R z1wcUyt6n-p1{T_4dvt9CBJ6rG3H$&y{Z7#Gcw}20eX!Z>clSfnKr~XP5pRvqs30%p4CsQmuw(4t9f$l;{)23 zHbvx`k}5(R60M5Uk1rnKomqL8e`!nL@Mz7p5#sBq7+xu5DO}*ETKgDiu?R|!8&*Rw z`xKb^)Xe-vIE-sxauJTvU?HYY)tV+Cb&Ccce->AOO30A2jM#7xc@3g+gNXef%1{g~ z2PBh1t%z)53hIUt!5VgD`nCVU1maKxTi)Kx)RQ04bOTWxO^9*({5YI09@vK>^FR$w ziyK&RK#Vou?|8>`f&q67QLIUkR+vzrQBI{I;#MeWc?vtnH2B+u8JbG>8VAt;X+rrI zp1$z*mGsEHPQR7YCsl1H2m7(3?Ry#tU}?!4@ElM{!LjFY6rim&bfO_DkW7PMmkiPr zh@D&6+v_|P99!dqAl}#lWVwA1PDhypIQ9q!#8}~|v&mcZWnWT@rS7xZ|8pyv>n z8cje-=pWDzU$?3JJ~T^kOi9~6?y!`U#}px=Pa z1gPyOc2G^Gx{^AGoE+p7|1hv&qhcZ`AW$j2j$YF-kZF1Z+eOCpI+eLwxX6-P2uvieyu4cT|RgRXnjr&EHo%tRQmxra0O7nd80~i zX0>Eq`G1kD_g|dYP{PUjko*lxI;vR2er`7aC;}MN+tafpSa3Ev`IiGC3u9D#T@c*>B4_(D35QzK zp#J#{a7JCajbQ(rE218OsIsP_s@Yj~D-V$J*&k7a>CHc1HmOu?LuGy)FM2Dm6GlN2 zDZ7P+2y_vxE--;bLHM_r+N%TWRL2@5Gb)U}XP*f1Un~l(0E^E)w7=Ic`}sk(v0m$G zN3o>9kWF$0SXa0p*^S=N7+{N z-gj+nhHoAsmU$Fa0|6S3n1=7!`H27}RV(7L2kHGI_4kBSS z+NC=ALe?GX!`82@-PIb@YDH?b)Z!RFVOG~)-F0AIEMvu6_C;R#D(0HFTYvY{=%}0% zx_<8Zz8be?x(e;U(oqGRo=OUs{~CzfD6P|}1ge#SKJ7_*gUHcD$Pi6of(S*t(=8Bk zBtWGf>I_86Z-JDGgJ#*oIkMDhtT!lwci<`^ni(J}YX%+*L?SZ+23ad`$0q<=)8(PS zZWwMzvPsAWS|S${%G_jts68A7q||_f9C4#TZa5ySUI{qvNS81((J2iK_>I8ef+(M9 zh)@V|LqLqyWI=VK@A&;WHc@ITbi3Ak!iOCeN&bJE5vMam&%7?t*n#mgv^74q!_=eM zHCt(zq#0Uy^FsrmDA*P6v$BT9!}Z>1yjt3q2!aA(9g|-@2X;NgdkDcto&5H(893`O zBi>5~RrVvm#Mi4Hi#_MnqfCzS1vK0;iSW7hs@{Gu?Lhl_^=wE~wyi54J&WA>Xn)IU!X(Y) z1qVL5Hvg--oX2g_AsN3iNWDm*GTTj{V9193>bc)?9lq7F1y8?X25H!QTy-1MlXSSx zs~(8|e0@!>$ACq;xbRkOqZ^PZDs;FcJ70T4j+Y)eBVYvfsoQHS1F6<(d%^83YEJJl zC`>b|#fA02x7zpL)y~Z9YA#?LSKN(>m7)J}_MYQm*#NDNocI6Z5kU<@6YNZi+TGK5sXyWVNbr8YTDEi1 z32EkkJPU_KE*?@fovXjN{rg{Eh}{ZepB)0F`nYMM8 zeX?Ql-hiLK*X<%`y}7tQ=YM|`o$@=*2m|xOZY+lX`p-8%ov37o6bET|{#QLbpRtO| z(5*;J`sROJa~ti8>Ros#QX*Ru7NU;rDI<`J8fP$rM}6E!kM#$w-V19V3^xam)ARPL zjBoN1gEI$R-htDqZi!6hAevpPw$fibH`GYdQ?ZFD|LF(3%9!TK2wo+IR7ae0g=kX1L}>g; z-x~$+lAA#XxUhQ9nzHgmI#;!UK}WX6zdx~AMbz0%;@uYfnJYzDe~rK<+X_;ke+Q#C zuKP59=k8q}WKW)2>6y&Xb84KBx*9PM@XEN`;$4{T-M)3)E#osAqOW`HwFm) zo*$->bdBaZ{&(EsQYkNnw}SqbzPLOgoR!+w-5yb2lySLz8wNApgjuK6K~El7oTKYa zu`Q?$O+$A5G4^qon}168m*y4DjnUt=zwa_Mhd{w|;VswD&7AAnkR>kANbq=%+VG;b zu`X2%qjomev`NX#Jtt>?+HYzOp7nF-E!WoXhX0}mTo-Bg*cCy0Fo`!-9|w<(sT!KI zA8vgo=?a2+)}DJDgC@4`#z)s2SDwAcX^e?rfCN3M?>f52Hj?L`savkpnAHt*}Jt?wJx1ZT6ty;em?$QDvgVL6$2;Re>~p$GC3| z@{+dkTti@JQ)0oqyIZW2ZQ_+&XP9NL(_Y}UAcQ$}r+<}~Ip3)n5#IOZ=A7_>gMN(O zvvOXI@y84TgFA-4H&?`2NGZGfb!U|AT0VrPNbXyT3l_-416*9tNbqpL4vIl+&@V8o z^lqg;J40sD)ylC31+*$_AB#kin@0gi>yrTr9m^Y*7C;_vxqYr7mkn5!R=lB;FqgAU zvxgIss)|Mzl(bu~oUCyIBlkcJ_gY`7SS1d}32m#xT%Krs?KjlGTejc5HAYd!J6->H zHzcagaWAH14VMzT52SsM6-9(3w=3}sjs%ZAejTQy+S3yX$OQab?#2B)+HSv4GI+ma1uVrIdA@3 z_#T7#d?7b##zTA8q=9L0g`W2fOJ=pdIHjUeZ#QPwGuJZ)(==9e3pw6-PniGzuM_>< z!lIfh!sH`LB3o)+x$4I!9*6Gas>cKd6i%j*BdGR?doYiavjffE_P_t5WwA!`qBLjR zG`ZWXQqx25TfvUyesq^W1LyEj?&Rf5efx;#?mKg01Ts*M_`o zyGkdI^#3{8XOTW%X&?ZBxlF6&ZA_|V2d#g$iutCaf9K9!>huA%N_WN!N{p)e4JplF zkB|{jT{-{m)awA5!56&dk~l{_>H1_xo9G$FF(BH%Rk0s)XehQyX{e?%r*W=-?XSM< zR>m7uX&dIyyqtxltasyYe>uX?+lF&5{Ek5_X1=Gi>RLkWQD;}_&Mo+ih5pqzRvv|Y z>P!if9=4y-_=#%V_y9&zCbys;R^7(+P-fnWIHP7=N-g-yZ8s()%b)%0RjaqKK2`XO zP4>W^ZIIt`ZR2iCa!!?|O>Kpf{h}B~WO2zr(ZPSMn_?jE{=4li-sMFDB zQ5)Fq-K50xBe|17&&#Q?n|iP3;+&NO?RaRlt?t{~wUm20M1obD6niMzv?P<#?=hMs zE@uqv>8*36jooN29JuBpqNw&x4^BGRzrD?{c1K-#nLB08ZE`F-2WR?vX8rb#O{%s5 zpYqZU)aKCr!an{r?e@h`*aHih%a#6S9Uf4%=4Tpc9}L@nQx6go`r-(d8nM0X61(Li zS_%_CP6;@LFW6PQ!KS>#6XRV^{wXzF8v2ZEThs=_^&R&t^f6*O@xx(PA; z-A2`5^ga~cR`;z@C;LHJ%m@9nI2TA%7Yt`m!%PnkurLSA?%#K*piS{Xjmqw!0(#(s zKFd?j6h;zHeRj?_@NjNy$G$7PF`W}%H9E$C?R-d*tDy%NwTp>EQKWndl_R~LfvDR} z^77Qc^;F(y0q(GqjM^LKNJiGB$ZwL7DwQm`SwVK|DVZ3>d=1AfCuysF^THA;VCA-M zbw3N{0Or9Bu6h4#k{h)$cz0HH0EtvP{{gMFwWSB4{;EBEU^L)Azv9|n4cV_57fLm+ zl2`^y_m&d)>YnTZ`fo2<6h4w?}C4eD~@JBoT>}@+O z#ocOnMcwUUXA^}!IqQV#C1C>Xj}J3EgC`YdXNGI168~z+mbM{u=3lv74F2;?5$6vS`|wzA~EPj&*8E1YNUI zF(0_JEi_&(B~u2L-x1u+;jxNAk+M!$b+41SMBhV`DkZUjRZp@(ZT!wjA?xfE8SMOB z?RURrkTkCAw6~qC*1#Nk37Tuj%BEa$K4-wBc=^1vWn!3t@<%emQe1vG)tvaQcWAc- zbaB>}Yn9o)t?VICswKt-jMJ4S-rF@!qTP0GqLk4Rr*TWS(tmazT~Sdazv|khbOVoL z-GI(MAcZ4*L*`%_Vuf6ZxDeZlX-`74>a(jmFpu9RSr=t3Al+{z|7ro&(Saviy8l{E z#n>5gf3AHTjNg0mmN>tWs(H`6)L?3RMWhcH75BNdc>`g~GBJ>JxmLBT2rS9Re|Jue z<>drZ3zZ{F(7l^>0pZcS7|2!s5dq8=L*Y)%7iom4X7UMT*N-zgAXhQ3xNSOH?fJgp zxD&<%0r6t=faXMaCa&IRg8baxncr`u?N9E_#J*)>Ba5N! zIwvt82G=iq!Ht_gQj4?Pyg%L}GXaeAUEL*EFBKnOGPevm?}=lTd7e^w^oXy%2kuXk z@8mYV95YRIm;5xQfq7?1OSa1XSn(*=@9KWqx$8rrpQWeYl;8zIZ)YFz zMAbaMx-B$hvCfs!8nYvVpANe(f?MT0BexkAjyI8Wg>@ANq9+;0a1H+}9r^^U8_SmD z-;ND0W4`QlEt{oDlR|K{WdYtx+wR~0pkhB4QA~L{dRBx@#Ddt#rrCj zk{CMd!7uko?AJEdzJ8`si6*JA1Pu+g)xm4luagIN9=@Ej4==jvJZdLcG_s8Sk zS|EwDx!3KvRcS$BRLc5e7o{+V?&a~>^VU&pXmd75w{r{nCmwyd!*PzaV$O+IYIk7H z8)kn9-GvtvBq&+=7;#k91#aW-hQ4k_2I$llBAt!kqp45d4@MzbeiIczphg>*!m zl4z6z2EfVxaL?$4QdWT-CH>CJ`$JgV8sHuYiywQF0*3=jxTb?=cTvczfd3RuiXksMX?@ zbCWpcY)MbRgT6$tI@j{~6Qh)_mLJ^{+ZP542z&lWCqGg}_-8wQttZ--ldf@;Uq(SBdVyK?d{ zNX3nz(NfPfooj6zLyPTb>f(lvXVnafr+pN;ft3B$?7$g0NF$eT0&O0_qtP{bViyKc~M zZH!j37~Rw9*b=3FwxPBt0}iq6ND7XxNlE!B%%RkQx>CCGATrFW{d?p4!Jr}PoVaCk z+N_7J#%ictPpnr<+10rCm0mAc65Hbfmze1Wy#xq{9qV3wZ)rBveD7VDB8+hZp&>wX zV~k;kD6{7t7k(aSpxM2|4hO(8nVa2BqbJqYEG+m_tDTi?Pg|lmT-_D!eu=tU5!DuQ z3tJW)MfZpy_4Gr~RL5&C%92%mRenwK5k5XX&LXh=gKH5)_%QgJlvGWlK%D&$H1>G5 zK2HA;A9fhKgERXL2e(}N*07^v1#wME1{FD=<#*Y#rfNY~8CM5V+m*q)G~&$RrWU2` zp(@IeHD1PInDEvQtcY#e~dk}VqtV1NLEY)IH)gN#53N&e@F(9+-af3Ek^_p+aS=JTBA zoco+}-0aZEyz!C+PsFs$(CB2gj_P;+SQiN7HGmZUwJ!S*=lY+|84|_ zB5+L2|2E%`U0zaG}WN1yw0DepVe|PWPJpx|$d{s)Hx32@Wl|ud0lW3ON zU@BuGFIq_)88@X+j6}e*JE6DPuzxC9)+QNK9`D>0KCU{u99qwLsRK^lyN7#RNz97w z2=0vYtH$Ut8x6e&%mZ zv(t@kzVyb6-EO6}IXU1bXqqo1lK^Zd2qp61>EGHa%AGfcRhvS--43v+n`skIdQTRR9-JSEfdz1dg7IzJD&Xk6 zs3`?!zW8rz`A1u+6r;sFkXk&?(b6kBZhDh4XO6k~;8n?%l?Pj0yld@JjZk2IaCXz9 z{-8y7)o=Gz?&^)0>I!vUxs~hPmN!dQJz6~26lNeJvkcJbgTm>q#D}VW)uj%2ou*of z@6{BY#mBc{jfk(fKy>zX1blJ1e!Q4*l(a;Qn4(@uVU(tar7eWszb^~+>o=wXeRxPg zB{XX$L8UNL;ckIhsO?M7sZ2oEPRXmW96ICD_U1XW^UD@9=w*PlHm$h9X^(I6p8~#2 z_YgyS7YE$ScTgjBVzF7gn807t+vfQ?C{dhQ-Vl}aoLM;rn8wl2R{N+wVZqO3Y?|mN z{5>oUJRx}%EG^!{6Yzdz4&MQ{q;@&KxXjP&6GZfw+N^(pN*=fcO(;Fh8O|6KrR~ z+Y0tuz?6%;it_w?P*nc^p4D$)%N(OJPO>b?8K&6PrIfxyuOem>zM}2_a_Ua7cTQ=` zQ_QpQU`3)>x`03-f9zAi(^M~9HAyb-diyZ4g_uW{|BBro#j2Wz3i+L3e4+}UXwNJ$*hFuBt-VRt0~39S?L1%vzS*NK!)ZiXB(V>9|liY;1-X zLH6qW90BnCQu^*;_CrY;^Kb)GFvr|YG-wB+_j5!C{uEDlF^KU2< zW4L*R=Gd@cPu=y9biUFIogA!Y;*6zV#8MPLa!ns7ZL9kGULFWcx=QpAx_HCx@r8rG zadu{MCM};+mW&ghM)z&?uNikg(@5JhOIL8kCz`T&9&k%Z0JV@|d62cMZC60k%##GW zh19S2e|Ym%tkA6Ch*G`ua|!SBW&x~;zIC~!@Q3J96;of+7TL63+&5KMZ(q61Gxz&w z&DwZ<)5{m|Ej0=@uWP^Ei=wgqp}xT1c$1Sio3Eqg@1`qz)x8*|t&L&zuBuEaT?P@0 z*8_Ld{tK$}XxoGyTQ7E2Dl-NGL;2M%r7VwTALM*<(_(6d|6?jKUml;;_xQ9q{ROA0 zIc(NtYFxsz@!g@!Vq4PG8a+75o_)Kh3%xm`&Cj%(>8WySXf~2rzZfHO48l~$Emc>2 zOPvhZlTowecGdT93fN-o1sor(Lt1$RFwbaYUHyJWIU&ip9)Z8V!BJR^z60cuno82% zA?g8zqu*T0>=Eiqpsq~Cj|&}9npao5$d{lZx6r+|6Yk<*{l9{on?HxJfAC(c$t6FE zu!9x&*W0INS!|jRAKL%H;&Dyt(ai||QEGgmG}R*i8M0%8yiSE^MLZ*m?Tv9C%ph^s z`~#KEPwHG?#^@pPn}>$UaOa+{QyZAbk!cr4XXoP-@ByuDHwD7hwmk)EU452?U5p?A zx{&?-_-dCbL{dAtQ633%(0lV&?P{l*6)HITxOc&dfC;!Q@J2DwhOuR?OF-`b_wYWW ztkYM`=4+aSagh-Ky~uglI=KNh5+pAwuP`d?&>(>_G}g8^{uRVDb>%8~_w$qJfnn@& zQaSdBKhBJRay$#vFr9e0HE?>)8sp(HvrCeWx`df=UFUz_=^;eh|Qu*br)cHo>zoUSqT4V38mrYAfy8!j^ z0gszDZC|TtZJ}?3?Gm&dIe-Y)ehHHKu6GI72 zqD*{*i)V(;;ltoU{y=&}Vf&7bYD!GvrMbXezr&`<@-if_!Wa@p=eY@^2~~dC6DH{y zmAxpM#;Dxew8PcHngVpicX=@iP#%rY9>Km}O-pU;od9w$M0pkK#Z6PTf2D_ElIvj5 zH9A-y+NF(r+0+vGsaF|&;|S-$?B0|ysQO~ON~eVKV&J<4X0jVbCx9~R#ZglUB z;a>>K<1^fgZtwFZS35}wCQd6@F1AuvrIS}CM9`7#q7?}zPDkfSn)*7r&%}nNL=LD+ zV2=D`jE4*twep&2ias3&dHsOIO{El7d2*-1cTTA;G7Fv#r&mT~tj^ChnccLSPp1m` z^I{SJ-D=wzK=mgLmQ9CNbK%p2eVg9@86RG{Xwlj^Dir%ts4!v6%v;7J7A65H|GE8c>VfucLW04YzB@s z3-JWNJ3Ab}zZ8&|z)53lD3JFo8xe9Nce@aRPdAM}d3-)kgb&p(o?!ngb98WP7DpqO z^>j5()x!$l(bYJ}?<`kjXZaGc1aIMP&pViR{|N&DJ<|RNS#( zhCQq<{R$jmc5XJkfgOIvEv3o+G#P>;t8tsP4wF4WhWZ*qs3h$Ct94XYifg;pHqXsD z`OH_;t}y#!4rL|&G@cVFncd9>WyL7%>Fg@bHNU?9J|5pT-hY31zmT4p+2n0CjE$x7 zR-XPmIv!ZZhB;WC}iB|*snvPqx!1|f9h zVB+Rkl&=~aR&HL8j};Ly_ItMr@L*lYdp;{iLHvpg_DM?3{b$I>s@ZHScDvxV7I8c? zE@Z6)+kUE>cfoiCB~;u|d3_7-v$`#TPEqjB&FNI+OE@JrOBjJlqQ=kHbkRu^c&y>C zuOqY~!FH*DlyZfX<)KdStL?UN%Umn4^{H*eCd#XWHxiAvZ|V2^8S@H9vr(R>R(fJ* zOiG_$U$%27qH)%~jcxw?#DJzp?h6p*kVVk%r9=IZ=`Bo0p>) zjq~9m>dcaKevCSv^c}3}mne&m;oao69So7D7*rGwpGO&yQi#5xh^MzQr)0~Vlg!vl zWN!bTS2&Snjq#m{Mfk#TRP^J=b1ouZM%BeL0pA_R%}@O+jX9*78F`y(S?JBqK30#l zLWosbdTC4#5vpG1A1lNsj*1ACLb%?)@-Khl($ma6YA5M^UoOZlw#I(HXG)vyBGc-2 zT}Rr>$$bP1*1!&+g8ziLPLn%`xhK;V=(hCSd~>A`&r8KNy*9lEmWP58Yu?<6%ZJCalGXlqom}mK2-_kK02+7PgtxwzkQ>7 zd4A@FZkAJK#(4^B*x!GA;)bXEEJ_EDJ!+S};O}WFJKK0|e)W;g>LPJq0Z6O94;0o+ zh<%{)?1?JITETPb28oZTq)uhGJ)7#hGI7%?yDq5L=abXrrDqD+FEd_#^uIePo0L`Z zo&cXkLvvG2=WPWizGGA$n_OTZk9Om@=2FvvMK!=vJmMnb^MhL4LWb}?JHZoWZYfg= zFJG&`&ySng8KcSYb!go2bk(m|E(DUBvaju~q2+~t zSkjV|qwx;8u2*xS&+We8vn&Ozh27)oLTi2l(P6)EiR@nE4gP_%#`Nqt4qu|5iy$iM z>DM<}+Z!y(vgRyMAt~l{(dHwi&CEiD_W+~J#7ETFFCd65%#keCL+7$~+f=CAY?%=q z<=kWFJ97cf(tJ9>>$Hi32=udt&N|KNk=wF%DXkM3@>pkpk6k=b<{;U&ucpJCpi#{e~+u0tGLG%by8fM zn1Ji9kIr+-MWRlLdI^5AT?MRSC-Zh;r$lkrkhgoo7F_iv0uKQHhm6foq=0GPn4x=Nm|tf}#!*%lc0Sf~8N z_!R?i$p510Ewfft^=Y8OD=8sgk-x^gC?K1QU8Vca92l<)3VI-55q0htdcCP;2&vyk zy#p@MiQhEorgp%jVJ}RR-VuW8Rc1$rt6HsA%AO4t@4*~@o(iT_Ig6=lq~I!{!Ze?a zj`_snv;&dO2Q)&P?Z%V8mRU*Um^(8Rv}%sT8X6&z%1o1veAU_Vt45}El{`1nTTdkE z4-~`k&HKyT|Hk277xm<;cn{ZHlM6iZ*XKQAX!_lJpM79td9pBEn9%Z)opv)+6@JzC z`#*D_iZX+z>R&7kA|D}G07Y=~{m976?8(P=cJ+y$n=75W&{euNl|R!xgOM20R1Q>1 zYe*c(bg9eTMTUb%rQsy(LuA?`3DhM2T%nEYSZ3$TwJ4q-8Jy#nBvZ zez^I~k=q-z3-?<*iSgCDto#!CAFsdf-9I9M*^`mpc<1P9Bz(qg|^A9JFx?k?BwNaV0P1e!7?;^W-UyZ4^gO2!??PCyS%QyP`z>wjJ|07aA0F%^fJ9Dt%VFEN<1tsTBC&e)Jad z9y;4a?9{F=KgwJtojuA-CMHh&M2GbjQ2zLv6R-8Vb8IxBLoTXTh^T`26o8W_0i<>8 zfyV_kvdO#lK7p>_&+YA~=NIpedVv{0wvH@?s{RkGT%@zg#g`$I&E%H+DN zbbb}rav%04{q-lP1!ySuE)U0)E#EioYP&2hx!{IXmA*UCHwoc~MiX#bsv4{eu4$jZdABJ8?ml+UY?*;y}V(8&$1##Yqj;Y>a zxt>Codf*R19EEEW#=w7=1KlEVJ`-u)&^#5dP(H2;BF;<}&I>vRk$B-$E(;M%i~^6> zY%Xiv2w5l2h3W4@%?c+Cfc!i_KBM=|X(FdwbGsBre&^V8?j{=2&N}Q?rM(8in8b=P zCiKm4rAgu9B|aJQ({L})WM+(%-Vv`E^omGG5}+G5`lQV-pse#4I(mkIf5l50nxLSc zYkwiU3GUEHZ*R~~5L+P^@XjWF-oxEX=CC1>FyZ3w+3VdH!(K>No3yq}EzgYMc9=sUAC4*B#Wl21qHz^_)I21~1j zn2ur80>lfdyLwc#QqdT@8rdkRw(zG;>5!scWoF05_8KUVQ(<#3e(vVty8D%}k(CJ*97Pjd}NbDrXsgPk;J zM;-w^?0S%djX?xipv4Sw&P_n6k_U_|h^Yn0tB9jbiPV{fCTLAW>RYIfS5^;2b7(A@ z@JAhsH9ip4kuI+|X|82=1zCsPxF|Pqm4&|^vvR5ZC8*64V~vIWj;S!D9*ml=6j_U{ zNIx9f@TU1z5pkLubXP;~p%dbQk?+6)HBq#Rw>!|c8GZOjKG!3)GK=9XCT2(D%|YHWsf$IzKi9`K*UmC` z{*&!c=p&j@hiEPFxc78mSj_4p+7=D|!s*_K%i~Si(>KKI*sp5d(a$jc8eq&TY9^Pw z%6+W^H{5BAX0SZ8Myg9N1#t~056RkIFb-*RMcVaXU{%dSZ|d!qQ(qq#Q>EtA7H3Na_P)tLQJz{vx?Xy#=e>4)q+ivXf7~w}}uTkNe7Ght8&uayL5l`G6 zYc>*cb9J40p|yU~0eP!3=Cwtr8VE632w0J)gg z6%Z=|G*0TJ8Q$=U}yS)wE$D&CCZrZPU8@FoE zOv)XdMkT4?Tb<+`YO`qmkr9{cemfnzqtC&ll2SaJe|Mo!%w{_oP1J-ci5iWNj+T~C zL>|$08nKXqxS_J+v&LJ~1s$Uf>P%BXul_rd*ordp64GK07c+2&26EbBtA0~DmNnsu zILf|`%R2{crEW>-IyNHKK=fe_Vt6P7HOM-i-mwZP%hY(+3 z)JX?MN-t+I@1A{ohoRk6Qpry!bPeExg{s;v*Q62_LR=fl%tG9N>a13EkCvaAg-CW3 zm`E5?4(dH^&(}|@kt3h2XH>x6Hbls1s%KA&NCQWe3@=;Gx+(xz1=Y!9vT3QO3%qtj zzbuY8Tabrg3yhJ|lp%iV$}b?78jDE1?bh^y^1#_tU1bNgx3sj_ABs37 zv%9n-7>#1@in9)fnNv3RMyE4glGfOw$t3F4fO0ducSTNmxTH(Q#miHU+L8Sf4C;RRO1k!xd-gSCr*g7Qp@P2sdY@mfa8OhJuU(x$?+`RjRzni7yHxrTDt5BMtP?)CaEkh_X;4!|}vS;=-n zzDgXhf!y=k@Ku}lZ#%7OX<{U{-`ndQH94*6<2wk=PCLbf2_ypqv|r4wrRp-=DmY__ z=~DnyD76Bs0*>NMD`4oIL9`8t3P6|}f9i_2p^?$33};>j2aL70(1gyV*9g;BD{h;2 zb3$~-h^{hP!OaT1r|zum;<=v{YJbd_&@ljJP6tVu!DXuSwBnxpfPy4}`#Nqyk zqEzGh!re4g#leP*BPWC>Cq<6!Z*&IHSSc6rLX3s^l{(YCX6nDAzX%Z>s-8H)OP`O?~2KZ(|+B+x4`O&*2~4S)Ie~KolFgGnfehT z<`eFk$v#7TR)C(4KV3tq2?9CAH72aR&!L8hdaZ? z(}&!|swi$)|B4)MO)+(Xy~6<)XHrngWzWKJtK5`Znzi(oSvrR&B-}fjU+M5uB|O@y z6OQl1sJ^XO^Szs8U<%RmQA~5S_{HQFZDK30PaH6jDr6H`lX&I|Fc9Q|HgF^V%OAkS zLJn8ApZIeHt7zo^M7vfec@>>*jed8Oi`Irg-YF>C4jCZd()mFQO&ld+hwKm3*$+bru@ zG>liop|L_Rq7)8$xyY2AnUT=|WFartnA>+9K6M;1f~Pyh#KtZ_*!(6;WPQ60@a!&B zWUv*hBaky{2xI_tGkp44Bu!VAS}vY zx5YA|7(#jl%2%JwOoF5Byl|TeF+plr%KEMr;OR5PtJNBFO|DkZ9Ec6dJ{HE8x_^<% zgI(M(65KpieJDEh)FD^^=BvP_9i8nvBH@z7MC3ZaQu%tX$OHw6PLF<9w?}18LsWMI zXqsLeld5)j6m8}U$=yFo6HMYgbbIO})g8a8&P?qBnt4|mm%$u#r$AC>PUqZa5#)IXI{^cnmbwdoI)n8UyND_L0+QYFao2h$F&+of&Ye z8ceiA>WnK_+kDrCgxqj_C{jaoig2rnDLTn{_c^T+ekf&xr<<{_|(# zW6Q|GCY)<0G_i<sx&@o)YW+={#Sup?E>b z42m8R(T`rtD~CfTlBW6mf$y>9yD&H$4Gm>Usn-}4>&oHy)-ZpNxJB*)(ay%qtWr1Y z9DCyB{rP+73lLry1M1)Wt2$8ly92LBYI1UNn+Gi(Z-w}A3=Iu$x7ey`18Zumljl_D zr@zl%<(i*=EQAs&Stc62KozKem8E}QAWp{zhY&)K#B2871{gJ1=A=1yxt+1~s@at$ zV~&FU*ADPC{kjG4y^kvyv6UpCP%^Vzjw~t@R-kyo&E(kH}zMNU2vf)iRXY-fYp!bz)Ma( z*%8{oqFx*QCP03wvn}*|ll%zj%EPYQ>3ck~f+lYY=gKL*hUe67tv)?;$=H(1bTe1y z_$iTg#eD(j}UeUN9yG$Pr zhu!WY6d8k> zT@61TW#YZi?wRDZy{bx$1{|Ls(f%_!ItteYzo&TUk#Y++c*<}f0C%;ypD(~f+yn}` zb`nmqOrd!Cw-tPp#=Qjoky(8|nYlwb7W#|SsIGH$LYX~EEQ z2`0}VP}z~-X%fh>3PmNZ6Q9!75QLz`l#9dGi4HH0lrll3@lSX=Ss@ zZ+4j`0H;+$%<1$tF8uoU0@VnS=hTu$BdYBmDHekF?e%zC*?j&X^T56YWyj9}@3{VP zBe;rFdlTTJ#JSgrAUG7qf#nr1Y4~8x zim-~xyAeIreTA|gL9X1zqYwB)aUGU;J7CCd@t$T002CT^v~_gQ5TR*m!@Aki z*kimnUJ2<4z2Y)Rc6dF8AgQ=MSO$}LySaJO^&^n7je)-EX?>M1Kc`P3Q4cUn5_?5- z#$J%bV6(BQJ-<>jj&z?TrCy^>3pUagaOu{Xp%$$`o5dI<; z0!ZNdCQ6>33mgT=&U?4gSdw0hGxa2JBk3fnsfs3eT|)>G(j`E~B@hQ*Lt?i7QaW7$*0*%Bp0qswRwhWD_hA zU#aS93=(}nyKd|xVz5FQ2h(Qezaymdfn4KQczMt~0;MX~Mr0PiRXu^GuKVhED(&~Z zdLQ9!Ce+o@1-_{S>=dzm7c)j<5&G=_FJyYPihcd-gxZ9Eo?d*JfEl5^7#BV~0T%WtSghI~ozY z+fQ;Gz*_}=!_AP&8ALTL$QK|)n9A|YghWL}VeP{050h5QC4O0$HBFcV#qfYQ*tA5n zfU*t;7LJy5clSl$Y`qU;-jMuQoas}BJv4sgTi*DJwVq3pz7Q9a4p zqIIuCL%+b$+r8C1?DRqqDb_a&sH5!)aK_px>ba7YW^>M?+0Htx^mrN5yb4Fnz~w_G z#_?jzU3HoiuS>gyRFmF&!y{>QKp;1E2f?WykA{F_FDRx$fb4h{h6{)E%qlR?hpD<5Sv5td&y{Iwbbt8QNj z!bh4503SQv0J;Nmeyg`dxhkCS&zH(d)hxM5RIa}qKWLqR5_=1NyI0`9YIBo-m(rpInj_^JGUEY`my`N&6eD}&W4i)VHb<^w_GY~i!B_T@lFTNFYPH2k>^2fPBS}85EC#6c{i@K7PyZ9 z`>u(Ar>gJIn#4K)52tB)$rHYCxR`s3mgopTG>t%l7Vpnm-OqJM(Zxy&ZUd3@kiI0y zvxKfq{dvVvEJ6m$%_aJPVC>j^*Ea+AdvCtqWvN;tQ3y5-;9uvO5TV4&X%Die*k@tp zpzjrTyG5%BYYyNX(t$t};G|IDCL)r>iaX8oVxtzoywDl(v9FMv>W=wbAFlL`m_( zp`E4R(sF+Ue-HvQ`NN_+ghPB4x-QM7Rr+a)h;nf5pQ#8pwdbi4lJqGQGsovc#{D{# zqR5(iY)3*EFGh%UMUay{OjM6> zHft|tK8o)yW^QR7QmJsZQS+nqHdy3my*DivmzX!!lrJ0hv9mibvNN;k#eKHoc-7Uk zSGR*ufx+UbP3OxIT-9@@Ra@pQKd~vb$6|bb?{Sc+uP$l;AX$e3nf(!JqvES4s46AN zoVyU$?AXojW>9aj++c3$m9-aDsRi`?irE1AF+n-5XLDT);P??s%OV9#U-!|bjHbrO%LB#S z$F7>$G+nAqPNz=N1w9PitHdme)ZyU05<$ef!6*)cvL$X!P7+~LxlB-wk88)2G9*0( zibNu=SmwcRD7~`#0`$*VUq{4s7>#A{-ZpN2pUo9fz5oe=aIIyyg_j!$BGYDeX@p#U z^vzt)qeBK>B5+`{-{#7i0M~0var1VGo>y8Ns&E`j(}J32sz=5W!>M>(gW zeKCv_(sTEQH)pw}IhelSf66YJZ$Xw2{H8=@_J`rP*ibWJF-%DflrG#GE%)KPWej#{ zraXK0tQncbB*LcmM%PITKb57^E_3msRFkE7sdW?X#;WjX51Dc+g=3IwL~DpQA?Emn zEth_2a=t<0(H771)z0;<-Jy9K-~JbWdQYbRlA7Dn zgpxx^9-C$zbE-FTZIqvsovl@<((|RPl5Ow)G5-+_!lKu9%tllgvDW|8MJ##V&L}+e zA-~nHbn-0GV_QeZF)eWkaasFIE`S$!Seu~}r*3+R?)I`D8IAe2OL2p;nmXdrJ1}$& zZEZ0=s){m48GmJ<>+ZxWT<`C1({BETmO}FunPpFucKSMGu6ITBu4VyzciJy(3v+)I zFNV-x!+Rhq8S00_4zEgZw=aQB)j;{KZ~I8km;k2xU%xy~7se=Ip+;iaL0Zh5{o+?v zJvTgFJYscrqjCUarobdrJM31^Ux6B$zsEgpJ$jEWa#fx)=;9 zX+lN-KIFe2s+W&EO>B9&#g2^5hc<_eW389vrSuCkq}1>qUJRmYo6)RJ!@{ZViC0tV z85Lgv1q4BF96v>=(*&;cEbYT7`#@}UdhSC|O|BhhWZ+A8~%z4+&7#BLjQArM)K7wcV*xmrZHuTm^a!?&lI)Bk<7rCb{ zl$B$!r!HsjwkTm_xW~MGJRnG0A5~TvAK_O^T8(T^*{P&KAq4#8!B2zx%xmeYGL?stXIaU1Q z`_-kHIc_Zgky}6Y^;Ugy1Klq8&;My#8+mR1k(#>VS~hm2%->7a_S)qumO5&X#O=C2 zTE?OZeT3pG7a7;o**K!}w$H1I$VlCm{^z5OrHwXR@b|hEdiho~Ds(%O_C^JBJvGHe z8TWQq9)z5a1WnSpkl5`%>%i047-Qck$Ak&7&vAp&k0eO$YAEXxZ5>B5oh4792j0 z6YktZIn=p^AN{xsnOiD{ncjSLa;R(^+g$mKVt+W&%M*YMWd+99_uLh6aq;b_A`jBU zo8F=$w~nQAN0`-VNDONzH%P5~+rQ;>a-2$`F*hfGA%HT~#>?}G5#GuduqPq1Y$g%W z6MJ?SrwcC_$sdU9D18;aER-w34h)>-6l(F zg|KN+(i2rcd7xTs`1jzjx>pdV^`DO^nyqU}G>KqH@aNrTMTT3Aet{@osZ8JQyqG~? zq=M1h_&{Ft>z~BEAnNMxDPv(%?c(D`fmwkD> zn6d{#swMwRWPR$Dq`oO=?%l(#{%}P3>dnw$d>%21B4sXHrr(mD+w6i)Xtha_d`wSX zTGw@T^2IIhThXu=9r;p-_|pZTkVukqb73miwvzGk{t?++V(5$f4Dp8#?Yhuh?ccwk z_P2Fxj_+lJpmG9rb$B~UZy`;KBkkF)L}H)6@k(6omI;+xq=(tJ>C2Y{F9nCC`Wrdh zSN=*0I0>Gk2ES{3!Lc5ELAWq8>9HRen*+#*ThF$qr}HKedUEZwQ863%;y}j^xj?Bd zsCL1lEqc6RP)@X>0-5mYiJDB)oLf#^^ZU8Jh#yEO6P!`e)NBQFzBQ43 zYLD8AHS)*-?ou~55TEW+Cb?28R8i*Q-Mt;y`A$d*$U-&<`R}M^2@xLSuluh*V1R3y z;l;>(7MK~(rXHN;zQP2PPbTdEYV*{^pcw1Yw_B~d?Z#V@i&^xZ1$EAXIubtPWXzS8 z=DM9fUoAMh;BHD((OoI*an%k*HA?6*Na6oNu*GkW%-M#P9T_dB4-WrML{VJ#)tMl8qfIfg zBIU1+sGu-pidFX8TkVE8MY&m@j#62uzlj5JK#+GJK%z4gVj1`!q$1Us7v|S&WZ2iU z`}|l!a#m$DAt7_nCC;i?oj~P~C~1vo!BK8ll8E3c?jRHh%LS9tvh*8QiiX1_LX9W~ z1u=DYGxHDaNUH8rRTjQ=cfQ67$7A*eXw6$}!2_zmn2)NA8bACSGL+ru(U(xLs>|d{^6iZ+SqE=Sk8KNSZ=Amm{X{E%8k-B1+{eC@!?Q=pnvwEgYdvGvGM(y4k zC_FL7`gx!aR5l{zMnZb6#^n=Nreii{ymj^!ap4ePAoj4!y`^XUJ>4k zlZX6npDc!21zx@^G6y_)2n@w0V+!%doo@Q+t}c6zOXb|1aDuuCwxUPNA8XZb-&=hd z5J8V_d3MX2z#EQ^B&3>wL?K^et26uYkBnf(5CXGKi0q%+QBWg=;S|+S=OLJ z!VAY3iE`kU3BXMzQ~9F&K>mYUW($%aASq{y;^$A#HB*672I?LODm|cqfRe{Zts2Kx zC*TDw@s|A@jz`#SE#sedoa!?%+a50cLpWLBXN^nW?>~E0BmR5MTbB++9U7@M-ikjW zFhFa%#c$F1?fHF-?YsZ@PeFLWz3`t*ONzo<{M_7$#1m4<=9gECiyard;#%)6i>Rp2 zE_&^z<$I5?R)&y#FM^E$aL(iz+uHKb;NzBtG;-~+jn z2)(IGr*(_=p{~y#HTMH6gZ!JpM``yS0n1DC9l!0?dO8TKz?fK{E7@bIDA?hP?-6eD`n^w^VhsZH;Tl!k+cWeHxOQnDsr;A zSMW~YCGS>Wn?uC}4WNq{=h&Juf@(r)9`YA`ne3eN=C3FuV?nZ2Zq{#>fI~3Ucxo`~ z&)?QxBIaK7E$kOE%PQ)i_Lkmh@n!qT9VelL6bVZ32R6h~wp+}HIc)$?mgI)-s_EN= zBBnU^uf<}TgB-9Xk55mUZ=bEOr`~@Ti(ZAmoh>&-4W*-y!O@m3J_aIrO-NVgfuL$h zcdfX^@=PBpD6xC@J2zqF{_Z2eCVnFGm_M?@-2B|#rdAp)gkQvhZ1Hw!*QnN zU91i7GI_3?uphN%f-E^a%ww22kh8adyadX-RV*gUBx5W6+tiFo&kX#&7l|p`4u1Gk zap-|u=!b_@=)GFBc-pXWICB_k*TJmtdmH)vAXt%}<@>X%yQU>m!UV2bVdVze|WxhmTm_~_P>?Y6%m^tx%emrxaPVqQQbJuZ1jE8A{{P_wKV`zlbosbov za#&O(NHINh`ykq8Q8h;|$VW3k77{x>gq{J7_^y&R((gjY_HbmqzeK<2y{wTRerhUe zr(jgsmpm;F&yMTgR28b`S$m5#S%snxwL~_zYWyCuf$Fb1f3HX&bg$-&!3E^~ zBt4hKP{_Klv!4sxok>5blu=Z%l<5rxNiiTKXw3Y(WZfa()@YuZDiWL^k<#IC(|zE> zixla!Ni&_jm_nQOXAz8U7yaROE!>W2!2)W6qKD2c8s#I}^T8NTy1tHvLfoY`s&{rf{KRzhguzi)k_#_B z`d*R#A=Mvf0!7#XOZY{AIyUESUR4C2}1q11rQHEJhoWlXhY!l+J29Gs5 zfX5pC;EwBVdD{gsiHmJ7ZaL@ZVmj}qEkq?JTNJa+cXy?_--2TTEPu8vK%e&Oh_CD3 zPwLeScJ!EyEo1B;ed5~(A_DT)WAgH^O~c1&eCo=D|G4x3+@Az^wzh=!g7OgckguWa zsw!!0SwxlI%Mb)@jg(?-@s?>yvIy0usS_%qgBH;z^%UM##r-M#ap}7ecUc=>+1VW1 zPdHLcGU_c~}Qq+r6PS)U|xOG6=A}yx5EBZGNs@!J_0GQhnn#fTFGd%g6ta z4(xLo{V>e&mj?5HvV55(d&u*rmIBR_st`1UUYVQ^BP5VM&<>2G(V`rdN=6?FnOE4e zb}!#>DlBU&(v0eUaIjffbGp(&ZT0@u@t)`Pdhv(g3fA~d+ym!hPX5SXD2Fbk2ahkg z>g-mN5_3_E`zGMx3a)j{m!6{KeXF|rCm)(n5tiMgyju#9cw(AO4`K{%K{#Xz(upX4 zTHw@?Vj*4BlNY#KpxdlMJc;JvH;8f8V=}mvdW5PV_)Ww+$6R z!3nHjU`O$kG$|C>VVohAZ)$8%=V-%w05J?;#w2$JIOd@Z9mTDM-b1sa&#^^YHg>nt zazH=kcad80BKj;x8etbxRMY>2;>2$+w3p*&q08emS&B`k;*ZFmU=chd%Fqooqx<`s z3xh&(mxXpJnL68D;PlIbgO48{)kH$8<9(%gpQVY21XV%_G(3MDovICP7hM@Y%QEl8 zy9xN~%@;~M@Za(><{595&9-IoNNR}m*WCwbvRg%pR>Ur(yr=8$^)jJ`sQYF1Z z-tEg5lzAr^7b`~gv+Obv3V zxV9_CcD-+IwJCAq8+5Fl?#fknrm)sR%rzg*iaM$PXfUt>$)73;$Gzu~!&OfkEWDd9 zxaYy|bDMN1`%u{z55K7HBX9Jx%j~b8yFbL`uR{!`O zcb0hpYh>nX50y<1>PWuqIK)xw58#qE_Dqze`2Ucbn4LRPzh zNMRVFoyq-zO=1w@kH&au=@#q(9|fQc;|Km>&Sk7+0+pHYMFu?qjMs$NwMpCQ`D?M~ z9*M&S2aR!sis}`#uAn8&-KV%F{N*toYqQh%nR<1WTkDT=R)pz@qVj2%wlf=LNE*y& zAM-EdA2s>F;n(e@oRX>U$bfC;1(&V>BVLDjVw7o;Gq^unp_fentwQ7RpTAxmgPDF| zp=YlvS!hcAYo~e++WqVYaWY03eWe7;Z3>@_xl{uITTZxK!d5P+zW~8JR`>D`fB)KL zAm6s_*|k_r-xK34<>==rj*Trr1)B17&|-UKB7~0QvF=U+$IIN0nCM4$q-|8YVe<2$ zm-%}5J$>g#i85eXVjW$@Xn%Uwi?;6I_EaZf5bqL*GgoYoUIT992KM`vj*tC1*y$C#Brb}a-9 zHvR|G^XU}cvAR3)47=(SJu{p8d;w9gTH1k@k>uWnSN{>g?7f4nNSShM_8fR1Q54r`hA^7*4z zgX3Q>2#&zJKB~@4N!c4pvrUi_EY$|HeA&dZna3(8{C@qhe1NcA*Cy0GPuNoWIXu^R z)-`*Dau)rzTN5UKRn`DVk5eX?97ZCit5I}g{T%;zwBrDZrr-MirG$wnxV=>3J60)r zKpy_-Mf=>3%Zn1{I!aT;T+ftS729$G3xT4AR*p3ax~ zyip5KW-J}WZE6cXuzxx1+l~7bckLD+nbnH6X zEl`{f#={f#rO+tXEqbAV+M+gI(_(kK(;+BBg+{Yy(^~S%=oU9|-~x#~$XR?RX|;iyrOFh2Zc@JngHtNtGep$ORH~pJ7^K<=w*}b7 zF;tF+T5gcoI%;BY1ugG}1l7{IRODNs(fJ`RFf4MZdg&3HHryG)2ZAXs*JBLUFe~wa zyTrL$cU5D0I(Yizvpj=~dF zg6C*MbgL_^`=&(B-@fhbYf@6AbDa3Kr5;jCmok;mS}FXV8v5Bodv%w7$>&*MlItG( zv$&eV?#Xj<@%N=X9yc;JzmA;0fNKXac?KYKNgWB2$odGlaqQ)^{9B8qX5V`R6nfj;qOBpp=w~w`V(pJ=2_oxUs4V`y><7?Z6Oj_TQRYW z5o#(eSV7&$3m+nAInT=5v#jcYjxRk96Zzv(2R0GOYknJ3q9bK3ENke zQFAT!vD!amqu+X`)L=uF!@ zdQ&3_Kp-Ym(iw|zMy?j1JJqWr;o*RJ8C!1Tjm_B3ds!1&SfH`0cx@Oz>GQqYR@x0u zMd_-iR_}Y{&AJG_>z@@9r3u%!0$-35ylC`^pw1`e8(`&*Fp>r}+rEmu67H?NFFw>IY{ME%=`}^FT z1ZjoEsO<;w(pM@_s{Wx}+x=!^u|CwR+1hn19A0wRp^Ki6eDE5+3xeh&9bgELzDuh3 zN^Zp5AYl5SD1@()bP4@>9uM-vKr-r?y=A(h=Z&%pAx9~xC3WZS5S)DMnPae6Xxx6w z%93CsuvAe|K`U%qNP_W>&gS^#Y%T*(4DHfr-m+$LkdL9ISmy#~M)QX|9vZU_C6h%W zbk0^lQlv12?lm86HMtV#$G6f`kzWo{cKV@ro^(78LoWdbUC3P?=Pu<>$K#@=-}F0R zpU7o?s0Q^2u=B#-?^Y$0%$!{7EBj5ilad&9x3~B$yPvENO*|2n)gzMUpH$IQ0d)W; zGfIW$4c~i#tx3LB6+MOEv?S?lwwNtUD#z)OQTqFe`^A&gRV1nRcq21V6m*rJW$0m0 z_Er_4A(FscG@0(JBh)hmh)Gs}JDQO?ZR8hq7dYxc0SxfnfPPcz`qIRD4>fvoz>R^OWa)MVR4(3} z3Jno1t?Zfa9Aa4;F3)Z5H_{u>sD|p1eCo(EeVB^wz+FeI$rX_f-iLxat;48d4@z74 z&t#cM=0rQxc5jo4`A;=F3SfCj(Fyn=GZ~i4`GkX7@CCSK7)q6mxFPdv19^lFnSGen$;kQ&Cr2@}u^fH_JaWc1fueRLS{ z3=q`Bh{x_h8#ct6wR}?`` zVocW3P|-%a`Oz7F0BfPKZ2U_Gw5ZW#!#!zFV!q7p?W`G`zdSye-@~BpnAMZMZ`A5# zA!_jLyX;A=qK{O>ICWt_wu+OrA@Gzlinq;0_P|O^JqB#?3RTe-nDa~3DZwsI} ztFDWjZtnUk>6)BtV+{k*5TrF^;w83!!yQq@14KT;!UpY6#v-pQ;b`@C{?wHPOd7h9UO zPwQkg%Mf@9cZOLt3QEfnfSFm%@`5kcH6?jufyI&Yl60rQ>`beKnpPbnInt!*EhEJkKnsA_Q z7gc)3mLJJSkU~$~u(C@V`84<@n_<(9+}aRp{R)WVFt4p-bqZa89|ysMa`jS0pYZbc z?t(meF>yxSd&17gsp@!RUs1j3?#es0MC4U%_zxCOy!rC%5DF=NR4{~xfV0LLEz1c1 zz-da%s6;ODDoB6>wl>$5)<5peN@o6wG3+uQhOK*|Q-K9Cm6n@cuBAk>NT8gq$kUYs zdpX~=* ztDtv$MvXJ@foAZ=v)#3>Tk}q!HLmr7bbU{*eg0KLS5&jEC~4U1qSQ?qruET@$EV4qQIi7+1jKzxx8-|GCn0arZ!weqh{=8-Rj^W>E4_(;0B|nFJ)lMprw-woNtSj~NBfBJXHvTo zLe_@k?yD&_)oLJp!Qj74qXLB}+xu5_jpinfGBdT%?HVtf37p>5S=J;o!z4XYnr722 z;Og=0xq3_ii$Z-BL;OVi%%q-O&*08FJSJSmP?M8aN5nm|`Aol}k=35H32krpt2iom zv^IG(M-wnReUF$NKWc1wO40v5$+{vDFepw&1{>W3U0Pf-PI3tKQ|{n6N_`xmh$iwC z)HoUHj)1k~OmYI+HJ=EUBv*OAP397R1@^gOwR6VG@IOB3g%Z;`i)sBGKv0QyVfi9n ztgEBc?h2^%HC8-T0@KdyU)3zIXU6L8lkFjXloY@brhKyQbzw_S6wT-LjxXU%1&TuwlpK~4s1)6BB zY+W!3A-3K2zrN+36ja#~aS80Sw@>R|4W0Hg^kL=KaOo;AORIffF>})Uf=X#$od>sVD!sBdM5&YvGN7203js0R&KA9N3V;D$bD(twK zwE_aoFVnPvq2xxvM@?uOS{b5cr{3=b^Ub5`>p4}Vsv+ibM}x^oJlbE z`<2H70sTO69+Y8w5QglwE!o-D?EmkrRkP;^Gc*ILu77J2m7I~nq+PH$2re} z9kBbq?9nId^h>9ECh7$#pUBRtWBSh+Ej{S4BD2mnzm7}Ooe`l?8FvBU$|bYqAlnhW z0woD=$$cT|<$B%9Oy|5vy8z=-^(+Y+to)ziO@S++Z{v zCC?N?hN-3kqAakKaA)Y(1;rxN69bg>$@10&f?hfA=zEJ83;tCuWJ?T0* zEL#-is#(lGB8N)Z72p5fjlys(P4Ymuwg9{lrjVehuzu!jI}%`2v1H4y@2!El!l^aG zhWwaaUPXwRHn@NtFL*Wm;U;ip$wV8AWtC%gT(%YT{)5FNWIqt<4_|0V7b}bs$ZGiJ zf6&-=K7oWrk$C4lm6E<7n?Nw1rBZ4&05Ao|S&2f1S;*UQb)RaxP>^REw}XJftv{a( z;I%b{3}`Q%h0*#|P&EMgE8n%TIuC93D27pS3n{KH`JaTa(7NMNN-5W&vu~SL6i;F8 zcz&6Jd#OvnFOeG|dnshJktD%zADH>3Cf`OGL4K47k8)z9Z7<9qA&{5z#G^LX?ag_p zy!0nuRExIhK9P<}J8eMzTP2Vc2~N3{K~N+NDyNYRLef?xnd?ePqDBGFkOgogd!9M)EJtav zzAIKe;4g-D@2o{DLmAVR!kkD>z0+Na}(iyPg3aF|VWtf=fselJCnvj{(=c1L<^ElAAM?<_a|d z^O049llY^7>CnOA@S84nhK6eF$hZnE5~TqxP$|n2Nq68;I{FXxR%18Fw(5+QYn4SvlSHY}C)+Dw(c@cN1JE2( zsF~kl&7b*-l6Xz1_OpS@gx7R+MyZLQF&&BWk*++<5b_2UBc$ZE&}l9VyNIYv1d%}& zqH9G`c6U&0xC>9kl1LGCcZWIQi9f44%6=b0wLAa~=~&();c!b=m+J@X2|fqpymjX_ zUA9-tZIe4bxz4T0Fg)rBZ(3_Pi7}bA&sWXOyebV`+L%jJ?n#^7WIWJ=@j+;)Y1eU% z+r9~RI}bg?jNyuEfONm7nbRX$*q~0^>piu){_5{gjhh5u|48+elGOr(%?i1>dYml1 zqg=PQ?4d$T0AyIRJ}P@v0U5FlMXuW~LmYwPfjSwL0Fuu4J|i2R%A2l<67%5dS8Yh@)=$6hMPfyWZ}}Zs|wy03E|zB=ssVIn+#f@4qKoM zFrHhU$L=xC`zP1n%^c4cIosKsE8wEbP?A1-!`x%p(K?~(7Kwx2Xc)h&>Oc`9`!TCy zumeS*_6MrVGh9NqWe)NUvmv04G*D5q>T@$KWf@{=T3?HnI?dQbX}3+DRHy1O9144&26bMv z>R)DZ&$|!YaPF)88Wj7=^oQf?Git;j9%HHiBRCG^W+5z=kq;iM#4-*Wy@v$9k2fb| z^ZX{AMMGk?HG44-BJ3?t$51%bREMXI*=H@2SKYv?y#qk8a2P9u8BMp zzz%^vGnrw-^Q)m=?{_(u7&C|l&re=%lH?x$=GtNvxsuvjq-_r0-WUN*&L?Px0-?{4 z#VUCb=k`jLfSI1F34vQIYt=s3WrD@bUcxkQG7Bn3)$c(_xEgIBO3jXQ=YnfvT<$aP zKNJ?LahXUP|GmDzMC4#GKcI0A9y{{}DbfPDEgvW6j>o?`bM0a9h0cq->@8hwnkLTO zZp(Q#lR@*ff`VvoPiFU+uIz3Op^;P_8z6cg2CF+VIMT^NYb2G~Jdwu~-86-^DOL#y zEJP|9^LvQ>xC@nBR!3a7MkE8T)4KvrZL!p*7Yh}%^B(n*zAW6doll(}uI+ZB;e*

+}wGcpuj>XqUASLAF4-;aN1nBK>=U4$I4?Lqlnbm7z8s= zY%VN-oLO-YU$kZIvRb8yc8Rp5rKPvA^=~1AKp?__vhHYr}jN7}M8aNEt2t$-B?C?I57V$)#ApP*>m7Q9$Lof`IE{Sjfmm_<-!&tj(TxTk>bn$NC4emu= zu`hzZ(_ku%?6yG7L@xE*SYIOSM6GC31Spw+M}Q`2Yb<<=kyr$PZ*|beekx~V4n(55 zAVWgw$M3Evd&9izKn)D#)Q5MVpbYTb;h++T5%HoOgBgSEo(?*N$1qt{V3LFTO5F9r zoj1PS*_{o2pK?>lAdk;1slNHEJwEttBUw2)AvhN#8$+UBEUmTJR&aIm$L#p$8HbR5 z1-LOJO@*}*zjS~1Hd@P>PPgWqF?Q1E0vb#Gcs3~@-=bofl_$olXS6onC9^0S^@2*kJlCyEPgq*Pl(ynPU|u2X4imn zW^zv5l&Z+_@7uOhCw5%%hzq~OQ={Kou1L77PW2<%+2CcMB-^XiW%$Btd)OIShWb0) z*_Rjvh?wnJA>cgszPQ*%GWVSF^~l!YH#>TsL^IP0J!W>GINy?>uDd`+@c#;(taQk> zKdcOEk!WG<<(lCtZw^$o$S0Z+se$6D%AX-kM5Iaqd*Hf$YBejr_uuXm5HOjn%=?Z2 zY_HlwPqJ>aLri1w7618_piM0lgLAJHAQ2vt&g?iyI*-DU;%ku@{RRDMZNL)`Dz{1N zu|S&jS)xz}@Gr^G?8JwgCGJ!AQ#sKy%Kr-DghV*zxB688P7f56S>pNl8QDk6qe?o> zxx+6Pd#qO?UZN)1SOjF>?Rjn(mW2v_+K60B(q_15wkeJxkp+lBi6dLDJ~Zh^vOK1q zN;LNW=eyEP6)YAzYzr-i*}R>-BpjA{R!?IS5r9NcVq`seN`;OseLJMTkcjrr1iyPG z%o?J@g6|-OvVx+ZXKVz`YjHBMEd}~l zEP@I&v@UBc{-&EOw;`Ik853|C%lLr6@*e(ono$+*T?#xzy5kVs5q=1%K1Got30@fkX=p z11{W>;=*K6*V?6$*GTQrF;n;I&I_(XOOs)4Vd^`vb#d~47CC>C-8qoLJ`8qu{d256 z6709JFfvqJJ9Y$#C4Owzc89u)D2Gkb2{NqH{?T&f%_m{prvpd-Isf#}epZ!_=PxHm zkPl|22qv*Tm7s{f{4q0A!F=D_JBgX%cTO|k`Te)wFaDnP!dOUD^m}2=G+D4Oec+Yn z^fb(ST7Y@JK(XOiXsLMD}@20yuilhT1#d`xle?Pv=_O`)Rtm;x*I63D%Djs1ftL(u(6IWUc z%lsIhX1LjHWx^j4EgU=Nrz!iSEiAv^B9HL=!1`s*>ko=(I^;ILKAWr|nrRGExp0tZ z2>0&)O8)+(Ne89&g%9%Y%v`%YQ^cMuw}q2nIMVX8BMaZk9Ww>_YwJ3-G-XVj$ElQc z-d?o-tU5SdtxB=;T5xMKa(gTj@t%?L3gQWRqV9!PS<|b2A4r4P=#I2@;FRj=6yJ&S zCFzg8K5Z(its>^N!!JZ+T3TA|j%{a5No8dto@cif55H?)yv|C7;Z*WhmUZOZT>@ z?f0EK5dSRx{ZNY-d1=|>yBgY1vkmiKSu%eoUYQ_SHS(L*&gUWw&in*j&`+-3uH+oJ zvEHK%`Op}JXyr{al`Q|f;M{DotHcfj@DcrLKAJA*FqD*$A@5E`r>LS5G&eu5ATNJW zP*Cu|!GlcKugd~G^v>VkKeEG0C007L0lWw6sZQ>pk&!CHOs311MbDi(2Y$LgkM;QA z=;>cuV8l1Ku{D1RFFxsT1~Ltc>Aj_Buqo=(m)Xc_7lwsI{~8K|jeu~a1P3eI=X9$o)v}>|*gf|_$@zmgGul(yD#Q~D zwqN^fy#wxOno1In#o#}R$!c-nP>w+*cttI(h%2WhLbFFl^+mGP697#zfQnmG*B(Ac z!VJc1*XoC7QZ6beDl%QWb{_(6GoTcIFD)%KfS9VfDRo{{LZWe^EuEZ_G7hregur1; zuw7B|wy?0sFzw>04&j!2`}S=Rzhf4p<^{cfwDU6I&*Fb6?bpl}6dDS`#cpYr!KSE#7~=4BY+S%-#)d2(6u zHfBo59Ka>b07*<>FEy_X#miuaIA>FRq&RyW?yFKRh$j|443Fm(}R^IR_3L2;wpe z<1}fH@)B4R{qp6D+wiYlDqU{q$60XM#8Ew-$xP+0Xa@V{v}|yVTh>9WI66@=A#F}# zu_SK8LwaKq?^RZm@=>WA<9D?b^qlCfnK9lOXtCc_>{!NiP!H4=$~x{fn;gqoqkQX7A89UD5u8ul!AZhx=dOC%t{fyROK} ztGX_d9&Kvo@2D#2s(z!gH;-UnggjE6RxRY*T@#d(6#0R|I`aGPb)Xh9GE5rw_VIvgY`;_O}C6!_IVGw=rq`bPK?V>_8<&#TWz-@VIW}zmdH$$b~F2G_Opz5{t#>x}4ZWdc0rC27@YD_jV z?BK5_x;b(qnr!+_4J{|D57UoMD6l{v1 zKpL+;cKC3;H@!rL!=jCokXK^^#ti2P!>ffPItR9?kM)EfBAPXSTB7m@_xh9mC(3uTygny;?**MgCi<}Gn z0=4R*zkdD7gJ(JIfewTY)4ZhmHn6epnhl!)nN=7Gd-`-gKZxhoAj6L;^k;mB-F)$Z zhH*^p(GA{h$+QQrzya*tF9uGO;HFal&*Pf=8uscgGYd;I)T++ZE;%^anko!Wrtsv+ z>>bBMMWe{;Rh5-i3#0eX^4d(KWx}&VDPKuQKhA^#-5*W6a@(4VnE(CfpU?WOT&%3p zu#&BFkd5qd z(1k#?l*!)L_|m8tYD))Lv(egX!Lo#1(pBpv1Y3EHCEJv=i(bCF*R{~_2qF2mg zGch`9Ghs2&dJR@&%WxQ=x%WePZL<=j<>h?=vyXtXeIIK00pM%_hawTq!FGiNZWfh{ z@55JJ;3FD#eFyRg`B0!)CH=7{oVkYT*(ymY8TxOx0Mu+(--DvTJFa*!XuA-SNMpfC*n~XyCcsAHK72T@oYWE& zT>3C>@zU4_=Pc9a@ycBDX)nR8kI<0F5FYdh85thn)wt)+e-lx^6nn#RSQ6O}78h_3 z&@lsEMN3Y1x}FR_=>6Q9pt$k7>c(hhW@b2+%_wCPxOMdOj7ndUb1q*|`+QG8K)?nM zi@Omrc#Wr4;mr5*@p)v+^3%pdv{7lU`QTv1`}?(Wqmar6c-VDL4rM}@U1CaFZj zamjs5r>9*d|&0yQ0eQJ5=>;qrkZ6( zw95w3i8)uvbe6|t!trC-;^fB!$4oAEBp`wdXL1Y^Zjd4QjC{tA_aoVn0f3ZbrYlzx ztw*yRijr>iF~t~Ooi;@$B#n^ zFvGbZjyaaZ4Hf$Aq10AR*xR@70eU~9(s+f=dEssKB1lcXH#RnYa?sGw2oiA4Rfj`; z?~;C>C@S8=LhsDvycwdCWbB}rLWn-$C6>K?Cn!^W+`;dOGkAIKkCb09C0v~no*MXY zdtuG@mW6G?=BE1YO@8$CjUMcM0J8(I?p9Q(2L&^jNpDuFw1Ru;&kD2H7f$t#)2P}v zD^omf;q(m&4^IKMMjZ-^HUkk85BB`-vqNO2_vp-N!(F#>su#t4E-_xcT2~hY&QmTl z*ja?4duQczH_sIG)2_ZiIo>Cw#$>N8A~r1|`sn|Ftw z=QqRQkIA{t=FdCNZ0*W?g1~C9!ZHyD>@pc`TBv5M&MB{&l)TO+-|;2|lxjRyqY*PR z=Bw-LRd{^%@Ni$>dpH3+Ou@BKaB#?d>EU6Nbid>97ymE;Cxae8KR=ah(@?Osv2a2f zL2ZI@@G|+84%R#zDD&jRGe`yLhNSQo(9U|}=>EA)S6V5r=)A!t3ifp0xM*-kWQ#W607tmz;Yk@~WVX>q%S z9>U;bCFz0z_Afr%-lX4Lka-ZRMQ5Koe~ZY>!=k-#4V!q14xH8b5du^e&J0^JG8$cO zc>fh1wzRB_iIYP`4)e$5p%RzC6v-jIkA2|6?b2$O;YT??Va8C4f`kj&%9F~@27^ohQKWSn!C zHNH(vMqIoBvJ+uHGRTcn_W@Uynq%6MnNXtvr4vI5(1b?@)9(;T(awUw$!UY~8gg%hz4(^`{`lh$ zkE-%gcimf8j3r z8C_LTMYY#hQ)2Du%8p{@CgBs}9J*k;*Q}1{?2$v}w>O$<4(RCWjzLp4JUof=jSa^! zb7S@81Hb*I54H|jxtcKk1b)Y*(PkyhW*~HRR%TLIrlzK#DOLoqaFGxmGxPGQ=GjiS zz`4y~-dh~xLU1%yOi+Mbu?EV>NZ_6Ifu^ipqNy_nKb#ZqevI;=;pXShH-ia|OB2^J z3;Chyzpt;aj-^*1KBdsewzqhnpTB>w;!jKv)BlvAE*QFD6jdX5gA)La?FX66%^4E` zpZ;t_H9XP94!bg`6N-;C=h>REXcnr$nZQxd04i~r`thuUK|85t{vaY=c3c@G~xluUqb8Ll}w&6_e3 z%F2P@?@1;6a>m$Oi~L0u$bUj7-qPW0^mcpw!OW*f9O-@ zu{1dg*QNCEG0=l1T)%#O0g`pcpm>ijU?CSe%szqtH3kV24X@AgW|;K|fcGK+_LCwM zyV5MMkPndsdidAIbpAJ;Rz6iPLI@M2QUvZDCmtlfB65U|$U-9uDCar8ol=mW-$ZQa z5wg1W^Q zKb+h{tn~myo)9{Xf*?XpT>RxbR`vLOBq}|z|65;K(T6nwT^ZdAx7Lh2&+=wH{@20p&dCff7o&l@Mhe2hVjjF_c5c{q7L<(MvI`ivL393!evh~p{lleMJ^ zr?f4aCC*0;yBW69E^zi#@1(X0kq!X!8S@AX$^#h9ix*?C+wQ|?kXx8#(!rCP^!S?1 z!~!GO8(Dd~5Xco;w2rH4# z3Dvw6EYDvJk+8AJs$PtU_!At7;Pz)JDJlE+?>C-`OOX+QwtvUZ@&t4XJ9C6Aw*O~Q z$SaDD<#|>erM@V&DrzyZ@E5cgKO)X-bw2OA?}R;mvEgIbq$IISD-2sp&}F@;67Eh& zEvIdSCPI;K-uzD_dw~5Q8EqoCZ7LAX3NAt{%A0#u?N0`V@?nR2_wJ=HoH%tV>gm&` zJa_`3@qS3(TC-A#ata`oyO&B_Vu|bquWXqHBjJsFke<-TJ4Yrjc?Qsv2D0WjQoT8h znOjGb`|&u$+>0A|Des*8r6S~Z3E{VOhw%!6!&vu;`);VYD7vm5N9F|LwWeqZ3X$x- z49GZ7f%VAD&)-#_)GG*9TFQIV9+|wzfF;W;XMik-wi`Gz4Jo%@6|1g6~{1Ua~rae8wMT=%#fv zcGVC$XN)F#j=xl zcHd~P&@n9X7FfmM(bK)>L$q<3=d44l|7oU7)|4o)*?H^mr#`)xte| z^oX2-f&tKKk!*LxsQCEG;oQ7D$Ml8!nxSyqJsyiph4q`+WJF}Zh<6(qQB;WeZrRZs zGx~hL_;ua-p(4k*#LKegV)5D>mK%;#?+#$aFZ$D8ZR7s^-L+(|7ue0;A&C71h$wVI zmE#30B4-+osrt?3p6TM`y7nep2V+34&=;STk*P&r%*V$k4>7=qgQZ&0JBP`ikKWtK z6CxvTJZ`b-ughVij%bd@A3s7nNa}FvJ~Ix1Q#+r;317ut9ZY|41z<)BXVNp(RaI5P z4wj@?2h|6^@#)6<`T6-Y0$ArCDe6$fjQr%uN5s7lpOLYUw%*m*dFsp={hjUbRYhjX z#?sQKNRX}yP?w4FU+YT$xQT@i`{-zbMdQ%+a6nvTfAZXG67tbLe4_P}YiJ*MN)Ic= zH8`v~{yx#1P!PVK#8XiDjQ%97q@5MY{vw!q+xZZd{Cb}jyZB<=^owW3xVPiHXR{I$ z6P4HW{}oR3MiXE+33dIFK#mZs5ewye#HFPRCtToVssq3fgLj{A%P{bnn`he=)hlFx zrFx(E1wkY!+!z+aT;tbm_rP$tPgBf-;OKMLt0=XN(El*M8>^#AY74z&5dJ=JlBB?T z*%Mz`63X=tiD&7r{dng1A#BD+fc?m`qN}PxLb&S1_N~bBV;NyoAz1n!;*WoVkVcB*h?p$UHBQEsGM+VKU5s|+|8|B%`ACe@7j11J~r}Z z$)Zslo+!8`zD4QrI{(*kjwR>gs?5tF2*_}#pe#F%xgT2BA68H&1z?DH^**3|Z3+NG zQIM-Fjj-y)wKc0#VDT24&0GGngc+=dwdPxnPM!A*W+M&g%!e_u0>aAF zR(ujCyjie-rz~kYS65DK7>e%y8kjzn{Glp;BS^VI$eG(Q$`4?44MC1GH`{lpo#j4= zj*OH2-@OCpSqb=)Yf0`C6UGoYv~><73MVeA7s%hhlYSFtcP26Y*%^~o1X51*yVbQpA=LG~WnXcO|5L-)n4+0wm4(?^(T2iau*XIII zHysASTQCpi1ippCGJBMa$j6ivH$E=MW~B>EOqC13k?me};-|uWDm{Kwx$1kI5@^kL z!f;i}IrC92>qBI2$5u2({qak6i<>2eg;Qq+ld|@8yS428W-oxPcN1hc4FaL?I#_TE zb1watI2@K~(xKSa)@D5gh~@q1?gA;oIif=aHDLy)r_EHH9sd#$=}=3V&Y^r?NCmAQ zISPK+pNv0p7^o|`p+0j-eVf`69ClVl`n-F!E`~KT zDW&HZr@jHOPrP~!iI3&H|EfwBaBOXAf>xt%;ugv11dJ^U3b$zD3cFD_5)wkwI3CXL zs7NH)$^%n=1qvaO8bPyx{0yRGrru7%ub>p(=R}UYMtKc`8b|*R9c#?R9VNcTyAM+1 z5q=~$0xHv}0`8EU^TN%ICzrnWys+D`dgyvWQ0qz8^NL$M36Wni87*IH)7sKMuU{+b z>wm01*8?GuKE#GGO({?f1!kQXta0w%7)avxotHu|8jkVU$UoQy&tA5E>BmFnlj~LB z1l|g-^VomCdFeP>ITotW9<0Ni8;Cr`pp3P-76DWW%l~`gOXQ zU$^(9!Iq4eyOv*Y7l01f{b|FIv%ISMDlU>Yf4a@g;5NSiw^>Zq&@di=NQ6e?6TyjY zIz~c9#s2+1%hx-=BUY4`i_p{4XC?#Hqz{GFa{FI0A4@3!d=3WKoHI2r5D9ykN&_zn zdaN{VEMK?kG!%?0x*oj*M2|_b7ZpdPZ|=`I(~qX&#b|!GtCL_sJ!F9+Qq|Kxg#f+Y z$SI%!Mx&`SQIT*b8`c0=1F@9+xtGw1@6uQiNeKl2@oJXY&Vc~61Qn@Xc^6camoq!r zCA+$^G770Ee0+YeMgxx!Kuk(OLK5zx6CPfp1iR7_HA*LR@?S`mwcj zS_0BQsX@$^A`UX?friS!(jk$cM%Xl*7lUtNH2ouSZ@W4I-|ZTSV*6|7#=ge8J4buC z|7}Elq;TO$GXZ*kr9hzh0hE5DAbfPqcvyPmEZ92b@N%eSYgo|J(^I6pj!PY#Hl6?_T-2PQ?g*TS$&0^fU!Z}Izh&KoROsufR2W~|u*2=! zPy0%S!PK-DxfWIPL$-nYdyeW}0K32eZXON;@!uH@Taf>8;?43VIqmK2&ir>aS3W7wga`VEJRpWHv^Fqf+lqqFOSlT(0GqNJn*6r3wc12#cRil(NS z%+IANlvG3GD{H&8pm%3hW|=(1zzMW_9=llOi&s>f868oGL@N^)T(;i&mD3BNQ2kMveGD!^qo-LajQp*7h0GL$a z!GnOVOtf|3=N+9l9+e%-Be45JS>!kX>^_v^JH!`MO_5P*a+A`aZ%BaIrIz+35kgl z9}1dF3KmKCX~w@7{sK0oJ;yS(e_+69YJP4`7Fv=T9(;P}IL*g^fHUyu%@f?#M5S;(ylIb%i$mO0IZL9&I1!S4*he`xj7l{7ZQ>Pgj2_GSdQgLyLCH6DZ7`- zdv892wu_AGA_LbcLDzC7F|9JbTN}OWVCQ$vm+JnDW|@zh6Y(!w)#MhQcN0kWF>*2 zPubXTijIxN^JQg8icvwAW_1}lmghj@LVvQu{E+KnJ!KC{2y1AuIS$pKjVwYzIKM-_ z0B9l7-Q6vfe18(!NsqT@CRFp!kJREp#%*Ss1PS7zYy}HQ@nNVAOe!AAmqo%ZtEj3< z5aSS+kgx`Bt(9++3v?`~m66ZfFJtpEDO`7ACdJ)ru%`wJ-eVU*#QV(c__nyLq}{#E z;N8jk%*Q3dg^l!$jl}`LW(0_#!+bRt!tFt)V+2j9t&g`Wl1(d;%_x$sYS<;1m-HkwX9HY+64%E)@M_>&&m!TJyIz&9ivRg>0vp!wa zGaSaMo;wPPZ++Rq3kbyoFr9OGqCHar%4dW_gh>^usjM6a<%Kml6J6sdH0*Be+qciN z=BF1V#Qe@tcCBx^?D0Vnacd_WD6^#AhN&hNIoWpBNwV2;S)0|aU*3JXCa-;3t%JkE zG2pDITWKyvB$Ym_2PTrkteX!3#DKebQqA~Lah-AkfpteT1E~_(f!cs;C5aMG9}ka= z#6p5^>2MglUQaqf4cBeQf$l$NVD}n8by83;eae{z)YUH~#Vj%{v=kcd#<#XU2zFFV zeDEH40s^FBk=8)))d*-&G7ze5om>D+^Mj&>v}Tv8088T`y7gn_M{iA;-hNE2J@&9c z?%<@D4WaFtP}o$y$?l;bw29=XI7h=K1sIK^*`N`uh1<*FR!CyFXcx z|A*t)Ju?%pJgeFl_CPi`K=-cTrROUDLKd+isI*L*9sxF_V_6UpA>;}|d#bJ~07{$T zW!@E>x()Pn3!BUAQK;+%EGU4PxzOT^1E@7vbe4$l2zB)F@yUdC@eb}v^kYEnwLk~Q z`l!OtzX42z>=hD7dKHv|<0f=nU~@sPw7i_~ff&H zJ^J8Jkpzq-L=dUKGnc$tGk z0XqIA+M1b~CZjj%4C_fMc^Nbw$WTbRfK}PORIVi`@Hl>3>D0heLt8|1WlDScN@i9r zzU7z6@7-W!6EFQxke~=#jn>@)iAEFHJEN(pii(_3-(Jwk5THVnb=Za~Y#0ehNUKK_ zJP=grs_rD#aO6Q!zbE94Ih^HpXv*M$Qp9zjXNU%45};Ue0#MpN#Yn04XO+XA<8a+_ zk~7*H85VJXH~gF*1yyhxqoN_c3g~#81aE-$##oVa$h-mfPYlh~t0_mNz&5gpPn)&khLFNRpZ!=8lv0BJ@BV>YK2|oInu*qWxRtB470MiI|cqhmiV>O_)X$ zdn`?LB@n3tuB%t?L6L;Ie@hQ>IwvRx9-Co4=Wf0 zRo#2bJVJ6FyTza=((S>z=eTGI%?efW?NVW>kyiW^>IgC0v=r~_<-Fg(VusY3{)aJK zl+H65%;oVzO?8UKdSdHD^fXD-Fts3B%#BmcHqC{i88lr-)H;zRwx82MWRO|@tQ&BM zt)s8Ng{ThWSH1E0#~WZF4y*ITe*Z3-q?~>ixG6LQ$lpwW0OGFh%G#PC3@eD&HW~J) zv25(mY16k(^J3q+wsm&P@oP$KcvEV4)2dzrIhlA^VcF6lOn(u8_I{a=#=<7Gv(-%Z zly#eR9kb}FIHOvMziVx-m7O8=IL-lG#)%h>faHcRfFg_m@d7pr(`6gb4em%KKOyn}opNKs@rXt*en{qtLJEgur^RkmIT z<-Y6}wmrQW_^)S`0p0^45$9wrU$PI?c35Xc{Fs?YaLB@c4tV`j!eg%f9})&eI{@P8 zyl%g&4MnEwy;h|*{FAldt@0%_$GZ!*npA=)52T9h^t(YFj_~k5EHUVfOAP%A0~jV< zYCr$T;(t}OAK(LZ#u48T`@$_xsZ%FU8~t&%3A45~FAD_&LrwVp(^2-7Ysl4<6R@NIic^VwMg^)HTvg65T z@R$&LCI`_`hRvjk$X-`b^j$2fx-UTHUU9_x6hBpeN2C;~E~<5M+i>&w%40Ar96oPb;?06TRu zRVX+1#tdJ3A!H?a*6ZIw@wu6;X-_a2LMLfN1yf35j~=U?tU6qbh6Yy%2C|(G4!w(C zZ}kE-M-24iH&UTl6>Huv*c`ySvt3Oq<$rmy z7lIC z)N#(5mO#mW_I(yOLRvcrJ-&9Xny)4Gq{V80_clOKyD(c$r)jf)CR$UX0T8!L`}xNx zCV~nHPz@ms#G02OTi>1EeeL3T|8ZeZ#u1=e!ZXyW zK40qR(ToX6$SYoqHueD=FIeyA7#1zTw)M zip$r^7JkFb4OZ!g#4A{@vo}_s@8Y@q^`{r1&vX!{{tfAx0BmIe*O{$w@zFKe-V-JvV0ohz1I5+W~vcGVO~0_U&6xH!ICr zQo^=G_yEEyz_C<-s(ja?^?nUi-#V+{l8IAyK;jgh%7+97DHu}8#W%ln?(O)giATg9 zy6DsFkl4ifZ5OtH;678o{(J%We&80QSpM&GmbQu*T4x}d&IB?)XdMaBAZWA(VjluF zj_gmLuEGlVP86j9b>Z#(2Y@m7PK2s2ELcHUfpl7NadCk8wLoSI0HVr9bj{8hAG73e z3DbGw@d+SLWix>G-!|$ZzlLwlD8fa_wL#qpeEVa`({Q}dgWi_i3|4?ferC~5|2Fuz z78%U&J;+-*&8qehXfQ@4LSbG*h>hLA%ldh-_Vq}3R*ehX%^kEY#IUAI*&ihx&MxjQE*8YMj|gs7AH{W*qxO4G9tc7jM{anMI59!f*REd1J*80!Vy;J>v` z#}V{N=D{zP()CmDO6iPD@sXhplJ*(x9@W;X_+qiChs|Mmi6VsjdPE_ z{yc8$(jYx1cw=*u1HjMffNR3QUamnm^*C5_vecZ$bs!&PZCAzL`^3*mv$8ldQwOI2 z$CLiQq(W}qhfv$C<<~pL)FOIcSuK6KrX1!X+bQ`7a`KWI-U%zC7?efu(v{YXJx=K= z31Z_x@i7Vwks3gYPftY00nc>=3n2k)W&^}{@*1Y=?la9KUrD(cZ(g|~`Q*uy-7EnV z79BV+D;Dx|ePeZ3q@DECTC9)K7u_3}gKw@0^BIw>TADML%U;@w8QOjOIH=Tr*9UnB zFjsZY$OJA!msRFQlor?j?QrPLC$||H8Bqeu+}xb}g9jf$1WtbXbUcWm!E1uJ(jUSh zm@W8O%uY4~GZT|I1j6^qU!Og@u~%&thE@C`+BjXXq*|D2-4&vq_V5FkezW(D+TeFx z36F4mU0ssIPSEH9Zon%jv9q_2gJnA2Q&beGiU7o!?Y6x6%e+-Q>aDh-#q`{ zAHQphVyZf)PW?u;(SG6pC5=j{;;B3L)>=gbpL|%vl`mNe{g!&-?}Jf+(I@}+59vAF z?|JA=-x)AJvCr$>vm7raQ|9Nuts zJug$Osvz1Ow&^(dR^l}qh-=`ANP;$@yT80Oo;l*3M4--oJg7YscmQW()-@dDwDAA1 z_1#fXCC%Fd2G)S=ief-yRS?Mv0wPgeB?%}|vVj~WhXH0>7cn79lsG6Ll98N2Sw!L> zQPK=blALpxuX<+O_xHzl&)GeD&JOqX?b}^l^;FgKL>}?y^IG$m$WcDZ;$w{mdx;0`jP-tvN~vE-G0i)AZ+7BatDl%F~*ZB4AKZ zG(*=z#l(Ovq*(!^84%+TVoIsXgON=@qJY`2A23-901Nzha zLN8&+3B5LMe*G|d!~mIoj-G3luURBhbPPMbR6VU{jJpz%m$kw;^AWqK4mCeCQC5sy z0OMJ~yA~BLxO==8lmHS6hLpxIWIOB&#UUf{NaOw{P9fl^_EH2L-M^TS9u;&5XJSbD zQuPeomA7VB<+QBnUvzKI?iHE^yIS|2lQS9RPv!#>`~CJDGXMJaYSDa?6nh5PpxY&v zX8@QL@!eSYn}>c_|HK28L7Od~kb^o8W?NP~d@<!`fp?3)uBn_`OolFwLPScrw93w;wH#J=6%2PKKX5J2g5pZY_u~jj$|!N4d=*HpFGlE z@Ft`kjzOxv8qh~s7v_V4!y}RVKIc}10n!#y-%aY8H?7f_0WWaAMsDjIO2)EhfPW>% z1e%;~Njo@!t8*0O18)}mhVBX0pj;Yf;i$(%xC!3DBz)bvA7W8+8$a^&%I)j-fzaoM zw%?@d%4>$z@Ya1_5@gm7hEW;Gnmc$gtv{fioG=h52b`ri@2WhYHyMU#p*Q2OG?Y%a zwNGvs$b*@7OFaPI{xF&+PvCoUhORmuB|fn)Rlv>kCr0V7OIrN=qVOpmUB15=52knr ziJLYyd3H_R@aq*KupiHPw#x+ZS{w@AAzv~#n94sNAZ0#OtNV-}h+45pvGI0s% z*>6u`S*9X3{g)fx#4}ASD^CsfJ@u@1TU=k^WbKaC4F>|Bbb*bwS@}F^TWexUHr-GzeQ{8+$^l|F&Y=NL z%8J_%c}--R>}8v}mD_K}DOK+^6skLyB)6G-b@~t5lj5#QyZSf|ksqvcaTcHGnhv=; zhq081jV$0ZDPJAUHVq`l7t9Hx-&Tr811+W|sMsPtcSJP?S~UI@u7FE9makLUSny%mkW3VGvSn3Yt{kkwL@`D1CGgV5T49E{78} zL^dhnKAYbLjO9iPD6dVw{cGAQ6+D))gPBPlI~U9}Y^q{sq?gUJZ`vTt5RD4Iq|ESI zd<6XR#tO=M1&`8|)n#xEn-HliVsY~CgzA+GP~y@ADsJKT0%gQa)>^`YxFBbSLrhN_ zQ|=Y@5FWBWtth#8g5G@_cSV0eD|?~nT{=ghy3^A1(-@DM>9ZpUrv zvnRFkmoQoBP{=S0WM3pVzuugti~LXuP@`5~;V{fG?V*53{u&5!a)hmgBuzcNuKSGl zgS51@hq9{nslc|?34oEM3<#x7=Ghr+ltEI%AqMWW*e_^E<+(=fx1H2G_S( zSZ8&R;$574T8Nm?&^wyPG)n<}*hWvqra>$y>Xc5}IoOvt?XdynWx?Qa1v5e>hOV&DiLB-D7sBKqbRW7;DycAqzDqVh9}u^Rbq9fX z42%Y{8xZd~L!-!{Viwxn<)gCP9JANj-=)i}JWm*@ygR}W*T**kwpz-?w2Rgl(apc( zcK7peV=pUz8z^Yh)mvJF&)suFNGMd9sxmTviT3kBJOj_7jB`P#I0EOSI0 zn;*Js!5G)qot1c6SkS;EY~tbaSSIa&&0^hMnR^64uDIZ)dege)DeI> z%PLg*L@tik&tIcsHS*6qr(O*D2M0@4ytXy$%6%T#8@bSv^Q{PDSrBWGE1sw^TeQA! zGA6Z2R-ms$>mVl;c4=pY&0FtVQ z4!oH1~>9k_Q}Yv9*Sd4NlveqnD!Q`SR1HM=Kq;Mj*@fz>(Sz5 zdDY?@pOQp_JXRcatXpg*1jQ&v5KEZ2Klv`oo^L!Baksk>Et;YupgJ<#m5yrQvpwcI zYu~ju)_)tHxogf4XS6yTLmY}6tqw&5w@qM^O*0?JxO<$TRhCU0M_>PD{57O^snl}+ zO%YHTZgb=?m6uzCo~&csLoex4BDtFM>GL_uC@_aFD^J9rqjlq!;T6e=1F zdZdXTSE-a+`N-k~8Z8O=`4JAcDn3Hmyu2z8QhW!B>4TN;YAj4yJrYa`)>=EvAa5aJ zFZ_fn2S6pIp@0JC}oh@pS9A z$%JzS8g^|&2bYIVINqLj##rjc3SMDY2~nzQO)pNNyPedzw}K*%2EY>vq(CSlfdusJ z8_+1+fD~=&c#{Uh4D4$mJLM*|4jJu+JN_JDNEOt-6$iGFcnlOis(b0Fb9u?eH6xLM zlwmWM@$k~|lG;B;4vDgY&-0ZBqpQVbQSPcmM}lIsU2Rw}B_ek|{UZ%6>XMVWt;j|v zLC4>lECaq!4e${l>X!h9NQYuz9jw|XC7{6Js)hV_Shwcj0V5v^GGxKfiZ}u=ClOjm zBaz1p{D?~V_25c>fkyF8>t6((&1cjNI~VfGmK9%={wewMp;G3h>c;KzB{%s(MQm<< z*wK%Zb-lZfLne!c2I8C0nQE6=wp0gL)I1_p?F7~5D|g&`e%J@ul1e3!*@yo{KA*X@ z*kj(te(vsHLggzzPS()Z(wRV2o1miB$o%{io4F#Mpp3GoF}v{M7MsJ74aV8xdvxrt zk21>{lvvs5IP~g&k$vdp+IW>m^$QaVIrSwiEP-{v1cI*-kdqUi21*wsFk}h^Em8*_ z1W(qNISdC>Bc*15#z(+tAoZ4K?8j*9EzU5k>}6Z~dAmttT++s#=8uAUIlSRyDJjbA zzZ(<73f6A*AvZU3Ix8!D%gsG1j(0f(%1ZiD-i-E?sW`GzcX=G<`uc3_aw!iaR-BLw z3lh53%d>8GGb2f`VciwrL_)6eK!C(>x`U6+s{uM*5<+b0QZ*?d_B@LM3ht3=Zku@$ z#lfq?*80bxtEEp=)cfT8UmU+h$26r%R-Se;a&>jxckyRjGz1;1 z|MJMb0;ZCZ9Z5TBb9&}W_MxbJdrF1+&PmM)0Zi@@3AuA}^E$QyDod{~m9>;a1x8Va zmV2P$RbpR{JK2Xyl?>8o*Mrgw3WOl*+6aZkIgpv>Qi8ON$n8q}b9MF9NoUu#ha^S-?bm; zjM*$nARezKZbRNdYX>Nwy|Z0qRXBs8dYHKhbsfj?OW(n%u%4v*zZk`!P+{)G?$7Cx zQ~a3(%wBo_MF>yK8r>PGJSFn=8W{5eDoHJm?CcXD-|IL|H^yUdKCgJvm1! zbQliDRqS#5!l`miygdoXm9Az0t0HTT9rC;S&F*TZZibsn3c_1c&Ynm=Zbk> zY_FTIMoFU8_G9ekGS|-WsWxX9uw`- zIrmkKjq_#2Tr(-_H#7~x1;t$bCPfp}3!*PL-V*X2S=l?*m!3uS@G))##*ppDI2k zCQT3urX^hb$G2f!8!L^C_H_j|s&~z)=eg!F{Wf4!E8l^X;Idgk;ZT*C&FZjz}81&249o(05|wWQ0Kw zCr51W%p23GZH>g9<$n{fIf#f*7QzK2u>xKUGtJ|JV2OQ?`Du3}E!*K*vg);pbf|OEZ`%lE&vA2B{a(cM zVnUZrA6N~J*H<;50`CR;Hwx{~K{4TY;4R-;B~T<$;JKSjL8ctV$?l~C9G*X(@EoAI z!4Szhd~R1Vy0jzn!M$J>^6Sze*6KlqW@~dnzO4oFt8HF`FJEoa-K4l%yDQJvLcMMT zaF_jwHeHZWIG#eJtjeu^tC8)vUnU7jrq_s7UUKl|6(?|VV5f?O;KrAQ?$R4Z@NC*8 zVxCh=!z0hJ7IU){ZW^0BVplp^XOw$Ij90yyJ4Ljp(p!A#~ zL}G*(Hb-zQf#OY-v|PSy1{F4{-4=lJ7eST`0WOBljbh2^>3vgeCe`#5ZJd$8If<^` zhQD>q!Us1iu3tMIrsXbZE`-rH0ynAR9_7vI;JNh!kyH#w-ct*LpIiqN>LNX6_p)&# zgz&KME>gkyJ*wdw1h0(gx9{&aIN0s|`Ih2VCxOYd*^i8 z26A|fjA9^om4j;ZT3~{IN0mH-xyco7!<=Txvt5S~Q?gSY~e08l!`c<1(Zao8WYc0o}UrA}F|Zp3Lifm!I$E zuZb%V+$^8_pZM=bB{tNKR>rb7g8|J4Py5R!Y4^}oM3(9JnzD|{L2c%drX7jyo z#a8}4tWDB^gv}Prg)TAbJ4c)rT zBFaDGsFpCHOFa zhPw`QyDU|h0wce!+XZL&hZtaiLh9r#KrG26#pX5stg^?rXUWUwjt9W{ zMR2x@+I62F`n8V-JeE2>XCBEmnRUk8a5JzOpZoN~)vTUy;jIH5d$II{6ht3*n2{j1 zd)L3!XS}{_G0>}r?QbYXC->g3Vn(R8+QrcXwiv2c0T@DBZ27s>*2Mr52@moQ3x>Ff zVF9CX!92LJ+}(+|Y%}V?(L8qm&l?5YA;XXmZvw_N5vccl#OmX2*7IW;*7+RxxdJ)n zjde_*coBA#elo?GHAIB%x`)a%X36QA$5k8zgd?WvG1M> zsL&E4>5#HGZvY{RSf^nyQci=wf&`I^or$JH&-fw^;IE!gzmdkM@c0)O`P}yq;iJaX$6Ek$kT&v>@c2|67{aGRNwP-ruFbCVjYK{nO`@+8cOWQj0*IG_crY8Or* z*)`;phLzCEwDC^gvSmFdiv}xjy$jDjvObMs!e4GQDi)%6_lQQwT6muDoQ}RAK)B#F zv9A;BmR<+wL2H?c_K9`sBsYswy)bnYJ@1p6$nu_f$k_lyp9TC=r*Sf0C2IF|GBFubyi$(MeLdZB@!wxB!o+6E+b*!M{^EkqD>c0 zAq`OoO}}R4%jRssr?*1`L^e#&v4lQ5jk-CKMYE?M$yc(Z_F_weI*91R@!c}31teeW z!fKB&Ee5GVVbt|lX-QaZo%@pJ%k^dpAa*dC_R@_7!DU0A#r7^3gL?!HX?DPor2;YH zQKz6u6(ss#vfkY}=O^s_=D9mPw|L{FUIEV@g23r<899|lssg9?;4k;BE`W!rz&sHl z3o3f_(`o$;xS3t~kJrts$!nczAiRLWAOKD?u1B7?Dp>O9=^=$NaeAMvdckSFVC-!?k~xIhdAJMG_gT(Nh`>z1vug#|tcc*eOxZ%e!fSTw zx58k~bn~}H5oSpyTvt9z$T8uwBl7O6evb%7sbVzgKPSKs3zA^NL2)1f`QOlC(gc2M zSK0)aa2^)9jr+j3n`^YI&^L2!{|wmL829q|7`?LM6^EPjz|1l%ojrIlQ%pEM#U^|D zNp-_EdA&4Jme?L0I|1qC!EOGBVrd@O`diHPcsqj)@ak-k)(n8~JjfSEQUjNl4$FFb zfI6bw;Nw#-JX-h9K$Jrj>4WMWKU(%1dTbxJ&qoo?Efpq|u>Q%=ovrumsodtW;JuyZ zgcH9&zc`4()U)B9?aQVXp8Qy#Bv6g zQX);GgcWzj4V7h?+6h&-yMb*!nJR88$dzN`YIb_>c}d%1FB^U^5| z?a^r(%599ouGMN`-&bh6m9TmkXh62y7c#jP(3rQ{QBdA~W6kH@E|0~rcFEC%;5l&C z#FJv&^ivytrS%h7@%|jIOD73I+sFhhor7|$n3Bmcf0H^hcbV|+VvRRNxPs+M!{rYZ z{4~lx{EOu5Jf=9G3)7|Z`so`b>FCW@A%-WIm@%EH4$cmp_I-IS;K%`LK&#X+ck2zqjAjg7ucYZ5TmOXk5ooPhE|*OU}vTr1Xs zyC1>dG$B)-|90SVl*DO$j#^JQytUTM*>6jn&R5b$3H=o^=E{B0Q ztN|Llq5-c?`>$T*V!Q@#(Q<0-aC?A(ZWs4xnS!S|Anw#E<)F@jzbqHRSo{<6;7;(0`R=hY5}Y#Z_=g&-}F{X`JHc$mCbq}pBo#7)RyfU zHUCY8Uj#ebokl9mgIaW)p3YA=O0Z<`(?!`C)f9m z#yDQVCSecJBjiZP2kirn&g?t|`j@+yQe14hm|FX^D3h|fMd@2e+rl0cXTwP8@`XCp z;-q5?VhwNH8Xhd$IaucZLO_5PS>z}FS20y$GyZNcP)_+BY zY&pFdB6CH6%l?K2t7Hl8xJ`fRHx72))4CP>dTZW}5eKzv3t6FjJ8cdQ~QKfE+tWw=y4T(_;;i^dX-NldW1|mm{wpN9p|-n{{+yYD zh7B{3+LXH?_ESX&C5Q4x3TV@;>x(r&~k} z>5J}ex>=}fvNev9p69GKFCXFzP7$g$XUtMTYg-`Iz|~CXqSa**?whe6P2Qn0gAQh6 zFqL78wXB`odkBigQK4`UnlDushW$L^cH zqCLUBJ^8)ICb3;R^oUfU?&--cVNN-(X{g4^c}c6`>vy2J7r>Z!yL|>FMyH8Zgfj&8foj%d+g4K(Jd;-hjxDA z2_{FsYP086_w6LrhBybs%Muoj>&MDqE=F{A*w-m!M!edQD$W*LMn3KnLPNwXS?LHK zI6cw%_R99sN#EwCJ(sycDf2qs1eu_6Fa%FcF;|N>V!I&kaT*o*)zfQj1OD3p@*@jl z3#RS-)k85ed8P}0R1Yy^0S}yw(+J^Es34B=oxT`znaj=T^&j}AQDKUZ-VHvY^4%U-UiFO)r;#^>Q&OG3Qx*_sBm9(~p15VZJ59QVbEp$^HL+xtMt{ zTx>P%M>ghLqTU`jHe%1Fse8Gn3eid<@CcP)zh)D3!K^;hM1UM!f<+>#MJB1h|DwruIb>K=c>y> z+C4_8?-iGhHjAz^PX|A#T7L&Q)0e>H0#}^ke@4YcR#lQ=rBo_dhDFeq4HLvgS?mq+ z{-GO~l%aLqm^{^9G&s0O($TE<$ z(a^5-|Ff`i%6WJ6pQt7>$OjE}j|y8_TQ1#~TGJ|jw3Q3nTWgy5>ezPvWI86?zK zFS|yu>Hoeyv6wpm>y!CrC}JDFL9bXSRl;8Ie>r|kxA6bD zH~8{Xi)BzeS_k#KVty8G$thp{msH1xz5Qi8FAF!+3jfw}~H8}NmYS0afN zc-1ko_McuxOIrofOD(90E1?(=@=X3#&17BTG8%*sZ7RMD0;g=T=tTJWdsu_=RLOa0 z2XP!DG&0mDg zJXis_cu84*Q=6QTA|OCJ2lO8@o}JXU;^CRL?aJmx?)hB3$(9JJ;c^DaS?Db#e@0%w z#Je5pT%8*}*{(hVof)yqYxi`a%5#t$?2mgHz0o&_$63z3219M1lCGqj*JEOk6E`ba z=6_I>MV@EA;qUgM*;!9eiMC@)C*@WVB|6)tOtl9VrgUOmPdo&OvbS?oROP8=)u%jHJQiV_gq);o0SP;D6IQt zv@D%-L837l%DcWk^m^xBFqTc@;E^|g`S#CCJvjrlwsWDG-rT@---yI>VNoQ~AMj5= zY7jThe$~gMG;@gh0L%Kd!7!YFy4$iZXxk3e?)-`OU0*59Hd8-FDzK$nz_2rz){OQ; zSocLmH>2&w*``Y6Gk(IRy@ihHo@k2Y4LmD~e9zJnmR^LG3=(jQtcq_SrIJO=CL4)_{@Z*2rG}aSxlonV#q9c2Xh^*TyGG z+#EIdxE)rIv)ZiaoD?ctQowk&a>@$|*4xTf6)r}a{rGjNU1WkXr$nn(x6R>AAX)(M zH}^WwYL_@oH|_oix5O|H%XM5_@32=BPgC?_wvO3kz(9U?)oC>whUC^mttrIy$8Od| z(mYZ-KiE?(kSAV$Cnp7QU=SBHnB9eTn@FfAA9}!a{0pQ3J7zAL-G-aTT{1Efv9KPW ztZ;jSEaLgjHM605()e^;ICJyI2K`&*j57u``x=_d`|9cRQ+7`vhUo_2D9UHKPlB*9 z$P>(k3dpaVSV5&bb)ozQo|n7TD<_&R8Pz@{tAt4hx3%Xk{e^QK@hjQV3pcKvc^GuBJi!Hi=3u@# zH#c~E;iGAD;hgCD0H=L$;O~MJK2o&AIzl#XJ2OVy!<_z$CUD?C>gIXlaQ{P}hiWQjfcAF}V20$3RLT>jPMfc+GYlmC)*8 zXV!I<@GUi`3k??ALA6KDE#tlwx)w4>~c1+DHHCAk3B|zB$de^WUAkwZZBbL{I{TMB*6er#oYntqnI&v zhK_o9#)fM#q+6k>WBRG>o>iIyA-yLya>t*1y))LstAB6pG~Wrnw00U&j6PDw4Z5$3 z$4N!zi#f0mT;9{nwuZKsuDm}0#J3uD?oRJ2KIKD~ZclpVA3 z>PijY!hoD_vQPEF&mx><-uN}1>cjPP*B&}d{`Y{MnMVm7glhv*0#=*Sqy803OMk); z@Y83co-xk!+a!_(8i|Y;-;|Wki3X&VI?Gjw^IwuuUiCs=RnI2u9eI& zr&0O*f~2$4{W{5|UwWv>a(R4O))1NX)onN>XYM`gm==qTh&^zRe(1xW;V%96ZEVQb zYPAO@d2MeidD@i9AfK*Zs%dQdZScgJ4a3Z=jHdn=C>pK(&yB}e?*8SptYmKFna>vo zglJ?pn8&8~QNjeq2btgwzrU~3zlGWNB;@j^$%q}8jpp(nyAOuzvJ?Lon_(i^CTPF| z{Jv-6oQJagXZ6GX5X(kIyH+a4Az_7BGRDZU^wf>>+7x zCoX;dRi22MIrK|r2cMs585mNabFtJYg*RNM;$)F^lSsn}vn{RS{yV%v>9gD;ecHN* zA&=DZ-9gP)Xy};Lf=`Q-CeaDE&AKj;#Xh{-_2t_284@ad!zbmg(58OBlpzuBNiu>;;ST2u2~#6tTfKS&dD|Ob?MHjm z6MR`|+wL}}u3cZ_1O1aCq*y&r<>b3yoa|?_bjE^wZip?c&P*>Uy;e$tH0E=$`k&FD z2TH~6-VUyhf3y1q*J3bRFBs3-0&V0w;6@4!3j+#XEy(w#WMt?dUZ0aEk(>zP5UH6z zG(nxAI6v7fzplAV(Ob&L?+OWXT~0Y867HT~z6sbd{9vVEE1UZ2 z_|7joXlYn2T{ACuq1N7BRV?Nm^ZP;N(O;Gf&jwah$GOO`yVx}qNn8MLDk6)lYiw+v z>ML;tciG$w$fn*yCHWYstOT+xZ-7_^s^3*03G@P}SZsZ1n0;I$ujHS0zC>H|k-fZJ zy@tkwT`g;?g6pyGn_6bK4V%AA=oM}lMk~DhU2YugU?te5Bojhr1gGr>ZmenM_QkQo zW^{}Ue)ZsQ;2BLrVlX;s&4|ND%%;N<1ULAEh2^XQ%L3AkaI&m+|cO>u~QuTX!i%GkLfr%lgEmc?8$f=eavA+O8xo}cz*AE{wAdEbF zfko(QgDh*qaN<^+*?7sm@SP_7fiyRKH~> zzvX2$qA@xnp<$*3^nq6diO{W!VX&X=TusTa>uT(a;y=Ns1xHE#FOo*g?}{s0oRM0v z#;!hN8x4>kHA9IbdtFgdm`mS5pD679`##q+^>~K8A?J;#_Km$pxw(OE0I=O+NI?OA zW3%}r?E`mTs1KU!jA(p5c_J}DEGi<1`>LC*?~(7(QHhT)SbbS+Dei1&%3ji5CMs|# z4)|&pNJtpKDT5cj=zD8zeN&@J!F=xIkH$fG`9-22lWqMJ;efM_L;%{T)Qe}J)%!vt zBywD*O>LwE>eL05P;-uRMM$(=z*Tc<$JxmVe2S!sQnqCe)kQlDZQjngf1NK-WzXp-eu^>}#6RP-JBt?@8P;VDUd0}} zM@OdNXAk~iJj>O7@ID#D1_O?YDUZas$0CX+Sb^76Di+6KqSXZ_#FxLe*-q{LxY+6J z`Vwv3)2qyb#PCsJJc>S-)p@@a6c1AqIK& zocS3??e=f(+p?aAEalTG6yTS?EB;+3gDFh~F`CTswUk)gmM7AI3sU3jihZB_HdCrm zW=ElHjghfW$CHSF&>%#+3Z=3?p~OgIb2PjX7ka6)`SChQ zQbI+}LmswNaAyeT#%1M_8*82M8YKPXcWOy8cL8)?ZhNND~NT)`utd~})LYK5bv zoEc7#gt0k_Y=uQ=u1%55yzgwO3(3e;6y2VrW6WjeRby*z`nSuYijnOYTv*QZYrC#j zZ!R6}$&9yKML$B<_Wipn8R~|dtRO*#r1(M!1e|_yzOiPfdfTnq&QX^Xh>?Ik0a@5j zRaNZAfdmj)l+l|vZp1-lNeZx|zv5{7x$9#Ri2scBLVgv|P9geLMCwOpbZMG#fCvSy zm1uBLaugEtGL>}f#H6=OZ#jx^Cjzl+(Cc}%5l|$AH zwU#e@eL%DwFCUSjBT{3p?#z;w>0~o9NCB9coAZf^YChb_jEI3XG&DkhB{MEAj*aLB zYH*W%CAzDttH{oSHWLW_r2~sya!SfrLXld`>c5>%Kawkha)Gcy(75y#G|!cxN5BzK z;6Y2l^k338Yl+lN$ULN|;6^=?H7ZmR8+e0SyVgo`4jwaq=iTdCIQW~j&xvAQtPUiQ zVDCG8F|d;r75NARMY$&=*C%-~ETbKlDx$xU!)&P&2>)XIV@E$G+r05;AH+q7;h^V- zgJzjYf=06d&4d4@*@El-1UWDd}aS#jWgnZM{j$*7`m{~HM ziRyBjxl}n(%Emkt2?SY~?4>@|viqx{)kkfO(G$)QMntjjAr&u5^Jm5xwc4Se^7X&E z*WTogkTn!d`;@F6W`>HKR=IRyX#z!5ZT!MP`|LysJFrk1q^6Z_zfl;qaw3L0HKQbR*5l661hX5j9KvH;Yg8B(S?kJY#xU3J{ zvM%k~x>k_w^I9DW2ck;#%rY8mIm1biG0)%NS2B7O(KvtbibIHwEKgBNqs5`gFjB0B zE=Kn29i<|I3cv3uqk>ycM>Y?@D<1ygq*RSfX!)CB+_Rj=RX-u?Xr&Q2-)PQ=XGu%>pZ`FDCN7F^3wYWLq5LE&qkPT! z>R*3(*bV2r3JZIOlzM@S6))~UN<&OCz@VrFW!7BFi6ao}UkAXWInx(NjT>oE5*LRY zm)&|)SHpWX4S#!cQJ<^VgIu;`T1JRn!8q&H<-Zi16AMl&N#IUib&HACADFE*OwALyYT!#LMh(s}e%0#Zx}KRxiueG5A9q ze96rlxRIm8$^SxT3??%Ua||y~uL1k`xaZ&>=-@#_w=jlMnJ`CK46U$T-Xn((Dm9Ku z*c)E?gO>PMi7U+;78T7DCyc5b+c&BptSGUeJtnKX`^mz@mL#WAsQ4j7dDTzY?GAyK zuy%N4{oW@pgLYDuzq)$#F*^&bm$}sN@h&nAFEL^`7divhwZ=u(BOV{0{p0EGJ>s;o zUi8%?{oQ|Vdu*nMn08?MWrBvM>Z@1Bx8&a+LiAAJhqgkGIhCCX>TCP|x{dw_i$ zo$>y5#v;3o)QP;H$$k;)>7MPU_J&}}jRag!j*QAK`Pvp=vSl6v98jmp!|p9@G@9&`JUX#%$6zP#t}Dm zds$XY_e;C=z$3&7GPISWw?-G~GQ&3_Qcgm|uu#2nfSrAO($V`f?C)ID+Wm+-)NAFt ze;GYz|DbUwC|@8*AUvXU@J&l15s-_>+WAAXGH^n0cJrls>#WUPP0oJ8a@0RB{Im2K z<_e?TKLnLv9`HIwCwwl}$4+EG(7rw6Z8qPeAfH66RJQKlv)5^30eda&-Q7gABbOTi zOYA(90og!*AOzxn^|Q?`r2k!{A4XGBq7B|2zu@ z$GhC*j;zE;e6hb&Xmv}HXyT{ognD0L$zuq@fN9AZKA3D7xZ0a_nD+x=)evKO%E|V^ zri9=*jVmRtXKCeKXh@O%U>f5$dZdBkg>)Q+Kp1@GcPFJH{zQokOQR+hoM6BPXI(<$ zL2`Xh%F_r)bJA)7SQW=dRFobjI=}P8B7nr>VXBV)JP$S-`#dQ6(vm5_RxfjiwhZ6C zzcg2y5N4YGRrQAH7yE^2^dG5VQL2v(>LA+q=y;@obx9}g;wry^2}@|tRMeBW*$bce zx4*zza<5O+HWk;#q8GUyij#+(OXXK9@zb(>i5QWSD5)x%7*ub{lKa`Oj54G zo!;T^=^%@SbIKuawPA(S(&o->@p9D`Gs6%y|7>yQhpkFXLA+9XG!;~zi%%^{F>IC^&h zUe|KPT(sl{#{NUx@4Wf`T7^|T!EKTsHu&2Q2D3N>he@AIC-C&GNF@6lnr?s(f|<8Y zP29+A81lQOa%wuPsl;ISGm-E;7+J1@IIT{iQT*F%>w&J3g~yua;rsrF+~6e-;J?}e zQ5fQiL)ne{P_Ja%ikKFwli{wg@YGY2gUWsDZOw1I4+*gn7ro(feL03POG?2_X-`Iw z{Z>+2Mp;1;EK+%!HXRjMJL~0PDfRj*jr&HsE25ohPgEx=aTGg`31ceE^}?nMvp$B+ zWpX9*RDb)AL<-aJ2J_t9`NFYmf$@Y)>UziYUVJI2eITN7LRMqKj##+{9da))wxoF2K0WO%lmzdya581b$6`zO?F|Q_)`$H#f9~H`uHLJLBpa zRArauQ;`AAmjxZ(<{jtfBObh+uGaYLZ!MkvNu@}OP4CeSY{Fc8%NsilyP;ZQjmxVa zSf@G2YU71@1w)J}uUsr`#&e1TEPX(m=O(8E$-%&_2g;m#9 z%)ADDgg&6#ARUiavV#UNG;rhag3q?boqvEE-DtiuD9dtmOk#ZZkqp=z&gKdg;m61O zeO2!lhIodapSsB_LOOL1W-@LUc;SE7n%7lKcB}02F(7Qi*tHFB-0jI;cYSg5WiXLe zLkG9-ACD%{yd}WF1aL7$X)i`w#2mom8y4AibNN+ENI~LKU#ZNKBVt1>k0cVpA1SX( zcw*ta$5-Z0C|Qwris~6DD5`B;WS764Euhk~?^uo??zZy(fkG;e0S<}JsZ{!g-lzGW zZBejf6MlFnUr@i8U$7W4S)zPuD&&!B_}^9f1g2!-c3#)?+|iig7Tb^RL8)sM#7-@E zrk6u`&dr-#W!M;(p544Bn|fN|X4_*o7F))`8;4xk?S=MWx?gWr9|R6g+4)a7E_&wK z|AS*Hj{zJrZ;ab?l>uKEvFia79Y{7L0-=2>^?+pdo%nl?(99B*@TK2i$^K>7hH~9z z>7ripy#&rJeW#tUo`Ev3K$bOW&#v&Mh>nH%%z)6PjOAYG(+4JB>1|l9umw!*kImH0o|Rdjgf!;6y!&Q0r(GHz&Fux?W#p zIP6=UEuiF@*bf!`UY{$rH;M*>1iicK)vov*^pl=xGP6bmT&pZC4Rh_=SzcQh0WyC7V+3E@I% zycu8edtjCkT7Eq1v*!AuLo-;Utwb|-_PhS(ee(VN7jI~64qoL2EnZ8UQ`_NU*~i25tzfBmbZ z$)@Zq9A;ftCZk$^V3NA4`g#4N5`EYk%=eXjgdln)j>BJhAqwXmFYJCGrL;I-TMr=y zuUocq$KQNZ1Hduyqmk6lmgihx+YRz)J~=#bMgR>o%uFl<{~+faFp3upnJ6JqX8(6o zYsQ&>?+L)LT&^;mw#W5_J+oZa54G@!CQQrDE}d`G%{3Ui*g(xzY=5*F)i4Yeb6dvw zs9hM@;XYUF`GJRmDXtMkCzf89Kk-`a7C5Dc-V$Av?%?Ig!>36HrLC5k$IqV4FDc^H zvjkM;hZ~(s%xC&PA{j3K(^No!Gk@*ie8d5~kLG3J(eCAhQ)CsU0%foqY1d@q;PfUm z&4F|QZ};RR%1ANRJZK!wKFOLm&Zcr=vcZfIAGqqI@WA}20Ej|(X*~ZRKpg`7t6%C2 zhA9q3%#a0DtLii=c9Bf}9ci2Zky86JRz}hX?^P%8((5OWs!^y*Ua9?{#?+x<=aTz( zQ`MiTq+<(NkMeF-P>7=Qh0Y5~f_a9)iTT_0p`jsWob0TaWQ>}_^M~Rog@w1C9TIjcF^A3eG$3HH`7d<4{;Ii- zNTT$J`RG67@vqnXt}1DgLx-=wR9?b5yf{fs>C8MH@J|?E(qEE^&`d~UpNwF_c=sM6 zA3RKa{%o&y((AMTO9D{`mbG>{v+DbWxXaPG~cKpbZ(GN$Omjn$9XA(p_@4ZteOuex}W2~$hVi&@=bDS{iGZkkg zwZ4gR={#yRD{T1v3| zo-Qd$$=a+gyEmPM!t2~W0QUi}_}y2cH+llP@cB^BdsJ{OR)4pwtLkPa#5FKwp!(hh zS#b8)z~|4U(+~7k;BW?8EmpuD6JQ+p;)Qtmp^Z++^!Le<;}uu{IO({8P6`Y@5RT+I z9Tf}jyh)Q^>$d>^x9;^s7m`}+ zP8sk|EXWAiXKU}nwgZv{DcSFIr1o)0#A1hD9{4}YTmo4h=x6AJeV^Lh-5s1k@EUWF zaW}hNpB=gBgSeMLZdxbPxbMCoP+~?zL@+1z!(!q)b?VB;kB#f<^GMnU#4&_mubfrc zv_Z|qIU;yqvnli;jk=5h2gY0jHD2uJ&1-iJd>3+1dCzGT{|c*3;{kJ(_-PxTeH$v> zhpj%bLa0@iLs4*7F=~2s7wds=4}5-H@#XGS;nA36^SN&K(32OE_sid2o9cILFKi%f zx2em@7(06C4!z_R=5J*m0Kt~f@(buL0?%@R@a&NS2+sp`i<-WH$&`%dt`)6D!5z>| zVF|VjB;Jjx@<1yb={UXlT^f)$5cT0defr&1rSBAyXr5cCakeF)~Vrq+PVu?xvgPw~Nw8`nrt zyYo|;O22U_ybO_U%fY^#yni9#c`br}OU1xNhU^MY=B_6%FEXEXAM1URzZr@QzWhBM z3Soih-!KAIeshr-6lQhV|?<)0|?S*u}v$II`YTK`w!(HMzy>8n^(G2ewRR{!z- zVpdLrTlYK2vYoi{2ni@K`zeIiCjw&4d+JpD*Znh3ObDZGh=CPxI?ytS6} zs_)Ir61{Q%{PWKvRxBuCsTtU$95Afd`gi0gKbO?8eMm>X(aYyITR`j)<#CS~LgWED zl{x>)9ppL`A=gxfB)bP{0#ozzb-sW9{`B$V8yXrx(Bzx~WW}CX>XH#OD?0B%JT@Id zjgCoOhqjWgNX+l(?^YhYGp3v0fHW0H3h3;N1*r&q zg%;Vt!4NKZW@Qq0n60+Q;>~I1W~k2EJK79PAfGs>(8gFO$E)&9f0-_h;+|zu4va_b zGZpu58c<-oFnHL&>DS!L_dq$wHAI~)D5we|NA`tb;8HA(cM`Prk}7Z%C9?ZFO`Q71 zNV1y14u3yClsJ0&{Q3D=r~Vp%;DNWiFGCWzl*B;1iMV%=8_Xm2SqCVNThZKrWOURb zQgP^_ECwYYP$si&4MFpzAK&^xmDKb9n7R(IsE)P0YK#fCn-U*i3V6T_&xgn5@&m>{b>(4sIdUbrS9um2}DUY#!o@Q%gkmFTk zPn}TQOW#0l#sy;f-&8|f`r(exLBsSd;40sK?Lj-a(uWmVA0);Tyv3~4>+?`50%`~9 zFe@AvUi=^pTW4#QQE6Y+!dfd%wF`t{;K1KQq)Ao+=cUD*$5dR$n?LlTz!G!$s)}dq znz(wU;WMS>ft`7wT$yQ-%(oqY%|X^J&+5GlF;^z>Zc$IrQH=3o^~?Rtp}O6nPu9 zZlUh0PjPwan6eFv)U@U0sit3fvQpY46(%pG&Dz4JaS&YlSVFCFMM%@U3?+BoPM1NH z%yul*gks&h_`m4^fm)*zlx%HUlU3`$f`V}r@cvX?jp`2EF+*5Q&9?{>0eNv$A7?sz zSjWI14VE6?rAxPgwXp-vcf+vXuUDB@2hmMbEbJA7v;HCX?iD9EDWj?zk~;#D&@7-B z@bX6G(qD(3=$_)qsEHjM?teCYQPub6Gv%eNfq9b{k))he&7`9oIRo=0o0K5`TVXr8 zN+jV*33&eOi&DSM=vxR1N$Z~R$rK&Cnrh_jOvDVGFPxFH#JbsBOZ@E`_11r5m`5)w z1?2PLoG8wEeF-K3@IP?b_Z8oUB4?rN;P|*T$WVJ;0T17<|Ij0gum3)Qjnci;5~eYG zWDV_3XcBNC+y{zGRC_6xQOn<22*fRa&Om~0%U&Qb5h`e8v$-=blav$?EzGqO1Rqa(|f2g_%xeOVOWRx4A%Xx(aO%KUrxy5 zm#X6=I_A=H1WIw*oN_=sJao5WeF?H=^Fmu?kMh5?;Upl50qb5M6iPCXEHv^Q4H;lR zc$p6f93F1^z*C8NEn6Q~9cF`497y&BL*+pf7C2G}ha#iRU`6@8d-p(vI|~@lk=oOs z?^+BJc7sFxyxiO=-QH!3b$n1}Y!M+#n+@|_8V33f0WbSxqM=}~n%>RcPdKQ?R|UUJ z^0p%h99C^ki#`61U$o+DWc^S4lF>AMjr0G+S(zHUePezmV3?iLGt55Nd%xYfs$m6Gi?>uI5}6DU+lxkFD>lApyaU1IaaZS)sG@ZDdQXaevy|aH8pi? ztjx}d&Sj_2+~x+15Q5wVYIin(_hI_+$NNt9w{HCnLl7JpnU;~k4=47n6AB=WA+yvV z;suLETT9EiMh1DY;22H-cc=L36_@}RQ4^Kxv0tRa&flWuo_{ZCk!JJf`2foUjknn& zar|{GTQ+Uvt!q!rgEzIP#_&7m?0S)s)K;qIvyQ?mw$}%5>YRLS zY08VS#;%5RhiwnD3%W8D3H>*_QGhmq?}9~Qc397z&0uvX{-Ds>MFuw$l6xI6vr|EH zMq4c_ zVxH!8^x#dqhkO2(_wn0;gw~`KBX`L^wOJzHCA^l=Io0O?VIL zXfAwz(7X7DXzcA?@*R+CQ~iJs~l8zjt7!-r2q$O&YBmJJ_1KN`lLU zyugv)P4EXWCbx$Py6g|E6&`6Fs!Oubo7#~R5^uXQLlb8s{M@6j^v|msu5LUPM(Ks< zG3dSN2Qj>yNmK3k}b^?dZ<%Exxc|KRkDj|M2_|{#q7yW3*X1CKBtJKg_geC3l4i z^tPYX(y)JG^LSkwd>U)1p9Af0+kDVWhKX#i(7sal`BGZ;%=dUEZD*NPr|# z+RK?na`OCP=ATG5?hUc~b1rZ`4Nesm{!-|Jv9|RHJTUK@>fL#UoH2eme2@d<@q!yS za524bnKG@!tbM0OxU~8^&;b7T4rF$J4_rgrLjStw0jrM_E?(YndLT@azg~Dvf(0{_ z0Lha!I6i&@cRy_n0T6(4DBw`aBFD`@b{(LC*4EHy9*KlN0wiuP$K$TD{cef}F%`Aa z*x1-ClrOydn@4X;lCqAbrc=)fY!@itK70ZW#)v1RX?tY_YPGftVZx=IvhsXa8lAS0AheRo5L<4C5fY1e08T+!} zL{}&954s;$Md03bA{$NEWXJV8#eaNJuYMkE9oR}Bu8u*~CS2R8$_{Gd->WBW9j+2; zFX0y$$mxV^kJF3)6%L0`qIKRIkik1!REJLF>w*@{LW8{DWCzw!W_Y3kT&ksJQMeaA zuD9}wkEM?g&*cUm!J(r(3NwxLBcMHmKW6}C_&)6Epo91cjL#>DLoX+)a+v^VtT+>} zr-q2Z(4ZiWAHR#9Y?Gv=}<=0j%_ z694wtT!dHzg5r^!5Bnczgu67BY8s{yArpJ9cQx!6@{yxXyaHdg1A_P59LyO7bh9Y> z6i-M<0CjCWPnhCvz*$-B>$mClG35x{2=izXfArwcKD|itcV(Ox@0{`T_oYgO-by## znKSE;OX?F!T>Ncw6^8mUHkqjk(h%-hgpxQbuHzUV4LVl&kgI+6t6ybf|63+A5bWwb zP-UzxOHG8*uY=Iy;d(a1CuDCAJvuJn@UddnCef3g1J@O;)MSz6sDFPIMOA6HggF&0vV=VEF(To4S6?|2d zz>V!bVDowlB#yRC(UN)m^}WOE!E91)el_bYdn|R>;#AG)lx(~W5IhpIXyP!aXTjQ7X^-*tW1I| zPA$^;wYH887q|`a@0-TH8#?5slrS5zVZ!A~db@S_*I)01T5NqcB$)fPgkOZjpyEd_ z?1!_UV~<&#V;~fOn4&D!Z{t1?T*)o2-ZFNbAG#_7S_oc{B!w+|c;=yLK0PY-tHSR) zBkNP_pS*yZ=`E5Qjs%9P<0>evy#8p?>Hb<}l0t7{%L#|XeDaWL#+9SNg4;1rE)+a5 z&v|Ypkwf~|qvf~jOt{(lcy+cYqABlQYS!-4Ec&UXuu_p@z`|6@{GUJk584i>emvPP_~{OOmeGFThaB)< z7W#E0(iem_v@kcfhP?sk(9=gATrQJ|tn~o|r5BLAA-zw4P>VIaWMN^ez{`T!1TiDl6w<^foFg&+X zs>1Yb=G=F9c%Dk-DfWPWl*KA3p=&5-y&%(Q1+!Z8X7^7M^@BxQn?G+vg0_l}yiR~} zH}(3)nEXG-LbPL7eRh6wmJp5&|Ds=6mRMO*bNv@Ec)RV9zq-fwKlpzUhTr6rf zB?IaiJQZDMQ-06DuwXrpUQp7fNKM|luPN@V!e7 zp^3>>FA+q7@N}!;Uolj4X{>Q(J2nyfu$=jH%}vL>F5_iTnRFEl(3Q+B0C1mS54D&8 zZywF9cF392rJq498ByXxC0GqIh{%p1g(YCe=>&?#0S%8VTw@Ak-a+NwIGn|81BeR_*Cd(9rTQMJSH=0E3mhh0ou9V5+J*EqQh|dcV)I_Y$f&5VW;8 z%iR-}$3j}%N=L4Ek{N2-w@0Rp;I!$4-#* zP?OqT{ge%rHQ2to^DIzE{quNkmW)AbnV)HAl`zztMUlEs@QDv z;D>)Unk(T~n0gh$O3x8@W55#LS;qs@O7qFF4h3n0$?9?jX8L z-T`M+t21wH8$#*|sg9wOYA81Wf^r?LOt}Hf<_LHUBR&Z{K{}977c3e74eYNP5dJ@E zX>BcE^}3J>!Yt^J03h2DT+$X~0|{z^Yq1_Jj%F5=SFirl4@5GNGTw!tUn{e@-?X%> zOd6PotRU4HC9bN*y(a(r48-Sdn?9i9=+A}r%%1o%F+v0G*Y_9S`Y)(d2~{UYk~30Y zz2taxkATbozG`KgX<|xZhNL!b3lLF{4-0i?d?THk3%8apFjc`7=&i~a%-AR3?JIaV ze4`v#C%u49(`DrI>l@E21DLJq>*|)lH=g`>d}{W$*jKOOFPYU?!*2mYq77XEJ!-p% z(vlJbcr86pBIw9A$!6x$y(lGBdbjX|a;0h`Zql}F{oC^u;Am3Y-dM@Eu=E%N@ZN}% zbID6cF+#{MefhR&SD}3r9POaEHG+he4Bew>{(dx5j9ve9%hix`Y%eJL{dg);WQaH2 z=%?>3Eh?={-0pE~=IyKc=(NhFrK8%40~YLwy;DK(Y<4&HUB-WR@Zbb^?d>qlSElpH zlaL?R00Hoz>q9kl1q7G%`Mc$y4&()v8Z=m@yKY0#KuJ|q2XqBLo(H|$+qZ8s9Y5~q z0hdXA`}P_tq6Gp@Vh^ZX>Yj}XfI&eC0C?5~+ZWJuTaNP28L5NCJ3UZ%Ljr3yAa$3y zvG&6tKv95p9Uc+ZT1ceL$5h#Uv%n`NI~)mglAjL*q1R!rU9rhJ86EKF`rR6leUs_CLUYf8PPnI$JcGfDkNY zxsERzWV+sd`7OuA>-2gXg>wQ3w>MxQUNm`5vU4}Jww2T<)k6smz4eRi-~XMY9L6gl z(aDH|EW5?XzQW-JZ+KCM3ulCK1-t>D0R}psLCA<6TAqOH+rSA9j%?tx zEP~S&VMyN*s;RMV`*S{iePyA~Eu-dJk?NZ1EBZb#k*hOiy$^_XR$$vzfbvPg7OOmL zP{XTK5Gq7@6!u82-%qlzpc5jhp{rBKs;4loqeZg?6=qFUVt2z&?vrx5(kKI>w4*VBOr@H!t#At zL=Y)z&x&!M`xG4&mEP8-U1WW z`ug?j4JsMuuqlm3FiOKnklBZic~o(OJXdCGELK|E%$oG0`mK7s@Wz8%MwCY_Bc3fc z-IYdfHkvya@w4@MZ>+>?@Z@H5>9@?z6Yy+`WVhk-N7Z#<%<>|_wc8*J4*_- z<7I&FNj;#o?Q6e13Bn&nyZloeufk)5)CEfQlHr$92t$b=B+&KOfN{AXX8gUwG}-Nb zhN)qtBbW-HA^slJ>|7_iaua6qt0V;O%{=ls~Rb)Sh+PS zWY4!h+Xy(EO?=;jdMCNq4Y>NB1qK#bAgdhTc-ilk!A?QJ*P|qz){V0G-&1$oE&R2f z&75;R^J_q{f)dHbSN1>eHdKQ(J8qds3(Xi9>*f9PcMw4A&O3yOm!J3DB!^mzW!~TN znx(Xq$kAxi{qEt$t}zljYr!g9<*(FkT|4^YkGJ&X4Xoe%^Zeu^ooAa`-R7dmmM9B3_yhk6*XLGes2UoC{!$ zJWQ5xxs&a)_V%%s9@c30j6)SG4`wM;4V0P?d-Z*5>(5BHAj+YH2eeb-TH4xzM`ql& z1oD2^Qlpm6me?Y?K_B36ssnR$7#mhN1qkY|EMyLs=Btvxr-!wUtSg0@fb-@|5v6?2 z*Aa0SM#I)K(er-l7zMN~L;>qzkGKI+a&s5h1}ni_Qh*(F`dBsqf9-p|rIL=Tsptv` za%ETCbgEuX>}gEaVCmoBHp}i__jF#GqGdFCWvs8T$VT-o>yeU%34Z6Fkq=>d0-umi z1!)b6Ovv$eZ+;q?59DN!OeOE}xvB}E8Q<&Un6cM4U$4&EA{;)Cjt*-KbcbnBZ z-a&FR{)411?UAFW5F><>m%NC{zYY)(5~2l$6Bm~u0JNyMv~Mbm=lk{ft3XLX{xBz1->v zIOZitS&hPBp!yL~5E2X!u(ad-!Ld>81Drr>IOl(sfHbE3&pO>gW8pG4;9D#7m)iso zmVaO&cXoDC0FY+==DtA+K-@=~q~;nRV;Ny?_5lZaBEVbiD-423%Tt{~;6bZ_zGG{1 z^D9o}Q1gXv)t+Dr5lv&#n>Tl(I;J2&Gh00Ta+*kq9W92^g0)oa#`QcGuiS{o$N9vM zcX^e&3z@9`$wPYKPk3`P*zqVPe#Yibv?zaHVfIAVd1{n5LDoCWiVM#~H1l$0H_+(& z_+`>2E&t}A;1duDMeXF(ec?0W0M&wI$Q9g@1TN^peLK5`!$M`RAf0Cg^#a%w^n`%} z8wjnXj~+dW=wi>DIfGUU6e3~I6Py6l2Gp$xP)D~MZ+>$clvg0Qj|34pK0q8~&oj5^ zA^`@u?Fsdw_1Ju}tP~JG+r9ax=P5L#8Rn^fVueY~H}|`6v~9GM zd#P}?f?&QvFdt~Gw$yFEP|9v-$Cb0?7{F-CJ2% zp;NO$Mv@nt{wl6~nx@a#->pGj5=qyp+gxsW&FWTcQGel&1Zw? zeMr&dp{@*a9gY(a%&)lF@*ell6O&m*a3w`13!lUvTDiD;RNwSwyRH`u{X;nInMfp3 z?a6w2dK6#)e{fh$+Y=H#buw#xK{Yis(jewTgv9nD?CMBguL1JnO!^7nB}jrg4Q$|) z5nw}91jR@u5YWWCS?L11=7}9g;pM;Yi9E9JbTk*9saPB(M~;)PV5aRXX`G&`64jQg zY_F&PIDYG(+c9U|Q?xY$BURTMN0v9$=rbaI1zh2t0z|^AXY6T_RNKV`^sCCL+Ps@r zK!${VV>tioC@T&kP|`s1?g=(R7|KhH91uV?K%AQoQt1%+BE=hci)aaKtj-hnEM>Wu^MP1Taf}~Suwq0dIP=;0xYEn%s;ux*3+@x{g z%EsC|*-E(&+~EHBvak5Chrik=mKF2v1!ay`Hh*sZo5((1J6(l^2<{itVGb*7&yF+v ziLR>04M`kco{_2b@`2*=Q#zFA>6aUP zPmhzskDRkhkc4^m7So_h?W4$s;izG_)Ma#xr+K5nmzPL02_gm&IEAd7_j%lO9dsR5 zi}N=QZFA+}I&txatE0>dos?Fu46LNVgP{&Ts?yD~$fqM>2%idJd658*nov}bgFl*p_FP*q9)I2 zTGGfH+O4}ugZVomr*m*EW}S&z+4qDWEsjh4Mx5^$!O4d3d+jt*N|#mDwsrFc^-0^b z&^}*_hql>9p?wPrBiVDewla=kdMbd4>QYKq1G@s@gFj2ukInl-MMcMmo_xZ#q)5>) z<89A+=X~+RyQ(^&8GK`d^03)bmdw@~BMy1wpo{>Fi5Cwhzuj;BBZnn~?uZJ$73%v+ zfoKyBS)n*`9yii6H1-!HjXMXOk;{4{ZZ`fCsg~nbYzb$?c9{8sGOPP&|H_bgTel)* zfOSysIBbZcK+>z2QesbLxCGXUvllI*`arHw61Kx7 z;Md}XjVf#TGW1pBbiE}PZVNV`Quf5H!}hmT{YR<}OZb(=Ts_34Bc_;|+VvhsqYA`j z&qW-O;+338OI(|+&N_-YX;mFs=g|8Vf1Jx7SJ0(`7xwbJtuTPwKA>OdHF?KP`&d*2_T{4nXR#F5_C^Ze{ReZyl4*SnZa*=mJ!J&9@ zwyT_<2p5GW@S#xHE(qXbz$66Jb2pwIB$Ee7)D#wQ8$lx|pYK_Mg28 z#30`MRaiBSvJuN1AxHWug++i)$I;sz8)sKtb^n)<(xJ%XyBJhF~i_eHYUMxj0JYQnOO~&SI*f?8(Qf;^HFOdfR`t z-t?ocXXIG~o^6xSar=XDV5R4GaD2Lxe||tH+ghxboP3uc?9f*X`+v#52%9K>IDFef z(}q`ksj5 zFp`jv^3MF|NcZ4{Z0T1GF~QQSk4KU#l^jYh=$F3D6WL$YWLZ6J?~Pl#3LJLvPgJp8 zuWF7qTGVq$?r~;X_nyRe^8yluVxqU9YHYIKxX?}?X##*URMtHaE)t^Nf>2TRqyKTT zy5C~ZGbC*zFD2%D@1ef$%?qdcV_hb747r-UTxY@zw@S^Ii6OBgGcrr*Bgy$eV}H6| zIfNM)D4fM)V2%`=&>9mI!n&!t>b&gASMS~hsTf?dPdXHDzrN8~84Io^T_uYUkc70w z;D0b5AvI|MT*#hC^pMrD>=M-Hjh{Ca0pQUPLPFxkWO_chF^$gX)xBX+S2Zq956^Hn z3Xa}rOw3Zg>3g!)Lq<4O`ye;ZJLF| z9Kg7JpVR`JG429nevH6$L^oeusBhnV#YAtW*?&6>%pKSnt+)+sa1Mi@5HG5#s_Lk} z-vQi4ND+m@N$t@Dj&1Ab4J*jEr>zIl!oihv90)XzqcpLb6;&*pAR+1+7k);6KyW01Sit7%Ct z>R?>`K1{DQ)}5w$6935UjW%yc5(uJKh|@g3e&{a675%%54={)=3W2u1JF_kt5{CrH!iyj3L8aCMl_&YCo$_8zDBW=VxA|sZJ4gRN1qco;v)DX zbPdOz6mcmW6B0abO-oA;f*p|hWrFnW6rWW6h)KoD!qbDKEmC%@-1Z=Wz4U#bp_IUJ zS-acpqQrJLePNy$-E7a+g{CPfP9eLlx|4%*ETffkEZRNA^>cZrNs&p4snnGey@r9+ z&$Fd0B4^|e-zl>(a_}(qij6FnZe_`;dzu_TW7SsTsn^XGvWw~Wa<5zXxH&qf-o;&B z3gXXT~rI?hP$(0riG(-FIW2Z@=0!5`a%hdUPLLIKrmq!B{}j8gR2 z*jQ2jir#6MO!%4A^gtl{&76I8L^{4$+LZFeUVbrmGf0l6y!aW%8NkOU^Ch&OnyRFZ z(Qam;4K|I0M(%g}%?*6Nzp)%q5!nNhoP3=QGY75~P8ak?I^7xUl>78nxijmu)L6L7 z#P}*i0?^{O7g+yO*o&Mxq`Cvr)O9fJmrKBcHfH01;oAZ>bt;&NSSSwKEnNYmdjnFw zz=3EQ8A*2(uA?WGGXHv*r0jkwN^%|#^Eo%7swqLiS9q+R^pF+MwuWL|XiIO=!r0yZ zSaOuwAP~eP0Q|S{nWgRY5d%5acUjAr0$<i)J4aB&1KCihob-Z*|VM>3@1nWYaZE$yfEwYer`>0kiXD9CGBqxDW=) zskYBKhagQT3jeu4@^dLv5`>K7oFVY10KJeYZ~|_GRu6X0ez(;#i~<#8EufYl06^pG zlT%amKIkC}SXEgG-GQf~y3KCob%uklRX9@M$X&{zHNk_yJ57qeYdL`_OL$0b5R!Jj zB~etw=!+Cb<+(S%LyUn`lAHjORblbay_KSstU^Lcrm0#f4m&-dGd}`|^ae-|hC#e& z_q-amI4NV$Tq#wJCS3w&mys&0t{%}Hu<3;hMzxaY|u&o$@cUsva3YBV2 zTR2jcJExdy2vCDvG;oJ_aV1LF%JXZ4LP_^F@}|IOP}?9*>j{J44@u3a19)Vy(b3P@ z`5$+!NA6k=-BAi)&U-KlP*~@XB8NlSLXD`HSh<5cbczpDj6C3JkT`?SO1eoSa5Ndr z{sw!IHO^ATz;56l6V)5IcyRbKZ|j7dU49e5!FndhLWH2Xlul7@B(3=CImlv6Yp3(9 zlDIKlZR;*FypK1%gQk=OkfcXqUPvQKc8y5pBt=^uRO<;azsaA`c-ZEVE3kSbXF$1>jh8Jjs$ zuIe?|k^wJqF~HI1Jdy~-&MU!Pt&7A(xz_vyBG%egtz6h%`3(7!Ub%C(i&Zy%uOYY@ z8~Q?4!gC{32~Hf^Jsbh?7)1u z@8;-<+PN6H?c2L0k}m2+jFuZ{lsp(%id`FlnvierzjL)&X(ZGP9u_=*q9@tP&&D)O2CjuW1>MHh!(te_F#%=BYstFDPTP=Ht|0 zoSK^DMG-=e3`6dZ-VoX`00Kw?`ir%ae%xS_t^1(?_=htju*Lv+t_Xh0VKoR3ST#szqgc& z+QwYb!XW$H&U%giL)cLwYm$BD$gPY0a;lAyE2~tHf{5j10_GZ+~v~mu9G77umB`m_wQ#>?hgvJ)9~Nu zS-_3pW2)DMm=Ux62mg~%hnjU=rsASEgh)KJX#Ti}jL5i84u%40b!(*-R6oane*#q@ zOX28uQ69>r&g19&9eiIox*uLT>UgPLOpzk1ShSB-?vS;au7ty9>Y(>!^+p3@kJZzg z$Lp9=ruU><<-I|M_Ab;Vdfeqt9kwuTUVJ8ZVncNJ23^Wh zu|@X17H2WmA+qjMT68LPzsFv|oV(kv3}Y{WXi%c>fx;@xKUj-#B*+sP>y7s>$Eq58 zZ)FZ>>F9(2273&NXny+V1a{p9^+3;fLqXFMz@3mmS(zd`>iI*i zLc2s?bUDal$S4Z~tlekiJO>F7Xajlcn?3jDYy*$~^81jz`;S>^X?5SKpQD5}%B~6c z>cc$>PKngdo2DL+z2n0L|CHxjPUp4^5h!&wQhmBQYY5Ok)bNFBkZDDc7Lsk21Z4K& z))LuKYr#Ft$cc1wNB}z>y8$*s?|f4qNgPc4mitu|33BQ-qQEe zaYtnG=*dmIuFbdQB#V0XOF7FK*F9>6OK`36;XpZO1GL7WjKg_b^@P`Arnk1DHZ z!kXoJ&B@@YQ9UT=D+fl|6;^JeF#r}-j?!>(xNrIrK zxkHR!jiplC(71CSi7LUZSayFfal%zgON*|3 z44)Brh~o4D*TzOtYthNDA~Fw&vr-xIqX>ZnV=itx5t(6F^u~^QbFOud=NL0{l^$GO zhH6bvSw%3YI7O8$tn;Kq6OaPTX)&8NmLX86Fn^QMkI3QHt5^)- zHz>G>IHj4&W#KkG|E$;s{Wz$`PIbu3!n4_^t*4j=ngv}wH0!~FdcnG=a@w8NpQLQ` zk}YdDADhDoUT#Py%R`BBzf9Fyi5RKz_{V666@g6bmTvaLPe0upQO9j)AsY??tu%Yk zw1lz|a3uvJDZ|v%RGzW@XhZGo$hwuhb%okEIOCyP%T5Xx;`TR;)ZTOl6dWeUIa0U? zR8??SoGV@4rS8%Bqb1xR?wRrpPT?pZhi?=ZxB9ZSK)>4xNK@znJAlWj%=)hEemT5J zB%lZ>{YE5Jy0Nh_Q~4`;?81X&F5J4(;9Yf-k>hp*=3Y0b5a+C|P#9bT8y+j)is6C?0|X zP1GxH)8Uody_Jn9uv(th@0-1a$~!0-5bf4;-xFwf1`5C1LRo1*3O7MbtQ8Iv{o4Ua zl=zS+nu^nu|8qWYdL8^(!sz{}Q;j6@#}P+KDn?xzw+0l?Z&Ko#`sP$?r=;2v-NV?t zU!fEl;N_a$m9!jaE-Wkj+ZzCyBT(I`F9ONiYxR{;%hTN=DCLE65a7eB8e{i^mQM;w z30VTC(-Sg$U!HHJ>OEq^34;6QI8%ecv)zW)f_i8c2LK_ z$CHIQ7zD2u0$o`+uhO6@(H{&6$WYgEsNsyF5*2h}vygKLEIIOYZ?b!uqt%<&1n#9g zUyhsSVng<`#*C@ZW!Bqvj1{*+?B%j}s9^Rc0+~_K}!PlTkn%rNfwicfQwBkk!@DKNzLmc@mD*!>eXe zHEDZw)7V(kWA^i-Jpj&ikaSCjqKe$-M8zN!;ylYRfjt22RY)UjFQZf8^&WhEIAtLtAQ+!!b5 zF&7~Qv2Oy1>BJT&mZ^X%LMRg4=Ll6$h;Z&#TcUocL`DU5<9GxetHwvR;<&(Lq%-pr z+|wEZIb2!O2Z8^JF#HHNxA!6Jn8I3AkY1i_=R;D$5Z{C`(wC6I)Xmkp1kZMmFNB~U z$f>>~s;^h2n$~}a`=-xtk|QmNg$}h#@Ow-TUMxU0qVR#vSE5ygt;Vj997YNp&z=mF ze*oR(Ij0VND~r*(kSOIU_)39Dy%lFA)m(Tbc82_muiD~lAUC9bv)?GD7*{u<6l3!Z zX*rxl;)157Y)6TCQi@7uhb&at<4oD>$< z1Ks(j4oF-`*hvGaXlOk-R+OxZqK=)hF-|jwj`Qyx1I7n{65SG-UZ~K_9qVxqQinPd z58)eKw?)_$YkV(7YX1ysI{(I-^C)*OeAQB8v~7JheaV}5^& z%aS%T-*B6{vxig71~Fx$E~wYiwRU0uY(Ol9jO!a~&8hl%skLm4v1%99XC2}c^V>qN zroa)rlr`znUrlKJ`4NTh-sJRc9BV%FZ-Ry0xX?iA_}oNBV1 z#V7Uu0#aMZB%(nHl+mpcybZr9$QaEhnE1RarWd~piuvJZc-_gVN^fzR%-7L>o!186 zTU9s@lroVS3wEPcgsj62G4DM zttRS}%G5 zb)_zfdMnp+vs|uw4lES?3l_-@`nL^WB|D>?r!8_1EsLqCoc7@n=9unS*4|Gk^gt{M+!_nQ|hpH`EyWh2X${qHTR zZAH=rK6A99gj1vs4wbcA4&#GlEc`@F^J6pdZ;0r zr0KNeiPYg&)xD1K2-0T}vq6QWZ^hyiiMkTx%tV@kM6sV!_g%*;##p0}59L=_na?G%_zMMW;TOUT9kC?v?s@7xwY+wCsD_U|J6 z4%)?Rs2HHX6qp5W$FDbha2!ZQ(<@$vIuMt_Yyd&g>&LsQO_-ja8F!IZN(zv|oU)f- z{BzsJL2%S6u<4>S)aKduYV#VfGs1;H0y`#Fl%HQbpYqCl{!KNVv%KIpb+U1+zH;Zu zSldIU@F|!mg+RLle_jmKKk=L_z3fPsjQmCq)(!q4IftH#?Ivb%DR{dJN;5(i{31i} zsLpIGp?d77oPZ~J5DJKJh2}byi2S$n4YwbAC6<(=?W&An>QV|@=+kvZJ~g<(^^3LmsiJnJT@512G~`QxNdd#i%P6Eyo~zUQoYmcCkdJ;mB}sDX!%D`gA1 z?h1urngI@g7HB6{Sb#`LC$()7-q#yA^!FdLC%#8t=QUT*a!wX9j;T)XD4*#2G@;Cd zwE`QzsBSeI29p}QXNUzD+>##ciE-SO)IVCF;IS7&>Bm5 zsNj5;=szaU!Reh+PthPNG!GK>Wy-Tv4y^T|EvP_8{}BmN!H+pG~aGlv~fK%R~W_ z#tquT!8R1W@OL9;N*Q$nS_ngQ?n3Kq`p`EW(q|FAVp;gHyk~}CsjRzdEVgj#^?_Xl z7EBKxeWL#wAxCtwopV-dalSQ*oK?)lAVrZdtC@|lywTp>j86PEur|Q22vjZJe22hu zq|-Fri1%oC>ZT(k>+2&O_a^)*L*&cNtx=Wqrxn((|ARj#&eyxeUcNpXb-j6ia)S{V zTi-)2%H$?c%BGJCCO*%G4_Q`>#$DwUZq|-qAzWBFVI!7RE_;fw%=-F>w`1PieMKD| zY6sf6-sSK(*Xdz)sy;m43nAs9v;!-ls>xwzWN`$PWr^cqisW;nByW(bOy0$0j zb%gSpae|VRSN(On(joFw@$^kas+6krtTBBi7?O@7U1WOtf!<+oP8=;Fm8&VM69!=% z#y-|wE|VHQ4A&f!$&f#rJ`x#4;C4_-?t9JeA%6eP`i67w+q5gxbedXP+JH}4?W;uc zfTHgjTij{r4Jc#gINAFxjYOkMkMW!2Q`g^y1U$)VO;u2p_2_!FwH;pGnvlh| z@mgp4q0B^<4R64egqJ}gFhNd3g%L*TfSAkRiR959Z{xZ&S5_uc+3Mp%$?9Px5^RI- z^-`ug(w!mLANZCIH-}~&NT1O0GT2gSBDK%_L-04@%|L!2R)f9;lzx;(0CGsuf^B=%9-xXo-IXw}!nk^m zAbqM^XOF4z$~t#GCfLZ)aXoIvT4Na(rSr3ruXwM`8F=h2Bl|EZH<;V;<&kUJ3lW=f zSVo?PRoKE|0iZ-TR+Yg`*vq+Em+lUxjX_)kF1f2=_Hoc_D`tk#t_e0fG_-V_P4mCc z8AZ3Z1vd}JDMy}pUO&~$NgO%_Gvk{uT1`FSnyK3B$ErA_0NzlpK6q`{f4AP;T^>0H zSjxkt{mg`MN_jpV>9wqS%tbY`wHM52k`oedi_!Dqb<>E%;M2;wR;zhpJR!z7hw7dc z{T7V|h0ZG-x|D>QbFbB7a@5axGR6jpK*QgfS;Qo`hbx1n7yA?2v{lCL(o9-%duzz) zX+Z|Is+0OpWdk$V6H##ze#wh}dZgZ`ir7o$xTV4=Ko|cWr z4y8e?yyv$zSI}AO)KA`Q+D!hrzB`HYk>4Z+dDRogR+Bjyhi?@#VWpI@jns4`vJb746 zIVK&yP9InCp~A`rUhL}s%Uk{T@}xdRMJ=-h;(=-U?WTQnGkag9SPBSXE9fsAy3ot8 zj6D!wvBc?P;~+BjK@(1%Z>_J7*`o1(C5LOcDbFaa8Z&*wz8rTW+^6?UPD!C%I z>dj}hNQC=}srQE$QrB3DZloBK7EF|m5i=N*P~6;C%Ncyey!pP8o=HRZ4_E098r_os z9~l_5!C1@NF7`PFmF|#h`u(2gP!<$xJNxW<%pSBjn&-`>veLsx%uHWidjOI8<+P{e z>a()4cjp?DGzkF*hia0?{_RLj&uju=WjcJyp`HCbC(r;`^ zaj89#pYNdH{3c@a*m!8qnIe7o476t9Elcz?y!P8Y=4!c8Es1GYPJ8_UsKXv6t?8nBR*^ge^8ik3ONyO6&n%_85Lc#8DzS z&4zHER>4Rli+>B@OmA)O()O5rXXJfyj|I(<;d}AgTRu8CG}$u}%}Rg>QjnfFIm%Nz zTdCmX-n8$r_g>lr%mApc!B7Qb%@h_PN%pvtYfA4_kmP!EqAe|vEK7QHinDZDUxl$wCCnBk zRbum{g@kNAKTU3lYEq9RX1sE>Nl#z=dj9DshuRs3H4`-QF!7=p*KOSp13x&f!6&h} z;W;kqh*VlJW>|OA!6$*+jkUZHhVNPRk}d>>cY>Y!Lef1E zcd5P9;p~Uh=P*r}0T-3JyC2K*F?Qxr;q9GoBK~D541=jVy;^G(Cg6Q*u4%$}5K`@^ zyAW8HGj`0gk>VHfIfTUXmjp@kTF)7=_$Yf^Zh;+mwLROrAyEfoDc9Zo5Nz(NkQ?ET zUkK=5_Q8GkV0(N|C4)N!@&A<_aCoRLx1@0 z)(@|I&uto{Dz#I$zrF|{Xoq^K#~8@QO|{fVQ!+O<1O7_XB>6(>X8MR~ z94{R82Ydb8+mc$7Hx}nJ@;MK&4nV8gp}W#}r#la<9_rWnUiR#)ywL8)isIE}L3JTM zlYJhG;a4M^hKBa+yZlWkxg*;<{!>p6LDLpQ5d;0WBWN6KWV>IYqjv(#>q@1NslhZK zl_|H=(syE=Oj~LfNeS5n3}T)!eB4dj&5enn zZfzW$qWdZGr;5CswPFoQE*;i&RMb+Q;xNIDSHFKkKGRnuNL$ytIr^^V9KzhACV!j$ zHcfH-Wl~hqLB-am_ZDAnXOk4;lsAs3*leB*qKB{5_6{~Axxwvg6>C-X_Z{r{dZV9~ zOrDjsF*U}0p7&W6;TID{S?Xtq?#Q{DKYr6JKturOIna=moLiOAew(UP;L40vh;)$fKcIwctN|B zkD}ubQS-=K|f#IV6wof8cBHx!o`&Arw^6Kdn%2a+D-}5i{;~*+v+78u)46a z{hWlR?D$)F`cR?%4V76RH&=a%XqygY{`LWpsiC{n@qbQ;_{hi6%NX!cyb{9*(kQQK zA$>ck-xe)>FG#NcwL1ylxniT7XWiMG>TQd_@D`F17PC1nkEt7jj1sTUG1PMm#s%tm z@W-nQLIVJjzMmTrkpHZa(GOYQ);_w!x>5XrsSHzO*q$Iy~i z=HQWC>N?Cww~qfAYfzYL*WFq}+_TsN42vCl(hw8tV$iZ)a*rOyl*Ef+-ORh6&REpr zHVZCUAYvhC_$+$16F-pYiOrjw__kQX5f{A@1B;m9NeWJ;CXJSEyWgrT*%}T0vX?Qy zXJr&J*6Hn|y2m|bpH8WnSK5NC7k{Ms`s*}iD##VmX@-n?P+zP&x-vXgvr zAX~Jvv4re_jrFM`@C9hg4m+RVulU%^BpxDFfs{`(RxytIK(b=tgz#*HaoHt3d%*$- z&mCi=uXIL>B;=sQ2yHwyjgOA{30B40IxR8kk>?zB>198!C)wMJR46JcI<*ylctQt1 zz__T>-?=<_WjYhLuKv2Fk(W^pIBY=7<#Cq-&Gf$eW_vj$Q-)+?v$M=b|2Gj<`j7Fk zbB|7SBxY*cS?cHrGxDL(msN&zxQte7&B*BH^Tv!U<(jibyGCt!gm4s$nzX6>_sgjQ zd!CHfZ;Vk*wg}|pS&xiVbX1=_!^q)}|2ZZoPyy`79~2JLO(_~8B@_eTWABp^s;$^J zKQKbSl5p5Mq)YE5b?u>00chHFg)5 zj{;S?<9z{_u}=p!D7_SRbcEm%Y1eKjH@%Z)4VKscuBdQB_GUqg<~<)iDBjXP@MMgt2~Qc@4`{X zXaadQrf~(cDh}aVhLAk1X;QJ7d`8!-9lyrz_0V2iVul~P^CjSaMzNeuI*aMA|C1J! z5stMRD<0mpy4ToE3f^Q;TWg8*2oWy*jBXC)*A~~0KO@^k>oBrCrxv>2t^iO*F2m%; zk#VhER1Ri5lkV<}%Yr9%y;49tzeMmf?dh(8`x{i$B1#K&ngTY9Lu%*nY~$5ow&WEt>wErYZ%)T|HH3iFLNsw-kdtNv2k8@4yGf3+k)T(~>~W zz>`sWokEgdzcFrkr8_w})MqO832_2mZ+;R{%Tia56V|-Qp<@%hJakV7=0FiW?2F&L zV_>?kxI{c+>9P580b_H&(*3Vq;fM@vL!-m4JD1{rSorQAG@q{pB+2_NpVjDl2i&!M%GH}bZEw<+UB=5CVl~LypXqsS+=*tVfF!Y`=q+Z~YQb(-_Pu$(5)9>C|%yQ&h zIY8JsPx$K3_1^aiz0R(2w^OG0V!gPXkmyqQs&Fw61*!TrRM_@ z?X7B;{*SFMkB4&a|Gpe|b)Qr6+`mpqg>&u}Wr-4!Wt`iuB%ux2l|9R39s5jm$2lz& z*}_o5DO=h1(SpV{maM~&ZD=qU+c0LH&ova!>-Bv9sOY+`@BZ08@6S0sJ&k3}HFs`l zY+>OQH(%S!UrQ8fgpYl%65NI3Uw$v4MzctX3T40X%E6Nc%TS&fMu%8@=CsG>-D(T_ z;OP)1Vfvk5yk)M_(nC5wM9boJ(eh7iD^ufWb7j=V0Zp@$FMex|WLbdi&h=fKmgFJ9 zok!PI1mC%l`TGvyD)yH`<}!Y0ZC$u^@oM&q!KPCwN$u__tnb7xddw&zNeUV7z6*WU zYc(M*`N{QL1)`^&PX&+W!F+>fzC7q%`aIZRRiNTrcnVk7JM(dQq)(y7r%r}HKE#^B zU%9_CI}*vcwLpvC=p3m?StEZZsl^qCMFN>m)hd0p(woFONE)5oP7~3tOP#OR$rhn+ zjcnyYnR3&@J@I~@UXzmr*A%*=DPpQ-tQXD_lV4`Bkjg^yG`BfU4D#K%w=2DEbdC2S z0c$tVPB!ROSNR_{kylAZYm6Xnb>c5OKUg3;ayGE+c6!5kZ$ra~S8t?5RbOFuimCi2 z^x& z3e23LN5Yid__C{?+X(ndByiKs->*C}!iTu1;yU-mmCu^zE_d5fd-^b)xw0jU*_-y_ z9ye#Lf-Tpq_af5+AABmauMmcIiW_wV@@Il1`|?lZMA?;NalHEBFv?-Z9-pZR_q;PW z&@>UvIQ6BQUeJMlr5a69={Ju7ldOF5rD1cBRQ}huI9dYi`_P8);=U%ElU_HaFN4INsqf z+gsO|c&6x$6uUWo=lB=Co&y6q!9PJ=%8R_K5v}49(hvU?Dj5`NWDfw0NLBFC|mr-cH@G(G#b}Ky-E3{5Q8yc2LskYtLPZ=r+nOM>|BDeFYjDOZ z#$nrziO7%Vgg(!?Yh5wEYB6SxJ_+>7lfUb47mYM5O1kgW91g9>@?fESaiK*vTuxez z)paj)bO@`G`CT7NcAkkw#r25_!`)Iy=NCx_t~2N=acf;WvO^~Qg4;(wc=q4^JpEyv z4HL5YhA~2g@n8E1D?$cMTuYDXpA#`_i@WO2m9`@Xef;zfI_|9LT?g3oYd%@w18j<*^RY*t&>$YO9e{ z#b{h~M`vZn<&>@S|B{q^fsafg2}0vy_}j*!(kUxpKT33IprzPGC&>Ov|foSM|g zTW-|d9fzmQY)j8hEB$vKx*%}ioA}~jRZ>r>lHUTI{Kk)*X56<_1~9n_%R6;S}V`yW6{5|LV@%ot>XL6XBb3|2XPb7P$ zHnLKSH&*~!{Ea_b(FJJED$lof=FWF+mp&QL@%|&KV;xytSvnZZ{|+)H%NhR-{)xZM ziy~X#t;}hJ%jD_5s`-Eg*P3A-51pi=d& zU2Q$twFt4Fh~~K(&P7TwvOKw+7)=x)0BuXV+z`-t#wLBH&J$P9&Xn+fL`t6)nE4C` z2$v^lTUo}ObuLOxEttem>aK%nLRlhM(}aH*QDVbCLdivD>T*tfmjko+^Zn&+gCZm= zqCx-Mii@+`6o~WaN;y8N@yzsk58E zbolnWt-ZG{0{G{3MB9!4ibCbg%i$-abq={Bcwsm^>%oLcG^ZJM+K$0|_)xaR?|}2?}7r$9f?KOp&2HBsD0w>+KDd znNPb|VYu>x4n#kDw62d%{7=ZrNNWEf-psh|eEH4UkOR-=MCaaM!wt^q>4O@3a^lHN zdvu*9(yN_|Mii8xD6&Oy;lEk^XS(;lUO$Rr;3M|h4knh}i99p~JI{fVJ+^b?t=D)f zKhFm0zQqHM>(qQL{CONj?02hVj|L9zO8V?aPmG}iFXV|rWlhndEyzN>E=eaFqu}Iv z{5UHJqkm4^#GKD`{)onQ5!*z2VNJBJ3U96INm$*0UNd-ZXUqg4t zpx)$5Pe5upUg6|cT}RTHz0)c2?8YiXT4^2ac?^o$3HZkW>f0z9?4GVM|JtQHH}!2V z;IaeO{Bg3VL&8(|-#y?9@~Z0HA1StlSE}ZJ>&jKLHK9Tvcz)uI+VqE>2aWiTzkl>> znfSQzaT89KE5ULY4Xyu6k{Ij98jW(TL8F_MD`y^;K>CWp%};;kHVPmMADDRaz|q*0 zHA$;WSNOPje5j>)yo0ez-6*DPeDS@A^i^&ah%EsQilezj5^HyT$y>58p~?055UY8nYRF* zSUoEVCg_PRxa}Y13S%ia-Wcnk8 zrlX8UP&PY8k<<%ya=&pV95Bv{aiISO&PFCRh>(`5cZi-GR-`|E{20ZQ0l+pQAWdYj zfxyKAtXEoJ1C;PP+-dHqr@@^G$2sCbERpehwbbzYw!8K0j*1K3loEI{@1Q~^>Ogm>P zT>kcmRq1@(gZ_y!Ng?lcc3oL|YFg==)(rj%fDQ-Zv8FJP#Bwwac~Zj@sxqKygS|{q z{Jb$f3ZU_hLaBmwwy-(pP=pMV_d z^RKVueC<)smtWjTf&O+eM|r3|l`w0M-HPy>RgD zB8oYFb-rZqf%Hk2SR8p9VJG$NX*QP{DVy=2UX5O3%V9j^+amn49#c(E;^#**yUT|R zEc{ds&mE*%~jPojBV`{ulQLWRGCNb@{9QjZ{x zmQ3;k&{}HHDB!AKzj`h{V?*k*E!5k+PuW7S903sWB$cURz6p+CITSatpH-x+_Ozq$ zN~&>pmQKpH(R2xQjmUGtZ|0=dzKjH)vEk|rb-tiI?v%fE+T;BRSJT7XS*Yj6#xklr@b%_oGgM4U$1VrCC6<-9W=s@dlT;Pb zFN$3qS6urt^2?BHn1Fw>wzw0|z6xb8cJV=+ncAWNE>PuYS0!Z5w_e-;TmY=t?GYO5 z`gCd5Xre2d!4PK{jr2p+J43$h7QX0z0L%?@@{Ns+z(pK-g6ttv*)ASG@vgQofD5@w z>8YuQVax5P0*HTR>K4+|nmY;+MS%d40WT-lgQ3!IIMti|_2WYYY;{^@&zHI9i~FeM zHV$^tRD)WB14KEJ=dIMv^|2oX|F)(ulz*VSLdhdtQBe^Rb3D374HC~Nwzs!CIXhGN zhZkTtV^YG-ym3)QG{XyqpAP1xHR|Y-q+UB8dDh$;I|V$K<3kaKnEx-GoiVP#K|w+L_V3SgY1b`gefb{yY=h88WkkBM) zpgw;MZhgxX3)Tx2O+8_+>=!1w(eyh7NGjCtDdbrCkEg=;)#sXXnYSUssL%|dwS^(g z&IJWW49t^ySy8t2Z*HF47N)artK>&vy)=qWn6LJgp`yDm=H~W-Lg4H5VG}L^t{Fww zq(=Jb*`GUk6qZw8wI6Pw0~}V}SHmxQ7nlXDt9P`<{^hNu6)4Qt%3PqCnHk8gC2ByD zPym3d78Z$D^;HgwSo+@3SDnniX6Vf%U7Ce_u%duq;ET~gp#W`M7=Wg-m0glLjNx5B zxu{)jN1PQVGvs6-0DMg8Ij#^jnSiNM1unJjA6cnaEW67ON-Hbbf#p-u?Q`~A=CYA; zdlN}+f~G51^vbW+89SKCY>SY@X^;#|xIbSb;)SHJ0lLoO!A`D3s}dF2tO|z2=a$D> z9wP}U-=n&bm>fBMVVnq7ndIQ~)q8&PNPK3ot(|#tRmxkh(`zmr(cj>c(}oJyM_i zCsNV6Y7FQQdJ#2zTk)B`Z;g5-^pbYi@zL^fALoV9yQIlRRTem0K?#uN-9_+oJwM&f zRq&g+uiyWVG0Qg@5%;v`D5!q3D6XubShw!eL(uX~+)t29MMPy_zB~o_K`8!Kl%-Qr zmPJ`%9}CJ|!TPB;cA?wL0P8BL0)h#9LTta}gQ=JB9~ldhY^QquQQ?Z>ibQ zh_|wf^Z0NhgdWgI74y^Ou62K7{IcNqJ=R)D#Rlo!FI?9S#!6uXK3@a+S1iS$UOZ=o z#0!9`0@ugA7syZnrAM9l=n9KyKjEZ}jCm7DvfY)HT@5F+B@5=!(Dt&qx!lKo9^?=; zl7}Z;*S<+l>T@&J!~UGHPtbX3$U_GSqCxq{+YR=HQq74P!0wBOI)L+hx!JDn*@c|E z&W;=`N$nNFG41D!Dzmb%K^YUC0QFp4-wB9q&&!yVWfQD%f4)f6xf)BLjZAOhMZ0ft zI4IL@KyhcBl`E2a;7Eq~|JB~0DuE)GKeCWB@rz=&lv-vT5 z-!^dnYxKkNG}8A^g!io$3nVXsH>9)xU=tt_Ka32J$R}NU@=qx#p~X~1A*TlL8uCCK z%d{v{$}rAp0^r7HXkv`8+O(z;JZa1Z%xf~R06wzE6Rn-cSc_?UAvXTjFmH>p<5U-qblSS?6$puB?L1Q{&#^xvgB!T@zSvAkEgidzJKe}X-uvJ7? z7yUghnRVaN-b{2=r&j6~UbFi;`liWh2ZWHsYPc+7@1A_6A=;MnZ2aQ|(Mv@NW`$mZ zH#Ktxoev!8p%9+7=`mOAW60ns?VrNG* zFP*!7MB~5YPkm0FtfmoIbp&#EZ_$|QeSu`0qmyp%yW%s8Ihl1$5qIT~sw7pLKxf*? z!fQYHo`3l_ux!0mMq#>8A=4z^@pACYL#tsl)zpTK!vS2R2OyE7N<2FqznuQ1y?t`V zh6u@@C|c->Von~+P;>F5EmilmzB{wEs36#uczR3=Fe){%t*z04^pbDAWiL&^?lM5x zku5i}x{L3gLYc^!hx>sL-vAhs`y$2}85y1}XGKPqhQcWcDxSH(7JQOO01Ds%d6u?l z{^Zo<{KCS8?f(n>&9483fr6=-S$(A-;wAF2ut`qF*+$Do{JF2r^KYTMqkl%!-=~cZ zr#2dzypwgh)fe<`k+_>C_b+6uB5kK@{d7oYrN-OrXDvaII$9TAv&R1i9S#U@=^%!d z-uIxHs>0Fgg$zi)ws_jJ>W3oCg%SW#8{KZT^dG2x9GyFP<-bsgGe19nVj&Q+^!eji z811k_#)LxLOrDUX-M-z{Kg)|HgJ{dI5n%Qv&-#l~9A-JuDPw^lgK#j7S!9d)43Ey) zZ~6Hp5b$DcTr)2>qNSa0@0fG}yG|^sGGKWRiDH5S(QeCU9%CCyGBM6|wWfx0pel*Q-dbT|_WBtU)14q` z={HFNK~~)&$ou5ql&O9s73+F37i(y#oTj9(^KX5<0%cu+QYEXQwX4p*6ZcjxTUc0( z??(OxUp#^54B`-~?#vOUw*b0{7}{ zYtEvaL$5nILE@12>Xm-n`JER%tY19*N&PR1@>pYKa4pMkFiJ$KVk>OC$}oY81}=>x zYD>hvk-Bf0>@cIa6G`q3tQ0_=#Z#2KBL0J7U*Xs<7x4wUIM;Q zwxb&WRNN@I`TeyofjqtLV+jaueHOG089V8tBuV0i4!_49Q7yu$VP{n%|Bxaf(+qab zaFbugY{TqhKfC%cjEWhgrdxU5vD9^N!#v|IS>e;9y2E*x)q`XEemyUpVc_b$FLa@P z&i$U}+|uu_o#|p+2)wZ$glHh&Dn$9aDRk~PFbL$Js15)H`?l{c6M*M)0rT?F0hQcc z%2X6Xs2;KeaRD^ZEd%O}dja&d8wVj3FS2CW?AnNQZdNhC*X)MO=)UG2S=HJ5Ntj3~ z(e(1Tq14ODv@@u=Z@H&0h7j=zYoWI3?g6~J>Jzw zVYA^(l|j-PSldr%i-0|<@1nEWF+A&IEo)krAyskVE5v)Aq!-tGnH=n>6c8#w&5r|DI=7b@vT<|CA=f5Hzx9_L~!3kPJd{wX$852~yDNVGoyVAOW~ z0*I7b_Yk>99MGvN#Pqf~t;X`V3s4woO5HuGGrTfafOw%sH0{x!Fa-FCc1|5s^ZX z1#f350kvOxVgjU4TZL=t1#BK}xwDf)E?W80KKv)dU{$!^*6{uCU%*+s^a3P{^)_}4 zm0oTDhn^&2sfAgQO5L~ssm|lq-zHC}PB@_{I29ivLLWA&uI?uj1R)}X@XN|bn>4GR zJ4ptkc-EX$z{o+o`+1FkZ%==y#IR(R$!Msb*I7Vhog^0J=Xv%%Ndo}WE&UyQC5=427{oBa(R$Z!cb65qRN?8N5Vy)36uQ(bL6r37jpcM0W_nTI1?YBnl^~M^46M?uDN*hprD}TMf7m> zh3nnFRH1*B(E+ODXuUZyc4c(6+(x1w=jg$8CI5Y_dO{F-jqs+<);sj@DsUx2xBhO# zo6n6t5^MGDA4WAKek0HzPT3k1gs=B~D1ekf)rp@-0-To@eLqb@3U@pJSG3v11yR%& z^8ytN;=e2$^N~Zw{>X6Q{guME6Q?Ry@R>?z{CeAy?`Io{mw?ai~@C&DTVk$^~@47&>YP7sK^FZ8N}BG?$>&V+*0^EtLhHyUOLOyJ- z!YsFh_o(9+%lZ?0Oi6P{vz9tff*ftQviRJ(1dmTFN!9MkS={=r zLswxQ?OUocWUjyc4K?DGQOcoWkv`NUl61}I(ExG~tQu`e+*9>2a&j)Th{L+GfNP(r zr7ECVq{Itb<#oB|J)i=D-B=RS@5M`2_yL8ZNrCk@cK7`_!~7WLX(<#Ot_{XNg(`I8 zuUyZd8Z%gndnf&Lb#=3g2OoSG4VrYes&4|>DL^Bbvy|Y~s&l_lkZ|0go4LTV*&iRHF(^ue%b0l>lL=TbYAEOifJmDyn4tJC+$kp4Eu6C2*w4}1DlFdn!USaiM=r)T zPbr}A7OYgcpx0WS5yL2w6yMs)=$KsIng%sd6F|rJ1O5Gql@-ZK0c;Xafl(FpQSqUG z5-1!rrnM3!jP!lTt&N;;7#|;7gh<2t*@DPfCnwkX!#pMBq9zN=cVd-6Qzzo&U-FJq zb{=Sba!1HJu^f;t*4r~H?^F?_D-i`XhZ2@IQTxA3Uul7i0+>JfGB|)68GyZ^j1mSF zSaU9Xupkoz1U=yL7Oga(U}@&J-){-vaG4jJot*)Iq#X53OlmBS$l+B4x9;cyyZD$= zG}n!%ksYk*(ZIf+{S$I_`HO*+88@iy#zBv|FD<~Rt1P(M-@UPLXweA4F+iKY{uIS( zMSTuvRRbtKL<24gS{N607qH5Qp~6cO zlo?w%g9DF=3Yf%LLlV5=K6==hZ-1k>P~8k5r%DhmmhN^TTm4`Ooy4@N0r604-^0G` z$Sl_EYXQe)|fh8-5J{#xMNX^(=}0=6QmY6KA%QCM^obG@bivA!ZyUqpfZ z*r+FD$`b`1+9G291T8}$ndo%|UGYbIPy8GFFsPOe80)B{&YahK-^qcRBYs{q+zt8) zcf0wv3`z#6<8K8tB`T{()4l9Du^kt_drx3{ zKlXjL$``nnTu`8hB2TfvTUOMfee4?w+8?2o@vrGifz$US8qhiy7eM3`@?4P&rNxr$ z$Apl*cZow4?BPY_(a3)MslM6(gOwG`YN29DV7F-cDnCY_r6CssR*r7QkH9 zP|IUV_?5o^?fN6ALWZ=NFx)V}$DO63C`Bk*j(Naj!PzoI-sM1V#DuAG{<->C+Xc2A z;1bSYKUK-+vbD9aGQ}?F%D*ZrI?#X<@9KNINE$EMKKo|-sM5shk2R3L zlCQXoAQV2J=zQlImYf)&SoeP(`jZ4V`T);1k`8F;s9W9K2`Xkv(wHP9L zklApIVt}%Zya*MqgBl^NeSL|Cz!7-`h-@^t$Rsn2vg#fJOEY(`-hFT1PQj`_4F|Ul zZ0|okw-wpZ+E1Iku0>Pz{t(OQ8PR2hiOB3z#Lu94@@s9!eYi}6C~OXD-vhmDf6%iu zSUw_nn2(^o<&^NBkdL~|nc?jHk)fo-iAuaeFI;F^y>Nl#Idu7AK$8 z(2Wcn^TCPLOXA<2SaeZ|)m!mzr5a;K0v6_@Vkla#r8-Y@3So`NUnd1tWIS4kLZAeD@X3=rhWG2#eOIPN0!izHe6dhtfd#LUylo zEGI@SVDKMP<2p_(%;c!nhLba!+~GDwRj!9;L67qMw{rc}RpdVjOmh^;`PC@tz&^k@WKJf& zI#)r;`G;VRP#T1);0=R({GUaNHR?JW&XzHIx znS*pk*ViK$^V2!GXisZxx?u+z07i7=rQ8c}YxwW5A5-6wW2Td3v~Ur5bf&B1a32mhi8Qk$;!4TY$IHz3o7TR zP7d{(%Cb`*j*bX+W;P5joJgPVTOT>B)$1Q)7hK`K-u@UbaMYgu!iK%F;`1xhveLzV zRL>PN!kTf-GV!SSWS;A28r_g^owLCiss?~FAc$Ja9RV7m=6YF?j#yt?{-#cC>$H-i zt$yqzCYdA-J;ePu6NFpEX^<;D(C^K>7&fuLOW~>zLEtF8P;cd-a!kVnknr!LBmAod zU6T0ZnyjNFk zgw1_6Ge#p$FjX#>uRQQ{5ZV0jE$2COQ2VA{;Ln3FQ0&kL>8g2O`mHD(g4(R+?5P7P z-MG4(ev|i;qWIoglGA#dzZ%5Zx{a@(SL*5SB7`|doX*$akN>B9`;EMhgD zWNiy07B1@Vr9Q{_Hu}L4PoGTuJ~u>DbZZr?|5!(Wn%_j|y#SxtI2~$NE?pq`HBjWh zfqKSloSAY`$0G5BlR1~Z|9HdM?PzvEwg%3bjKuf@T9B=y{pzAdoyB_$@SE zYCkVbqAg-vY)G8v-y0h(6Q^>5VsT0q>px}UBtbPL^YcykVTm$;3P z#!B4g<6uSkt8UqOkA6m`(2sXcMWcjIzVv|llfadahQ>szbP)tyNU-xX0Vig? z?V}iEqD!IGPaY045UyZ-3m4`6H2p}tr#*3~Vl`^M-)r0?iVwHLe}hoNy2?O%dCQI- zUV8CD@eEz^sz{WIFamBUSuGB(iQ?Xux;@wNoc89`o9Wqyt|g)EW@jnT(+c_5?IARQ zVMO)>SBm>inIC$kZJ2#aoTjE2HQt+jK<1+78nX16nRI)AG*Wy$H# z0zF$#q)fyid!M>>7t4i)FYaLyF?f%eBkQlgVe=?JB`APnQq9GTt7=TsxkC<-cE*wg zrfdZP`G05i(+ta1vTR&N4O};0?C+gBq>US-dN$2iW9?y~(X9hI5T86i7Vm0_@~<$*e*5nU_8j#%Io1fjUKj>C zN7PKrzK=o-DESF7@)EfnSlJCm^V7%@yP-<8;yl%r0R4nnM)-t^`Gkd>h5I=ge*S^X z^Onn*Xyn>jJ0&b=%^#%e{;ow_lg_PzTTMSzy#-=U>E}3J^tfTPWp-t0`T}3;Wy~hZ%Pt3U)WK;GClRrH{OR5!}WI07Nzi~(*4!hJle@(2jElZ?gtbe$jm3*ni{^a^8GnPlf|b} z&)W|6>-h93uRl4jS}Nrn?(9q+6cyV{($)u&9-x6)a*zb-`)Dhp$XFSv^r#kfa-QEP zf{j!SEFJq_bT_^*$SFLvVh6LHh_JY`;eu7uS93b0D+HFjMUqTR)+700IF7+vtH71X z>aNfj?^Z8%NSD$ zDwaH>rNwMFjWEm+^#@h=g=G$1VyZuiR2JkZ-rJox85$<^TG`#)%#@hR$ZEe8hbd66 zx7VwSKdvqJ$ay}idHTlEfV+s-pJKa|jE;~Z8_X=Sw`qR#l2DDaTBR1S zzlJaFcIGlxvd`0(PE`AEybj@3EokWJ-e;=Z+=->dv!uB40p+@R#4(mu$t`E(;dYDh zh$>lqOB?dkY1dwK-yf-|2SnmImr7{QaYu{;lg)(*A6WUDj*MnN& z`_rsqG%k3rA9o}il!OugnBGg-TQooR<@-3#jMk|{K2+YI7{o9>FU&pA^{kgm_NdVD zj1Z+iV+b@~vZ&P`EquK45NF)v4bt-Wc6*tB$`97#c)yKfOtOoXW?vaecM2xI5bwG? z9kL{O{e;7n!xrBkM+iyPeB!QBiaW9x^uooH-EJ3vocgjn8Tvq(5_{@6SU5yBQE@df zL2IDm!`FFHuV}{E%HB6}8<4%pahd%shUM&U4@Xl+3w?ilec;p@PYw$u8D_V)Mw_on z>gYO`96^Kt!?gEAp(3{2_K%hgI$Wi|R|3w3?9z_V!yIkfr+UJ#Q8FUW$~0|T)!W;^ zjfE%G%riT$=yE3>i=d?BrrwXv2o5P({2e@fwu0EZf+Me5>HE-PyddRx^`0}FvFH;z z)Fs=RZn84jFraP)!Am9n6-3u<;iGrN`nrS1#*UFHnbUtIjO`yL$q@&8{Sw(Z zIp$Hid-SB&P#gK(?fs{qHLQZ~cn>jf#yFz(m)?by2bhb;R}Hk7Nb_xB=C>woZm<@2 ztSko>umpqggEWO7p*@2{dPJM#8`eTfHue$ z+p&6uy{2inh59-##PM%crAf+ujJxwYYEaS`s)Ksk>q%`AH1|GO)7u8zdCTb|HKevZ zl5H{1oCKQXRdY41vkpIW@Y|{62MvNpRYZvbpySnJA_l+ z5aK%-6YfJhQ{>dOD9HK!cDF>dv%}P6LxZ(G$|oaVUwlG*2Q!CbFfsW{24V#Jw=Z7q zC(!krC}lZnWf5qO+*;H8IamtV*j{n}kkg1Iw{FJi z%q|6f%W^*H*;+j4`u$CWaAjS*J4F7fE{GpJ%+yUgeqq%7Ny58wP8{-gFL7#!O*Ip* zU!|7Kc2yGRK&FX^3|eIu@lF+=JJF2#0ZtH-j z<InZGqPjBbT#ha*ig_??LULu@wHq`c&&zQZPQPBVp11RvA4S`#i0*;?VnySgpP z%l@B})~vSvF;Up)mjd!t=jX&pA8hEi$UZ*tbu9lVcmTmQ zT-;HCoO?A-EqkyKJpR(JWU4jq!6xZ(U)CCVJ5M3r3F3Ww8r zi(h?aMZ&MV_%{>Ibi{tk{L{?Ro3E+(AMAvXW`kaYYZ;aXQ!D?;ozf*YtwdyJX<>a5 zPJpH6Y~tADn&`$U!!+GFDEZJ^gfjNIt|T!WuU=u}65Tk}@Gz#a0nD(~w2gxzpTJ-3 z_HkNN;J9(b<9=ysq9bf&!rTF7qa1!Py0@&LVY1S|Yt_zSB#UBot$h3XhJxUoz`yV9 zpomv4h1s?())#^36!I8|i50J`Oqwsol|)L9Z|DR&9M)_%&9B_pR_%}Qk*_`?d##I$ zo$KFohL$a&=3^*v*ER_{*2R1t^v0dn*j@m7ySz&;a9X=bh4g}SPfqM+I`NTD2QSe; zq*+kSVBi`uvxTY%y|ZJLbva)VFH1h_%quEgSR#|>@-i5L)0yfZX3zV3uhvIj%sKueCo$8eqWa$m&;;8v0^l|E?7NII8$=}b?eJbHX&yVdv4*s#GE1Y`Ks*D(z zMU>Ct4?VQHQnlcbD{YV}~*FG^O|FNv663jFd=S{~|mLD&2?X`Nf z2)6D~S&Er&9UY8^b}f&>9=SRno83?x2v3{%pUiRSud2lN3=YpO8iRJa)o$f|irexFXAXkASnwmf2=1s!i4ibh{#XoRFE^?nd-HKY3r#PF`VX0?6y-T?mSWNoqDQQ7#7*l;%gL{>Ha1xYC;;!nloYOd; z&15o3VlAk^j0!eDJS6>sIc@Tei_%nRQQ8Fzj1c0%8_4vddb1gesO&-x&0WuAdt zP%3`iq^_STE99Gv9Zza62ysLqyCK17-d`OxYc7$wSA!?B8@D~EpxB*qpj6#p7SN1t*uw2H=m1^PyBPi_>63;+GT%8aY&x|1f`w5Y?fPwXN z!aU|cSL_!Ch8;)`5@cMAz07q%)Ut~(?7^Dox@GB6K8;+T=`%h(*wK5h|9s^PmHfUo zg!T;-qrY22?iI|_r`AHYOp!`>*qn`xb#|RTgHB#{=WWb_EoAh zV}lq!GFqdK@^=sPCIpU$I2zkjAwM2#S-D-l&IRLpsz|L=4lH8&oh`Il z3@OOLs%7yaSXHgc0-b0xch8Dq(h3|meJP251Bi(g!ZBFOrL@wAnIT$#?X0@XP@-g{EUZG6->kn6>SpGF@Lh>9v^6Ci6YA z_q3ojbR`))jfuqK|2D^t=6c8?L|c?*HAZ>%aW@G9=J}^kiM>jGIwd?x4D2yb^C|#Q zb6X9Y6kdTvp^VR>3}Bvd(eR!Fm_m@%$C4Hu7Gl&1dUHyw{9U#!w3<5h&hT6)N^OY-AQ);D)xAhmIO1|M*WBqUO7IwIStciVpgU=Os%#~%-HUEvt|yZGS6`(QK6t*Spu5xar6cY?&gv2+ z#c~Bb2AKF$PXEa+zUkMph)!g!UE@Ou+(1F8M6BR5`u(~*7QopC-YYN{^8L~4PM{7Q-XVAF-tWe7is{bF()NLX5;zY z=(QrWym>&y%atF8>o99UI8w-*p5e5G^g%Ur?=RAuTx*veud@vTw{rNML=@w3QiS=; zo#DYEz^Ah&1TTHAoLewfZcS8vkCNQ=X8j7)9SALsiy_1RyI7SJ(1KO>8&D0taMIcC zwD#>KIb(W4Kx9%q-DHj!N67-OEchnSfs*GD{yBZUj zg*&7=rKf*D-=|moZB3UBIn%H`LD>3Nu&~Jl2utL=LIX99#~B**zq`N(E?DdA8eblG z-c1XQl;fq_GA6Yc4S4<5!96;JR;7ut>{qHz=4Kl69g5xlyvcDTScLCwFW=jeY~t-| zpy6)k!D((bbI`zz2@x(&_+qW5Xo2#mvtTMaiMABLEc}V2jj1-IH#Mzfn?BvrCTYu9 ztzJi;LO+INenHEIb(md<(k#ljB-sS7T^il6>e>9GU z=Q|T|QyqF|4{&cJUvCyTQ-PhB>Fj(?5R51 z;#scTZ%WGW#ifE^{Nvl_wg_5-a(iTT6&zAho%>Z!sL)47{E?JTAz~IPEmW)WvO1xv zACDs`e42SGvNrh1fv#)WxUc&oXKL&b!Gd6ISQ`(uBYHg3UvIWX?vRaY-5e~clp9jH zFsQKEiny1!W@t!$0!*W`^bV$Iz>i$4gJJiJN=F<9FlM6|3~-DV;27I*J|eD_UsW7N z*}CZ>n`ArrK$LoF=AC|f0vzVn6!WFD;dY6PQ8gsxOHGBk3XN)&$rsiS=4dE`-oBX( zer@E>t-5JtE4KlHm@wNkcY)%{ZW1hGRjU?_-bw81_8#jx*55|8lDJ)Dq-)A`9Wc|) zweI<^OuYIrtRL-zd1+VUhAkgSd5p58QxD(oAUGshaStGRZx~%<)JQvGCEjzje03g2 zl9wL!+Ox@YDSvWp27AYl;*RGD?_NI7Lr%qkZI{#IFx9XqK{G2yV4*!mjAJ2>euB^lQSpO4p-{Tj31qm^4%vbE~_ zW8nJX$CNz!H9-6VY9FV`fEM9kv%2tYYZcg&Hb0rbx7wY%D_bOquS_$~@w99`QDH6& zjNwJBv98bgF6$k};hd}N(MNVxwih^aGlCHenF7F`*_JpFqP$f2?bN++Z|E$6iJjr$IO}J-^~J z`cz&0Y&=|twA56i%@WZV-yZa_1uiCU;vrtOgtN-S1mMI|9W44E^VAjMbWW0Og~=EH zdFUTMi3j4uUFL#-(=k-YTQiPcKO8Fx5xjF z`O$~}{NMllPvIe#xPRozMFx#>S1;?fkNx*hr+0r|xg~w6ws&zc7_Tui+)(m4ZZYs7 zbxU$mDf>PB7eLzFfB8FLA39AzgP<%_8RZg2gqhv+8p`=FQgN3Bviw5KqR($&T=71= z$h?!(+i8jWYjiEX?Gkh@w*7F zZ`~HTB`-1*+q+7!%snltR0v`G%P-hsjO~;I%7M3c^4U8&Dzt66gvuW@Ycq%0A?XOK zAaxzPMGSu6HRKSN-T0adXsDIre-@rn`XaJkZxDT{s)}DIqQL0&p`yS;e#5E(pvz7V zE`UpDkBs!f)`1{x;l?dFaX(5Dpf3r=I6Hyn-yyyP5-;zFPR392Ra4iSFPjVaCPlwz zF9+D$_fEh6UX=-bL;fuvEA!Skn@!FVnG6a8US^qJ>S^Y-+@5FB{7%ClhXyqSXH}WT zQslbFW{bDZSy<%qVn@qorVGuNo;!&ubz$D2Us`LI4qy@?5~tv;oyBY$Nq1^>mgb;X za402xDrl!BW*WPwo=91(O)(+aX}>7Jd)NKp$GE&wxisJPRnN(7mLm22I|%aZqrsb> z5Y2+gu4oRG8sWf{J%Sy)p%WAYprS!tMfiCaZs(%-vBN8d+a5IzpJ+_A-MFp5;&+03cbMiS09sf$T+x+}hbc=5Fbi}Dm;~zAtLDBnB zfw@1FF~z5-Wm2iO2Ky9G9gN?vyIx2H9VG$tzo>ie%{ZAFDHi{*-Z|iG>nPY{BpS?& zOnn04H;AL!-m z-H{&E`>C51KTSQzmW1;#p(C)=S9GM&=0X3KWZ~D>q}X2%*0V@hyjnPhv`zUnkGNW^ zL?^g^^zje+)Le5hsX1bo@V=yv3t}amp6DpnnzaGsO|5;-w?UwqDbO71g)^Rgx?iF$ zOIS`?hIKbG&8|awQCeohyoWq6vSNTK(7Nh+f#YJ6@VW@o?PNLb?9m5DB=k%@maYc~WtI+aRS+w1SgsA=un|3C-^ zwcZGK`CXcHsK*3OLbbS7^%YL+Yjihjdn+6bzs60v9{gn;Mj3sD@Uor1lVdT3ZWk;4 z7Kkx$UtmEd1)I0YUM~d1`URsc*6SaKzx**M^r_~*O3NUnF-nH*H_JIlp7jez0<@GJ z)^aXg5xe&n?jZ&=2-ti_YervQTZt-~fAAkCS3cNw_ull}O}HcA!Y6;?#gyst!2YNA z=^NI2%@*_qSYutxpK_>Xk@LC_8(keQoVy6s7m|fdid}-f#!0A74nY3+?oCt^Ih&C) z44Sp^5%(Pt;_^MSe1 z?|>~=5j~?-ME}8Boz#qki3N1v2@+4Qg@*1Eg=Fcc+Sedpu%4$3=`dEbZ8S4%Lmq9G& z18vWC#;Bk?!@F`O?R*b58WQTyD$tu6Q?Rqki4&dK#Ckc7n!`SlzT{aV5$NP9pe!i} zRfs^+yJq%XUEm2gX**o^oLx%X!ongL+LLdUS)GC^Um?^oHY6m(bgdkVO6kbpY0tU| zj7Mv80}}+reUiQm44(?#nJH97)QcaQpSOEA_|wYEW}2{KZWkOJ91u}Pb+8aOO1?+U zO>OP%7nXvdu>Cd^hH64b-@xOVzEo%v>^faIG&DpbT0q5fs9OIJRRYdTqFn`4y-G={XOoli_XvYeOR^77sNGw#-;N~!@n&> z(Y!}7pW2Gkvw%{{+~TF>u>XhGtECiLuZXa9O1*)F!6*>vTQ_opN`B5D^&`zb9Hpd^=&N_~G zq1au*Px)##fFnMSqU7-U2z}@8Eidj%!1RqMb6_Rmv?gDJ@~bP zjWsNL5)%J;Fe+p+S0^*&e0FPxv7>jFrCP1qp!?p2VHV!+69#rl2CTJP%fZKNzUj5% zys?q)&fa1}uTF`Il4gY9WvVoamzz=D3nB;L$Lk}eIz%T_w%2%9s&xt~{0az>vFa;T znO$dU1P*43G3><`l=lNoLA_fZD^;`9x}86$N%saU=nX30 zUyYuLSS;Z7pb$MGKrgMcWe6P|A*ia0W2LR!8c}HgsRC)*6$}Ytm0Zure7ouWRhK;b z6x$vrVzcvlT+!=%38$NXrp-*hwK1IG2pZP}Z}PtT=>1p?Vv1!*sD(rxV^vta_?r)O z2;lHDU{8|%3XEdaoIyIisCHjqB!-~77gz+6L9N2>ef-0Tu+kHhoGjz63VeB0Gl)Sg za&6pr(U~7}tL~SPpIo{PyO2wyaM_j;S*ql8y1nmHgP;Zw@-T<~_iecfe32imF+6b#}F-eyEXE1 z{b)dgzV8Ms^CgyHj(tz_CDWn)ipTsn*&4~^2LnWC?CvxbT#*4SI)5Kt&#ql`ush(E z5W)7GHkXeHzsN51?Qhre0T={fkC2ffYyi%Z>Gl&HJQfVH>gqfdJ}DRPhN+w19jo#a zr7Eb9QdwcOj%(}R>Dd8WHK|s*fZo3vPT0`wybjlMyDP_PWO#Tfngm23xt^Wam7FA2 z-}5%UyM4IBc`3wsefM`unwCpCCua-Z{&QHgPBdwY2vw zli(k_@k@@Bxb~JZoP3-5`i0{6cZQi8%h-XrS3!xBv#ZCK7YEfle#f1$bKop4;3ty_ z+@aS3CC26>FYB%SV{MH2->F(icAZG(BsYXB8#QJnf3$uqEIiQAxXo#LEauO7v3rq$ z;4N}~+PFged18SrS-5{>?iCd=Z+iija^BGhsYlANhARiEK#n#Fu>Nf~hVCZo z0WDajShKtBwS7oFP{+A4k*yz)6_*TEe+Lx;k6)6LlS8#<$;ru^_lutbTWexrQ8Q5C zCj@j8S}A`_HP||E`?!h*&&J)JXdJ8+Uooq=Y02lXK{mj=vp(FTa3!u`rn3_{CEu^! zcPiM1i>SgZ^ln~Uxe%09y8=Z(LdI2c(M&+f0JjYJ(qt|%!q(Pyd}bBwpY^~?xuG@# zpBh9?s!=$qzBWqT78QB@6gRmdpkn56Riv=3Vgn@>j<(8M;#4(U8VEI%Zw>_t#(C8jt?b3pYx} zMn@~TrKg{=;}Po<5KhK5TyQ%J^9m%o%7#FAlnb@RY4#RQ4|m{XOy_+EBuL6d&MJ0Q z#WnrD{n9G%4D}B;+Ls&BV!b#54|;9+^%;OhY$Fc5P%oW;oXuVPOam&zkC_3U4OLwFYlR6 zC9$=yuKY4}AaW(R1t2seHYf;8Oe+FW24aKNFo`ZQgFf_P{m+GFMwC7BS`x6e_N>|g zV~Ehgj{>xB0!!qNZ;KF=t@HngK4H7k#nUXs7NiqjfGEZ zZlgYFd>rx3$VV!Z8ry-IUVqV{&!O3lba8A(;^cg=rQuYTuzF;%`Ns;U@u=d94sNP5 zy-b%P-Y;*(47GCN6Eem{IZhu{#;+Jg@LT*QHC?a{e12nK2QrTk#c*j(J&<@acSSVvOkVx=Mw86zS?7(K4W33Q2Kl%;-~wwsR!>&|YgLEa41mjW}- zNnoP+0%Qg0;LRlJ6^biMPM-rJ=*U5$4AqJG`1L7Ygvr;cgNui+z7$3WsxDacQ2=9j!Izu zuT?Jb6wlB1^N#tR+9e*%A5ajJ>FZZ!QSoTYU^jnt#Q)a-BWxWUTAkNprqCs7&kJ`b zC>{`sBrEzD1G&^pW{Mk(j!(TKUJ?jBJZhy^#>0UAQta#BObu;qOLBM-V0J5gvIE5i zs5%@m9bEDSF1EoCv*Zdd(H=xpHEumbpso>!@1wmdI|-D9j}*3&l9NXL22Sk_tU^YO z97R(37rRZqct1LL$yZ+2O+0j=BIM>qqxz-BG^eSh1|oynSq%s4MMk^e{CMdq5zcUl z(FLBA*U4#(X7iWIwp?DYNFK!{!hnD-4802#~b0_N`9Vh5i zFXq4W3UHknPCk?N^WAXa;P5e2dhX`6ZqYP01pXVT2pV}Zm5kRgNw7vdY!KrtSIKan#MO64IYhNT_M1JkJ!BqM$7rsHf!j2_qT&lKNh5Guc=3w2@1;E zR+ru6V5zJ-SbXTNm zQ5`TzE6%L^1bDG1=oD3g`(V+T6$UKLxul{MXGu{AL%Xc2_}XDP5;8Oi_K4o`>qqFy z6BFtzxk$!)NQ-veI~$PI;nrX7qYQQ0BR0%@TKUK!>@s#D&00ZyZH*q9I;)k`yS8r2CS+S-I8sI5tWxkv0 zVkqBwNkQT4*W6u}2c#?kW9<(Ha==jHmY;UxhB8p0(ljbD8EBRrYWB$r)Pb4POgEZH zd)v|0_6iZ)0$ca{2BWo4Ph{y^| z)d`u+3<(f)9Vf#%TrS6Wv$o;w-9F=xZ8NPD0`^7`JS!&KE(rrMoGth#VrrI%Evavp zExs0~HgkWQ>y4m6!t(O6Ydu#J5b3Ju+dfa>q${Yd0+)Ym{VYsRAQY6a!?DHAhY#j91t z16?-wq>mTY8bQ^Ht2*6))u9&r%DH`^tw*xmGV+8TD_`tcD)!sf6PiK2q@tnGO~wkV zSG|#!tjHd)>`c)A>2^c`C%bI19gv$4IjGYd4o;ICl&>7t5Nd1OjHZ|^O?}NTkRk*1 zYFvYeY)a}>%Ud%uJ0pO|Qwk-?U(Qz4lN9#tOAum#!1&6UbxSoVuhi&IIi{c``F-~h zo5&R%Y3M;fn&|>{2nUvooK39r9w|;WX3nnE)N=NO+C#FW=~ADn$g6}`Y&L(+XxRAq z@m~sYF7jf#abRRLd7ysqGc#^+ztkyXwid1LeU{K9eMm<@a?~B9@-`#yf*>eDk(n|y z6i{!wbK^8P04}Z`z>((!gF^lpkHzmzU6tIGH8OKa6%|3;1~GvW8>4)*($av;(t#zg z^`zsKB1%LsIx65qPxyApwy!qv*QMw{oQ+5s?42ghax7m-&K(NjF+X(=SWFCqjP)G9 z0;sU(D4>na&#EeD!U3 zDFDuOEPbUv>cBjJ*tpJ;W@5n?gKq4gzD0|L0*GQKAZy?03*KzGRYHKg#DCUQke?oU_qk})$)IzvCJo^gzBKgQ=&JP^19sRjL_$7wgS%CGA&uA~18}Q5LU%4D|DsEFKu);;` z!pY24-5$S>0NxdBj=@aSqAJ{{=!%xRODKKlKgSFz8EFf|WCMxmwUsapE|Lzw#!U>= zzFPsrKj_|e1h>WcB}$G}KV;1@RK#=JlU4@|e5W@C0lqIIXgQKMespY^Km&@u&xo@h zf?Gf2v%60H6Xw1=(w<{w083jN7TkF^pAXQaga#vqP9XDX>0f!w;qDk9vd;AGO5p8@ z^!&x()Q#xmKqf89z%35CJ$=6?xTh{?nkx}D+NdPK2Y}?*bXS!=Wd?N+sC=?Resl8& zpx8j(fmDRpLYqNC#+EBKW`RfAYgl;zqqR5rCk>oyIg*SxIZu&t1ZzBe0)EX zBC$3%G_g}ns>*}@s!A2WJWuG)eXv#hC?Y=tZbJQcH95eri}058av^YFDgi6ic;|%+ z0SNABSKx%MX2vapW9{5*r}&L|0fYX2$)*6s^PKbk{riFDR&@sK^SmP>??X6gLq~_! zyPE635JMTqQ;tJVqjDQ!xPu<}jPV(}uh``4V$g0Fx#LpM{7jM(0Q2h)14UXD~xbSOtOHi$n4!6H7yM~Gbuh-}`G80HQoFi-T5 zp~GX@>%sBg>dIF~yW=z(7i;gd0A${X!bPE-VfdZ>;)dST#>#evsBP_8(Gncg$xo1^uK@VmY`tF^ zwe6-vVb7J6DaP;5hZYmzAUwPlT{(irVOAH0YQsDGbAgb3aG}!@51<-yjqd$ROjP>^ zci4-?V(J>=?H6)gnkuZ-O*gt+wDehE2s!v!;9ynFB9%aVTa)uTQ7rLlzFq=H5?DBO zi|5yFl()RK`8;XpCH0}L8(V%Q|IW9{7!L<*60TEGihCuF&sP@xe6c!iFtCLU;AmTe zijU89Ax9rXMoM7BdSLI7A02`ljsYOyAuf{lS3a|9wz;Ilz0OKaOgjBsgaZ_m}9MPC7* z&KTl*!&NJs)<_57J$fgpE}w^Zz|HS+*u)P=sLR-s@6F24yx~T#Lb^XrTtZ?Ns49p4 z*~oER(ghHsU?~@SCAj~`^!xkJ(K$K_Ow?z_HtXni2Xsvj&!UtFnCu^OFRM>G5FM65 zhcn0`RTkHAB)M^s2kkx+MNV->FYrpUMEP7#vo-)^kY6&p(C+rv;2&SdWaq)weP~78 z{)nY5mr7X?vIq&4e68=?tM4~C@tNo?b|B93D7wijLMj|azV_N8cIV^NFHRjA&9EF0 zk-VgGS8qc#ZgsDVI|#?jBfQ4D^Hd?awW`7Qe70nSvFxLtY}r73i44Zx8F&BA*Q5#uyn=mvw0ixRjNhqKEqA45pNhBKtreDW zJ(W(h-xcEW@z4H~ZfB~V>1TVh`99#zLI<#W8``c6AOCr~D0>70ZV0gm^`$O3nrcy` zC@Fr2jhfNj&`E61>R^8Q%_{GY=`wR2472eJWz6&^$aDN?H)g0wq3Wkma!2t=3CbN% z7&)n0;ol!G!x6Qq#iA!-kutXS&L7mHtn?S06DxcMo`LSEK*(I>KezhAn$ z=1kod$oah3BBkBkE<`yZHrzB?`}^?uq7_*u(Zp<&0sV6dHf%yON*M@V@wJQyH}AX> zN`4%!8k&n0mcXVPoNcRXLY_#X_c~5o0Zqi_SQI!e-gUG|D@+%eU3Aj4{=#Y|#2Uro zXik1)t5I3yKvzJHZDyNC2`9L}y2!yD0Un``xQ*Qo#w|Mju~~;P5RM4*<6cXbLsJwj z>7OrFmw)FDV9OhM*_9&-3PsZ8CV~oPhi=bQcT{g2=47_@*TCF$SN?u(dY6Zf&(RNaQ7IX52~|FmydVGvqQ zeT}#ycuLw*mqvjCnWcBpyesdpC}k#CGR;;uFmb%vds5!_Z9=|pt%dHxns$e|x-fBr zGn7&P2Pd7ctKQ80ISyGu6eJ$kwStLkUvhEXay z&B)_{>QCAZ&TjB#C_mu#hM#w-6Gb+7&R)BPQ-MRVMH&`3V|Im?nOSDmU-`(VGUiCe zI=QvERF;{q)WsX_HeW3d>PcCcFYNEu(K$eO8(Kr}rjO&>j4qTnjJFlJ#b$317U420 z4tVRE=y*y~S|H9=!!o;(A_B+R^NAhO))rwP9Bn zw-NkXCc~?W1)N_yCmgY>c)#YmrWe5GaP{Qt!jMnvoC`T53y!m9O&&dE)3J0DsV{x_ zS?7Tyaq}srt(R*fXJzzTg^z4uXIw{l#UYuN2-zqtJ02R-*~_)ZF&nWGS)swD+jYHK zmg~U3O|ymM5Fz@r037?bbftLn8D6u(b+VDuA0P2)=31G3&3$}%pC)~P{r&NNK5_FK zFt@UghOC?LY=o1iQ^Le!=#wp?s3@&(&qb{c-c4d><$!p_^9zWeBmi^65J|(ylZ2e=+}Scv|L)l?dmvV1hFQu$hvqHgyd~KRN?=)O8Ac|a*o3B^0!<7G>yCDiX==V-n3|A zbDKceyJp6`UB7yBr`u>jlEedg1{mt2=m>GWINQ z`Sv;OH2iZY9QCazKXUn#eQiR*N@2>F-#_wquwqhNKzQ!go>+zd*I^6|JI9(nKIZr$ zWixaeLNbZM=7t7eKV^FZ0olEGA&u&P=BZ#CyuW4AV9nO}Hv#Vq@ptyWTwc!8<@i~J zh_wMS0aL%>Z#YY1=Ib~e4;^RF+`ujoI;40JBwvqXvm`7|G$_f`mM43<0$xZJf%~Px+ zCUq7_k#ZSwV%Mc_`NN(JNKGCP!ssp z_1&#w#!h>te|;4rJ{+*TAEJ*nJ)wpCZXHS69Ny-um=7%l{LZ;eju8yUcy`k;J1FnpL;Was8mxfYp@1I*-WauRNhQPNa z8(RgRBzG=KG`21wj21>5qDU-${mm3>Iq|W$c zT=71yRLORTXTJ@b|AXp0!5EuErwv=1q-x{yC3~ZN((J2iETY2HwzCgyf5@DDFmb)- z#m0s++v-GKKYlBgX`-|^``AbE?WJwxwaFEw8E0LMlxJN8{hml=k3mzCjz$j|NzWxX z%7%Qg1BqrANh8J2jGlW5c_&?>w*Uu#O&UJ9>+ih%BfD_1&CfjneQ1n+f7DN&&i#^Y zke{Im)+Yry4dtfh>{7-pNvRI{t!63IjO2s$V&{XOEQX66mR?xMy(*M1+oP|x#l=G#lTt@6d;zO<1J}-Hut%LTGKdvu; zPr@(OeF-v72LqE_kEIs)#dtq8Be?3^qF3~XZ;lcW>~Lakt8AvD6+@D#W6Ajb2zDanT;6GT&F5wKTXeRB9uIwEp|GC!S`LFE$Hlhwj85 z=R4-vU*@AENw*h8ZKo;Ii}<|dz)~UN<;3T{xAYt6e2%kzq(E4Y1L`KbaCjN_Gkw9| zZw@~no}t;8rrYW5*Rv0kf15Ily?mLjiU9lm_8}IRSEA=-9o__Up zgs2vtA#68aA-(2M(Js^%Z5bN=%ST=xtDtc=ZdQUdxt2)SyDi1y35%Y^vzUciQJuz) zdf{F%)pBo7CN7Q7j|t)uN)gwjdL@6pEA9*gn;2HIqqDtZhldqjps!f3EBww~E~e>f z{bH#L0nEhw!Aox}8wuiB@j>Agh^fQeGt_ZiToO(ffTa!NejpMXkRB&Q4RnAn^Y@m?JC}q#{<%$C`0wvZ`(>-PuIKvRKLQK|U#A_|K4m2zEc|UMUpbg9Sdr_0exjkfk#&q!OSOWZkKdEG_Em&DUA{-j4S+{s4sW(+ zedj;#s`|-_X_80Z7bE_a6dSyoz9o%oW@Y=QvL^1biv%bzO&JxTcd4P z1ua$73oIyq?-6_BSVDLBfIZqtn}$P&Zs|hO>LN$PlNRsEb2IYKp7oKErTH%GV&U|q z+q6&UEb$|qzva+*KW9N-gZmoA>&Yvj)HC#mR`1azCG?@beC4}d`)l?;HRAs-1-+3& zGv9lL(%Q|tR;sf~ZT?F~Pw(4Q0(bb-_|D3sFL(AACGCArTiMMvb`n}D74(%6 z*lF>9znZr^z*xeq6z3@zec=dw1b>3<-!Gd;u3MUEjNzi+k51@(zw;k5>l}MZD|1}y zGtSZPY>$}Gl;LhBW=8Ys-R%mxt~c@O<@Ch1!pkjSss0uwjd?z9 z6)9bQ)Y6vfKxM7f-e${r(%78*#E}pz)Q9g8=e+=}PhiCVUYnngDmOs+#9wHFGDib) z$Y1B{GX#QtNhxkai_E3R8WZ$a98KrnpN>g8ell3`%`a=pOMAhC!}=aYoPpBUgX9{1fx|d;HKZN1OFP*7m4}>X`<3p%MpK%@<5*_m(&ld(toa3gJuvPy~@8<$X3{H zn?`KCcAm@c5;xoTJHc!``L>`c&d%x6(Zo^JD*Y?k0rbf`7%ljNxiD{UWKY_dr&<-6 zLhqlwfFwz{&%w8Ms|B35-skCm1&!((A(^8s00Lkh1OE2XJZD+YRC!Xhg zD0HpaLv(WNd3e&sosp@IH!WPJ(;f=GX~VyuTcUuG~42kIL`y^8Y|bC)QMoja>m z2_z}8+Hfi9R61jfZAkvM@!fMQTJ4{I8i=fA>ov|0I`u3mq3yw&e;XUs?$f5G9;>g0 z_lP#KHF-n71#O0dPW04!mLHWtf3KftZ~V#a1SrbOZ~y&a=3)3#M4LE(DB$<{Vz>9ktIm65-TR9r8*= zif3AfZelhlpK9BdUA;xGb{8L`X_I9iH<8#Lbe!r` z(3K-FJ+7b>zEh*f#QB$vZ{U%f47}aIb!AHt>80>k)nnkrRHr2Uvi0G*Xgc*JHL^HE zBBGfv%z6y1!Rz)}|o`24EHH;op!$xQe_9azadmns4 z|G)Gymlh_yI9s!le@nZO(lo6>&DNW>@cxG^KMGzu)_{-7#jI zPo&yjZl%3`zdZc=?Li_{EB0Rvds>{k^!KkLNb+?RfXAH(YkD{JdvAm9o25QZ#{O~5 z{+)Db`PhL)+M4eStT8h9yc|9~*AnAsWvtCMJn1%J?snFCeXjveRbQB9e;*S|?K2bM z!KZ_CiuyvIHjF>CGzdE*m%j=a)Ks}JRpc*Mk4zgE3yp0_(eMu_ZL5FxwEFwN;b+tb z+Eg4F2q<&2s*zc97&jp)9=EA~o*FSpck*?jdez|Nt=bgJ@;H4ucC7( za9_(De8H zC&h^UAm%Y!S`i3e?uqVzc48RjI7KdOvpNzlDQq}XB=Cjsqqq@jE9M`X?s7f zd_Ro3i4MTQ_N>xI?Orw88A{X8-T%FNZJ-6fIKqeGbZ(JJ^UHixP!AQlx*hDsoo|oX zVmDt?A9|TP|0t8yNStcpA9UNpjW7RxrnsvmOl!f{#@p+X!G)MWy3nbl?usw1OTf(Q z=mc&NFyO2ZFSK|kx9U+B^;=?3k|r3r%Jc>FUeG(a*jaR}ft^U4TQKS`67K9z*jBuK z3*Y`Ye5jr(yT|lG?(_<`viF-eilei1bNg-FxSNBFGFmLu)uo}*8KrQ&{i3?3Nn28U zjvn)DFIS@}WeuGs-*BW2;*l4)BVl*QqKEp%gZul!+WVR4O7?(KmA8@>`{dSj!q)0B z{tosjuuZ?H$|sszapHJlN5dWg(Mbi##dByae_T6h+tg;p1W{402u)q-Lowd_f7OB? zcW^Sa>L9y5Xc)*^H(kNZmVkoNe4;cy+gPwe-m zx{Gnoa$O7fd`UH-KbnYt`cSoe;5HZCyMOYdE&I{#+|j|N%3?HrlFmv@t2F;HeoxPn z`qFfY`GU3R!G3UQZJk}xr<15{{#uj~p|T5hPA0!Na&?j4bn@O?*z$I1FODnlQJY4Z zr0|$n_6O;(#$Rdm1TrnjiW2{`*8z# zOG}XmrBuw7GR<_zui`DeCSZ?MzG=d8V^h!G{En>!3)8$_D{nHRB{H2fBE_UK&FN<1 zG#h%R>^~+wt-Gr{7H)N|%q_I7u?`Y43Q5%?R-+lCVf1?e?g7oe-Bekoq1|6;DYe(7 zL&8RUv7s@hw1FUV5IlM%x>{GPB^EZTn247jjJ$9pBC`3d}=8P(!J;~XuFWwU)jH?9O2tY@AAI*9Vx>BVJh*Z*R+?M z=#c9q08lw=KKSQX-+dN~gfQ*L#Xv)9-}V)YPERbFx-i`MAw_f@nmB>ThK3F*MJ{40ygB5V6qBw(uK2xCp@~x zJjf4-D&Z~*$I(!KT#snn0=-X!PdSu|vUhJMxR`3s%^BH4mpWC`t`fR0<+YmnsNyFDyry3{>#H}n!1@iyt^=UK>ylc(&|c9KX)l-tkQpd zayNRT-VbZNBNnN4_@aVpy@C%SfrX?DC_t32%I)IY|= zQ*~?M@5-Fjxnow#&qLIVVD#TF+1E5(+FAwLiBOEbTwutPDw^8J_=`2f{R18UFzkuB z2y1a$3!9n4sq%%Gwfa!EeqjP7<#JrLd*?KhY6Tt4{_i&)# z$;2v5%1o!0UO{CKA|D%f(|kU#Y^g*h#dD!HqM+J?5Zq`m@T9Mxdc*gZg^=Wox<7td4Hp#>NT;`BFOZ0roUmJA(l!9VrJ$N!H1E`8!DRKTD`F=F zeldA30%-Bhfkgxuq%Q}A;lrXqj(385^JUns8Z^ zb5JIkr8EQH3%f~NP2yhNeKJdR?I|u6I_EW??-f3jNv}&M)R6ft+3sIs)E{e?QZ`er z=Sj?(@ai$YOY|6aFe-PT@jqN{3!5r-F%s^ zrGuqN(L6_}N~o^ZOj#s{n&!2g>0D~155Wx*Hm-T{^023BDBU)SeR_!Y#9cWcXEKh? z+OBJ{theNBzr%g~!i2kjaIEA$Ln>5av_Xe9XklLlZHM0! z6iD*$@*0db#R)U*8dz3_nM85uFN07(r8QVpp*^H~D<@~Q$Nz#V$JwtT1pyVDZ ztodWH%SPE1>eHVZM>q|Akco|r<%W#r>EQRzcagR!~p>dAEkn%f6V0hMid! z)1L+01@GohWZki}lo`jHnVUa{+*E-{NatFD%-VfWt@jiqp$S4Y_^#~rdz|-$Nc5S> zxE;J^arZf&%fg^bcx!d&^}QS}D_xGnrx8nZj13qW@;Ww~jNpJsSV3}M88jK(2g!a4H$HuA>g;6Ir!KelqmMzi`YlHj3JawI1@zfb-t2MRyi<1z zrpu1<@W|g$#l0T8Z=78o>#^jTv42>4?(?zS!Fbife&k3WxuAg3aRZ)P^7HSH@>I^P zJ*8VUSvcgl|K<0H=ddTzdIbDA23?Y$aVi9E&M8^$L}l&QGwxjNa$lLSs^APd5~BMb zXx7>vpOEYcCI3h3yCBJH3A*;NLtg9?=sA8EO8xxqNS9ohsj{eViY*WA@G6PQFmF%GS)Hk35};Bb4O1Hx7NtUpxZ2FDVQaFk6=cgD(W9(g zM$L))AYap~JKrHzgyF`CF>q8^C-wYVXDq>sC?L+oIsKx6b9m5#KZ#kLcb_4ifwXqp zXR09E(lal8&YeGh9+gun+g;;_)JZ7Ap7ws9kf7k!0(F=D9~lLn2k>e*?>uoL@f2*A z@qAvX)8J=M3`-9SFG{B;;nQ`V zHs6d!Q3~}ItN{T5NXMXhz%!D%O0VE&rTD21aB)-cu+M0X0ZV^*-*q90+a>Fq*~Cbf_Cx zik4Z9&VkY--(@~*SE5^Zw^fxVOMfRdQw(g(Y@t#yWuT_~GsFPFBw@NS;M@_4f%^pc z4?8tnVf&#P(+ABmBpyC> zgx0MF(8_vk$j;ur40LM;6zE-|*jtZ=5>|~+{^y#WU&ZadGFHpyP^MEpGg#HX=uTR^ zh0K!mz?VJ3rfN`Q$;V%`)RzNUuLhtHR?yy-!+H`WOXooCg72~gw(IR=M9)$>Nt(%n z+NQ8xn^JT85Q-ZKdTB?c3mx475^znSJGRE=J|ThVN2$foZZnr)#t+4|&>7o(yFuA= zvBYY~)I5Q5xO0HN!CI6})JFEUmN2~W8;+YR_D+^0avC_>XVaVXLg5I*_ zQ1oJbJ=mb!+so2@Hq;784nCvOGs|Nus*%fTNSXy9Km2e9>x~af4QI#tjalsn?H>1Y ztC!UTMY`6d1JLzKFj?|~_tDzvYjg`yQV-tthKJBw^Lm!KW-%P+FSJhs|G_yYC-M$M z4GoQQ$N}C%jP!6%)XI#_w*tm}-zl@$ngwWgaNn zVL+!4O@MTYiJ93mR3JB*)9-z_cH@`qh#vD*I8E)NKuKy{AQeM z8=O3{5N7nPK6T^EDp~A5gOe9MA-g!{zWXmTyp$6CxfAwi52RA}T6AO_n}mk*?kVJt zEJfQP?Ul7IY_E_}X~R1Oxcdr$>JC!iBx_?m0!iE6<|3U$GStQPL51=vj<`BOpjZH< zN+y05c5tXJnZ*&Y0eMvyW1Tf0>VClY$$IbfV=t$8D;F5(6}8eW9JccsiWs*V0t-cb zV`C$cjI>9YI;YGOJpXl@$7x`Pu`Go;|E5hbueM`nhIjrUHW2zsjHQO;tp#dJgR!X0yx zf?6Y z^Vu_|U=0& zb#x^1j`QIfX*=E9-J8qUfcq=!)@RT6DJi5`SC|Z|8sXL>;x-k&oL8@1Yax=o_e=DF zJyozZ+J~gq9WMhU9Z=?bcxR}FmKNHj_tq(4CU<%WyEWX$D*jZb@WBy&r0aM=&QRjs zl$H62^NoF_#|-@GPdsisX=KATb%0*Ak;r|YpGBvoovaTAY-?INeB19#FX?rGST9RUl8Sp9-KE2#@Jpe>z|StQc_$X zh|-Pm#?(=CD!&H3f8~~?^r57c$A(2fk8PXelx!ps+88UV28a5~ak!lVGapHWTz?;w z**%?$tUsE3=-BOEH`~+Gb3OIec^!B1;8XmDN7*2(ogoY5qp)Q;E2v6lz7qtTuxe3D zE-@qLXtIoleF1fRFIkT+yurR426eg7+}c{6XE(N7IP@1I|3$+ER2|`thYgr@%a$#I zCJk@ZhPE|D`$%_?oU|4vTH6svLnP5hat0ErPTY_xY`+eWy0V4I^JZ-i^(D8=LD{0# zQH|y=4~pmc`72A|pgT1xizhJ5#=KfG=1_SkU4Vlt6$*l&x@txo z;Cx)w)@GfbpLf$kErN5F`ktu<%UpS!=KysLcTLmrkWKH-SOVLvl7+|#+X>S6Q)B)1 z6|Jv}!AY0v!D_CA4tY5f?KYfLPzzV%a*x1)f+?E2-mdk3|^ zS4KOnlb((a8`Ohew4glYj@SckN_}UiOWiC~K7)Vq3>7Y9?#F#hPnehODmHSFq%=(4 zxik4B!o9L!f49`Md_RTlZjkqRp|Uc9j_aA@Vd7kb1iClC9>784l@H+T*O8D_QVEv< z_re`73Y;3FtI>AvS42SCAuPCT;cjALf;M4PVn-Ba6}_v5JvtZ#r)Z}#=Jbaw%t_BZ zmhm;y9IW=|jq(3@oG7`G3F})MAv|f9vfJ>G(R0@Qvt|i>86(XvD{jwZ0Oa@MI`Iku z+Vu&=znPpX1@bD@aF6$^;0MHtQ}66IP01j2rWnsH5;fj0Zhe%$7A{ra-tBQIJ3m{L z-O*mIi#opGcvsuTTZC6qzsUTij#b&5YYM$EZN3WCW`COAx$|UgWf3+PU!rZMGl)vUKI88n44R4vCO+Hmfx3_FNBkd z)Z`-0(NS%{6U@vBom4{pImLv%yCYp&S99*%v?$V`fAAwz!E<1uEw%qet76EhW6k@w za(e)4*Ln?1x~WiMrD%Wc^H1d2hp#99N?ALu)hYfaJ9}x1@%i)n1xH5$*4*6}wv+R< zx1Dn_#$zIEdbN_tTyU^E?JZ7Y_D_e#zv^?~KkDW!(|{Ak66S!bH`) z{3jJd%}cBOzUQr4s;z#t4!y#(=`=SVUo41^C&ixPii7Bo@Y~euh3dy=avUCqTz#^* zWsjccvy)a||9WcGzuv|G4kukx=)y5<3X(BkO;B_v8MM9^7#HT8^q!n=f$u*^!U`Y) zxL)MyG-{*gJo4@VEJF_pC@#85KjaLp8FG1eGuGagYeb%-$6W>D1wqXUZ9g`#l|NlyjogX3Tn7z(yp@Y03TBD_HN@eK?~c`>Ui_& z#OgAufcE!$rde5R&u7>VT1a7EBuIa*!|6;#Fklx$7ol9eqk!=3HP%KZCTbQpVFSUS zb}yiiYDG%mSVfJ#{^Jmv_foU3w@-H8D6lN)6-ist;3NbGw7=2}@EVCeEdOk_klt36 z)T8ZM<)HudZN^FmnKc=|_G~Fz*|3?v`5jetAzU-qt7GQLp>1ma;!6|`7YB~phE6@( zRy$a31a+_1`OmrAEZdLp%x|gR>6`KNvqlNm{Zm|?OL|8tewVm>w&4%Yk&MeBWlDP! zW5lmk_x|U|(lw@pH>n+32XWB_PZ<7l@Qm8_>#{xe*&cJoevx_jcHLT=+H_-?$h}mt z#Tqx=l~p^JaB>6 zfs3JI4;}4wr*qdm)aZ;Be$aW! z36q%f@4p$=S7#;)tCc!!38)|YP--eWq`Rsdddl|rlzJ{uMcBUyK*5Rz{G|o z1V!txw>54LYLCLr>>06L!PtoxmvVcyyFiKmUvu@%elOf*1g~} zC+g-eFhsV3Cyi*-oZZsit;UtV$<57dvtUb4OMAk!v8l8vo%Ky>kwfT;^R>Y8Ki1;= z2Yg!2JLUEYV7n@T0qsp(+z3Nt{)68z@<1)^HIRU=Amv!xB7XKX8@BGo0Y6hSGp1IV zaS!)~4-TZB(s>;>=CeQm29afc&HNe3{N$yssC-`DXM1{zxs>*HaVxQ_u?QFXraYD6 zsqBk(OX%-{oTO}V@?$y#3fQdnpnC&@2~#WMZmd?FTO;!G6@7gUKv>Ld3b%g~gp5nE z+q^}yNK191MvKGshc|55x64pW&p$Ln=h`*qd10ykxA!vzt#4SUUGvY*&4$B*u+vc@ z@h;ag(p`S6Ec~V62)6mQ3YD_P)auuBFH{-W5HIQAn~eo;e{CO(fBBiX;h}ve3;sFS z`}3-eueT*OH_tzxt(8dlk1o9df3e=8c+=LXCmS~Jd6DA|1@KJ|5+xiapMQG1jeD}< z)(hd*^iHV!9F;OB6iHc0J;T$V7GMW>f5+WdG&MJ`&Lu)Mtwp?4261&^PV-K#v;0bK zW^7sA>$9pP`sZO$2|Gc~GyoW6Gh1nF(ZS>w&DBFC+yCWtK& z``{gv3xAnmT(Ug2=S!l_!FtFKNmL`in2`a>$T)aG* z5Z6KgE~7r@WQr%JhQ4L-n*BH!zszOyH{i68crnO7rOQAY+~ zJe4GZCe%wj0}hT-DHG{@9ek1pl~P|<_d<(4-oS9lO0>6K*V~++A!lP_!;=ZRy-%QU zPNgp*aRctK_2NQ;{u)naM{aHHj1B$ffqnT6WGNl^URc%D)h&|IE}nT{49G0@Y~0Fr z$EGkoo(IwXsF@N!L5X@r={&%FT&QEonk@{n=a;F-lR)=^9juQja_L-O1XM~M3g}Rl zCg1K`js*&=(tFmamtUPYXtf4znitGEv2gOA2OIl=0ZgF_F<}x5>0w(;_82l%d>Ys1 zjAd3ddF+CK5j4mBpY<$nRYdj6yjWQv%7s@3E5YuuI$hA}HlAAE*X=;Cuqm`86j=ch zIrP77XaP{j(=nLk=NkHM!YRV7iJD9T#jDnR5yw%aT-d0*;SQ)nM5$~x+TJ`I(|8neh%tsh(scSv_P|;0o&t|NkmLEqrz(eUe*&J zHxz00VH4X)o!Ulyk?l-Ck>PNCv_-P0h)9{S^lWfJ^Dk?CRQ=Q7j3y=)v4tQh!8JVliG6z)mQ4>$e<{oeuEUP}`{8kf+M>GlwrorNz9J6F)Z?qVy4|nS(|ZvZ*QhKbWrhFv zkP#gaq{41sADM5Ak62nI%5b2#w6930_Vi(d{}pu8AA4b#tphAu5W>WlW`c^ta^PE1 zRzM089%!O-1L`+}O9ZTv3)EN=3BTH6-P7C|X{ zk&)WG2oQA{8WM0ZSpk#P=cVa>1K4{}XbA@%sete~f?D^#3(_;ys6hc1!V_HA{y1;7 zJQ7r^sXn~bw~(mn~h6x>lof-W(xNJK<)^`y#w^mmL!=KOLO4SCX?A4JnGD^Szq7-fg3>IZTSxiHW2Lm*QazB~xJ9+!! zam}~`HHG46HqZe z4;C^m0~&=sL=6F4SSP_oFcp()EWyh2^oJ%m{FL!i%d zJq7KN5LNuuTxD4OO3(_JLp~#h90cvIg2p`8&~xHMXK+9&r3A!`=g*x3W*%VaDhI~N zTS)NBJyy#RxNOIBdNbWZVX~dzcK8aJHoZqtUux&DH5`{209~^n(EZ-ZrpIZqx}*S> z{9il}IF5Jt9gcwMuLEcQ?_Yk-$N$a7&$)n8!vB*Ey6O18*`S+@|DUo^iOzVRb^ngp zZUomj6`bI0u07yu?GgNc+WYcwtn;_+FKyE_ZD^6Lou(-%CCiQWsAw@E#6(ewl#=z< zv`UszQ^^)0lM)iyZk44{wuEGhLfInw`kvSArsnq?$9p_~yvO^;^UQtxjv2pu_%5I2 z`drs}p4WBlSvy%Fu&BMMTmp2VL}wzj3P6l5+!+k02P0YE$l+K$ z;@&;CkdTns)+1GKjb%oto`g5ySUd2eZBw;x{qlApd`O-86^xW~%bp+cczTmwcLth` zA3rAN{~O%pQ2vruYn zDxx8)ij3HMY)_PW-xB zsk7o#Gl+8~a*9!v{ZQk*J9o|la3Xbt0J}SsJ)hg)1Oav7jEsf7y{9_SCt6;|Y&HSKVm3a>M(J;Y7%HX9ZFV9|MRDJm${mlhKlL5N3p+%PU`h+A z<}ya6YoOy%Qf!%B-SzC(+nFK^#D%;0jUv@jjOTc8iY_$i7jAF5mY(ISIBus61wDlZ zHfg%1zP~^4o=ju#%Wa3jG1#%2tepC53furZggJx>PA13T`qI7XBs~lBnTYjbLQ&{+ zFXWHF5-ulcTHdgEy?<0zG!1$ zPbpTABRe*|`i<5e(Aw zR~Gvs%+xA?bt%@riF)$-;OD{$IOq_t2h|3{3K&MY_=e@3(1c_ycd1rv0*GJZ7MRRYuzeMbTfq=(?SCdaU3c2t#sXEz6Jl z+5&q`#SS4IkAo6QHy&zypJ;oOz=`H(68#U>utqSq|DffFrZ`g)#xpbL;PpsvV}%-z z8PVCwdiBSZuV71AA2RrmoICZX5F?cgGnIydo>MT9u7JUu4XCALV;2c1C$d_% zCUEj?H91awT%{cfQ_5MD14tr3L`;ETmD+CL4^s_0pH8cUerq>@JIz^&O{w^H58#+I zi-t8fU;zr>ylupGSm6f9rxAF5Cy-M?l52!MUCD_E37OyDW;n2%q)~V7+}T)?K$5ny zj%1t7ZBG7OqZyMO3rexB%c{nwFieISE^Gy-b46iYU0v15G2-X3l5D>8VpWrYp;G%? zpSScVeu>0-RsB6pOlup91qKU+oQ>;koGc32eO+9@L3U^b}y?G);E* zn^YG2n;csZLX`|HQ}8zOY&CXsWg207#($5%qnKnCqLB9qNNx6jkdFkErvsR=7vpe@ zn&lWQzGzJAR7)Lh`AkKkp-5tjNu9r#)7zr;bY;_HXws^1Ky5CG2ETz<&y^`$is`JE zdJCJ9(gaMISvmS!O|}P6+7*SG3ZH}HKAaV4*=`QIVO8lO`RH+3Nr@<3cJ~3oTizW; zBcb$QHLpE60jtt1K3%7&TX8jyhQ%G*T7ks9cf!Me+nB`ZN#JC5rI(^d*4OKGFxRTb zuYAGpRdkRgv)&Fig+!Gu_7?GO7&)8*)UC#*jhPibeLgJ#y;Nt`|kkFtk&%|*8pM- z8P414ZV}7G$=OQZHt#m4gIshWwg{&C5Gwbo>z6~*4L<+&o0^+2K>JDaRHlh`%>iEG zkUFKdxd=+4HK@UEbDXMj)J-Fm^|+fZgEDV}mtnVVU|%_!4RlVyF&PWevz^|xk3cDf z&oCdG_5D{`?fLcCQQscuu!6Tw!ygAk!{Ct7hKy+guxG&z;xGTpGYEpJ5J#!xO(j&2 zT&PFjP_48Ba}}BeUxg|2DxlYS1|*oVe){t2 zLP0wEy$`#0)$q><#@a|(`Pq@vBDt{#ZF1v@TImkE4hD#?N+;f$R`(BCE)~tFs|tPQ~Qz`zs+3_f{#FW#wkPZi<>G?p?K~+ zjUmKn)@HY9H$zgKktxj)JvTv2y~Gew$e{IZ7cffcu=kZ1e|K<0Q}5`(i(QI!9rY9^ zr@A(p4*a(3p_ElNF@fORoASG0H&lx|+}dfoHm;*FJ9WIiXfmYH7L|VB_CkxFQ6b_u zCpf<+VA03#X97eB&_355`|x2Zthh0{Uo?C9_s)HpnOPO+y7&UgNU?PTu|02V@Hsa= z$Gx8m&`DuHhCFLhJ?Mnu@2@RJuU)z+US$zKv-Qt1lnwT=r<%qg#cS-dEH(WZ29QTH znhK@i?`Dve7`m{iqD6enJaTZP=8;>q1&*~0dIF`gpcTC+?eJlouR=M_mW@5h+cx4Q zb7Ht_DhK|7U|~<|XTc=9Huacum@M!_TS~m{YGM)VJwCG62dkd+l&LV~uB8*0t^8Q> z&f96hz2gefVTCWpnRd5+-ezc69)=;o#%dBt+k=;Q$2AYDz~-pyH$jxRs{1){`wVla ztJ#As3NPQ)O+;>L!W1UJbs45boni)|LQoGx$(@C=V0AG^9l?!s&Q z6t#&vF#x!IQ;!*fzP@clL;(0o0y!e}_?Y-57~cTJB^&shD`C@I?%t386{nCu2SNwZ z)48}Nj<-sCV+QB^<@;n@R#wsNj(McR>+ z<$?||D(5lq)!~n^ddP9^MJYIKU|^r>G%fTts0H5~i>6X8_HcYEk=R1C zh4J6qC)zQqiR-2?T&zGF?~!vPl-ydvwr+B&pywE`8hN`v})hL)@|l z?1mL8*slYnf298=82${ZC$0f%H(rkJoI`hRy$7Etx%Ia6I&9L)Wa{>41?ElSD2tqG zr=K0mPpEL6JF>81SIh%;Y}>Yt#6SBjEEaE+U{t$7md!xOVa{##rx*=@5Qz>`P|aJP zx`Ea7h^n^x>R@I|85pQ;>r$jGaWk-Mm`UP1Di_olgc8i1G^TiDmHWj zuKCu%_awqS0gqU)1EVnqjZOtnBRbpM5to&6OiQ*DI)$UzdOUZowDk0D#+BvgYk4ZS zH7j5OlXU8gQmFVTi|hwAk_ zwGe7zk%zNC^QmKy&MP^1k=%EgFY;WO&!~c3l<;ll!pw#2iqKmp z&z{{kWmM!S-H}?}Z&MeoT{V0ChDD-cLF@k%T)5mKH8)pAVdr|WW$VS#%-+rovr4(* zeqo01^mVKFwEwd3-ZC|9{1mIb`xE$1_V-<2|eQ(v*f%M+aS++j8rL&RQuLgi_)k9{KLCL+6Eak zu9W{*uq?R<|1G`Z$*Cah0^Mw4FmLT=oI|q2M=@qu^$6G4+_=CZsjXmrb{{Bz53;Zk z(M6bzZ&yOHMb4OT_?XZ0u}L1B!$By*ibhnFnDs!hqbbXWVa8J{&Vp``y4POKWK_LO z@z}C9cmq#+@cb^wZMvU(v{3)(mfklieLKo(BC+|ZB@g+_{ruW#1d~Vh-)LeC!v5TH z?`{MUHOJ1TH^OS$U-|2=>SLpsfUYlqQwqA#OvL*?ZlFgz?4Fj7FWmeRkVaC4UIUs& zvuSWF@;YsUa%gapxP!CWU)eFLpd4&^V!LI1e>#!|pNGI=>ej`?#EjkYk1>BtRqxX& z*AH0;*>)Cr!D?1bNgeZL-}-aM#It&6Oy<#;OmkmZc|N@D_q#hk#SBmp{sNJk6M>o( z+|x6?$HpQ0pO@#J_Z0KeDO130PJx4w;}RGcczS-1AU%F}UO#Vc2Ot0G*ALI43(#He zN?|`dO5Hjb-b`~g6JUGy?%m8?meAm=_F|aVCs{u;IX>@#n3QCDc!pKI-?Ba6;hL~) za3G~W-2Vn*_KyRF+H{X%@253xtD`U*t;HPWt0+gb(b%wFOIuqmUaDB{eXOMi_;FJf zodiaP4lOSvb?XoqXqpKy0rC%U!h0{X7h;O!mhF3W{%DqbXm03BH{_;~voE!Hv4&aH zfIsB8vIbi|eOo{49oCW^1ugYwF3s7nUQJCc-3~`GNtSMR0R9Pr6wWv)ICw7U>#vnD zDg7TBV#~93sQ||k^d8BWO~68Ru6~6z+g=8*xC)J0E}(jVabP_E1jTon=VhF)+Xy`X&rr{9jS$8Fl$*V;;&GbAKPVD@C7rxeTA+b^WuHfZbjU6_YJ#V4j8 zj={&a_w3&Ug-~jq;CDy?@@YxuIzXwN52R_)9Xu^vU*<#)20JMg8t8h zB?nHQ9EiY&4`pw?h>FGxg#?8;l}U}nv~83FE##bJjph%g_q1^gLqc+-_$VQl)}Qmj zO@V28zVXA|sHLNB-Mw8g7Z7XD`;YrQh9WWz&209-Z_~~GT}vw!r#X4Gw_eOJ#ctoS zW=DVGwx8PJO<9now-3YqY;Le*E7sj0^+qTwbn}hNF;3_%vJN}zNUHF>-OGlRIbEJ%$6GfyBE>zKS-Ow^C!WF@^am zmUFpQfg%MX2~yLW_YwGjuBD%X3vt>N)mrYli7-$D_1=3zap)_-r@z$p3I^0GM;13U zrW;Dq4NcLJA&I)dhNB&A-Q)hgo(#0rta2VPVWU|Ti+jVj`pTAbUyvCZydi-Cxe#<* zY=gFiL^wzC>Wa-H+|a?&BwPZWKdb=aRR>RF9t=>gnLS8*)y=+g^=cYKOE(4Wk@G9dlT|nxs8v>3xbXf9=^cmfX?nDs0thyVn zi{qt`naa`b-~b4rbf9okIs^Lt9Lt#PA|VY>BscO&fQ0&96DKj?3oprxR2Mx>?8^VrC zAYQNR_90xP;GmNry$v=h1cfCvIZA^tj`B;uSrZ71$KG0w@pMAC?@F-J1o@Aiok&xo zwDPQXrBH&qQ@=#gnUyN2Kyg%?AGRZ_dj!)XIXq+rxLzgt7P(=F!)uTpHIqCRo*o<%d%;y!D*3lemf*q)lycHQVnG8`ugLvzA4T>sVAHA;2AKgdk z^7gHIH4uZgz|DVY;Xj5sVh)fl63`5*`v#7mG;jx(BFkdT3(-i&DKaCPjD`DWgxeN1(PwcSIQue*@M-tBQ$MV z)7$b9Op%SCq{hXt9idb0E}lP+wKay~q#g$kSkd53I|dTT-h6(OVAFJBps!;bD}6EY zJ;X5QSuYH*zPIYUZuoW<2Sd)Jf%T)A=a&FRaS52yf*R*1Dt89teuH0n0r_AJ$2cu5 zE!Sm?&q^O-j8t|)!VVPfiG^c(kq9>=z{!-H&&M1gKWd{lZtrPM8z>Kp!f4=4U=H9% zS;Nx#yQj6TP?|O#(1~nw3H(+*wEA%kkKR{u`s+A>n87pRV;Hj#?opRQ zN1Y{I@u(4*3UW0(36CJHZ7TJpODti(To9Uy)AL*Zr^(C%_6+F2e$$Uz0z5i?HHM*n z3|%RN4$boq5a)QW7(PFgYD*p;RYCyCWhcnu`INlFKd+-%suIg|?Hs^*TrB_vKF|#M zl#FG93qfpDK6o}^Q+PSt5o63g)smPF@PCgZA4B(Y+>6@^d1HJZM9}6qOTffORDUoK zB7Iv464fb^O^P=Li@?>w(XvtL{V?&U(k#YvCkYJ+d{xHa(xZ_5NAn*6oMJC^JqU}3 zVIo22HeFpx<~k3T$)|K8^FWgBog~!{JRqV+bbc! zi2OB(16*NL4EjqPzP&ypF5OfHf(7Bj{;y4J;7vkyN`n^+P$fr+`;od%tPR>~C1%!* z5wqT^f9&n=qpnNoLUM0Lyy^G?qGxnCPL59nd4IBhCagL4qq>SZy^A|_ei&`8f)2|; z@cBQu{9HvzCDvc^_g^bSitcnG@A=@=aX&wAfp5(HIHw*$Lek=d`l!+7WM+t3#UF=4 zCN6v`nOsOXWvmap!Y|INiL2s%W?FH&-$syV9S=t(Z}8Jo!70>4To@R0$)`4?^^j

$*Gc?=kCYIcRPM)F2qEvBK+uR!RH(P&t&Get;^d$wFEMIBGwln=u3m;miGVlO zOeFC50!qCBuBCBe_TV)FJcmc{=Wv)$C@HQ+DnpYpGV}$9O3EaoWW{LnfliNs>tAI* zQyH4I*Pww9FSUNNB@(X1Y004hA#9)f2}qfWOnS8Sey(Gw!B+v$R;dwnZAP1)6FaVh zmiO{wHLr-1$AaoY51$kx*}Ia6Faf`x2LJwtH{=J-^l}$ng_?C@cJX3p9PR=@d%n`P zczvt1DY^Fz5=NU-15)r_^S%!=r0=}TJvhi$u{+6b9Y7fYpZRPc0@FIm+3Zs>7NzlN zaFM;lq|T6YNhNM(ggYWm;8sK$t2uJ;0z!WdsSs69?j6U-g@z7LOe5@XqzI8WmZjQ> zKm@IyZmi7AGXIjEh8%!_nq6iGyn_F9KU8OQA0OVw+*#7wxecyqBIk zyiEd}qeeO3eD($fv#HNrWIMUJ>gwtOJ|Um4FZpA2dNHy;gi&1M``?Dek^jd1)JG6$ zgt`(hbSx+ERe*Wu#NYczIw1m=T={yS368xB=v_rPzjrAs;UHRIl1l(I14V_Vf!1<` zqyb02$B2naOW*|y_*$04S>@hZbFK(9|Kb?T2Wf9Mqg`h%ug;pY$@j^74z4f=dJsscb)kZg*)6-@afJrzAflw^p05nZ_?xv#-8 zBNqL5DPiEDWx2BDw@3Tm%qI$jD))$lYu;QjJZRowfv^GHt0(eIR*sJWD%z0GHm~>_ zid9{JH#V<0dKMMQK)>wBC&lEdYa*Yn%v1+lQwaziF3^QI@91$$R00FSFrRQvDgqXW zNtI9N$qv!<7iaesvP+Gi8ifvt$aSLOq)vsoe&f5o z+>O|ifD^x7AAUEvo<3!Lrjowa+l8h~ zS*~+8BEo}&Thee}>Erx#*tdEfgqPQeGEoa;QM_iB8~D|5jLJaoH-y*j7u%YgIudN_ zk`T{N2lz=zI;1T~Z0m}~!mRmJw%8y(6*{`51^y`Bli13uy7BYfujQRQqa|xh9x)2h z$mjaK;}24MIaQ+p_CeGtb+YYeBt12ygPWX$(ikr@`_vRscw|`t$+$4N-&g6XA-gxz z19s2nL^k=E&3^1KVCKZsL@I-ILjjkUw&ie4k+$SB89{MoSLvC{ix_=v?P<`_s2%2I ztIZsnc1D~x*a7n37Bmt~XZSIRK$SW_dTA~#Kp0k(*qVfRWes@zZaDL6QhjDBej!&H_vKr z{BHEb-LPf=H`v(r;b?Nf#rO3-es9TPDcCe7YO^-Di$2y?xwgqNv3Y%go$~6Js8(?i z!Oz0F8#DoJg@zI!gEa|9t9y)Z)~-#(GaElWJ$7J+9(Z0-2{j|iUkBZU#o6pYVDq^M z6+1htJVe5?Z^}tG4OLut@x#I(bt7mX8(T+|iV|jr05!Xhy-(v@V`duz#iEqQXYTLjGdImok&DwqcGTw(v<*|*0S=og;bX3t&T?zeZGKF{)QA(oW;QGE*M zA*$eJx1e)5OhkAaHNmZ6QSp)(D(djfPwhZG%N_wgVa43f4~yt2tUrjyDvW~WVegWK zYneFg4|5oX2KlBN!5I7Xu2XMtDlO|-yfOBkIy@q$aqLb6LSmj1y}+z~|HH1I7@N;| z^URZAjA~e3TBzDWL$A{@(rEC;X1l%HW77wJX13%2Z(mwKpmxRFu4XjSHMvLm?lr9U z5BCdV)d|;;Kfu+!IeJl%f{QT#QGNybB;do_4$mcrA7&&GsRZU-Y=cx!5(grkHRefp z72D7Dh-gj20mVq)e_ZXI*t$g>g3=-)7_w&A;H<(T6y_d4t4@uchbKYe;=X$|3mFH< z@Ycf0MEl)9el8TJsn{!A{TO*;($ODJ4b5u3%J+qG1@;KZpnzF7ANKB*$`^FDN9YV) zQSrTK92IVAUh~sdjS&+ftqnC_CQxPlv&=L3MLmC2zvDd~YdF8bGXRbkcZk&bAwipC z&hnpCLw+2gVee~faG+zD50Exc2B$lP>y#%+dAuY&G=>7f_U19oDbuEXXK=Wq`0?h@ z)2ps7h%oeDzEuI~81PvA)BUs(0IDapH3Chfv)BsQRO8!h7)2H;Z&u-Kb0cXVNMYd( z;{WzZnM*^1c8gtlqRet)P;XMZ+2Ov2q z9pV~|dcZPBDr<$u&VYL@PO4WrRU~biT++*8VQJ^d^4hI=e)r18qL#}`9dm>TzlbZX ze6qhKG;-#F!UVg22llc3ZI_efSqypF zo9H+K^AMG7BaOsQLR`W>H0r--Po_tRKi=ToAXje+x+>Jpw0WlwuDE1CDl<-5<5TWhd z5V1R{Wl5XAiG4Yt&t|z#o0vh{;#|FYcn|Tt^XnJMP4r_*V8O%NCaUxno?ifI zMD93dHmpr0%`Z;d=DbbPX{1BJiS2^3ys^N5;BBJK`=KJO-dg}%cq!J=(gKlj215qa z)o@@OZxo%eA>dwQY}+7qwL-S*YPBR|N@O4%MTFOr2p!jVh175fsW(fzyG;EZSM0_r zO?*{QWM80D%kvY=b`8xEBjCA+aY&uKf%ZGBI|quXYca`Ka;N9NlY=Pu{J6z&Gpn=lQKx!B{- z5hRS%=2tp;Sksho^<@8%Ae`Uu=E~Q>*IMeQi!hypb2Uj+&>_aJ0caxk<1Ie?gi27u z=pseeG+bLtYwpS|OQTo|Y#=Y)(y{;>XvFAW&Qmsd-3{Wb5-lGwUvHfgp8=DSX{$MS zt$@SBL)dZ<>EF6_kaugCUH&NBzP1?B`T4SHjg$wVTL+z@tws+;`KSnRDbjDzL0(dq z?3UpO%eEb~w`usXhT`Q4$G%*tkbSWdlu=Mz+)87JiS|R9@P)Sao)#w*bA2;kEigBnY&W$h{Eyu=^5ho2h+PD)~i$POVb#9}JD<1Hmm!ey_>c1ZI-CYHk)oJ^zw zm2bGu>F=fhN~6&L0v89YOt))>PV#k+X|qfA_5b$X-Wsz*#aE9G4cW$X{~4^I66adf z@QYTKUoo3_7&_)wB29usAh~#zi>9uwu9PhJiUgVvWmar- z2&WCV9s*URqm=-%v!Oi+)oe*8)Y%rn7Q=3MVb>1A`y!T(l}EM3D{`_S!yaEi2WlK% zY*yjrr8fE7Hl)GfIC9)j8CFsGf_@ zNN1Zuvdz#SM#9PUDSZbX{sdr(BQyHlI^WoPy@1z$n&-d=2%B%K37}6LlkYBI@pYn5!$pw3(#CyMndr|qAG1imKnED7`!45YS1IjF z5K6K-<}k!?gpT1;$e?q>30GaF`q4iosR82n3`0L{u+|f!DEcS8R-dvK!8eCR8j;;K_oo~v4zAs0^bxvrKW>lYer8L7sWZCd7{|S23i$j z`bEN7;E}B0kbVr#223YNo+K#G1-sdOZP!)UPEcFazww-m+iT=veV-G%Cz}I1mvN09D-82a0EFT<)tRxle+P6G96G)Un zDF?)Aaf^ijF6ADyz>z4g2RM!y_9=GNI{bFfj!+Gm!xbq26^aIW7obXerUQFFRYwNg zH`?6P_t;J)KmjhVc#BEsd)~5(u>27d9Gxq4NEV176NsEY%$EX!%p9Xbh`K2Uc^EUj zT)<^0xi9iyfGR65EucyrF!~Clt2OSlL74oMGx(+t{J##xH;h1=Z+Z*(p!}2}=CvZo~YGaEXED50m#HaCZ=Gnx#uLXxN^Nsm{kcunn0M(v1>~Fa? zR?|xyn|1tI#F;40%>RLBw2M5x_fm2Z!C^z3WkO;Zga;>}@PnTuKI;1452y+hX%=m4 zlW^!#23RdXGQJSrO8)uD_ZycO*pyBIpIH2?N zx#kca959oZfZBJ_HH#xCE+A9SzgcTKiHlEtC_k^lTA^N8A2hW%^RCrW@vt^2xvvmV+%$3*0ns;X*Mo<{ zH($K~a$X^-H|~RaHVOGz@T&PY^MdE#lic$R{mVr1+(6!#{IB8Fw*Ow2!7%)< z)Yh)jV*amhT`>@2nZey~r+V*&Mg}SIHlNYjq2)g`c9VZ>9YkNQA2u$$Uzt96$WZXU k`1c~rzhmCCXOWGD=z5GP7l5CyC4=WbeJ6 z8d=lLGTalDW7^0<0gde;ux9V8?qyJRj&Dw2@w!IuzLmmG1jqsaNpGOzQOIoR(H%T3`|XUIe9owpE|5>Y572yi|c=1=QK6H$93H6jVuYt zVGh_vq+JfL?vR35kRfB%sYWbN7fe}4mCZyYBfR^@;HJaXOs zi1dH|iLVYH*`)pde1qhYI|*AuiLwmCI?$%jZ_l(3dwC zMth1SdX8>7n`m*XXxo2o;^#(Ua^{STO5XMNT?o$kD`ZZlIa z&{r?e$p! zB-qopnS@V9N=hmqFi`5ojT@s~`2y@GPrl8_I1Ryo`oMvU&vr9J8?~lf)6k%=sHiae z<#uqu{`Y~twS^wP2odXx#P77FAN8dd+7}oYcuh%(YOEv2udJ*r_xDS===k^(o?c#W zZ|0a>yL$EcMEWZqi#?ySKRw%1HIiD)Xj(XTyLlM%)QK37pK~?j8t)h6?CQrl>Pnv*KXW6)Y8(@l%knW ztO>CWb_?SSxV@$i_ZkHU!-HnltnQ8E3EXQ4&z)~KlCZpqPmm8ieLRR$Gpyqc$?HHW zlK&_t$L`LL{z%9AT+C?<;W^6r@lQ1UWwK1=UAuNo1sAU#|DJsFAYSz;UY|?F$NqSy z>o}|w<;mr|RLf&C`IF|f-X(`|izuT315%Q(Mx)fi11D8eyuW_^+E!p|0nJ9KJ@xhL z!&`UK?8Tz_U3+`6qU7=B526OOO1Ew?p1hvqjvuv|syNv9r|E56foU+OX77mBhTTpk zaZ!`pUrz-$R%bp48dwP~Ji6bWt}C5%t5Eos-B3(hu9@y=M^0*W75j-3?s8m(e0H;c zDA$(fyk5S1d4i42qsVck(spoZyYSH8UsFqGj+2sh7rk+v+da&moc2XDDgPfsg#FGPEBdg^?7S~1tE#niJpAn+F3b|aim zM7=D}x}LwaeDc?)x0#u<7jh()e)~^7VOlMj*hcdE>bU{sR7O&gOl>OG%ic>fgHc~~ zMJ)g9U0IkQ!sCuD`(Y`H1E<`{saV2id2+h#j83Vg9hRm#SDR%q*sxf4Pu${bm4?$& ze>(n2uMnU~>_HWibHNW^)vH(c4n|nt$~5jc)1GNCQ+kDnaQqn4s^!qv;~(+A`y*vT zlLfNxg{?+u@S^aLZnxt?m)>}}LhVeW^E&VH>=0E}Ru0^~xlHt8VX0Y7Rvwq-;_>$i0 z`a-ealWlwM-ti&U94SmM&}FG)Ir5$3q!G!Is-oh))S~5K8Kw`&c6!2d3W9*793Oz%&KIP|Jj!(Z`{qp!VO-;wjs*$fT za-CKk#%3#HIjqhRm3ghx;Wb9DV^PZ7XBs6Wuo_fM8;ezMmEtZp(LXSY(P6SQx6fB3!+i8Ut+<0tl6n?ilT z{dGHY&8E`*9Fq>Q+|QdI>o`axPhU>)nlZh&!=ksJHEK{LM^5KH>u%e@8)lm6F%kBu z#p`yn6FtREkMgvNoziV*?g~61c|V)ZubhWgM)X*@IlfO-Gy(7lI7_cjhaf_$znOH_={j$lGjUg8|m1uq|_Yaj_i;##_IA>;$oG) z40O$LSNy~sm-QSqNgnO_@NndNh@jc+B(3728-Dpn6C%MJhUBz75%N`!NH>SgEpnVg zIj;*B;vJ}eb#QKOuHLG1^S0gP=qq%^OZBF`2a6Y_^DO#)J!A4kIm^D`*R$_iYikt|i34?^*Hlzm?pKMK|GrfBN`Q;e z_V&^_+PkmFmQX#g`Np)1(*ZXpWuvC<|WA8JGRUPbj!Hu4z z%_Ou7gAyA;s84iV;tzh7{%D1iyS z0m*acN@biY{g|RAct~GMRqLI;cK!MRKe2f=??b#S!q(&TJ?ry1x=Yjj*Hl%5C#FbV zOBw3xyXQ|7t-SLK#a>fWQ~%bFR{Egd6z$+Q`8eS2W95M0;Hu=DZrTgacGs^w3+4@# zCz2Gvp|5lslXqX0-{3<=62bi_wrigk654Z2@!1BF3JMAigCad1L|{*?uT0!?EPVR( zX$X(*MQ=tiVW5N$MYo2r{s*3H-Q|e|9Mmh!GHR{duc|?bifVZIyU3wI#=O}H=M51A zCRL%`oF`JY0?{-hrs)69Qj<02#(L|oPtSB`|1_D^a^#fbCSFaL9X9o4l3=v%dZ_9! zVc%2x!=mTH9x-aIr5e@Maj9~E2_gW5^1E}fp1IRCCy8eGx!R7kS-qhUh@%qyV(nrM zlaTqbyY*p#A5dHP2{e)1j{2%wAI7iHZvCswtzL8&$=Q#%i@rV1ix-Hs{b)VG_~CB7 zCswK7{uGJ+wV+cs_I2c#np)alyLQc+mY@9@RYcg_NGq$^+sx(VWt-uII3kYkpshE> zU5R4pBI9`lY==rb?mm)|->{8^^ih(K)uu|s=ATK)AOCoQi>q;|JwdI|?jZqK z1~;}n+r#8bdGw;Bfq}v0RcxFxii$w|%&GrD1^d(RW#rog|rt z6bCuIp^5O!YeW?QIlaxnF>nmKZm`=ex--kWbch~i>Ns*!XlcIno9NnXGmq2iB1`c>=U9B`ZIttL zL_v7!Sm)6#`Br0|iK#`xc$=V!YnNXc$@_HRc6QS8{dp&_*Y*4DukU1R3x9Q?>gnPa zffhq^4o%jHlJm`DUJWRpDNWyRP{ zJz1W`;-V=%@EzCn)LUKNRHP)~nudmkx5qp4n)0nD)Cz3Oy2b0ZkZ_c~^%JMXcT6np zb4W zA>n8wN_C^?Or614bFuSAh?u=q(v1%+-Kbmf2?-uyVPQ7FDZ2F=>DEy?*EBTgOExHy zl%?Kz?Dcug%>Mm#bTspPN?Y0jtv#RNZLe!oHsN9ya|}>x&e=|oSd9DqUQ1A$2QZy$zS^Wzqxv1a=c5#_1QDsk?+Zq^Yc&Nyg6d= z%EQA0cq#EWh1%D2X-g?9t24{Ms*fI#7zao1qt&g^GB-bs%H`MArWUA`2$plvhgPR9 zglBSQ=2MJZ@Z{vL3k42K``FmnKG)Yv+1Uwq7ur8VI`pE)f(!7nD1?!5ad8Elx}oUG zNEuzE@al{XiUoUNta*P87VpgEaKXoTbBD!AQgAYxm3fX7jXW2L^~KE!VSLvNNE<-H zbkP6b2WiC@I<3)mcXxmO{8`({Cp7fX)?Ku&xKvS_NfO-0)f3d0AlmN+k1Zdk%||OvndX{;>)HW z5UE~(7}~7#ha=ZBjao0i_S}91FYSoS%@qVTq(M5Aq2lS>xf3(?5-&YJfBfjt&0YsM z6lr;l+xb5Cn|rV;c6lA-da%A~Yh!C`aNHRb6nFV1u+#NV7?`k5%X<~};)aHX-4~wj zECp@;_4~K7cDM%TvllNYlaiCKB`6*T%0B=KK~`m!Yc)oT?(AMtayHO}tnTyYvw$^} z)YPuXw?qvQ;@Un3Uyc&@0UYG5YE9K*stw|J^6Z&(QDeuCAEo$|$jC@^m#yc|pP&4+ zN8%?MtNa+3RuMh6;R48Js1bV-@adySG5cQhEcvMe2M!P$1F-pQ-*MU1L0iOx{54?Wd=^K1DgNCzxw}J6FY6eFb1fIjkTu zIQUsW0QIrs$BzgJ9l8=JdhYJsSoOS_>1po!ZQRQ5mC1L}ol#EQmC!_^wEh&ublV=r z_}MTZ76O|80bILpY#dk_77|iYUQQMi6cn$XHC!B7TVG!RGEb~Dy^uNCn>TORIi}CL zKWAoU<~Hk<9I&}}@7}2!8D#jGh6P*T!?yPJXtTb`5I%!_*u!T-&2hZWyP;Yzp&phl z^f)(aDCq>gdPTv+#B}V~G42XFIy&9qZwUm}E21D*Q&TG`E8E1$$@!->l?hn+2{PdJ zkBmF=eV#-f0S$3#emquf%3871X7TW$6zajgdGQV?2?(32niKJ z?_FDa#vQLpf+5g=1{{1%i*LH_Jp+S5P3Tr>A$AhlkR%yP))~v>#B_meKA) zIzXq2pQTTJ4Ge5mQd06U60sQAIs84@Yos-m;){|ZJsMN^0!?>;?T75zW3GFfk~Q-W z0MKzvE`d!Q^o$_O%oCA4dzPfRzQ>jNA()ej?R08j;Qs5$>TZLLQMzd5vaB2INBygR zj*t7I8T>+4ECQ~md|cw><)za6Xj$q;aqwHs72lVy zv9Y}fShYO!m>Q9Dn>R+uIulj7P*l#jc6&Uj3|Tiu%UOhY6Vk`PzyRgRNu$__p~rbc zY~r_;I8aBtYAR!_!mFoP*CU*qyRnSY&9Mq9?dgj5@hz1h0p)b2EeZighl!X2!wES^ zdk6`D)}-{4tZwyN{I$(heoW7zqL^lus`p5&KKk=Ve}LYtr6%yC8R&Uz8@}j6JgcQ? zlg@DV-o1M_M8a9zq`QC|F&f*dk#DsN)LX~1g^a;|!&~I!2V7!jp}p!$b)v@fy0iQz zT-0P`Wy`RHd?u_SB6Osrq??o_i49=h9V)+7S63Gy`Wlq+ftA%oP>WxEeNUL27D)k+ zKYWyn)ZgbXUTyN3s5(g7mGskvqb8>?Okn1KC=Mvs>&B z)=G0)vx{AHbtMCRknR_Cld-W8M8T_~?ts2TwryMAE7PKDCsjct9`x7j7Zeoau0W~L zoUQh=9HmT05zfua)9EeuSOm#2TbjPZXWXtFbLO_LE{|!qsM!wX%|1NowG9oG0H`5- z(mu3qC^#h@9XB(>PH}Jmx17)@u%T>fYFeDCV$v}-=1>D`PZn*#bslP=cxv8~P8YF?+==&*RNq&5|w+OlFT9JcoV8?Q1m}v5S1-#oN zur|}JB8LRNyT3ob*r)PV0~w{Gt$p?9%%MYvw(r~-kQVLS`SBqIB_*Y-?$$kwrxbWx z^=0(+Pk=2o(wpk*Z+CWfCL<#&>Fm_V{P-m*JkmnxNzY^fBV8oTMUWxoB7?%=;cG+CEGdnw55M?zfDT%MRZ0>3Jw0!Otl2L8oGpjWYcf z|Dye5KSllb?*~wcRcJru$a&JN!Z;_c6(hT!&+yx&u-n_4T*}KOZS3ujiio^oE7Gfe zDd@B+2!wRZ{LTh9AD=5q6NJTs1FfC;)_c%N4y3dHO++bRm8a+5{PaN&JT%Y{aZ;@t z4g3&?dgf0bqS*CTcx|aol;gZr;EqZ-Rf(X{=_zvLMn)e?_41Lf{zeFTmmnlUQ5 zVe)Q8%cbSz(~f>3A|js}8?U4lpz`QNE*5K-ZYrG~ei;%%GuoczC2*O=|H$FPj|{$Y zQlPElTNI~5y#?lh-X#I+4%-%Atm@v_1-N!xHsHkM(&*@Yfb@(1Ev8TZTTI)a;_Y5v zUoq{@MFvL$nxtq1t&5w~SoAhbX+@L(5NAFQ)(Hu#KJFbfx3sJYX2s0Yq7I)=KUXvUpj#=<)aF1ZEd4ZiJz_NE(VN$ zW4|yitNT4w%g@_;XOj_D^SmeBKUr}P0JVVU%$YM7jd1MTx${eosaE%*nEm`=US1{l zX(Bt$TfX%0AitiX;Q^{#Qd8r(^pKpKd~#~)+~v!@?k&VRxix$4KN%oyYGUFGYA2(- z>lL)KsqP2N{ku8NojV66aB9+4OiT=!el^2x`-^rImvr5#-LY!;CQ;40x-@^k-*E;Y zguqHdP5^3`s4 z!5tudvN8~A4e#B$y)jS0Tb>wL3x4mD+>bmkzKL#Mv@}2$+ZN2FMF13L)$*s6A&U{> zj$v#jV9O_NW+#1a*&8heLQ;Z_vFU>pb*d)XngHRv_jW6dPWRVtX-ri>*(%6?yZI3) z0+^=2HAApr9(j3rn?9@YPLIV!n{yV;=?hv8Uf+wHH*S5MFeO4M_w|1p$#vvln*D-F zcP_N*vXT-Kl8zmb)z#I44}LzXoFkUg_0LDZpI(rIc*U3C*?*f0nRcQi zcztv6ND^2C!HqPSekzO#?smqweX_Ems)|?P`dz6i#-=UE?-F2y&^|7W+{3r|NAz>sEsE6qs$^y7O$F zdB0@B8=xn73U0l7_jIAEy9~tYP85gn8&&52A$p5c>Jy?bo9J)i{u|SQ5VhDe(`Wp- zSl7P4SE0xYyzLg;X`OX{S zrt-u{24frY_eUf}qTjwXTU&nEEhr!$Ky;u?VImr>#kY{Soqr6n+BE!}cEq;%os7R^ z@{=sbBaJhE+G?XBBN;zF9Es%{!1iw6v*%zT0S4a*@_ex(CE&vmMbIG%Q}4vYlZLG+ zYpKq3eENGKrA5y^#JW@gGG2Rgev6Ocx7hG-dQqoU8r;Yye0OS~p6*>-+)*^<9d4Td zu1~1Er=QL*Lv_3Q1N5!Czg^74Q}2`V)?-7ohpCgun~|Nex8giBYh zJcAp#vv8lQ`?dj8} zwe|GK@X-P6Dm(By4<0-?3x+>6meXUHZ+YI`b98LXZ2Gqh7HKOiB_P8;d6U=>8=cX`_R2Yu--a`eK_ zmzS3x22VkZegf}!5g51yWi15!xUG$bg@uKihv#ub1OvNr{G%QF*Flhf-rc)p_!WHC38mPb_@M35($avdWk9VRcc>IcC&%_GV?i=a zy40f$m6cL&iQ!cc?C262z`{)Zrt{x~i4xS=*|{kSu`pOjDb-qDQ9-PdyRYv>bMxuJ zk%7!iK1}>+4jn4RhXGd+i{!Rr|Igv!_ZA{jR8wr!J5FijK4-hGrNy+qzRu14B_ir+ zL_`Du*JHbQu*j1@^12nC`}ZkdED8z;aD}S=3nd-R@Q|XS;`0|T9-~g+s`ujV)6&vP za(bM+&>^5&gmLrpw^;p<+FE7i?&Bk+r*{le$5WKd0_P3J(9qD&H8n1eAD0dq2~$x~ zg@lEbb$74NWJUP+?D9z*&IOMXwVfuz-XO2$oGXvZD=1t`(GU_87LJC5h5Y_%UJE^B6Egw*h34LkS zuKd8heJ)UfCo8i|dl>K31W;xLL2NAp)U-ZQgE3bh{zD`*3$ilUOR5r!*wqzbkdc%z zMNbGOrPMpNG!Gi}*8~n}cu*UBoY%~UIM|&F-J3w^(XB_bA+UjjPgb^ItdH2F$~pkn z`3+i;fJx_7TI;^bU5M*9iZQaZgYR@xwZ-gaOOU1kmC$H6*9LR_H%)WDL}=L((CED6 z0XjM_;MA!~$GnvZR?KcHW`~+z`1>pU91-;Wlx^I>jg3>N38036W!AUV#l>YWZW6%n z$kC%0`mLaH{Td$LfsTQ=qQy8dhKXjopzj4qNivrwPs~8+I*Xl|fQ&ykG+fW);N|80 zhATI2&pZc7CB&+qrI$daaBNW0(|bREzE{*?aW8gA)|sBe-OX(aV)0A1@lDG=Ur1Hn zD^tF?J?8G^^~r;ZbrKp+A4IDt(;#TRZt^To5)#->ojP?DWI;JWam)DlxPEs*o~%fs zp%NG;A*(@}AoN8rx^qOf^YTh?(Ss50I(YD)a^m$}0F7?>`69D(b6J|glxNWZ(hOVJ z2UHq!OnZE9e7O4tG17Y=mQW?r2-N|!5*poxgA&KdZQHil*x0-VRD!(ul=O^wBJK5_4K#y4S?&^W6D> zwaCL^YF|b%PfS*SVc`Yz3F-MTd%gBo122X=bnUV44mAAGTW_wGvM5#^ynOG}+I z_$un)4;}%5XN84g>?-fyO_}gQK&Ze1n2mP|X%yP+mywY%%(;Woj#S~(|3U&V?uwlb zkBE5aq&NxX;=%OqYG z>OKMfBWxtl-VgNCD(RySoQ0`_xPIhVUrVAYdtni59QxnlDb;gKd;n`9-(G$vE2CqD z{?Sc?W|nEtd~sGCyRzlv$&&^43zrQ#6O`gg%)%R-S!RUHddZYDptwq={Eq7SY&SRT zh6QHxsjaJ%eDHu9wvc$U%fj>SoCe(mLd|49Q5Amo_Yc*HG4NFe6faEl@UD%U7#Ogf z<9F5HQ=3;AXF-ylmz(<qSvzJDQ62qAoJJ3DkiODoELWhpL z%@ZRhmE%iba+2xfZGp}owlWkKC5RO17EhQ-%gp=@FHwnRfz69N7Ps?9WI2XKA?9pJ zyaCauOTu5hAzbLwP5dn6YqwLPTdvf0_tWYL?4Kzlj&M&w_Ociigd@#Pgwjw)& z7UG)2!OF_&VaFjJ)Oe7j(`5@qrsl9S_SduC}c$ z1Wp?Y>-o_e-5RF`GeEfZ&8pJ~2?=##l2}$BA)-3e2a7~IXJDV8uZZ)ysA)2AL~HfT zvFlI)`@|~Omq)m&hoSduZ{Bz-0SniR5vKcsn>TNcnYx*MpE7v>mp${Hj+S;=NSvA3 zCBYAZ!v5sDZs$uGB%H$O;Qdq0GE_Mykzec(z^3%{)#*Ds4uVOmYl;6z*WIS10G+lI zGJ$03pd8+wSIHPiuM_zFc(THFly3PoULKxby?uRInkJ9c{Em=x0yHTb+G8^ddRSo% zp-#B>o?zFe$>?4EfZfN`cL6mFU`HzgIW^V4G`@rMYyklB(q{_LaO%4rKnJcm5U?6_s3ZTAWQwPyYoi@snomgU9GhDv8~xNM}ER3Bdip zY@o9WU-|7x``J@>P8vk9DrF1J1m4-J_?cswxHUIDFgcH_yZJv@yvUeU0Z@fN0nK?fwU zK%IyUgOBl8qRc5!u7Wi_ZtkBzNXHTeza=QiPZaL$`vz(nWO4ZHN3(Ji+kuHNmvOHq zY9Ai*1xLpH`zr#Z>sBNz-5}paT-dKfK-Q=|Bm~T_HVhN8U}>JR`B_3*ZMaVk;5&4= z#=7U(Rpz5dLx+bt^FCDO{b}nX!oFJ_#E?biKf{i*RR2*_PNCeGVO0N{!IH2=J~k%X zy7ly~=x`y6i)E1s1MmQJVjPwSZpl3-i%=*u3cM(USVIrzw0W>%YVP}V<8#b_)9cY*goOl3ySccyIBmqlc7D=Da9)j9XN)B`M8LXU<=f4@Kg@5$%*y)gCi>ew=*?<9 z80I8ep7V=7LmJX2n1XRffus4uhb>m2^i^gW5yB5`jEtLOeX?tnZ(hE<`yQr|na<{U z8eb>&KQw9hE$BP)Ey4e*&7M7bnhY6v?|Ogj1Q1$MEy%`A4Gfqc+Acn zb2e^>?5Df?_7wCc!v&=X@)A(HLBsD!Y(v)Nancy4<$)RNPX}4h$NeDti3ykqyaed2 z5!!3-)zYI6wy_^j8t)Z+Okey#^)+tdewY0eCzMl6L^}Ccct%>YsnE@h5 zeq!Y5F1llh28a`R{xwXnUbY;23aK=9V+1whWlO+|7p1dwPrbanh~Pc?@eJuA)V{hN zevBz8W46-j?i*hTpKC8h7o_cH+o`|l!PI_g>hjr~C?ShjJ$}p_oAs1X4Lxuc-lZ;$|x=D;fb4dT2X4efy5pGaWkQfwg^u zx!@%Qg+RWX_qT7~{t_)k0YQu&6JqM5F3^(KU|N5g5;%mf`4xivI3)1k|sYd_YGakeXP6mJDcuHFM=KT%fWZ|0;N8$1Gjj;b#O zpbSR9Y?yN8dXm~>xU6;~CZ8YcX+^1;?5&_k{{8)F;7QdoFn9a;(HE-@gK~hg#BCR? zjEg`(m7R4U(B#{TKE$Z^1oe)lnSNFlmaW)Rs2Y6x_U$7x5;%2gCy;Ih?Cvi@L)p~w zKi&tUDd54R17r0tvKH!5xD$yPk!>G(!0~hZy~Ma3xe&(}3j+a&V_-b<+?3;nR-XA5 zjDuVT>uYMt@OofnTI4JDWT^3zv$N#@c2nzX_A(YHsdp?cFGu6OFgWnmw}m!N0iw{I ztD1UC2OAWvrCM24_11Y~{c~+?pAQ41Z>UPFhGMt18Jq*E^Q z5XuSq>9TlpgCA1}bMJSXUvG(-$o4k=bw zJt)qEcG%e3c-uJzOs1^9eixK#|5Y zxu8$s?5~X!A8&6x+C~%1HpyDzgSa5|wB94Lf7J!_m<(hKKcX_*oN^lw*IL zA5shoBrM>wm(okjl{69*W4-`hK*oS6AIgethY-3)rNn_9LugHt)6->s66@}$^!oYq zisi^fiZhf~sqQsKN}(P<7;IoL4p#h)as8ii?NLY!KL-Y$BE60B101$&+x7{IfZU1h zZ^JkaxZzk79|=kE+B{uBLBS+a_*y&qMinBJ=XUw_2*GZ5JJ=mbL**-}>8PoX8FKu` z)v*l?MzVe;3wc@6+)M>j8{Lmk`h*!2p`S)9?&cg8cUpCa8&wo6vTPc8wltC0;z42iyCTfzmZ%3aHvXnuSBDirk zfv7KCRValMv!>5ld*91Z*PErAM?vKzsZo2YGlb0AoJJg=qYplFuK!v?k8IJegFO)%z3kEI8Bt&drVeK{aLTr z^gZ2qh*_-xZXK9!bU;KF7pLB8k7W?cPRpnN2s~LXOf?jwjCdX0=4FIYTwEMM%+vrr z(+h8GKu;z}FMLSM>b|JR(Y7-Kmo8sEz#;9VsHD^c5xg#pU+ydUXC?`!a_Aly+HoxL z-$zfp=uPt&JoM=C<5C#~P#V>;?;ldn)IUejv`Ov5-CcU84^5z8(YAA{Tm?lh;6Z~p z4^VkLet-$Rkx<}F>E*^gdS|U8l|3}7i(%TfmNz>^@to}f)NcOw;i|xZ-;+P_RnBS+ z3=GJdfo57pN%FvEaxHd76qLa@nEk}}iA2aZo*LB~hiGX}M_iFW7+>88y4lt^!zb4I zM%OPYFHZ=*mbZK?u;ZXM?faa&4xfv*nIRT0(z@Y9a&_n=+>8ehCv`Z&XCDjE^5!=Eu9dAcxDHHiO@M z=U97||L9h6-#+d;HPrBiE6p;9kZ3~y040uH3;_1UCEK5_7qrFUnNUBz`FV2Nr%C6Nse|{4!yz-F2WnXeh z!2JMY;4?i62FKM!N_4fBVH>GSm$pMlo17g|N^Uuuc@({HNZ<)Z0=!&;%+x{EB$(x> z-CFMyAH$vM^UQdZj=yiy!TDB9OZ*!`JTRoR7kU&RLO#dy;FLI!j#%k_VyFO-V zZGBJuP4Jy6opgu+l(%l(x^(H%7b`Z`ODxBaZy`)cXiu4%J1DE+y!e8XL)F$}Cq7U0 zRq<$-kl@p*&0&f1H<e)1!sB^xI>nCv3@TU5k4S*H@RK$E<{5vX~w3 zdL?lA&DGb|6WuP(Ic`s%-i9n9pAK=%H8C;q^-@e(hI;qOd*N5%zJH8mQPup>XBIcp&6mo_*1+n&#-0ZjXnqA7wg z#HBE6d<^@QyIit38sLu8AToAEOtiF~Saq*RR#?}77QTACDwu#72q4-++&3&V)B{dA z!qX8wpfd%yhdF|a6Vr*igujO6iGglw9}pvN#r^?Jx*LW9{QOc-{!t}2-q}nH0i(xr zUm@A5@69FwTzuQ}W}zKFga*l!r+W?3Ij^7V$?DZk)*N1l;*VmP5M!_({m;0LIif6I zQk;O_+m8lS=c3^1e|<-;WKSGR!TttTy1Ka?5f!BeG`(%8q%UCFEs1RjVG(z(Z)&21 zAL1-(_tiY}I}R}TLI#69iX3Qra;i_7n0Ejo*ep&SLE7%c%|q3d$q+fl7Ct&U`sMYx z&4fV=#zBI5)&y}-z*0%*_!w8fIEUVXG0ACSDuIedjET4J+NEL;{25IQS-cqq+707q z_d;f^_gCL+BDxq>hZt(@-n|c_}7B52roI0jDj;J8!gbu1TYYvB-zK{%Qo#s|jTuCNF9P1kq7-bagjVQTaC} zR>r-1cNoh-O!zKcDuG^Z2D_l7q$HZ#w$F8S-*V^6^l?db5*O8P-u#4>0CIK1Q~*2s z93wJZ`A-BgyJM9j2Lx}OjyVcf3|KEQVZ!v6TRe`|oV~j-mno{H5dwdSaRc*nz=$NnPE}A3uIvg24}joRW^N zwqpPch})zym$|Su8*(BX^p9}?Y(5=nI-3zCtk+aFa?JWJcH^X0`|I;=JN79b^(71m zj9$BF`5vJ@OYS#FLBEKHK^-XnrnYx+aj|wj?F7a;Kqp)Nx+m~D`Aa!=jLirSBv8Q< zsAj}y3uYL%@bof+LdEoWIPVDSC?%L=C_R z<{4KVsD-m*9l_SmhM{L^<2=su+J5=59sSrZkko!3OoX3T=D~Wg9n+&g*3Io59dFUF z2*8Hp29HgPmbSt>f%)e-E35gz^n$cB?r;fbMik|HjKP;LT{;WD+JmuneoSj+BTNk5 zf&9uA7Z>T7n(l!-tA=cV!x$D8e3+EH{7x|904D**p^4&+%9qFGl;1aZcG9EmJg~Nw zMig8HXK2iS92ypO{>|0H{QPq>bDFSwqX>v=bs(E$g@0TRMJp<+s(LoGw!Ex9f>8mI zFVsq7wH^JSDM5*~w34|f2n-G*@uQ-m8ZoUUVwQhb%&lfh;jvJ{>wb!()Zu z1^L~9+fg-O?ZeH%@zn=p5$zKQVxrM6)eV?}`G6Z{aM1wi@yZGNAVk6M_XsmsQFIVc zqEB!F5Qq^RizjDo^apPy29Fp^-RtJ@qc(xwC2y8Q74KS}5zjYyg$V>jGUcKTgkYQX zRUy-GOsvUTR_R81Ud=5w{mz1z$c8&TU4ca?L-YJ?s4T53ztKN1P-*ED8X4&e0lW`R zz!TS^F$ke#E{dMkys4J{?bdr`Hnp2K<*wFmguZ(92__%w^xMLX{sV0@lar57@4ikn zWB69!wD$3;j|yRy7WOzw6mPaN#Bwd^Pe+`}3C^oWN}0j@l~a!+eD1A0k;|}(hc2%T z9SN?@gOlL_?n_l<0upH+=7og70wA~KY)-^(*E}%`SRp*~)f^&&Y`DL8Xn5*G5FAUtJEVcc zQ&6`%u?@Mn0;7PV;^L7jIDIaJC<|P#gpX^}+;k5xSlz1?tWLq)89>sRnVCMAXaff9 zp;8m6oq~4CKG#!P`dIGDm4p3axlU`s_q4TND~j!BSN?f`Q{yuS5>yM z9*F6{Uvd5xKImHaW@GIo2htJ_wY0MxG3+XEZ^Sxb>bN}!{>)HzhE&LczgAaQbI~{g zEh12>u=v^yDwz0>BZX-f;9RJ#6T)p)jQ(Dt=%+YK zorg#c>$m>YT*8m?hfRgta>XZI3dHrmVchVdq{2!4W_^`oX_Cp z?}rRR=B`6)8#qBcI;+c~I z(r6G4EcGH0`8;#a6+$%_Vg&%NOuq(tTPIPQgoDR^e2A-bTs_9Y;Uf@*CPs{RVt6nS z)xc3E!VqAA0oAoIUNNx<;#m4%U*9L>-bo+h))a=B6&&QE8pnZrTIXAFF)?OHnL(Tn z{fuI`#@dLI!Dk48AO&;4f;Az>Wy_-0AT4odISquXb3y$iMrnk6jh@)UQyfK-i#0We zy@GZ@Ktd^2{#rs1X3A!O=L7qws6s7{v9OpEsZv*0r(83K5uE4O!InhTL}kK-BY?LL ztn_bgZvHFi17@)I4>!m8y>`5_cE9Niax``!4hsMx&5aW~cZX+Q9F;znI)({{`kDlL zHo!~lI%X(FG2%fyEO3Zsb;RlVJ)rLp+IzT5kh#`0oFtc^sMp~GU)wlRPSXtV6=Lpa zM?j0@o+3+z5h33%eRdyR=Qe^k!~J&v6mZBp9_U?=RUv9!%Xf^ntBt76gY(CwrZ#pI z<6;bA#4)9hU66pqA$fkNP00sM&QuJpzMv#Vl&^R3(f_sMePy{E{+aI&T%yT}`Osnt zjDe@jvChnMr<`}Vxd2Nj4Q+db3CfPsZ2fX*y2Sos8v3l!R)13(U#1voF1Dc)w~+Vl z-LX=02LpIhG%#unb#B|+SEZ~e##k{uN2U!)iSTtr%ZsXVY*2eAp6auiudlHpxWmELa8Ty3(9r%($W(7=^quC+Sq33 z;b|g#HGvS^5p^>IFRJxA;gZjT#P72b9EG-MffG@`Fp3d+{pT`Cc3Rqr$-Dy`>JI?L zl}}ouug<(1g&jWdfP_I$QDLQ5$^-f;kfLxS0zzDdyytUZZ_O3laOg@Bc10mVI8aVT z=9*9=vNdp>MiYLxSc`@-;lCpl7=sGd=tOPO-tq5(0W^mNwX2Ecl&o9->Rn={)EYBX zABv@4;@mplPn?;fZH1arb5r-6f9pe?O+ZKd0x*w`14p_HEFQxHIfgcJo;&-y5X3)W zD-2D(|pv&18-Efcwu}y zJ3DJLLOg*Tqu6= ze7_t}*k~6PjJ9w@t9^Nk@k{|#Z6Gl(ZN;IB0SBDUPbOchf&Jsp%pyrGAw&?v*OrFh z@bJ31(H}}N3qpqvpG{l;N~Yb_0()?*IK@;~?0aH5+43F7agZ=&*on~PI3KALL0{eV zdX280e9TjF5GQ9b;3 z?85%vvCB0y6g)H+o_8=ndIkm+LwihE3wU4)mBs^KWXB8*afCS6c7{dizQ?}fX$H+K z#6g7~rs8Ip9sPt(ZJ8Bl-F@YVeGLJp_tNhq8MP z{Jm&n-Tu$WNMZotBnS7ZLbQE>3gMtjNJomVBn4ov3T7L}OH1ooic+_4Gei8Sr@r~& zu0m&_J@M3lYfCoujjzu=A)s^YMk<~QP>ROf((tgioc!IpcaxQ90;IqckL6jEM1oIa znq2{SOHg~Dw1X(%(Z8Fr@q@SxObUs!bC@pv!pU@{L`|Hs0~zM2;8aT^!IBi1p<$_k z)1&@9MH6|i(i%)0mcW>d@Us=9Bc5rnu!6qLf?Oo4IPxNhUZ#`;!yfYF8A|mVc)8dI z@gSEnKt76s6#J>(EtuUZo8)loEYWSl(AjZ*`w=wBAq#Vuuw5LU8p$D&Ac>UIsp6i= z-%|!5y`go*@m2QpX!VIY7{f+-(8eS|;qv9nZ8+C@tH6dhXk1!RAr&A>2KD()r(B}g-LV6=w)Fr3}RE79tLi=p-#1Q0fQLBjDfibG63TzM#XK+i_p-W^E(wk!Vcj-2M2gjlMou0Nm4AvK>%~bC z7$J1*>Y+|-$@e8)U*hn5cz+WK5q{yKw)?O%DkAq_vnC{3j3>R>Fe|`A4`_F|ogWL= zBH$r$R^&E1CUIy=IYr~fm;+R9%(RFn!h~q?0wg)4PRTS)uP#}{3M#BOCV26)8ZlY= za27AT|Lr){>!v<7V!q+EoGv|0U?0qAcq{B|Y}_?`mN7i)LBn$+q>R}xVz7xPt`G)a zr;RmhumMkHh9kXS`zO?KK!dQ@2&AMrwGL0)r^?=X*yF4@Ud+j8f2z+tY2m{@qM2*+ zk%oYb9Fe*X4_9}wb0b|`gAX5M7VVF0chN1_bCOfw(?I(3YUP8xDXGXPyyqKKJ+l0lf3d>IaKUjnyyh>0Fyc!TNic>Mc6<~SjRXLqDo z3|_8gVTKF07q%q0yWxt%u}8A~Q*ghO!VNYFmSNO+9ZJYvdipv({S6R2job(4`og2& z0o0uvZjn#NloW=z?>1$j@V_Bzwt-Chv>*9+A<$zh=H5*wS^=dX169$%F7Omozx1G3 z!nL{2$E)Lv5hj9|3ldU= zOc8$S7Yt&9K0tLBw6zc8bQzbv6Poto(h_mNyC5C&+)^#)wHUJoH2Hz*o6vEHGv;4l zCi5|;#Zg?Cu0up^GcJx%Ux$!07$F(~+bLS1XC!E8Z{L^%l2u0f?+ZAwZkT`H9AC-vWDQGtv zub*|lBYPKqbI`|r_RkCTo)1v#;F}a^-qpY$Y!t!Qg(KA9j{)< z0!Spz-O~t}zpFG>Nxj8@@#8)9OzzXC_Z>NMgm!RM52Os<2|Z5+|~xYIt(h+2;k4 z*6F9Z-=wCd2D**b1h9Rw9F@x>@p!H_@_o+Z$Z*jH)B(+DD5Q7*jW^qOXeW5S9CaRZ z{TG_%;x(K{H`I)iLQrB%5)WyUI14OfF>n}48)j?NZ)DHAs!})bqtmed*`%z4RPiOoQ;0#w6^?mkY7Nc3X;7o>m`ib`#@0l zsi^P;a%tVl>`DkQd+?wHaaysWI{*>&0W7f|?`xva)?jlcD-`;GDnoc2l}2%nj!mr_ zH^ki~IssP%2(y7D)pRf~@Jy7{MLtn+CV0H2{wB&$s+2pvmz4Vua{_z4l zgS$Pxt4Iwq15#*t)idijgel*n6}GCdh||g1FpbHt;ryUTb6!_4XssKR(QZLtZw!qY z05N0cA5xAiS>SNMvCs#cnPB3ltBP>kE+(4;J^&N*gST1P4uE;z3F8*T`8JSOgA^T!&DP3I?y)gK7HM$S+1UwF(S#6ez`zpVGR`Y z&r4!P2+i@1=NSCg4O(1Zkq9mE*Dk!3vVe0QqH#KoI>HQHhFn3Z{uF=hEdf7~dE21C zZMrV+&h1&2cM&YCIoCVozZt>!y5s*a_1)oE_wD~El(v-;DO(as!>H`Ni4++rGbJ;k z6xr$`$;i40$qE%AmDv!HQbuM7MHyMY*SqKYJjd@io469k=c4N*4-pbCAj)I1&+)4BkUx;#rCB zoNI%}Mjjc#$3{&f`upMa#6r)87*lW)FV^uh&!kR%wR)0wnx1#$n?gA)s zGv6sECsDc;E4=%FJ`x!y-t;QU3=8@}1gqS%zt5ib1r{&MvuEpAA2cWkqfnG5)+Y|E ztZhg9w!tjnFl0r{uM#%3|7uD3htuil=`grvYHg8si5FNVRlL67XTLGL5~6B%`3ixG zQZfgKkL!f43JE5v9w_NLyj?F|EOZ^v$TS5`Kr&LsPSSrabKjL?l)cldyex7+R`WyE zo-krYK+|^M9H^PJk2~mN>A8vvXCw9S4N#Cj*mnlY-63DP>40!PS|QxCCJ)Ba)C8h| z$gO*}=Fv9j6>uA*wKYR;HkdR+p3k#uy?AbS^XQRxQ%E?=gzhyfKC0&j{#jN)*%N2e z_B7V=bG0x?Cfs%UPo0emwf3QYm&ImD^@xNXJF`X>X)8^#SM|-YxuJvWuh_2%-h$9J z5BZOP%2NWEr2O_)Vq!QnY#9#n0I}G zgA>Vj8b7xNkAs`&jo8$8@N^ADMoOwgZ#<}GreZpzw9EhFv)skmt;C*^3qu-YDO!cD zPoL?D3TOZdE;-%6oH=!p9nvq{%*b%$h4wH6v{DLO$^g=d>V;S{l~h#N8_hNEYbP+k zaK*AAR(UkoRkXVq7dcU4rNl2Y&!1FG2%Y!l=JLtGDQuZD3_6zCNRdeC%>R1@Q1GQE zu5Y~J%QOYrR^MN&7~^wDr?R#(i+Gj9Vgb)_9Y;w_fhSEp8&jhd2T%7 zGo7o{wqOD@MFJ89{f>|A?Pty2&f)F=_WiVW4tM6=W1hf-r9Uv;8zJEO)Vn&R$02gG z@B?i{SKk`})pDptd9b}T9{jThgQv>eR->ZA%dSjlKpT_qnsEITPPaHuDQ2eEuLu(; zYF4Zk;IQ<$Il;F5P^@{u8fNGVi|6y9%?eu2mE*x}3xZ2(MA6C^XBEKPpS2+sYs6po zuIl!kT8Ab@(1FXK=fr#3*&&sX7vZRN0EwaW%XKXWhVu$0=Y5Ul+b)B&d}ebB?*Ie{ zb4esro44$Tn$VPz<^)BNMjx8ND1hkV1NUS+^MqL56bJrUcv_&tQ(RJF+m(I1jq3_+ z3iv0juoWQ{DK=-$2z;PB36!$cZpZ;Ut*g@w%4J&ole$MeHgqj2Nbf%C;XRI!C_osq z;}UnQx7f+an~C%F~#_;^Na5&#wGAplC1)^{!-u{T)y_0S>KAZ!c{7FmpZ6DoHQpA;{l+ zX%=20=;VRa4FP1UO1{eAsgMCK#Cg*f3(bRn(4)L__ysx_*ZTwVi=aUPH>9TNKe*!)0l89CnTCr4p zvBN9^TEteT^j7{=UD-tww2o$Ds3Y%sUcC+9cBtPozXtI9!uM#aruh(pa&VpYLUNnm@9pt0H#>+h@o+00id58m_CjQeHA>;&o0D&b<5Ke ziW86|njz5s4nz95anmg!1KcNY@L=5V;-=6~LwA#ZYS%J^HkEYZQ7I+4jRPESt<3DR zzjf;tL4sTo;jO|c|3F`i9qh-TxhM+_%7D!2m4pmJxpw^k2m~X_L=P&+RD9@X7xFDC zm=}F-*r^hjDv?+XZ?lHGThln6atq0;TDGp7DeLk~vD@y`pG;pMCo5Y3-`?Pb&uHsx zkess9L|_}BuzYmWeRu_0L%s@x9ESQ=0(KE%Yi(;|BVs6?HHIuN0tRG4D;;Z6M~9@X zt7hDOWJeA>-W}UrPt;rn|67|wxV^Q?M}CjC>-KR5A3vA2@(O?phZxnnz|^9LGwVRs zrGxuTYm*NyEzs(}zxsI~=j-l+qM}*>8cPom%-}x zH{)-9{1~5;Z8|*j^jG=Bp}kW@h}yf4P)wyw^9~ej=v>a)q0RayXc z8e6#(SECf;Srzad`s>=(yhgebOW5ivUfknwIpL(M7G}4&u*-YA#P5fJQ$pX@M=HQG zh{;aW;u!}RpBuQY0VHWIRX%#O7seH%-J-&b&+2}=5Gev~vQPolUGm@yGj)wKfj;tGqcOk&(x$SyY6J zFGYaK$PMMvc<})MO+?Wz2>C)Bp!hS^tQN1By*!MiTbYaf@r{~SiX`a>cI>cN z4Ka(5S?4r*4$7%g;FZIRGX(!Y?MkUV{Tso7{%xne8k8-2OmuNUdL!aB<%v>dM-I$W z!TlFDY&&>#(e7h?Ev9RQk@T&CH;|6R}Q~JcrN!wsMyk3BSA2daH&x z66WE`Oa6+6u=?;P5sd)x4?U2`)XdDV0nYSSEA``)5x^Nz*ibwGxWEj(_{IMVI)D3a z-TNP`P*_qUUk)<3FXpPG-8Il#@o=3sO&$O;Sn+q~q`NgqU57Za2M(PyX^pg^!$OX) zA?K<_BDs)EP)ch@%f?nw$(_?D8EK%g7JvQjs6hdBai2z78LS&QQ%=a|q>k6cbf?b9 zYrnfMu=BM%aVoC4PaCv-Z@P1qk5lH_clXEp^rA(JuYYW+q6}G#)~z?4{<>Echi(`O zV9F6(qpCPvMv~1A_^S)H&o8HM|HD83XRCmzz)d zT2Z?1BEJZ&PAb&AKWAoCkrOj=SUgr2os>O7bW0jj{***ghVBjBvpUacNtTR0w+_u2 zvT|zEuvFH88WYQTaQsoG)1HGuA+Nx?0tkL2I=!TULudW=!=gE$$=OMlQGPk7nGV$N z#&u3or3ou+%s>n)OF5jfNzx(0>1^vT*Q!gC{UQ4Mg|3$1%*$~br|I$#g|Ih4q?E%} zPtq>AWp^>I5yTk8^cM~s&E4yTax2@h^HeHd{+oMpCtBjd{m^e2m&_pfAo1{JGo!Pi zuRLg=2F=bI#2HVi%lPUKRH(Vk-Lb)jQv;Dt#*Z@CNEz0#V=qco0Qk4s&H+$>+(60Q zL12SW1D>wBw5A#jIh+XeZK62rr``svU=xgG{uVjmP+2!#tm^#MWPY6!3EQ=3l*&2 z;vW;pV|k^e;}=9{bpgGRJO^UM9pp7&?6PT0@SU5qLb(r0NFKXRP1!Q02Vab6k^pSk z{Hh7(a8K<@p0#+e*6h@%koUOv_!fqY6+cl%yph~-kDN}$bpJW9*4pSJk2a(@TU2$X z+jAv7{f<+WzG>19XRU>S;a+unR=YA>BK%|Xuv=P^LWFkYX{|LG*RFN6KLM1ILqDO< zbdZB3HyMgNw2Hwat!qQ+uYmT;a)`RM+2MWV4*6X%mLGukYI2*15v_2}t*vjm5Yeaq z79d6e`ZV=E$%#7nPunbQX-Fv1_ccvBl|xeyTPfoG+Y@MvKv|b0pE?orq{Tzu7c3B5 zuMTm67Q3je2vG{H7^aykr$KU%f{`Jb&PVI?76c*Z792i#@+9lD64$G;3_QzdW^oWQ zh^=N%carG1lvz|#QiH=$y~&X5SLks`pac5T9m2xuzh%(mK5swezx&36cqP#bzquT` zWCnt^%HByzaxRDfI2d;L5xhuNXet=K)UVMv`wdbmNckEpIU%v8UZyKap6dSA+ZzBN zZMY3t7=g0g>oTBV&*}CQZt}n#Q;Q!k{;6`ATsaV>KCsptUMvRZeT&Y%O~Y$xSB%^( zw81AUeUG<1K{Hnk>|WX3OzsR#aB#5RCl(cFp`@oYala2Gmx-lwhsD1CJ7+Ta)p79? z?dy9!;RmIY)Eb=Yz|+`(Qv2RZj`S*w^U6t%2rsbhO3a@B6_OpAvd z;#yr)XlMY>s|l0mm!3$LJij--(CwMml6HUr)x8RY>osm2PV) zp5`SMS$cUM{%TlgxzOP>Om(AbY|cM*K=HKJ9|XBuV*^v?$8au?G>8`NIOs9< zyL36VjIYs99Q%=Q>sD%kV59tQ=F@K`G7vd~N>eB&eL+Y48_>2{NK)`s*Vp__$=!|G zTy1`x#*XQ)F|o0kURHD(l6hbC?v0_6X?}R(07AC7;FA^c%HWPIPF4}lWPHx2oS1bn z;nG@zKe29a!lzR`DkU?|2N&wisAt!u@#CPmEjwd&#N&C<5O?$eED&g<6_9>`$Se}| zU|4>7-?KWUbSP#_pStpcCm^AW2!%a1DRa=~DMYZm-;b?~6=$&-G z;;CxqgOcJ3v47VW%j@98f0a)V?fE|=#)&eXI!5h~t$se`rYFPnx|2SRc>!rm@{jUI z8ci9{3kHXVlI+c2Z6>Eup(P;lXk;U-#0MhXMs+oCo zfqcfp%L^AV{b3yp@d{9Fl3-Ez6_x?*fYy%Qd0Svhda8z;tu6 zYCAi*!0Abla#idk2Wp#RZ34X8HR#8>pIo>WbJVu6zhcAT*`r2NplQ@?{C+p93Ryfm zs6LO}`|2-WI03&4Y!0(p(g7xG{8)YXp5qABsPHKYj@{YUK4Pn=(+i>KuD59n6n2V_ zhuayA!e|>w{o&(NV)ub3T*=k72%`KXE|Pp0Cb!$tdG&K#JZUxU=-vhY$`DkbV!12F zc$e?&w;KkXA4Cz9PzTuQ7iL}%(*&LK7p&iHO@8&?B ziV*RDES-%jff~l_8^kf%GcaJA>lh!za%K6|r*2IRinEasD>9WLil$6n`F)@v`T=sA z>wAb=Ij>gpKSx3O(<0Cp{;`Y58X%JzgwQ=B8)@g$;Fx2D)Wu?0{`9p`Bx$J-vb@@%7K9!i-SDAcDGX3(ni;1^%2gDfOvN1lBUv|+Gc?nE~S z+({L_VgwKeqx!i`YHA^z%4tFt*%rq`Jz2*ikG;dt#Fw0ZSz!tO&l!zCT(!=^KUNWrnu_8zW!)b>7`9Z5;*XLH zJD8^QFo^+vFBU-b^$iXB@6_qZf(72KuZ{jyyQuWy`SUz-s%Y|cTb{(&c(}P;hbNDE zVIY8FDfTCB%b4OiyP+Om+y7mx8K3soJ*`_vz&j;=MtpNVHuHT4yrLS!k#}_+6^;#l zG4iKsAp#{_8&RQvoY%{py$F*Rkf>LVdur{n=!>-i`MVuU{?|FW=f|3f-XTjd&j00I z9$d3)Uz!ph`B6$x=9;n=`@JBwCd+vcHnlI|?Iz49jex;2o39e~0^Z9J@T_=lCH)-r< zlU7yXiwTo6Kl=IrODg0akZkOhjIh-4yD@n1WRSotNL~_GP7I_YX?ZKLz)BxIdI_FHpQ^Sg zy*3-(1nfSZXp@fGhK3NTVR`zaM7_&EJf1;fr+of=LDo4iE=4PUFOoFZKO?s-B6RM* z#EJ_qRX%=P@Fr&vI{2%IN?}IUNi`0WpD^KXJM7Cr=rru2Ahcz# zt;wc<@?!s&UghxpDPLXY{;wyvjGjRK#?~1tF&|U1=+c${cOqIsv5#E1&269q!=9=0 zvpJmqh_z!|sH)A1^PDO=%@IU0p?gM0!vMqLiZL=|3(~%u=%9|>pN6uFM6AL|qdoR+ zS#SQYnSray$&-m$wMLyr+MjD~ORR5vM%Tq)tajC4;ng;As!$M6H$=J-GHL@Qa*H=Xhk8)fkiaO!BCj`1~bp>$bY<&fgyAx ze2h+OuJZBY1CS`$#&A89AAWHz^6F9RV0YcmIOFdHDnbhRV5S^6S?Jg=AtH?-!CnOT zgd9#_v$p;UL%F>^-rieEOa{TDLmc!dVNH;NwyE#m-`Owj2`Rz~gF;vDL=L(tkBrZV&v1gydGi~^q?HK`R33)|3LgZxZ|sUp_nk2 z10T@}WCI*nHAuIy{cUBlSU}FRc}v!j~Ryzlc9(Z~iWB11@-h;TSQI9XFh_ z=c#5#M~6-|T+IJtbI1D2wju8HWFS?kXyQrKK(_fUwk{h32Dq1I=jZz%IwvIr@mb;4 zhLVB?_mD~i`VZms8OoN?AlIq^pNEommmjA8emeA2kZa^}OoAsV`oq7SrxX8I{ac#=(ei^_Hq&5kP$Un~&T%Y=@knY4`4 zr!V$n&wTGF*#%smB&ZvfPwi=~tORkB(_zT0Vd;fl+xVxFjK`L~)I4|8415uec_C|; zU%fx-0a}D4dZJ7!n%%LA4#wX|kS12RG=$9Mb6x2Fs|6_A2ONwHJ0nHnF`tQjr3r~f zqP7+*S_b!b`xiF=gjbS6wk(qMO62cz#VTN*%lSIYBThRJdxmI%pg2SiN5FHrXLWnXy%s0N2m6cp3Dyo^R(_-KvjBV>?h z^ngIu0=poX*tPBilKxvRC&{4rRQ2rX({Z`=c@)QWhBj|UWk+Vb#uvF9tn-Cu`u;&& zUkh_rZ6$4kRW1cE-%YwK+}q)Kdcq9+)d#_#L1ePGgI$WI5q*N)iM8obXb@5X0-daA z3wR28gt!t>p5Ew*ZnEVOZh zqfv5sKT9&5DzFTv*|)f_jf{xoNDN3PS|_-!HM>6YIQ!j^w!GA#WE>u>Bo6>9 z4E@)2fD@$NC+RNG1e5wPy1fV}oFWvUyU+M1&%|k6i;CI+H&8H2s_<=x3=DQk|J*-k z9yu#iD_uBU5+qzWebHsC&Sh2WS!c1s|BjEKm#d%ut8U`tu)f&VrO;gg1h;Ek6WSd0 ztG!hVlVQ!JS)77qtIk-9-oZm4=hnj9RHjFuelWU%R9KwZjd#S)$;4by)~J)_7r$*@ zdyre!>!`+$6*MFR$wqUXPKgn@6k*4xVX=T~D@@oh^ZD!7Ym$8@S3^OYnkDxz#iL!{ zF{$0Ga+&7i;x;MxnDyUc>#W_HV6ZO>8eu$yC-QxccVS)#byz81P%rk}y1^YXVWi1- zEid_7aGjurXY&I*y0N@4bR^S5aSA0%3RJkKFT@WnK7zb)&A}7TJzpa3RLpvV1p&V9IW(RwBKj6T`jY(Mq0`1B^v1wpNd9-fr z&j~8Of-pDYw9in+PeTk$9sfM|iEVw#{30NkKskwbd6cAYUgHw3y#oV*E>(-{@G&R? z(o*k!itt^W(rUl<4PGgkkhsf?dzCa4sCr`-zF2*?kbG(S!VGCw$6aPzA6l;-;@0y> z60F(qw7K_ddTn82;c^4HIzEObWpi2n!;2)?H6$PE+*hpfTV$QdKnOb-E-*dOoo_<2 zKnZz(9!K&M`yc*@5|2FV804L8CcP))*}*`a``1uS;l@XcAB4B^;y>=;f=7>d-+n`n z=Gqfa2dp*)_AO+L>~+`%6$$bfkXgzFU~0Ln)>{5f0MB__%fO8*$;h8HX+!#n;}<7y zA7bI+(*AhK$47JP7v|`+wKez&$QDUr5y{XdA@4YQLO)>;-b=gyB5)&4Y>vaePj-6b zvSAU$^zC>5`J^Oo4?=TE=sx_71KDV9s&Pj53=OGrAAk}P+Rij-&BcgR1}WeG$G>jP z0-QutD7fys=O+SqECCx~;)^s5;pHw3C8L`c@sV{UD~T9>RigU(`w1q(y4#EuF#%-O z2D76ioT+S8wE2D86*}2Xh-;a!~zkV z@|oi>I<47*APsrY8?cY(m^=pT0BN+@p>Z!hMBzQPVtlF5>oxY3c+5fd`lI-_79?QB>a>+vSsyXV`ttB}0} zj}XH-T*KKt&B=N!bhzSy&u+=`g9t{;O1CSjg&agSBIq8jK`O~3B(w@4KO5UH0d6H3 zwLq+DKXs1hdPk}6f_*p7_j&;YZU8Ji{|m2TF)wE&F`Y(=Nvn z-*H;^kKU}fe^&oV68S%#?tf*?8Este;1&6Ec9|CREbpJYEdb{v6(0W*{ngKbuJ8;$ zi9eLix;)q9zmc0;Y*+>+cub>GM4Az)fbq>=eEIU_`}jGiaf&)tuH)Z=1q2iIj$s)x z2N3_+dnmSWI;Y{gBh*JSr|2|nT!J*au48HI+-Dgxv(9;bP%~TYoHN0SsgE8%CQ)?! z5zdipl-srK?VBMTBQQ=^ z!k>IvL@gBV^v8{}>x5)^N#5?=S3$Os&rU39sQALwfz`I_!Q1GK^D6ALMQ z3QzvG>3Vbq%@&_IQW=ClX=o$hGXNLJ*2IJI+BBKx3dF-%iF6xE=%Pw8J{JoNWE{eY za#PNRpF9c0*OA5FEXTXaRMfx2_rGJ%G^76AEm){&H9NJ~p4BCVy@^J5aLWz$+go41 z-7H!nF(mNNp~zkh^8qtfDM=+EEZUbEh&Lg4(3T~+|!AcJS$q=7hwtj zoS0E?U_}1-o;byyPckGi!3F_%WHbsaHoW`~pkj{pOSrL)lOah*b^1eM3Ii)Fi;X*1 zY+zism3rXd-u?U8@kdC;6%dO*ky7V-j^3>>48l9S6;{LsY!+Ml1w8m9`Z`eV13QjM zOy**s*CfFb7((*`H&*7AvmHwJKcoW4hcV@P)-i|X{e~>tw?_eqi!OE*qyaa!6++rq z*gJnlhzAHi6f1iU)aLNg0R*&6##!sN$3l0hh(5sf(d&9u#C}M4j-Mp28{trl^*GE<4A67AM%^L}e9l`ezH>^m=tTy)wjZCfs)7njJa#jipqe-)N1 zR5d9k2?$Ul<)Vm49tyPbV=ZSLL6XKf0z>|ND8w0b$49^TO13_uB>_N;YKwGO)V0;5j18@N7&9tnFe2uzmNo%43*^jK!M%Uz-t2xbz2R2H~&3pf%SNp5sS(+=fO zR(a5W10K2_5QK!G$%!t;@_J6N6oBnQu?r6d&gS3{x5V0K@b|~tGA%kC63%VE-C^br z?xeW3#c)dN!g^t@@4{FNuo0LVJ@#9?WN;(GlPH29hirWS>a<9J=EP`6i$ON@n}_H6 zS%}L6Ay!1?MZ%@ma){I5V7pyYi--y$$39+LBp?)MehL+9fFLS63pIxeW|{}j9Q}J? zZ^wO10p{z(>Blr9T>TSv1lc@@Uh_)BW*<16}AGw*?1&I<67I3H2lZZU{l3MQh zL(zhlmlsb zgx1Ib-ufJ)K*S;TsVVo$$jlUxt}G#N1bq1VNvQ8gXgKNvk&z9jPT7(UENc+evWQn2 zS9$n1Lf|f+L4>l9_W~}T5C>7I3ymC@w?GoN$qZc*{121_>XryhC|wIHlBCyHGF1qQ z=9p%~(d&}=w67Dspy)rpDdREeSd0|M*dIf*t*?!;x53=??IyGk29_)M)n1(3G@4Tc zBV_Ys3VdrQ?(4tbmed=RrSY9?5QH%ztk-y=hSlfX=MQdy(S|9S?+9ty2Pc)3VeP}9;fs!lkf-v`~2O|b&%eIk9McwjlO7tYvg zV`;U4o1gh&-c)PYUj^6fsryG zee<3i`41sr@-pja}X6eUlLjgL?!V> z>8`emgjD%~&e_ZqGXELrd?1srquC;qJWMf_@*%9q$x?>&lFq_x12i&6Q9CQSljJ|9 zt}I5NLb}-2$}Fzf2j>UhY^jJxsmdcFqS4xgj6=S;v*$1sFcrFS)bKj>BamQqrQ8Ko z0~yrO368<{{L+|&HK;`0hENX+3C%%6&)sSJ zuTLbvXsLBz2aEiOkOhL-i`fyp_ABVeNXXm3ONg>;^HNgXqxn4!Dqn}sLTxQW}) zL8y+$*u}o?O&nuaR~L1sP0WzN)6`FHuC4)5QBh1?LW%(O)XI>TAo8Q3JJrGkpxZU) zpI9WXAcfEt`FJZXE_ln{GeQ$LUzon;jy`mBw*dlXn7uT5OmFG`Est7UT>pUr_z_i72aC4$Sdb{k2l}`o31%)X z=by9TenOoIfWM4}8|T++SmzZIklDx(2mV6$@?vstB~2_BkBf*<`xA7Dh<1L+)b&&9 z*jA06gzQlDEc4y55|QAd42ss!K*(B`lA;L&Rv%W{^^A`+UtxJexBMK>>;lZhuFn~M zPS*%{((YgHKncol@9&+Dnr^tWXFJJt%wZX&(;8+5Ly@lWi^ov$Y1DC7MoYBA$U3d= znJ~#axdqPS+s(YTPtJd%gCd7F=S0!z)lN>W-rDzT&gK9mr%86rZ+e9`%1o={R4-7=j%lt5)+FoUT;9h zA9+_|yHNEQSuAJ?jDHU9#-5`RYSAHU`ee#VGwrn@;o*G4SxZCoO>!!`pypf!p^AXL zKQ5?f_OY8Q96#GgG77DBozP2mV;e!q4enRc0Z`V8fM%>Q8)t9!_kX|%iQjc=$9Z=9)@$nihaFI0g zaH3`69Y%p+|9E@Lm`zrKtJbY7rd%`AK=0mtaQx&% zXM5(&dEE^&1&p2a=O6$fBX;!7(SvM4A{)R)%13?_Gy8Jh-#Y|;L8}F)f;CR{Mrqy^ zXo~oWL@AtUlARYP1scuw4=@hxIfyFdx->VYaSWkFQb5C!eroRS^t814CYSKJ)DOcX zWDv@V^>7&M^moC+VY*~{oLHBQqHo^h>G0NB4Xj#GE$>ypcKS(AyB*=ORre`!$e$7# z6#*QhuH4+k*d%AKXKg4vQU4DSYWQCX@dK5Dikez*cIV9qEC-C^Zc3RjIPd@pN2m9* z;RjI$Y;McCOM|ossTyZJx*Hj8>-Vv1xGM(f7#J|)cFZw>-V`UVSyun1Q#KjdW+gdU zgFplX)SpZHFFhOCzvU&uwQ8WTQ8&YfL08PF`0L;!7_b4A*6UzK zn5Zyq{nufn+8(O+0CkS>*2bTBU&6-4gj@oZmT5?>_Q|(%5Y7niG5~q)nJK~_P@~jeA{91WA!A&d3 zLoger9J>PoG;pFkmhao!3tM`qLu<$Pm0jm@MbOBEe*cAvjf{%ZKeE(_6t%qg-HumU zZl~es5Hc-DVd|p66$wLMut;exo5tA`=jrf}#7BTp2pd82tkW;9UAHrFbntOyoJf1Bhj!I~E~=xt zFM#J}*(*~PAX%(!NNAa?SiX$5F|B(HbOd5f`Q~jS^~SAm9t*lV?KL5(jfiP&=w7pG z)lt-otUuNKgqnf&`-j+xV zxKyLn!hvSkwIwi>j{_sDc_bwb=v}^7kzzu!gB>@CBVq`z8F@(%Q`Fg}W7WI^1wnEG z7kQ9|LB#-4Mcjt}`VX)_02TOifceEam}j<~bd1~D=;wsO%|X3DHF6u7#F(WMiBcl! z9jNVM`7yvS8)!!_-{?Y)q484;{N%8Oh9G-gt=l+0z)`Nsax*3wn2^d6|4oQ zf@5SWkD&o#Ym3W?R!2FdB!v#yxSEB`^`Yu0)*c-`^J8#OMMLY(HIN(zs%$~)2ext= zXn)p2W~i}t+G7>ap$sJREGe~fWSuQe;+zhfwL?%c$4NP|A3x&p!!-Rz2_$qz(ed%2 zkSlZA-tc~ndre(h=hJ~m5C{Z8|JN_FJ=15z$z(8azGUJEmf?Z#pWjfxb*+Pr`;P-6 z0hexzGqbS~>vHoi)o>2082>>fJa;P>mwXf6RdkRT8Bf;l<7oNSl31qXICgggrG@d^ zSPtmbJ|^s&BLs9VCYZY{zr~q=3YvNmb52OB^v3eY+d%YuVN03Mh>C$Kw$|a|!t4dt zZv-96p*(3rr2=O`NiFVH@OHclS ze@tzByLamaukowJOBkzVygT+LIgLcwDx)Pym1=Vg!>?jkX%Jzd({zuW*VSD%>7gEy&t8d~+3WzpxU7Auh2p?CqgoB zPGq%*u?R#ET_h%xq1Z0>c+1xr6Y~OzF-GL2ktwnCE?qBXlKtUxR@7)&Jp1?*KwmPE z537k`{>(X?jW^2*OfTI^C-aFldUxTxhB%3uqB@zDaW)5y69Q!w*iKkOuRwT-G_*G| z5Qwh^RJ{E6F(f6te0(cWt+^$_(AnHuo&f$Ndc_^2CxoNB+%K1%L@3_8Vmvn2M zW#EG0>%>xGn_fw^=Aqfh!I4!UI07jRV@r2EDlInMm@4oF!&~ZsvO^ept44qvSrCzs zKvJ}P-|3u&NwEX;MBSv+>3ATDoh`dN9X)@1lE1X)oG>)CM~)DoW?C7L40sq-^iQE4 zP!C+$+1dH4S#^7Zb@UMTx<;AZ8rL{Uk8Jh(e>^A~*07?7M`;!bZUmiWSj~F@D3$U^ zt(6_+1iXA|WdQZ!omCkjjM0y1;SBMX&yM$mB7jX+Ur?VSd8dtu8F^#Xm=cf`y4z7f zvz^2~_cPrKzn~Yegk$48JVI>GXh}pAk}Zv$B!X~QptZh%tDj`B6o#nq(z9c%qNW>R>|}03$(qv>VXJ7~{^0gP8bi#y?wK>04k5yL7u5cJj;HHy z?ntYC2HbM)RFOP^uY0a`*nXv?tUP3TiB6p7;TH{Lv#3}1o5^c78G-RKsfpx3yxJ?2 zK588(KQVN9Pm{k3qDPTYr?%A*Ej)-;Zgs~zT-bp|2RG1=h920p@aWBz0=oCK*0Y{# zP78Fp>cc8jr4NIppNm!OGwBt}w{a8VWPVB0^c|QkNUFZ;QoF7)7p(dDD2WwHMzxm9 zkhzJ0&V|e$Fm3mVDlvd$KaSRFjH!Uwq zOis@H7sGli@*Q$64O{j$UW{V+KmJPkzp|V&^itLOnw<8Sy#yibM$&?}rMwcs=oe%i zpER23Z(t#6lF3=K=WpL?8%-gchfQ|wK+MQfLZD&urTGzME#Z_}8EBxp4s*aXP~+8S zz?VySQuSyWrI6}W*lXNDYYC8O+w~k~WQkJ6%pBZ}5C@sG7`3@a%0=&#Xs#-cUv%N zpu6#Yl_%S_31gD$;lOkKQ7$P$y7s~%1hoq{41{si5^PktyPf~3pIF-#_kO<9 zF>I)Dr7RWE51f!AZ*J>Egc(7CzHYDe?KvwW4aqR|)d+~X9>{$|=P&;3k;fx2Ffu{Y z43z`t>2&ych}%4C9Gf#o_Ax;Gq}DM>2zH2Fsd>71Aup5`P;N5<{Pa8VQCP^uf>?+?vEKpW19GXFwCf?Q8^K4!vc^$_^OV?!*IQ-z)Zme|95os61J%(1i z#<(&5x}18l7h$K1JzR$Rnu(gpV*&;;nM608psYYn17LnD?=(Clb2ojHuD(P@78 zL!8L*&~FVY=^Y*x#_gqHAZs@U@HNM+AD&fwxWS#il&{}gDHE5yI8&l!FJ z&iypp1~{p=*LPp=^t>ZwhxnT=A+zGFERse!iwq>&M~)GAZVd2uY--aFu-vjpF6s6^ zNDCqk9JXmSZ}bAftL6b|hkDY2i?7A#4z?1jalOGIK=;ejRevGYdBwQh*RuH3pb92H zI63{Uihqiv>EXxiiF2qwe?kF>$-!ZMu>RQmXQdkay?cD)N-_h9$PGGD#r+n%462I& zbi*`o-6#(I@p{Zf3Bbgtto=K8(t*Dem~+S@Qd6)7{PtituEQCH)Ny62{K-K`6=0Fu zxtSf%!#3ncuuYG2>(RYLE%N8_xorGPR_%irUM&tIyhE`+>*1wY8_GG@#-8}j6}{*Z z&m6=Z!j~kK*R;0g<41PTP5kyaDe~>)Yf#3)wtAI1)}EjI{gTo4)}4p(S&l9E?L|Xt zaK#&Eh~AU)R_SB*bLMPQ><-ODmcMiNZf%cw=ue2mL0txw!RN6A3fiZauU~5#c>;km zsAg4+lkpVGj=l`SP7j9eA$Zz$07weG^(>Q6W`H1HZ>wOpNuWyL>-N}C!Z_Q*nPXC_IUwHjD zcTNyG=*Q?kvu>fv|A^SD@vBtUJ<*HC;!OozomPhR%K5t`AB!jJ*u(fNF<#yk(2WaL zEVMF%qh;^Z!l>&5>dZ=@A@m6<-%0-FnxAtBVk1%V%C&ymaWQOe6FS~W!V1VXL?36p zKX(g;b{M22Q`!&0HGnw_UuloolEk*02F#j;!RadERwzmg`3A>ou+{BbNwB?pHbCJW)$ za5t$nSP;4wdTG`v8-P_XAjDetouC62r~nrFU&BGfCnUqo?HRHq>j&bGV|=cNnVJZ? zIMB8t-mmJ{4cx^*$CnTao4mOJZPqQB0-**F1HX_47dC=@0!B|S*HmKi6YvsDx?xi< z2eSooIa#*!sXojL3%@_;Qs;$f$RuFg?}!>O`1Hshnw$tixl1doAOq6HZEDxrCN*9| z-5BbjpslN`YG?Nyt?v;Tx~eE#!u?Ij-KH~Yh_YDo4}h-tveys6DNGg;nE{hdCSX4S z5TJk=5Jx)(vwGMFn7#*gj}csaHo9vQfa|93S9(x&-<*y@&HSro^C=En&Fy$LwVftS|tL zZw#(=fq9uq^z3Bp1RpuAY)jS=R9zjZ7xqyI(A*3p52QiuM%-gzQHTGof>l`VPY&B`7+dZrY7)U-03>m5CkavWGNVn~2}h5l zGvix@Tl&a228>&{f-9XzKtQF%6FEIWc=(OuA8;$e>%g1CvXT}=FD0fpm(0s%p!ejG z_1XxUkjK4PpH8Di2Mg$++DQTQKT6{Y2nIP0ApI>>{W(q}5V@<-Hm~C*o;T|Am(a0N z%Cpr5aC&}Syt67}%}?^`atLEfVn=Rho>^`C&M-iL!&$-mo(3jo0aarytimO%y^z_7 z;n7GE-eC_Fqh_%~n?_LtYHlkM^dv36kyI?8{nSgX#K`yw)R2dc`;+KJ)Mstin~;)~ zj_#~qhXY7w9j+p>IRfQ;j$j+_bRW5V=eG}z5rfC05Cd!--ok}+X(IHZR$Lrf53NqR z-32-cP$h)ZMkvUu(}#r`P(`p!&?Ijrs=u_=F+Lnqo-h$NBL#rsL2lOEUnukICvM=; zUdPd~)ixh&|19>SdIu0QZWK%h8oTBRrE%yMiP$YY=Z|q-&>4@&waMTWK-3}lm*A}G zi$=^2?-wzTg4fZc289WwyZtgYQGf4l1Mxq9wj;9;SeKGJDt^8(F1-c}2F9|_F0ey+ z#5zjj@b=;c@x=w3r3lP@c)A96W5R{SzwUu@)@ui_Q|vH1mKeiB(yn3!D&Qxd(p1Jb zRmW-}V|Li{Bb-*Pc_IuYYeryqSUOhl)|5y-5o8$ zFOQ@A93CTO`T^i3wZgj~Sug66p+un$PiWTtlSQofuP>S%W(ErLu|+`rX#Ch@DLR;G ztgbrdwxEl4A{bkWQjDz%9egUze=sl+ny9O>n-CoaqlXKH1c?}Wk)&X4Bvm+1k$+jfHbgs-JkWLU-R@oOivN|+4 z>a?1mA#nv5iF%uF2fCz+){?Ln$RhB!$W*tvw9C&J5v~Wnx*#Q=? z*Ll_lX(GulWBaYOO`|;=ij5vDG3s~~Rx@AzRR2yM9vU<=d}A=lkXSV$j%4!r<4JsG z@V|mp*@CM56^b0Al6-cQHwt7vU6tQu2sk2&&rrg256@k1WxJU?ww5F`6MQ*K416$< z8D%A<>rSP3`x-ix1O*qQ4f)j|n0&MR$vQ4+R+7XH>yo>=ID9DkIW#_;CeF0;1h(-d_?77tNtf zfAE$0*tl7Fak1cRRKU2>tdD4Hr!Qv^sekiMbZ7E77nR(<(tnaAL+X&?778=IHExpn z#zuoq0uJnR{1|@n>uXeK(c0TMrl_Fn(K~HcM~J^(qMXl1y97vEl%SpYg>qK^A$aLr zWu0Q^8F@F~1sR^~l;kC-9k0}-c&fmX*2yVGJ?z`l89%f&5g;E&+n^P?`LX^V1swc8 zIE22HYU)6FC`?AX3G?*A@DE96p8S3?uM?2~H;c*A1tdk1+pal<{6b^vJ2!9#qugpi z%wXQ8eXCc@xE}tiI^=JpUJ^fx^mjdU1^Q(87*@y`H|C$^&q=`OT|Rv>k)CQfh!2~N zfAX6CakqItApwAIQe>{~t%Y+@O(RR@;^11;$)O;V)15(d(xSgJp`IEJgg8crNV7)*!}4TiM!!_hh{TPWjEzli`M-bBLf-M z&P`0*MpPws-Ia2}KRf{ZU@kmv>2`n$AyKf;F)Z40en?H z2RCr&Uu$QWGp%7+qyAy1AkEEwJ#H}P7JcsDeWh7@}i}G&_2iM zT8Q+8<3DO^YDhrI6aVE((Z1s=0IGjSb+2!O!YcVI|67A>3>^8s^cqLvvYeky5;EU z1!&>}L0$xpXtn*Z!=d%_=T9DcKuCeOENoC_g)&A%u*C_Jl{~~X;xH9HP)CC?z70w8 zv@R|#B+#U}#10}{lJo*XF4TdGiwmYfYTTY!E%GDKQc$Mxu7UmB7F8B&e|X{sIu?w% z3Zy0j+@E`VbS)5ve|W&#`ud|#kQAa|P9Nhwc%BB!iGMRU7iPke^o8P1&wUQ9YWq@T zQ97fUGVZTzd{6YXnA9jddqhlZJtb&z)M|PnARlJaZ zX-IMV?3pq6MRd60Ir>#X8bCH$QV1tZ%VA4kb~w5eMcfiMBd=Qt;8?@N>CK|1M4LFhZv6%bEf2Zh+9Kt^p{}Y!ehW|R!p}g$j+E&K z6xDyw`L|X7Ho5rLAuK#Pn&v1(qio#1-NnK4k0iR>mO@n4HI|$>1ewt>G`uU<#VJIv z%Jir`=o?9hF}X=VGcCF7=RWLf*ZK)Z>dx&ZINGiwqL>UpQ`ydP8!Lv=G=q7FLQY-J zKJ&;xcEk#U(9NMwn1P)(eWKXT>h~`{9Pj;on5&jm0J!bi4-o!lahR#BmvZ!~Y~9S{ zBr_luJ_V_#s)oVXc%dLi?B*fCuF=1#H>MG_x z)gM0|E46WH&AOFUfs};$GrE{xC2Aby4{d3`BbMAAqU2WqnN>Y~EbpW+*9gUOoDRtTp8d(^MQw0K4T*r_RCZc7VHG4My-A&pG1dYnuHNr?iSVhRY z{&e^be&WtrLkje_Q8=Zn@CRSOtGe>+*`b*ZXMCXk3xD2*;q+rdcw@wQRFa<~c|p=a zfW2<+Wa+ui4j~_hZWBz-5O&bble$)jU8-Tx4&B-bB6R~O#-FeqI+snr{&-Q)DmKse z;sE%aH@7sm1x|>Y@$n7?73kkqLt7<2GNUuvl&pc^YnxW@(eA3M><#iPdee;P1&yZ8 zVw+G$A4A~P=1WO{N2f*NUGkA`yA!CQb}Va?FNh_p01o%G3^>{s*l~fVUq(w1rt_fj z!kPe{Z3oX^@m-d5%kQ}iH$c$o4|wctLx&8BY&jKlAH_czR%9WPtraWf>gDz1JrLXm z$1OB3P#hTh#HNrrp!&(nPdCK3fAs;X*$~->lMw9xHL4@&C_s`mW=XXld5TFD1rYmI zG@Y;QT1GU8+LXETWZ4X02jW3{fi58scX;EO2{5DzaA?=J&m+HMf1?F1C}n5Flv`w` zv#5@Fljldo1TEdBa2AvB?}k#uUhW}z(Uje&Zg$AXoG9(PtcnNDKi3R%>Ngbcl(A=s zuK>#%V+kIo)EM>WH&k9l+b^PVSDOa45QzTub=i#4x2omEJq=X=l(RNMm9G7(Y=4r&jb=c21crba|ebx1<^q4Kay1?;X3AGziFg9R`{N0+Zlj~{oZ!S z34>+Oe6p(+SKUfLzC}qWXoTI0U78#JRN+p7rCj0g9#EYu#8J^ui>DBXX7?r;kFW;8 z=g0oOkc&nMt3od5gVeh0?swCZ3L68402?Fy)K0%1HFJXE?Zgw zyHx3ZA}x=v!jyr>=%JahX{GN|JDwA0?F;;u{YXl^0;IjaBkgT$cp-v)5dX$z_rLk| zceZ7X4h;#C==6PhygPQte*%xX5rdoKXNSLk7b5s)D=a3jJr|I$gKOuu+Zd+d36i;n zln9)!%~!~*vfz%=+Le|NWV9^)=)8|!9X-}fa^R*SLL>k&a6MyV&PKiN7Re~UR$;*( zTl`w#J7x$; zM{SqnRJ$%n`s-+S$dij$qb8QPSLd00`^B;0DIC zOLMn&=^-#Gma?=zlvQ{qDZP-s^nSh^v-5ZXTCE09QDWD-hsFv>EcN=uLyx()%R(;zT=F9D=A4v&qS1fni;-qf+8WDiURl67X*(tYa1gx9$+$!E^<~!q5DkNGlPfS@YtH z+(lvevgcpuY{7T1;Ml!?K-r9RH)eg zy=jbPm92aC<_#+Wnuxr5qWu2MWhPc39+F{o%O-RD!@`tjYg3ah$x$Q9)fT@l0Bma~ zo6J~#cER-%q=!*)>g_r3NWB0gaUFQf;GuDHmZ0?15Thc8RqQ^&3enhTBA!dCUARkk;Rjg&4Yh>eOO!>HlNz&BJoc`}gt77-NR9 z6d{DM7u8fMv@uc%p;c0uQcb(0P3z1&MtjnxMWK>*E!vbkw9q=Gw5d#~(59kA%l$oH zw=o|*$MZXm??1mke#h_A@f@Bex$o<~uJ`-3oagyE-?`hqZ4Pra(Odl8L+l1R%;)Jb z$SwYYeo(HdgF>0fR)+PVv%7mM#bs(^$-?8%h#)o=nUaxF*-cD%Ui7l>oebQ5;-}{u zPb#&js2>JhTXCFIU7&1-zf1N2tpbaUv^S!UG>x5vkm%m=y-BJ#ezUk5he z>8Z>xqF9o6BnZU&{_!u@&^~~uzmkbn0oj@)B*?O;{^{Ha4LZ{vD)gmjNxo^C=GJ*RT*bF+VlCAEihn-u-v#w~s)AbC3C^mglGVXo@mu5^=Nj5Euu+Zo*0*;yY%>E3#fq&Ac;emi~!z!=9d{I;p*3u2nCL2F5lA1cdGxGa3j`N*H#;nI7xG%=pP} zV2C)(N7I0G#0#AB0npS1umB{>Oz1XDfY7|SkK%vJ+{1gjf&823AQowrQB zZr8Ra1vPWd$G3@zQ;|?Ilwwn2#0Hti3*3q<+N)?Z!D$eBAx1l3pnC(nhStZ%#;P@U z!@i0~=3|XtmdW}%C!quCjIgfqa2&{uD;o^`@#mjVjzCm_Q97Rced&jH;qXUKFE5h8 zlJ8Y92q!&A0o7*uayoq_Zo%k6>)sNx0x73%pPrpyb-KGltBzXnXkY$F z6(Evmc*R+OpeshJRqoe`)@)a>fc9!&u6N>FoA|K8eG$WVt#f`~Gu!~+loRc*Hxjli zL{~WTNxZDAOb;tG4Hy}4Br7n}f;h7=N6mTW%`sO`#9oaCfxF*@=v*|0w0&a=+=lrt z($JzF;)W1J*Y56(#&Oqgp~pf4UA}$$c6TgYh(Zn^6AF-ZBntCG)KL%Nn5Kpz3)QAe zD|JW)<=YeKn4;Lf5;L@M*KJRoh8(8`^~3J>e;$ZN6sv)lYdaqwpG+y*c-tdkyLff% z|GG5ZP&lLZmxBVj4Lt}QYA_!8wmJFKn~=gOgM1u2pf&XXQcPJW985RVjK)DdQ-j$! z`@w=Su@*z{;c4gq@v4eH3n!HG*uCJuaFIJ92=UXMu@aC;Y!&Jc zN+3|sL*;E%ucm=$qYm3QF__n^!I9u6pa{Vlr_Vvlo*ozGmjcYI2zeLsl<5 zTkSfmTGq3-z*|)uXpk%Vo3itYaEU(4vhSqea#%Byn>KFrSC9qy z5{>L!gZ)Fx0E%q(GQi{uUXBY0f;XB%IZe%`6=NX^n>%h^UgwE9LA9}zzH_#14n3>( zoIktP;gvt8x|{h5jPRaAFb*n(H{e?I9%(HW_lpJY_i^GL_$zEi@a4i>)^Bi(PztK% zol(J_lf-?XRm1OMsfG$)5HHR(f1UlApa-Sy$^+R1GkElN( zBn3ssc3$45jw7hghrkNUp@GX9FHjT0Avoi$gD%+zS(Cvy{l%p{KLHXjPTa3o!6ltC z&{>pVEJd%~c`SLD6$6Z<7>w0g;9XYq)NJu{faX7M4tUCbTw$U+q(8on=C7*7mB5ol z7UtOILyp-RA*atD%Ae>CA1YdQOf`O*;L|FJL2rq{d=VtYmAD&TSVgk8W{Z#A@bDW&e+ zJ^DZtg9VC%b8&K>%=z&Sn5&k{Wp@|o-Mh%nm% z+NFOTy7BvB#TFrq!9E<0a|@r7V+hT#aPH*5{kVQRr%KTVJkq*qH`8xkT2@{Y+SCO1 z`pl^T5H(Q|Li%#&QE>!iwQ?9SRhhA<_Mc+YZ*7%%a2CG#E{G6XlJ|e&3ki#uv%9|B zq35~=f1!v7qfx2L`q+>hmdvkq*k(p|3NCC{0bCy~ciGJ80bYGmz|*s}-#-jGiNY+% zXkx0m%U5DR!S21ca**Z&l@ISPW@Jn`#;0(*1w4IUrBsVlG#sj~EHw8Wt}P)j5pp;h ziBK=~vkPcL0y+yCI4FIpOVBkwZEYx7Wj@WQ+PlNN^k=nT@_bv5lyQM|hwlQ`u=z7- zFx)?G$w*PFS2-pXRDr^Aa?r)P+*f+;xr7jG&g4_0)!#p4jbe>i4DBosO+)b5R_e{I zvT1VMwP2)5!uY=5c+_D83R*&<4+;UPrw%zcHCt!!*nCsvNtv(-Ya){;1VHQIrXJnf z(=&kiLL@ufH`RX3eb>@HBerESk5{5LE#!z{+fWE!OZoQ?pPm)ogDk{n04c1Z5;Ah) zq?O;B_QQFGj8ac6D8X0gND}{wn`*CMA~Z!F8hRoK-Tq)10|@CUGLXQQ$uQ$W7J_$X zyEUXt`_eHhxMgzEwO^sMtvkZ5%^|2eLfAm@l*m{6%mcU>hP&^6+zX9vn1lM^COtnF z_SWice4M)RRxcn_dr`3@n!oM69d6+X9ANO?+xQ1#ZH|_irVRqELSm*!SwoN4&-`dG zO^0KncQpvKNZfxU2L9!&XYKK20{QPA z?Pg7lsI*xEz|=?T6@cUE^G~JtRcQH$sWnLL zfn(Rd!=Xc+@o|x!n|ya~v$EvW+c9u_mJ6F@)6)u2dd^&abKZ zun$X7s-85ykF{Hj1(=;%s5{lMa;RjDWlXF>##Rs=n{^zzf?k8c$%{5q#?8Q!Tv!AB z#p*#*6l$I@)hhaKTg35BXY(q%LO-m6*re*if(5%GQRTtg@sMVeM0%@j3%`!@hx))p zZ7483QB;*`+qDK=ow?Jve?HH0=(jvTb;raM4z4q~lJIX2GaLb&{~Fv6y&1^T_q%(O zG9bkeZ%vyyj7sE%D{Gq47Ql-`d7V>~PvRsViSeS&z&J$-x`j7CtTjIO%3r<&d%gpO z`(e947IeQV{Y$(W5n(%h#M>0!Jl>F!)8UyjT((2yxvu#++*FI2m!1JidwC6dmbb8T z5LObO*$CE35eQh7K=-h74cd0as9CS2&wwcA2KA`aynG2GP#kWn_ zN5p==%j+&~pBXQext&y9+2rqAkf5V+@0Xfee+1m!gF)r^;pu9MW)$gHE6J*@wSW05 z_n6cRmKxXz>ge?G7`dl^bTx?swowXPp!4qI#fPzQ2J@|{j31I=jmYr!iY&u%Y{if- ztw&{^@_v6@eNzvWxPFqu3S}Q(MDR>Bu92`cBZm#HtUZJIBg%o_Ft%$KxXp3%{_y94 zCBfQ!?jvgC}i_r7~Lm;O$TZ)>VCMru5%yF0Y)x@z<^^}6dE z`_fiP+MjEV?8u33*7uXr>nQTDdVTZq^Iv4B;KYE?9)W`QwX6Ft^FIT8XOCm{OsD?6 zklGCNSiG@wKimn!W2UVjIrZ)_S$&nFRP4AD?W<^)q&VGYBtssSMFt_-!Our7K{W!a z*E292+e$ft--U%M-~i})Wb(!oN@qzF0V`zSl=Cc1Umlv!XZE;P6pe8(ZAhl!8xYtp zY+KC1JYH=yO)W@po@~Fazs|ZssQy7eEAaYt9wa~`x$hUWw&CAy^+oNh_axVPzdy8@)2ipXUCEUn4w$@;Jc4?f7AE}Xasn%-)^Jd^DZ!Y+4)biP;qhC_ zS6*x398g#4V1u&4(IYPwSrw0tTF7bq9hxA$wYZDMdkS~*@p+aD+}{aOawY2Hr?xh( zMy6iZfbWgPqPNBmZt8)bz@S%T!C4>9>M(_ml&MW}c50A5l%nQ0i$3(bZnV6fYw z2hdAJ*ftvv;Wz=al?@+S?jtCPwz*99=lu1@8s+o48-f2@em05{Nrk zf&*1nLrxU`eDGgl+t5GIBeci+>0=uv4b9A`Ao))9Te^CIAG&SRt)GyBes~D=TS=X$A$*gc>(8%P}+LZ`26+&O`~Cqh(vg8K%om2Oh=%Kk_W{Y7uICE zJkW?*9uJ;6C5is!NDRK=7J2a{rA3QY{kQ?$*7Zim!2;9FsQ#z1Av&vpVk8d@ZH6+( zo6=D9y6*eY>l}f6B%gCeb`c)_)t$Lp(BkqyZ60I0dx_+`eL>CF&zJGG)SpRnw_K>4 zApBAv+a3pt1e&}NLD+VgY-uk6Lf;Vv%Sig9<+kE+XpWE+HHwg0=osgE>BeXX1}$Li zbrMk5i*t_`84J3N7d~*zL$H)#V>9>6vw`vrWfxBKgBcD#0ZSq;ugDFofdvxxK$oI1Vcx8Sjx{af5Pcj|QJmpVyB_P{M*6PzeNXDjzQ#Nx-4& zN+4@rIyK$bEHn z_4Iuc;6&8@&}B9}v1-R*ZxmEi_KFypkCf}qq$~ELPF;b&)m;?VB>e#+>a|fv4Swfs zl&0zyuw&hBR6B{zEm&B;9Ep_NV^KIgN}$p`OIK_9o=@uKX4GTra4!ft*`Hu3idKLC zCB8*>am126PR~v1K49REoHm)`4i7 zk&OhhLw3Rq3&&M`SybSG(e4b=(D4AG7i;!S5N%C?oR`1Rry=u0_C1E$N4eH+?-YeW zNSRCUq&v_Axl_$$up|+NlRhd+d$!=Dpw&yH$ItA740_A-aKG6v4LXkIP#H*60c?I! zU7b2A4Fl#il&wL)Z%fI0o3NT+Akh=BB|@1F!7A*Zv!FY z)>a?h0u--y4?o!?;_}A>9&L27ooH`;;J{WQRJv9rd5J8AMyg403)WCQD#!JUfhSOQ zQmJ>+)<6-Y+M8vEvM&dfu->D8eMfkeNvo~Ro&M4`uq279jMJa{=f}R++1efw9}9}uEumXhuR6O!QK6t&-AbehM-I>K^?Z7pajS&`T3WO!IfTN291`Nk;W)36P8E*N&BMNy-%_RKL zv3JP{DBVht1PEdc%7X8m+P%?MB$rjYemOohnqBBaO&P>B9C%GVID20V&k9F1@7RA& zW35#Y2mU8tw8VA%ap3p6jOo+iFRc3SHBg438qXc=mLP2Fd7x+X1eh!dNW2$@j^@~p zKcEyfk$mR5cOa*;<8`#3FZ!aLIA3u!0oG@Qa}TyCZ04kDe!N)Fg#$XXiYJk4Jb>Y)iCZJrLOeq{ZDRX3AKX&3cXA zBGxZMP&Sx)A19N1J8()D2$g?G$e8Y7a6_b1?K%v-@-2W2H4tI}+&du0ifTGVFfYV{ z#rGO?)=;@k=vPLy^cr+yiNXCnU0nxJ>vW*(@m@%z6G0!$kJYl-VB>TKzsZ1T#Z!4&H9Powi2LX%CK<^kxdB259)3?beXj1bm=cI(B>sx8^-Xg4WU5MoEYza)YybvDT#Q+_~c zws_C0E4zCltZ(TSy0jF}eQesBHU>-hQgmuN%*8QUzC7lpFxn>D7xtY#RMReKaTZ_r zZrL$O|66BO4+8I+xEA5=PQ9Cs>+}cv-sEhmz~N3oW0uNvqHZS4*qz`h`V1P~Vs zw4J)s^-U1n>1wQyjY@%1@DN#rT#Frzf--J*_ci^F-xdnEqX>@+3wSOKt6-})u^}Zy zc3>LRUJ`wS5XSbB^HKwGsvc~CT_dbYxUI@~5?tsykJRnr+L!gIVMb#Wo zu7l{_^w78~j-{N92bnFg)&vGe_pY>kH92b%-H0aV~oil~{S!YC6u ziPoCzGThr0xO?ZROt^h4Y8^YsN>A>@vb+VI!GeVgqk&do)@S+sfjrYbL=_y4lTC8i z{l+aGsN{;v1q;{0^UoG%L5N_7E{7n~0A!i$M*r}hX2uHr@L;nZiOrigk1EV@v-o|Wjr$M+XzJNKt8!0I z#41JFMYqFT|k(}qaNe7!R3 zIivt(MrW^!Te6EJ;-0{#+e}NhfPGA z?V6;+dG-Q;t0XNUDjz7aVG*8yvo}go58N5dSGmxgfgzcWi$xP2&Fi*;Nn1x(k$Mq zw0LXSu?uts)$gni4r@5NqV5r&0s846mV+KDUoTYYGFwD)G_oN{4PKe=sqVOj3#0ImAMMY1f*0_1i*rY6=3!GxDO91 zXkqXQ?XCO;Xql*l!sLv6Sb!z#0gyz@haI8Pp8g4puYFKaP;4V+x~nGwjD-qqDRe)M zl(5%aUVC04`I=^u*jh&l-myz`J|fPqr48!I`ETET=-+&aIEVFqdEw+oV(&0y>yFt6 zKDyg@7})ZVrHcc(j0TR^)&8rq-MZ)4fUlwB=mX-I!rz!uNqHSsyCsNOx-OQT_Xm&R z#A;e2XvLzjr)kp=T)6h!!#ThS1&aq-e!+ejD%+7-M17NpVTC&sSEaeEs&A}ybccH$vni`2>CEcwgY!~b2@QIBKlhA^j*?Hx_;`qCj0PLeNna0LwR{*1> zuZJt(;dW####4ZWplkwYE6uBr>8yodMZ1?4c4b!Xhv!;s{B3~>y_;DZ%IIj+cPEsU z)0@P=@L!Mw+Rl4q9<$Fzg6dnqhpl}du>_=X)Osl0D}A9Z`lk$Y_h5o>;viys{CKt} z_B(YVxVR{|r^C0?*^`rgP1Ov|2-gahoGdlwyoz&~eMd1cdQlP~BwRZR+Z`Od;?EnI z#-Z)ZH|*C<=mTfqheA`Wc>opf(fwh~o%l4q2x*qK)3{TeD1PXlFpOIz>h=b{)9nai zghZ$SxN{48hg&Fg_310ah9y8Lh{<3-;}h&>j7w@N7;Dpdb0ia}55(=P9hWhmUTc*I$qim@!~jM(I0EAKG3LyioB5HN}jxt>CaCzixk-zU-P#&1;PVD!j%vQ7y z%ZP8njnjct=F^Qka}bR?T@MDl9Q0Sah>^pepPr3p0@MHTi5_0OVzI&=isVeZ?kk^BK)*CoQ;bM8Kxz7M@o(!`xDu<+Jw+2`r-2@3KvDswEOLyXg!#! z1!XyRcx>zV*D@uA{Rz#M2oUTLjMXHT`vA*b2w4Wj=YG!sy2TRd5dOFXEO8^`08qz4 zTvF|o1&rHUxQylOetqM2vHK6uIudxWeCt=t=f&5a0RVj*Ea!^sR$DC`3!haxilpUD zN+YnQ`}24nQ~y>9*@|IuSM0BQ(EJwYA?1ai);N87E!N1-RJ0YxGiOR~ zGoNml?T-+ZdjQM)=$MLqCk;KrI{e~ahDMRCsK7Yb0D!#A#}hUsw7%)fjYnN6@6+aB z;y+L^LW{<{MFNNu7wfA}zr^elEmO4n^!=I1dQ9AoBMe3ie0o>>{CMK$5Rpaf8qt)f zGC_m<{qMj0g_HCPK-nk-T#)}1uy7rxU&s{?svDrI z8*l3+x`vc?i#!;Gd$L#^w9t=GZ9p$6FEuFV@;)p0g9GDN$h)Q%lH(3L&A@-1`6 zJi?M;;$KG0W$qYPi6h;1JAL}LaW$k{Ew9E$kQHNoSj4=!f%T{ygWd>SulHa9>4JgP zE~&lZe!&s$1~iu1?pT1DZL!q*KX+~ZiZNN!vxeEnx4Q?uYS_pk=Em(k?VrBQl0!2i zzGo&MuV$<;ci-N#v48Kse?IOz%m3XY|J)4rH~)7F;Qv=~wK zriJJ4W`JH|UywPlYWgK~OGoUMBl;~!#uy|FU1{s#xpNL z8{kIXCWg5eG2&CfmYd?7U?PE$HEVh1Gkk$TUp|p;<*9`XQ@540siE`?$Yh%;_zc>Ld1X!#qi|=FmL-0(2@!0Us-BB4+^kxyU3{PysLkBc=&HrE^BQ= z-Z+JUSP$7-k8G)FM+tOGl{qf@MW}W=kNyWUuq6vxAh)fqz%zSjdlQHwsnQp;K!ZgG zL@Eb<%OuEs`F<9-bwOFixb+LJ;=NQ!g{#qgo3G&~=8EF1*9S_Kdd?Z#ItkSe8snF< zv;pD*dQ)$_oo@OAqaga_zR4~7reGxuF7fbBpx<+Q3vKD~zb@ie&aVFQ_heeP|V&aa2WZu%ICX)?|33p0&)r zt}mB32Z!3~zDV5t-!|iF>l67JgoC7(;*KBs;tnk3z}8H!71PxGV;vrIOH{(?a@DS| zZyDuc?SCp&=0+J%M%salnNWi;V`ll~`{1X{zHh!mBXZY1=ptc(D$ByFq08$ngliuMCz(xFssoFW`&373}$qqSob$F>ixbK$sl5#LHB`;yMSVA5&E+x*FKK zfsr8`C|3G{JsAf)8G+aBeK>cCw`of5Rv@Q&Qt3FeqjXEiX->%g;{T|`6>rL(eZ{dT zHKDinKQAQ##RdXj)jK&x^jWIQheT2b9Ihm?RTgTj^!yVawV^S=*lvrIjvy~DoA!j{ zA@S!Oj9bO=zkw?Dg_|T5Li-_iucJ{eGg) zfeH$LlzjN$3_wU?dXzIDR~3jhvTVuX$E1wEunYi)+KX*8KtNn&d=t*RSxZ?a>1g_Ml@nA8W=OKl@{D#wa}xC>`;?5i9h832tJnb<;hRsuR$GrozSWhiq0>#IlmNw3CTN%+$d=Kyp2NsXTTL+ql5Gi}D#JqM#)(Inq6B(Ved!%h80UomIHzxvd=vv0%kO-C_(l{h%Ju>}~1 z*g9}p${D!BrO>yFJUE~{2PdqIQk9Y!)r3EZsXS>iN|G5%OipD+eaBoeU+|FqQtUtW z`4DbG!(_2-1kT$7SFFv)jj#rp8<*d23%t(i;hgzroi4|Gb#AK#Yq|{gH$s?%gLE=Z zpBdw3HhW=2q+1M0y@?4(c<$&;ik<6GY6>{H9^M!b$DE7r7$Kdgs)A3mVE3 zBS;}(q|EZ&-Qn&%_zq;`R+rSuvvYRe>eIsOjT+AW$inE$0%Nn>-GK;6VDM|D(RCa3 zG9#*DFh>+6oVIS?y&YKnNY1ep0iJ1ZGBK}FB>8OK%Ry+OYA{};oIye_lIVIzE@7@5 z`j6KK)l}q!Q4!W~VbJxtce6hdE=9v3qNZ5#>^)Gn?$ErKG_?VP1Cfg^e@|rbV!rdO z2Dj9DW<$X2JE4!X&lYkSP(MkdQnIon#-ov)!0H*q4<9fCG0yUCZ()BK6WGLU6u~in z?YVvGqY8WsJVo16p|aS+n;|px*OD~g{Yiaum@5{uFPz}m#sWvXGD*o4L3%H zhiT4)H;Nx8Zy?mf(K}?~-xJDMHU*%%vWzxI8b-bX9kLcYY@evIy9HP;mUN(AAU6yR zmN0G?$`c1b#s2g4Kp1aT1Pt#l)^IhE!6dft8X;m8Je(L$Vr(nTR$-g?5E4my4P$m} zkq%ZAn4=$wXobU{CsaQ2lcW97V0=iG`5IgaDacNsc6~du^v=Ja@jMCJJe>C_Nm507 z0H>YUo^%9JDK-vi=n$_u+~zKJrx79STAE5^s}aENb^^A1(%hdi`5Vm=VKZx*1c!vI zq`4sVu~6_0L@LJ`5?_sJv)G*(E(U-U(om)GCLh zJ0ZI8hK4P_&IytPq4TevB=vp8Tv3|+MBYJYPs~h+@F2XlaF4rmbtDky2rehpdEm!L z$k4WRS6yF&mp|H@5(K8hlI%_Nv871Uw^dpTGeRiFiSA~9dT<-lQAv=#5Pe?sCN64S z`()eLEr9nP8A^NK#6Y*Pk}tCts%*aZQ!>3!FCeJLRrCy zBELbXY}rx>exo4tgga96IUz3b1&%9C*9F(>?IX^RoqE$Prx89ts3vU6)!lWuB!X~V z4%j<=K)@{PO=7X(SXeZVYJj7}dP>20gav66c0}WN%5CSR!88e%14n1enESwadl4Rg zv9y+O&vj74EGV?Zx^kTQ^N-<+a4Df75y7z$Vxh{udIt`ogC4)7Q|FqX=6OgA;{l&5 z1FX*Dn`pXKXg$PA@u?wdKkhKK5UT)t{>|dGtJ*(4&+Y)O%AYZ%6-+Z&;2k;%@TE~T z(i2h`y%@ZOe+A5@HMDKih!aC~zLMxg$T#kv?rPr*sgIw`^qXU(>!m5V4%~mGXC;%j z)5}=Ek;==~5iJ4@P+(U(X}z$`$|5rGY>I?g2;-;U@Th3QX1CdBYdi?vONX1u_Jo;{15oV3T>aEAV5xvReV;|&Tsz;@pWJMSm&O4oP z)iVi8)ena3>h^`3;UMS&TqDNDQ1hy1{vjxlt_VYQtpr2Kg7h787}bTdYPn`g(Ch^i zG@RZY*FsucqQKA~8hkiCs!N?H=1Gc3o#+^}Iu@aVlxKkxBrL%$sd&AZ#_yc4_<2Y0 z7t|t`N2uUa*az6dHi@3Kvc&CS@N#iBIu0Oul9dM!^D)peOOfQNEahwFIR9{h*<^d zvXK}>Rac(RlYvX8N#5HLYB+a?C=t}|_i7!3ONr=&8fm-6L^jsy5KWeol=d}Bh1_nO zJuF63O!gSc?hG}G^Z;uZ((4RmiVbG=Smma~jRX0OajJ$mfxOhZ!dN!Ah4FQhqXyJ) z(3l`e1Zjnm@UY8e5UFo$IKtD>xi7%t^S2300S`RTXFOrLbr}V+NEV1EiVJGs{ zmIs60B2|r@_b{8Wd4*f`?oRLBs37?=*RvAP9Z+&4sR5*xsvk{LX*eJwYI>)f-#Q+O z5}kjnv2e$Yz3nuEX>uR1l&Oz&bte(4W)(to|yr=LN9953|zW`G}P~$EyNie zMUucG)z(4Lm8*5Fwom>2zr-jW0xG4Fq2@ zK$tp6fJ;*~C**n5VjW_RLEO_pvyiY^*-n){=|oSJUBNuJ6+Q#)pJ?y`yiuqHv?W0? zs7YJuk^s8MwO!asqz^H_11z*sDALScn#)*Fd4!M22CoThO7o_JS{lmQKuuI6iLp~_ z{7?Ue%F;1ZX6GE{#?}+F(#O$Sp8^gJu-k%TaQKVBvpD8th~B3wQiDUV;JvaWDkYC< z7{&7G094$KDePw#ZLuUGpywmWU!09VkR2L|(&X&6)d;QCPo_5cNeYwD7!UL4L_ z{4>Vn&=PrK>_^OC26D9$z7ofgBXP>}gw6GZuNI2_=ZwvLV9|AfJJL0VB4cLXOloo+R~yPg*XEr3HQooX=6 zr|_Um3`4SfI=la^otW3`f{eRphy)cwp`Od#Hqp`49Ck0PX=yD2+);xr3)q2RJ zkCbat$e;q)pbf%RVb_!YZlIChH25zBPW*6rtuj3;C~z9#PE?i;`LkwAS8v%z$<0A` z<}fC!zX)(QN={}OT31YNC=h=)N3;RAas}=c?+8L&F)FE3H$&yuTFI`(2O-v7c?7Ym z6#7mM61`vQ-a0Ya&RT~;`lwU4k<6qf?DqxDjee3Xq9GTU4tYTxo?7Pw=d=Y6S%vA+ zOHi;J)|x{K$YYw%D*^9AQh?F&^L)ETFo1ESq6OB-f3LHm{JoZpK<~(1V6QvPzhaKt z;AdTBZAbPB!D?$3CNE-@ejr*|_Ud&Hm zPZDQ9m?Z^rB0cA5Wj&6ZhJ_Yt6R6_Ur1jC4u-k$PQvTEGi8Tzdu{J--%Z%aJiZr)y zV`3d){1KSD22*zh|8Z3i)*q{=-rJk>3vza>;d<1z5WO00mWBgZkz(ac9+lXzybEI| z^$3g~8}C`D_>8KFCT#u}_8*T?LKUX?kdJ4l7Uqf%wspl3OPI_20wA@^OJA z_f@|*0|h(h2#5joi?#>JF@(_nmM zI4IPdFwWD&^1h(PP$H9|-#H?}KG;@NX8FD_+Nyuc}p%IR$aGfaEl>>UlCn~X# z({i<+J5IjPi8azF!gX+tgq@pvPBY3YT{;A-?$WGPr-p7?G(U;>fZr+auFPfLw&6H93aU z)D!Uzu;g}#cQCMIT+n5(JB-jJ5Z_aChhowvE`JCF=86#^HXX^n(PRzq-X+j zQ+HevVN#tm5d+!u*-Xqbaz_enEchsPuy( zS?FT6bz}P{yf+)=Ax{hdP;5Og{3X($But9bt@)|aSI?YAlvEb2Qw;E*Y2Nf^MA5e`t7k*}_|)>grY(T%S==aKfhSiu?ees~AJsp~5m~ zylCFED>5V|Ny{9kH2DWxUnP?qLS6$M@?7i>s0G>d+5kUF&-{+rS3e8p)MTqj0i>vO zqi6sIAN5>h1Siypi+|7!*Fm?s6Xv1H8QJD7!Pj;$gN4#i&r$X!-CTXa0$rN1rCGMJ z{EhQo0w?DintTX3=CbMp_jJWXgCLz}H8#n%D~OGsy(!=7=qhnV+lvBl9R56e)Vp~ z7&sDzy&~*}1V=8#6DVh3-mHNkhaIuqUHps;ZX-#C11Dgmw1Tj_SlgXPHDl||ma~_* za3Veeppz|~5`mW~&N_d&50C4=kjyc)Nqy*Ih;&A)0u=#LS&0vq!!u(<@F65c>7h^p zS*ae+jB3TkE}9|~a;m{~TBF(G?UW*lol`w&cB`Z=UO;fUd%7Bj!tVe8#6{XtstRa| zSq_*K{_P5qOp)RZ?llKNM=t9bKb3e5cQAG*lM0s{Idgk2X5P&zr-@HSFJT%I8erNOu0ky-=bxI!-IGH~U zf~nOBwQee;DCmM7KV;$s790}Glloy(sQZyEU#pVpdCpepw7{MZ^xiD z`rl3fVM*^T;xE9?RtU!RHqF&jM)*0MK7jy%MeH4^%YiE*Ile^--y-I&-McuDm!H2j zL`!2@oZOIXQvJy(ghl{VUrQmXD^_s1nWg|l%&aD7ck1{KId$W&z1dYjZ>~jHN)D23 z$T=8Y$bWE3n9)u=s7Zk){gLq8PL_|=~=t4k_yctJaDv5vZ7s0VWZ-~+k z)xA)2Pzc5ZnNjz#qB5&rtbgC%B5oiCL`1o8hTXXKrIji_NX5K91%%+~2Pt`$j1nKy zfO-csNN~+ad16xaf&X?{*HAChY?@8#2>~?BNq>$IPJ*5?ra}g^4Gq(9WjAMcb#=v7 zAjt%$S&N(qb4F(89D#0fZ@-b8EDZ^Bhu%*`#Mdn|qaquX{!FAvO0zEK`%b-tBBUXyMTsOamJ!+50ifSeu6v;O zss)IdYdG$qaB2hq$to%oC#GmD2|G}!+#=Q(cnEd21`jax;(eWmgY+ALnpw)i#;<+6TIJD8{yRlU?1P`O`;h7nMN;UD1ff zq3Y;lMa(TnI5NU!Qe(N>4zgzR&~;^$TE$2&lXns08As z^WEKPoChIXSlCe)qqu8me7kHaYT-kgE!O*C8gqzVh_P`tg|&qH@Ma+CdbfT>HcoQ5 zOJ(^q(z7R9`09d(D7z}k2A47WW|Ml{leSQpjoYVwO&A?`^XGYtgtj$oj(2IDzPSfOG9m`* z>P>m+gfU~3yX;Bd^nO%7Du#qr5nTrd#VC6bdqQ;q+gBD{bll!M+6?q})25zawUX*r ziyFAdfevQ|91GpXMa|pBFPb-I!=|f>)*Kvw1}sRjakypb05#F5>piLi?~TbM0!(rm zbZkHD)Qtg_@-p*0t{~OZz6uX&#I*4N0ON_%0a8 zZ|YI6!@yJM$s!rt=!~32s5WL%w8nrI(y>=`Iz&+UV*%-EVQruM*>kyhb;xA z$MWylg23c%|BD8oX~NrJ20Tto|L6?prGp#-U9GVE?E)~j?*c;Ph0uSO!ur*>V z7d3bQrh^?ODcPvKbw)4jOsq#`OCWzda~gl=ujPiZoU6iGNXto(;q@D-*FjOxiN5Yg z=>6%HOyio_i|7LlBNISBenfNLiz7&PBXBbMpc{w%=+}ud8tdlsT+Vm}0jHqoXqGhC z(ZYc=iG*F}fCbwz)kZU@23de|#=(zj2i2DuV8GjB0$n=09E$Cs86+BqU(ovYG&lKZ z>PdrMSS91)6jVhrL?;+=_>ykScroi3_WF*gNI+G)fIMFR)x7LE#tdmruT1jIiWg-j zw3c0PYvZOXJWqk6!LYQD0rGO3k<}W;?fop4yw(J5frkTfdnYj;!CAc8D07!tM*3`@ z>>STS>5y8nX1@%KN@#lcG$t(40QD`XWaUvH!v`P&kdTm4&<5&%amPiRSJZQXx|j%~ zgnZMhVkInxyu?vb1a#eaeX5IE%5>Qd3tXC-8$husS1B@{CurrmFb{3k&xG%8kaoBtGT5lsDyD0((0NFy^jJMFMv5ZU$zG@a*q{?&Jth& z>xcjW1|*NCLS*CfRNeKYG9{89(%BvFg@R)-RANPI660#&<1Y{i^$`JukciJ$_G2^T zE_}$r$}t`2S=;X1*^&yFi?M9DTeQ^if5Y&MAMQcP@P52LG!wFFp3s^PT<5_e-`jQwt0z6AL z5(Rw(tQ4sA6^s!UduV-m}c{amet_r=yY1NUFOdSe!)DeRB}%%{F7(}($hKB z4NDyfe(Q}_Em{3E1&c*Q>aPvq|G~1f-vwWTJ1@=|^|ZRWx>l@9<+(Ht$8ZP1l<~;= z^7q`FWa>t?Q|XBYM^OvYpgX~jCas;2-`IwVb7&Ov#zk=ADM5x_(H3ok^-CxH5HG23 zM8noVx^gv~ockAHg=%z*&{|z%nJ=`kCGZ&0<@oP9Gn`i#^zlJZ48jO`J;-6>)e5Jg zr8W*-#^KS`Pjgkq67!i2EwgI=OiC(xE|5|cAp-}*nwJ>?0kFal<5p=A=!JmG>9TrV ziz%FUN_W>1_DJ?L@;)>Ep3e}F^pNN$wlbpp!1-kM>Ulq1O&%V zkc$cwKqW~09mw9Pb>71fWJFYi<&wB74mXWtL-v41$Qi}BIi-WFE3S!}s;>pzr4|Xv zPvSKgmav^|u--MCa~F(*$XkO4ub@>!luRXvZ3dK9!lmthLgVT|U}d(Sgxn zcXxuV3`U=9@+*SCv(}~C?!m})G7~-x3yYu!zvdyy8BeYof!|$hh0FWs_4PTdZZJo( z!+xmG|M}W}nUGKcoQGIs^v#lW5wYfc-Sk)xowiAjpej*&^Sm5xK%z>Jv)IGKLm&B_ zVmyrm$M)QVLIm$SSOoZhn+$r&aUWBqhq(KIk>VI*=-e~oCn21?Av8*>uj;!YHxCK`&75MK3Mr7pcbV7 z6S=ARy<|jQsseehZ_(H)C!y9KLSwF485|Cq^up_xQf((p@Yml=PI`{o1kI9?S))D5 zjj<;bv9X0J6|8arZoneOt_a~`onZdEpYj1*(F3L1OTis8{&Wf(Z=w7JoQ?s(mTs36 zTE}&yhm6;Rjl^l7ziQHRnHzh%P`L%Fj&U+~Wr$|qiQ?I>;XVct$*4utOx6acnb<;w z(KmDv%eaF!w5S<|#!ROi<}y#dam6DOu8b0A(#fZn%9kP|ny#XnC0OjYiWaoM@$+KA z(vkmzs9DjB9_lun81;xEc|IsSGPNs0Z@V15hcAN2L3CbZZBK3-V6}arjMz-`?Wj7) z*ijx$Uc%&oCt*ND>```6Vd_KYU6N7_MhsM~VdR#~+lq-?*Ur1(fd;1pdN8uxNcO)} zNs*phV#%|gpnNQ)l>}PRn*$so=%@xP%WLpZK!7*V6Ck$(pQ)3hTEb$wJGW1dB*e2qahVgw;-v4%9?33CG@yPIFnXC%`Y`UIk8!471CSJp=Y=@sJ0ao#W9>U{CW z2%ZCltQiuUl}-H(3>aBOmrYQK6xc*_$;C(0dqAIik@ZH{btH2fusFEW@@wXb%a?c% z^U$S>TpK9!7_=dPlRr{M&WWx?Yj^*s1VeY_3|^JnWLBDyf1*2(RMOFknm#>+_oc-fV z@`t(GPGOGJ;ReKc28zFZu1bmZ`?b68)|o-KL;(Lz%fLN_u+vg>ENpf ziMyE5g+yCT!J$kkbUm~;LNLJCX%Q%mipCOWxI6kaEL^yd*yz+hd};^bXyt{+84{*# zQ?F+A!6+Nr!|Jq9gILgTQ%wff)`AT|_ra z!MXnKiH}6*k~61r1~?h~t%IG|SD&@m+3=*#Lv1V9Vw zb-Ge<_L2ISXWh~V>I&K9Cxj}J)nj@GUKuqg)rkP3R90W06H9hoWDlmy;^79&W0N|c zncO_@%$GMqAplWVe*gY|uS?B_%424_omKGvI8Sw^eU^>{P$oJI!6E>9IwrQ5J&_|K z8)Hap15^+a14AG2C;8yU|KY=&X%C(qQ6?XNl-W&mPb@cBL!yRR6ZI&vP;?w5%?YU? z$kv6N+(?rZ-achWPD{qk>zFciVDYFXA>05Ast3)uX503H#qgRVNk&edo>b+3kEc zzfO)V&dmJ9*tn*qxuo_@^uhx*w`^}Gh}^DIHc3n|(cpVtw9Yj7=JTCr{a;DCUbxWQ z9nrq$P}SA0={$jk4;6zmk&}~$ro4?(%CAqN9yF}ZyMI3s0Jlk7el85YQh@Lz005}+ zT)=Gq7i4wG(CURJ7XU^a#^HG9H%_h*KI;xRDHhZN>#tlKgn{bpo>BF>-23oPgeKR= ztH=W$iFqu73&gpq7KW~<_8tq^Er<6hE=OFerO>qyHajLEj(GXG55HVP^!8gcLfZn&%RGAWtp1Dk^V0{ofu?rBk|o&}1w=$t@SBQ<4%MI^xqw4ZL7%=s7rYlI zuGQAoraRl|>D?j`mN6)}Q#t2udae|V3=qUse~aHV2A5@M8mkzj3{Pe2_jW3_+>4m` z^XDh3#w*(vq~g!F&*J=uc8Ikd>NrTe2l|Dy-s=prTQM^~dA8fx{-d_!gc{#s8bxeDm@gu$uIo{w(wg z!$U(>6R^t8X01WX00rP}f{ZHN&zd6kIJ1?}cSpVaz@88d!sQ`X>4vski6eRKB z@M%>6u4p!3HT>$(K{>g%P~|N?g5B}$KwCi~G+~-aW4#U4ynArBF1&wz!plZ}5z~;U zaSVEOAuV*<5eO<>S0MD=zH`-=T3GgbAKx%BK2E)5bBg#)~<z0>sLF0*8HLM2ahPTb2@Kc<5e^hd-~A&ESURW z)~h`S2S;<3c{u9%o2ac$Nv&VACK2WJ-XFM`4Ki42VM6+U6zA2PNh$y^+J1N7$()x6 z3cMROJT&VEtW%5jajmU5b~n#|*>3ZIR4>9QqiD5HgbEu#3zepK2@Gt{zs@plQ{AYZ zkDHk#HHASWFf$xdxSQXrhB;hIZ@zQR{Ku1F zE-50l+`|FqK?2&%Z<~PFvYuf%U5BC5l_)xRV1+5g3@0b2h~VO1m`48=*TG(#L0a4l z#1&Qjt9RdH&B;cl{HIqC!&Iq9%Pqp)RszVRiqlPttr7fd!G7$r?mn{Zb~y{+YaD=z zH|VPs6%>v;IpyO(i!L0Bi}OLT-}rEhE6yTT2Azk~WV+uzVa{Y=76n!jC3*#56_m=a z`upERseCF)LZ2D;*cN%Eu&@xDIHQi15KI?;!jiYO$CWKu{a+rQB34ojaIOy!r>u&c z1Yh{xl{MyyyBDEy9*3%$VDB}j>0ibv*%!JixV3Z6?MF|NXWio~DJl61Cj=|UD#jz+ zCcw%Hr;*kHDGu7HSw2U7_>FY8i*A|q3v5;+7-K^+n{7nTy()Ps0Wh?mrH7O5)qV082?`h5)?x2`=< z={MLA1$o0^2sH~ZxDm5S-uE>|!RT(DIu!x!dwG zpo4N^-QK-Zi$ZVEo0u&gIDlmcl|pb8G=BT-w~DR-KspgH|6EL9l&?xRR=N)N^0C_9 zX6p^1t`Lq*z16yWk6#gflYoKcnceEJ7I>@^nAD4z5F+K{pMC8a>W|04GeKV0e_ItOVAhhXeb$wau`rqiIiTHC&KpypHnmn zbZD9HG5#5>L^1F!WlWRjZblv$d)&@u%pTBhtmfF+*`aLXq*CY%aDA7OlHHDTG&>ot zO$FxoF}-oa?j>z)ZT-miOOmaP&YnAG0%P6B(Jz&gljDf$!<+>R!l}-Zotbg#en<$D z_6I$MdP(_7(Oi6dF(?lSEM2;lyv6`K@A}{ummyk1w7e*TPuhl@JKiDnvvXKj7$Fw0 zBOz$FS|KD?1eNJkEp zu3SB52y=#Gw()^S;%`vWxOwf`;ka5DlGM7R>wQjqtlyN%7Wss%Ah)KbFOE84QR*(# z8vg47bhh|Kf~v;31kC8};p55Gg#$)y93?Fq3P;y!9l>@ z%F$XCdP4}Vr`44Wf!WrM%NM5>C~EHeG%bzC_xb$Y%WkBP3_E$S01`qFDZdNTSI~1E zA_BlTzt8B>L^r@L3HVL*)}I(bMLj3}<(7%Ky1H)Ly44uIm8;NC(qc3Vc@;0in`_7&@6N*~#O7%zg*RNmy86wgYBH^HyBC?O_lQ{V$7M3Lv zjx=<~wO=J(%VNMdv}9kkOW+3~Cf-Fs4FIl#;Bef;v|w0`8yGkatHp`?_~nZ|won6; zbxVLdJ+|xCfiGJuU-60LnuahRZy#=Fmhg0$&sRY$y+>8vb?f$GlJu_KyI}!ZIeBG61EXiz<>g^q1Ie~Gi3Y{3US}qNYXiqS!*pCyX0@iqQL&IG%g)mN)>CUNCVC=K@ zUaPAD+$;gjOj<^^2{=TEi3`kDW8gD}Zd1^?rArpCh+bsVxY|T>O=1u(wv(#D(^BZ{ z!NNaruU^Q*(|I+0`|(HP-c^dWqv=zJuFz2k(M;y~=QY^4A1t$}lic`^BKyGAcJ}PY zNO~rSfw7W)FmGXKH&&sf0aH)~po;g$RE5jQ`=|wm;?gh_xe&ePS|%VRaYh)ek!l+Sv+mvL=a2)2eg3q< z{(%8g6cZiM6m~F5LnMZIOsB@V`%sg!jDIvDE6fz#509mFsVw6 zYA7p30HGKltqxw}&733sTgl$h_Eunh??`3Av4s5QttQ)DM62668R6DPKOC?K%0Do_CD@3r?@ z%VXmmP#yGq1n^DmpE(rck-2pvg52X97=FktslhMBi5=aLOeJjem8&3VGwafhP+5(K z*aAwdG6E^8uXz|@P?Kvr)#7le^N0A`;EGj|2W2@ToT1sy%2*st=MljT8xG#Rd)E=Y zFprS}EBZ?+!@K1uE2)0PjeR7|d>0oCDxYO9R~z_>I6(VU3Y*z%CL5aV(Et+`2K4mw z5KvMAed9ZhD2VAo#6txKp)^>2I`XTbyRvAE=Wfkk6=|+>`Qk-NwmV(A@nMf`m?|DD z9K3McC)`E9`V9b;t#uqHS!Y60ZBaA863xxE}G*~@dLh4ZO8CEAwJbv@` zZF5_W_-qI{S^bOmeKiGB7ED=ri0-UQoY0m-;X+mlZYpM&MZ%;Qn2PtZ@sq1>1J{D``vxCC6tC9YS>VAbKz#c!JS$frx15U> z-X~wB4uww5NIaMVrEMx19aeoC{g1?vk=(>Z9{e5HO>av=enuL>I zkKT~>uOmZwwGHcUY`!AOj(essp#^tLFb)=JoRsCnGc;fDst&QEN1 z64O80%hxv?0ElL!l*vHMH3S`MkzfH9UD!Fie8Yy4*mRu1<^1Cqi$?T+kk0xewi=GW ztlo1hzo`reVppj!W1fE6l{ldBzNO_MUJOt3?!6C!mv_}`krV)2=VFraQ%V2*A^shu zhnfAYIJ)UD($1g>oulG)B&>%~DmxI)P7%eNe4D_h%YOa!_gIS!uL8BnOvyT@WI3Yd zQ5tWglv?9G*AE#zmNs53iOqGw6k|f8V1zXzF*4%Wg`>mSmF(xn=b;!jcr7GiER>Ev zYpD`@u*zM_|EII(Ew`r}S%1LlM$@%SSCfH_+F?Tj$rmQfrHttC5JLQlcFaPN9YQ?9 z#az62@dETxBsx~!101nH$~F=#6oYsc%oU}&561}wUyi(vzk0xJASeja&Wv3hI-y}G z#S&sua4Z|1z75b-fWP11)MqvX?tv|{%>)MR91DP5W@mnd5KtG7%-F83F1XBFTSRqI z-=Gj{rWUjJ?kVe2gXQQ7=3quwGR!&$te`dje{4__kLt9Yt&oDbvR;gTL=G-P;*+9wUqB|y`@5XHqLe5P3VRo+7~`M)gL79z8y5Tr}qGv zsuV6=zPzer)#}xXh{@yCVlwXno!CLrd|-baiL==7jO_$Xh;!JB4`$6PcY}M< z7+X7`dFc9myb>Z^Z7wFxrpVJ(At=}dp*Z#~Ehd6btgahcsR)DT&Bgv#TTz!Nvh05rUY}!#l%@pc+wWPuJ`ljk|}GS*2fNy zJ~T>t^DTT`pjeK)G_b~A)B#K}o;T&nzh`EyE`#XwU7!ff;UmzWnmS1w#23oUo7<qO~NPvL5H4941(%mG)aQ7M{x#=Mbsm_1SMhu5z1`j2D|~Z~?1vpzbVfK~7RNPb&Vy@9 zZ2F_ zsCu3N!pg%nWqd$BHXc^B8qPTQhq3zef3F^tlpKsO!e^Pc8*DHJ01*Ntqrz`h2y!Wo zq+`6YC*M7kMN}yosRZu}E?C@A55vO^A2|Fbv<+SK^c0O0gT2*EeiRH!Ipv|5{Ze;| zCms^88~+SYDe=|PlSkuIUQ=eUsk5ONOUK*ZwCDzvSQN>D__q#*>VIYB= zgZ$Do22tN3h7yAe-Kk3gf$e(vH2<7xMr@R;3ZfW90xgW#SfLSZC~%t(28c}w+IZGgetWvMtss?l0P+!If{w6ZWZ4uz~*!$&7Serahf zL9=?D>dP$g0~_ehay{4Br~{zL|I^cw9Y}%G**e zu`eyQxmyDT+JC?{@D2zR&avR5U%!3ZFPE8a)o|*tGXx1LvEYf1Bu*tPep5%Dm_QF; zHI*l1mn_)=L7^gWxjv)KAqU7WLOFoqs=xzE!14hAwkD*w_bCRNNk!Uia?C&*$y6r1 z_hVIV@7jjl2scQ15-$R>vso9^WH`a#d;L9C)=RXOtir+kjM&l0!Gbxl9z}`F6k&IZ z%M;yrlAWtn%7z1;+I0uqfcWOsjO0|wKM(!)Uo_1rJ2!LH!O%ko0?$N0r-y`>Rv) zWR8WRUP(zwS&p_7-O%l9_{E7p{mj%)*8wFMIP`&fr_R%nR#;hNV(SvL+2Zzqq{~{l zsf>aCeo28}P@h@&PxN|G8}JO3q-&LujE=}nvDE;>D~5OD(ZNo>3wSIXv>V&pz*U;Af{S18n ze}+R)bj0kSt2+yKc<1GZB<~F1l^6_3e4720=EOt>fE?+mm<9~gyGq=_7v>9mkNe2o zndtFO0t+(;IbZ5$WJ8IB^MMFsgnR3Q`c=o9q(uTdx>b?a9j?jE&25t;m5Q>hOQ5*&)wc@LX!ncI?b2^gLF$l{>Sfz9q5&kzac&h8ebMSeHw z?@PU?+ju0MULpC;)kC&l@@i_*o|&IHV}nZ=>-Z34W>MCszPU3e7i^1aH zM9~m9>MrESZ@{CEvan5Pfk2cAdN^^DjeFT?u`B3o$M6G|YnTrpf!oDB{;a$E!ZP@; zD70y+MHV8vgR_lS?sNC@GK4IBdeIi7(5FN~2(E;3cg$A32-Z)H2t zmnY|gQv;e0k!eW^ap2_4{rl^{BOV1GNTu+dq*gPNX*vqcP$GUHX7JZP@wpCCgPm+6r^cex1KpH zgXS>&QcKGZQ&&xU;{Ql@{I!~MFCz#Mkd)K_#8Hk&9T7(iIIiKSymL)bn9eP}=thoL zvjZ*)8m7$DGBAB1KkaxsBxxjFho5FS>U=%?%l0}CFpv=c)m(t4@2iY|fgwK-kVz0j zgU{8gGwvjDX-L`ib*SHoZI;41|2 zFB9Ef$Bs0ed;qsV0iVr8H|vK8aKm-dQji3gCjv+{=!r*FU_ihrqeps!YauBBcoDtA^W9tl56X%x!Mbx*B zIrR*|G2FreoE!q%C{;y%y&n%{-aiO&%?K>Lq`1NGzN@t{&{dgVwpKU2O68aaNN7SDk}@uL*Y3a}c=ZxAF{fda z%j;LKzC?lNnl9KHFC}t{wBv~%za;1RB$*P;^umIi%aAV$&o>+1innQW0`ublLbj5vAJv(_$QpnJ<-t&3#>45Duatx=2q(RJ2SWQ}630TpF_5h?C|ARK*@X zePdR$GXg=BgZCkUSzV^DuYdFU_4h?nC)hCFRk|9X>t?7yuFzkq+^RkW3vKc)_OA9L z_1UP+;HsD+SC#03xRD-^_??*DDwHZAo;v;+UBiZ#?P%IEl+w5LsXB5pFy6&7QsQ{i z`NJ|XP5(np_0Yd;2vGC8kmSm4PevVKo`rx&2yW{+7VO(f&7sMU;Hk+jBR_g%PvMN@ zF^sx7&}@$9Uth`a$3F%}CDG9Z=*+#(?g6bE&OH}1gO8Dp1ftfNt?gm-Eeo)_Fa{*v4O2s+sJMgzqX*0Hq>SewbJL_^_6#KEGyiECCr9DU+5lFaGeT+w zbgRycZSnTu<-^W^LMyt|ua-utAHX=qCk;O6BwYR=XJGQ10R!^`op@~?TQ*e~P_m63 zj&ADeibmjBqBq1I|I9M|>qCpWbn~7LR73I50;w&+K-Z<(0kc)eF|S>_CJC(%3~-x* z`=JO>;wFLx6c;&X&ANxRYe)X;2tgm0f!!!NLWlA81J&f?%?A_BD$H7iD-Q--yVg*& z`kDK5zFUw5SDVhkVe_u0;xN)*D8h$4l}G)U^Pe&Q3NNzh=%nCNDMS%mTz{aX6zllYo_j>o5v?DpQ+*t)vE}e_e*V7|^ zft24Ae0#1!beF4w!(z4dsUQ?}MB=+U>xTQpFqL2v?%amKlb|M1=@0SWaFP+AMD>E^ z6PnQpoe7@R%XnZg)gUpKnAw%6?C40M)P_j8H^P}c()*XgX^njbp1l*5q;suM?Fgo! zJ@R({n>ca!@Xwuvs5a2Fa&Fd|&`1sq&4HnnyRl`ZknKl+Q!rYRB>z^^t+;!4p6Z?J z*1sDwz99ZU(jSPWHh!XR3mOP9fqJAIG+OrT9?#e~ zoc)i?z-==>W@RHfev8UsWB_48b7suA+L%g5Tn$4i{DHa#HV#j?oWPNR6wPk`^})MA zPjvz3IN~yL6gHihQ3t{7MjXf^>~x15G^m+~Ka~RL(^(Opt(S&e*`(spgYnmgim`7Z z_8;p73!%eyAAAghR9zU-5_Fs3%2+Vg=sbPWu$Kh`YK^zq?rKC-hQn+_5|8CzZkKxu zk8~vKU*2FbNIDqaw-?D4U~)s&$v|1>5&+m*H8c}50-@76qZGUDXyi35?E$BLuk6c% zQm{0T*x(oQl@75P)O+izWOGP2{#BmbF?0x&xXm?S+r^m2pbc?i$7haWDzyKy+k- zqDpGDkq49)_5-34_16Y6g+W=9CM~~?)eME@e61$~`o(nFFF~2sO=4e%hEifs=AbCA z!3PUd@i@847tSgT$?`5m#eAEX!9^$@$_HYLyjH428n)=?=F2x&&T+o4mZySLeYrMAzaJ98VbkFCO3w+!T+D<3Wnwh`kOW z^^Le7<$wyzxN%c01wd+wDNOlbFl0k+59mme^0s8szbF zczFDSWx)sEkF#;`!LB(tW4l1BNK#0jGIvcVa5}2vH6$b2tZGg_6}srD?wgp*JP<}6 zH~1h84@U{TA27zF8aXU5EOC65ZTH}>%f~+hJbeRxV*HyUEOdV!apG4w4>$qSRaebJ))|!$b0l-FVG_N3+gfx|Tbs$QpKLtgBD9~H}SQNS8zl|zm zxaHz0@*n0u0%d?$cZ!Ooh#$YR?oj3?)?LFyb<+UQE?^4lEbh3v79tx0Xr>HUVyf6u z!y`wGL7}J10*%%QGSFn8WC(G*VXro-x21UF`*7-Q2)Tl)zi5S+SoLzVc(gQflCsB>Z*izX$+AI`q)j7 z{K>KDhS~IS4yfXIcKtJSN7|t`wqZ2a1T`UQT8AOs8iF!2Gg_e)JwD$@SRUu47~dAT z-r#j85N57ICr8I{Bzd+uNynRac_i@4IL1EbVYqSETPl5z?Z5wjP12#~Kdn}aea3G$ zX#(OYcAYBvIk_Ey8QMI?s{&8nL*bqDom;p1s@N|82I0z-(2oO`0qO|?FbMPK&nKQF z{0MgJX5G1<#`o{J`)vkm(NRf)L9{M#8{rxW;U?wLQAi`gfZ3vS4Z#RXPjcn|s=LV{kes7ofqs;ot1s7~}9)e2jRCGJfD)3k>7W|$u=IaMA;W}FJ`7zBgi=1 z*!2%|hEcyeJw1JaxK+@e0O>HWo21OYu+x!+97P5}_wzt^z9sJHLn8YT(IXHkKA4;ZHYzGcI>W*U!EI}3z(c* zW#sh`JUHMbqME=@ZcpQrHS>0IiP?O1GPwwBu%5R|-@9{yIaW^wapB@}L3ZWb{x8w% zM`;-u7A&4AbS6{md+rgn8#qFWpc3vdA-zPxf}^~BpnJ{!`{x6|;R5z6&Z_MIx!>pB zy?fwjFISb%@t*wq0N9TY5!9=Z4tS?m#}&Y;GM9N}Di^2qlFmL=VFI9Ze|>Oh$lq%R zkv6cExU?D4zK=sIT6-P4GgLMG2y*_7ff zBg){DwlC_4O;}0+43f6wbfmz)U;HOeXM!j03c5v!>2(xbla%Al7ZL8oAfQ~iZe3An z&(a}DuR$otv?1_Wuaj< z27|C`M8-#x&vh^^s}eMvNWdPg{lp+$)yP-(cm6%Y;SBsciYTrF&A8Wa2NBIkC9~SyCsJEc8H-%e*9)vesMV^{6I651_ zvS2K>*Q6#nvb&-H@KSSLm~D#d zPB0a5u6d;G_afSSi!j0K_U%x_vnzy!-*&WOC;4@C>$D80#)t*ZFC(-Al4x42N#HI1 zv&in2IW*W?80~qrmB>v99NwUTpmE^Ok6-o>y}G+ z^N08E->>`B|BaE1Tt@Z6EPnbN0YSlzBwf#Udo&R@0hUQ+r*#kSJ>hbVuXgPc;Bi!@ zC-h*o)|0((P!9+}LFL&au!qG`M&b&j;XZr;k@^h_B{0}0fx-nahPar(-N{P&-~OOV z{&V0d&P#IF5Rj);x$(blyC{An9(>x&{Amn@42x`=&xQurIk4zgBLBV1z8w!f1kw7< zqJUmCQp8Y z)^!n#20&U!S6ULY<^fuG-MY050x@$?IEJ%Q#p(4=FBOg1si5!{Ebs4?WBb+#k2V1i zkCt^E>bIdmf4MY>ld!4ecJn<5Jxh@7g0-_&!5n2`I6s1vI$bPv))^IWdn6!V&b_dc z!B}zopV2@jZM`y0AmlOtt%B8kaE*{q`UyE`Ij~SZ1iA2iWP45 zEu=jJ%W!%kfINu{74zYw`8uZ~dg5kFgVC0CxT<>U9L=}U+ENrgn3=;^(xJ-ivc1W! zbFJ&J#itKO`1;6tbQNrby$Dy2e+U7zajNqF`yQtK@&CQAo&x-&lDk@8?MT^@W(byjsv256qckPP0cn~f?ABgF4JT@PSHX%GO zL&o3!;=V&Jwmt!orZY;fWZV!+8Q9B$X$MfP1nMziMgb1n`FD9)?ce{m_hFnZ2J$o7 z@1r*as`}$6ab@ZkxmJfG>N*Otm#e)CpbTnQLRenWE_U*Z6=rv3n&p23pCt-RNY5?; zkJ?YPvJ#Atyaz3~;Aeu~6xLU?Zo9}?jFarQ5X0Ml%A;c-UWf1~8jUmI$Qt`GGnP2I znGL#a<$;p)%QT25Qd~k&jWbvZdv^JWX+5>yM?^!!p{3xXQ6F;q$C#xM{i6n$H(*ZR zt9P5?_xw8-p#D%Alx-{V_!*%2ikbh!Dpxci+p7+YsJ`zj!3Agp7$W3YQFF zZgH!Pc&zoBn4@(YrlY-SD?%JCgg9qk!M>M*oNNOIL$1=!*U`8=VQ@=8Ll2@6#eY@{ zG1dAB3IZ|+;%GZSM2Rk&)&ibti;D}jf3?)v%9M!#6D6?|T!Yl7b`IP8? zseLs-TWANPbkab4?!5?Z7DPi15Z^CfZqsWn_?QK+OAuUjDo?$m=Q~ys0{>-hmOXZ78{?R%pP; zve2$CDS>wQ34z38vx=m)6+{CVb$k4S%(r#{FHjjFU9io)ws|U$TjJ1q^2)S-Oa)Ex z9(9i(p&q+G%Thn&NnsK03BT5Qk$Qz zh(?_-5CxbYLMv22fnKefu7yau1TT2JBpCZhoec$na+Zni!r&l>K^hYyZ4ZEFy;ML% zgq7s_*0r-zB*ZYz8`wq|oOC;?M7Ju5^h5(nIZxugO?Zb|61bLfch0$HW@fSw0u#Q5K9X&O9{xYWPI^G zs^H~e1so1F&QdQR_C8H~{D$>3@ZA zv?7dYU)6{|3debQyF-j(L+a}fQD0E05S+ z{D5oTyil^nfFwzKf|3v-%%T@K@!eVgQbgUrjY0~4e8}d>?;s>4AmPpwh9y~mhFi!4 zM$O{ibtFtRQf(iowFeQdihx^>>J zW8+x&dTBLQd2&!4G_k(MIM63ctJx8IFGTa*|kRVk3GeuY+fh0wLeFJHeNMZ8bsPaLu!bX}oA zN*UX9000=W-G^|`5kNQ%YDy?w=-WRe02aI(>f$L)B@zyH z7Rl2Cgg%qu*q2~CyT-tRfnMT>X)S^QJ9q7RgAkgU z4b0d{Ng%_t1IaNo#T`>dtm)_Xckpn<$-eHoz|O)a$;n5-(f36kGkhZV)z@*L4wis& zA_5les8!b*jRfD-$qn~RN4TUJNthQvq{6kckbp9J-b`UAgcczI zx3;+=O#KAQZsh2t0geSIpq^;O@?+lpr zU8nv|Biz_<<68%&ZxprLBKMul!GW%*G~)D9za;q-w1E3z$~5RVFB$9hKEpH0Bhv!K z9JPghcDJQ>D%Id%ZSwVGz#YRrCFE**+BUxASgro(#m793Rbwhjtf{QNfs*S}3UgXe+#dZF1o?NcLJI7gCQ@4c)s5 zgAih?oFPtK0?naAaRIk(J;d6->y*``7M=Hf4YxLle*@N83KkUtRz;P}m)T7*;- zS>nE|Rmca%irT;p04xWDM^Dhlk&YUNOE;Sb;dd+t` zv+Vi?4Py~y(}X7n^|w~tU-oc9W#vQD@c%7QtPEc|BRI--=c;|7+K)L_?%))hF~wrX zDvxzjb0h2cbSt|f3Z5Dnig)|CXWH=hPHJ^&N$z$y{(?QV)$T8`DDefqFt*Icpct1M z>VZ&H+8`>*mCy=m@%!rvYjU&>7)L)(#HN2?>W=s(lVsZp$GXiCGc!gQ@?y-8GBUNt2A1g|(Q6iLGnWfMWA4_dl_}#g_(9;WPJs=%D!? zn%$7lS{|=+(OMI2z>p)mmtBdv3oi`@>JlFFs2^SNxw}crHy#-AXRU!in=*AD7QpzH zO4p#u%1S-lYai23(y5zU`#$Bam3MM-vKYeXiqZK=R}$b%vq;0R+Hp*?K#}mcLn~&( zd+8ZE1Ds3l3&cDnLzz;>N0@ox@rlaH$|Qqd-5-dlr~A|^26VH`&CTQRY1RF8wpHeU z**tkoNu&Hd%5Hg4@OM9a$57Lj&@<=?HRL!!q>d`>u0&H24{|sCHO^zK=Bs6lsRr+%sFfS3DI)O!?Bs2nvZ>NPJ%b{!YRugp5?e#_n8xRTA6}Nh_$Q1L*=(ca*J+Xcdp+972}6b3!~P`Ty(a;k@o~mpQW}C!ju?snGrfP<|97v zVL!$LRm+PM6A{T0%I3booN8lZQ(RPZHThwY-|4$WyWuYLoX>5Rx#(cg+1V)sEa^jg zdwX0uydzByEbbq(T1BouJ=;4G=-5qlOB0ioIoxOaIeo3y-M6xRAf43h!cOf$F_)z_ zkY^-2J8-aRxkuTLvuGG@zlHI3jC0FOf(OfU6d3;u2@f+NK#w7QHhz^d!ya4M6J_Zf zk&O%`^F4Hh1$G54DF)8bNMh+}h3NULY;44C#G%eyJ#ZrcS4W4B?Z;qTe9oH4*gH8| zg5mZwxt6ga3Y85!{|8qY6>pv{U5vd0u%ZJ4t-YmPeduZE;)0{tETRaJs zrzc3qorc`KEnNqyX#NS0ZQznp(to5;(~pO>wY7`iyjgENwDU?UB*VnY7cw>qJZS;f zs>N~qB0gM;eVUqgk{?DyM3ghedo3)qVJxzY7TXmP67SNjkJs&<^2>CtLJr2tNluLV zj|mA024xWu3O875OG2=Vi?MiF$?%0shtVU?RvUOFFFOkZDBm7tk2wxO;<)uw@6XWd zRNxy|{~JrZ+8XPxSq*kcTAvQot`Dm8*NxfkjVqU?2TeU;V}qX;9=>b6{9Rcr6TeTe z+1o)k)FG;zo-2{gP)r@KGrUsj=1o` z)7o+MJ8t-&9PjzFh=_;}YySkds;Vks=GhkRsq_cd-tRj;NhV=BqL@V*t4xOppXdo- zc3h{n1!)D|h8R$nGtE{+6L--7Z%kz5rI#;X{&ALgySM77tG8t+F@jcTSuz+8>U|+i zd56j2_9h}SFFk38s;cU95v!$bZ5oYr(&gja^sLgZoeTIqty^Zq%cZUeE9I; ztUVLHBKWtA;S+zKJdMG5nt6G{ zEj#(A*BiHN*6Pvo42)(bVmza`r>&_6%`d}o=cz8pB3KMx}fkq zpB}lkl;am1vx{Lxrap_eoLf43c!Jx{*y|}^6BI^zuViS2D&3Wsv}Ll9YKJwkcdD&2 zIf_Aj)u-laPvCdSx=!DnwbkbpoD2(d^G;Tp06sLVGQ-u?Fs;aRF=K@YogbPwVK{`+ z?CKnDr@oGy$hqIH;aSJe>}n93=HVcA#fd_+^$CE?fdszq7eL;7v!!GAhY#n`yXR$$ zPB*tqI|#|2vSV;DCN2^otA_scYwB{qu)8*uA%Wm}I&Y5h{1-Ml&6{^zN;!~RVu??6fMe>d>6Ipyyz4A}O$Ghqh9>pJH= zuip@3oH89olj}e1IarV7AhgLE}@gzB2>}X=>7EC)w|>;kgFpd!M$pf3hL$ zSDfp}@GM1uxa+K7yD1pT6S;ZwCh48iA3HCB-3kK1r(Ro67vk<(Mk^kVAoIB~xWNxV zol#k@Y*PB?+ZbdL*ryKCfHWu#GG)GZ?&zcTJQM(a$>^6`uo8B9gNVo+EjB84+cY&b ze_4hNn|C`pI{F<9$O&BZXj3z@OR%}K6elp8Zw$?Jem0Zjb4gZIhlx$`^jMR!B54@E zDu`r@ywET?+p_Yr^_(qn1s2E{)5;LQ%m>4#yIjki36@U5)Q4iCqAwA?==}a?s`()T zr~H)Nt9EQ7a`@HA%{%v~ql4+Vq@<)COc|}mDbs}u7b>iq$@qK)SMdVi&d-kQ^7H3G z9zbjZ%83sPf7XOBXL3GNZ9LzBBsP^#R@!?Q<=pcKkd2}RURD6DdD=9t9wuBkUe=;o zeB7b$i?Ow|v~(NDtdAc*J`z1(_w$pmFab<#c@i2CVOxZha58@cW=qKrMdf)Cs^ zQCqj^eyFBt8Q;Rc?*@8NE)sb?B;B}6+Ezfrob+)da5i{w1os^{FdOEOeuo3G`T5eQ zv@{v`y;`=tfq?-Wq45lC;p@xH%Y)cGd6>1w2??~b_^TBfnwkTjC0puH5Nj5h!q_m4|NFafy}#L#>N;p-%Fg6JxGWt??E?e8@}opAMSY^Z_^Z{!RE+%`ZO%f%`YQ0 z-lf988*^IEpw=-L zhM9k0*K6M$u)MQ7@zW>;%(XQ@pN^qi~p`r6Sjs=C{paeg7(Cn;>5aqPY0><8D zT9)^N@7`SuD#wg$i~u@xLXceU1s7QuhPh%i95W|A;|P4=Q8@WD+~^dX1J1aGJN)PURd3r!tjU)8m|Y%+;oi{c{~A4&g-vwJ9soKB*`x z&p}$As}+yX`yI-LhuMgNw^Tz2+sD)bt>dBL;gX~?_U-GcH?H$MjMCkWtmP$ALJ$kj z!#;*aMO}Wq%TftmVHaYyl^`K5fVNwQt4_oQF)^C@&K&y6;J$XUgV)OknI2Tzs%S7r zyG{NUh>=6&`KXp{g~9l)Uea3!eG%a!ZXXINmg!mZxa=`-|)~K|r!k zRdp^r+lWJCYN`}oY`AxVfD>?>;DiL0^A$8WX3sbB6Z#o|SMy8O_VksjRs}zLwExvy zw@2jTXwn`{(y$+5l{;xe61e;YO1TIE<`315ASTzO;VV9-@NA7xqGqydPlw@}Vx zb$R0ZdHLk3?;K(6+sO|fJm4QyYzJmk6_e(Q>7ZFC zM{=W@ovXzThUv@NvAoHUu^ue+3$gT`%co51oY^&_b2o5@7FuOMwfx0gD0`1{ zmHTl47|p@QV<#~_mBKIsNxTG*qNUOZ)kjKMjV&w+5|ji$_gI$>P@uKe2;?sz%=N1t z81orcM*t=TKcgW>B#;ibEABnCHo57#8svMr7B@a0ouq+TVAjbI$8a_=Gi6EKq35UW zb$@rbqaXL|ngU~<=PZbuYhe!0?4D=ir@uh_=kcf&|80c!^(FKuvPrjjjzJ-(b6zoJIYzUNAl>jD9c33VXrXBx#r%JL z$)~iF|4&2uM$vpD$%~`hF*=_Xz04QLw`p3Y%~`#AHAQ{|SHOvq1J;A=8bvH$UM!cL zNi%eE40&L-5$bqH>Mo}Ei^g;*VGa@L(+~DsalHhQCkfQ=I7uP=)~#FT&l@A4ZOC-b zhL*zu^nzcw;@qK6nc4Ie;(p;MW*U{DT=H&~;&<;q`rLbUXl3jmMDP;-PV${T_c5R; zdbkNfc;e^021SBMZe!*DdP)3hg~H9#GGqP(cs&rhF^8A2Xz@?a{`jV!$F0NPebWW_ z0{DrrVjH(Zc@Y*T&8NFOT-$!}fJ%4wbI!WQs4&%GtLF)A+h9ML~*TNW8{}brXPQkcns@M2|_tfLxeR4TbYhDhcqw9yS z*Vh^AxJf{pi%8Q{P>IPnfC4g6{iyha0mCC(q0~f!Olf!ox0qrs*6uypc`rlcT^?#g zI4 zT?~jY-7oMPE;Nj~&_vZ83m+bZ;0~4PwxUHs4@JWP&fy_T5P5{4MgIXU)Y9nki$epz zuNM8vXfQiUzc0q1C7LizMctl(x)GO{-!snQ^EPyWYa@=jUn2^@g0FpkSV0EkXGZ2G zV!RwHkZ65DMZ9|f185_9Ni1o|WE|XAsF+1XJo>z9=qSX2h7(t8|IQfZ@m>qiZ}QOAB4P2g=VkTjAmUkOa)`aa%&S{W zKN=yXK(nxkMo?{}jFXCnc58>(R{Hj6oz;8hHm(QsRI$F5V^&dd|2F-#jHcG8q}q$7 zF=@6~`Jn;!l~vJCensO7AKv%M>({S|Ga(3`4Y5wCto{^iVIL!~k+MNMUzp~|x`>*1 zh??B?;8E5A$afP4(7nTllBC1bg`$FJ1>=E|$`Se(AkynY7@`Lp<(IRSr1!0>PQ?WD zFKtS$3!rErSau~=$rIIJaWqFXLR{oZczAdyD6U}LyugLg!_^~B80xyObuzX&LQO}= zxG2cJ@v_)^OgAfVps|jBez|>uZ7^s@_4z#7!LramxPAcone#ISYP$8%2&Ef_Uctra z1e}dh>jfHhOhk%#!iKwB?r58WQ3b(C8XXQ3R5Nab`*H(_eV)*^m5gt_x@Fo06!ay! zo-}$I*QF1swi5{&44ApvC-zmtV2lo>M`!c;!jmYb>VZml3=hd$H0;y}U4_eNgIq^! zoh-1j={?te@yB9kgOfr`aSxQ5?;aX~(#v02IiVQ%JTYH6zq~mUM+ne=xS+7Qr#X<0C)k~*MdMaK1zdOcC5yxyi@s$ z*sl(8tw-wvUfYU4K~; z6_}6V=XSrXK(G82;#2hZb>68E1G@?qVtQX&2j``QVrxLITM)^2{MBM1bQ^<>_d+(% zIfvi-1q7%9D&pyKLpWJB(EkA*C_25rUG0h0;ipgnA>)W+BpoD-2{QADlL0c*+zuK} zs*g^QNgMv8Nzs$mAEI;f0i>df*c36fZZu=i0P4!eN8@!{p~x&sEW5m%8aKK{ zW$T4UpegMC9wf>OmM0q*`Z$yKbLVvo4UHeO=dgn7ynN6yl?_JSdZ#WN7NS)JNuUkX zBeg4KRlE_l4wLjQj`uyV3jz$TxO8{}uu}&6%QIx_CD6U8bOOYn=Z?67M^#ytu*uL%LZdu@rzO*UV zR`pWHk-C5_Nq_E$zW~20Y(@O1M9=`qco-I<9WWSfb&_-h9Pfnn7Z+uG=K^HD#n`Yw zeOSc-8GSV19K*PfZpe6N5jzbZn$z(WjBa9W@mGv7!$D!xTeBZN6w8?3k=%Ss^Bz3( zHXl_iwpiUsYr{eie|%ru(G7vu1xJX3rW?#616ABYL+Fdq%RiBczaZAdz5LuNSVWE3 zR&bp1T*o+XxAlu~HjWTs3(GT+32hb6i0G8?P+>Gc^FaB)BsLx549jK?p2UnaVP?6O zwIb#K+%xWlYW93|)W`<;?|*|vCGo~f*g&}Sv{~k3_z6XiiE!x9;$yU)Nx=vV@Vx@* z!H=1ZsdYmZhDvwS7E~dk8EyILNbY!)dr>y2$cLCNW*7tW!MgW2TGKp*Bhwi3rfmL9Vke1_V7CIze zKq%{?tk_!c$_pYbF;Z>ooiQK1!JJsAxW%*ipt@yP2(xDGBLm88o+F4dk=m)E-W6Hv z(42$bF?OPu(cH;4A@{LYJ}i6CQpMES#T7u4xu)8SJ5D{i#b%t=YYm64grzN{wM^{PPxHQV8943)y| z*nv>2^{__>D(tjJs`K%`9VDMG2(Q;Op$niF-8;oU1C~LnwL50BQ?s+Blkk$#)Bz<3 zgr3Layml@?TgYHSAocy>o*fTVawJDLSlx}bnW+KP zHuEu$+GctuqWP*2%~!S3ma%dR`qReM*N^sgLB}gEG6}7POPxr0EndgC@a5ItYece~ zG~*2wwT@-Y*{7=;SRsZfHa4|CnM1T-99e@tf2dYd=iyD`Rb!U>6Fv5# zvon~rc{^9XT5#=UjYxviLPTDJVBO_)97WP6-TxuDIMT<}@W+41=(~A@%j-8-q$6cW z<8-deOwJFBh`@dg{CYOkbQil1(ZWmWIymL*3clw(SY`fqV=~5|!JlDYSA3pW0q5?0 z~w#LC1W z|NQl4;T;iEF7!Ag7cQ4UqNF>}3V9>LVl>Nd$8)a``#&}#R?b(Xw^rWmv_H(oZ<{U8 zgTlT#hgWg&tNyzEPf|;|J0UoFW#*FYoKHQbta-8sT-3^?BR7tLVVsS>2^{dF%oy!I zpKcZ+cU?GF%W6|s@6JM;Kg!W{zm6V0!T?p9he$_Ooj@Z2Z@*(-f({-Ur zf@Y_H%ZtyZDtxVlFj&nzQ8P6poJaatomFBKPryU2EFQb1%^-Qc-iU4!VdjI$jJduC zz8&5Nj+P+tdmtixNo`^S)D=zX{q=E{Kb{D;hdb!z&XniAre24Pd}klVd@6i@j8z+g zg}TiDNE6hc9c!qIL#&VO*?BH?%(nWjr2Z^QQw*IUvXwkZoyf*SCzcVI=r*OMhI(D< z4x{r8O?!1!xZnCnA&3;4myRxyEL^Kbq#$el_HvUZ(Z`ZkeI8IKJ0Muj)7LVXRuNw^ zxzmfC)|r0^|F$_jGXo}N4dh}t(L+?&A=PqQpUAt^r*bd<$G2rnLSjh&p!71FU!4- zto`xB-A+@>?uE^Zi@!OZvjuCF&)evV^wD$fudbnd8Z+xJ0i!VLqtuDgCCci%q{b{I zcO-Jv-F}YkVLmMIR9hrnk)8UmHV=s0+Uyjin<0xH$=g+fM1Q57b^4S}d3hGK%wkw` zK}Q41-pSM!YR>ixMG>wmp zL#_5*C#m=6m)rv{Jn1X(tEqvDGT6Lypi3_xEW8l$LcaN*O(~-*F+AFIwRs#-u(u(2 zT@#PMg9mCQ2)x3_)t~=8H4Rx*a{ihVwgGHv>K|u{jo0|pWey3{9kL$`9 zq^{#-1+oJj#)#8Tv+%afTt`R_Odl{4M;U^B9>kqF2DU;c2de4{BIizi#e05~qdTQD zk?7rX2;yj@(L9E_NMH2O8i46>^;&&neolP^Ej-E6QfO3xgxXKb@LMa>w_c#?cazVe zBfRYax-3@rS3@0pJ!aZ9=LMkgk<-}%FRbOze6t4xd6D=S1kj^t7CMiL?Z*6^pu>2d z?UT=L!w>Mut)}^yJ~UCXWqpzw68yO^XB=gwCMJ{91?*g9dPx4+@kl?>?RRQA(mI~Q@53U#I>J#8$@r8MNs62E z0!p^rhdb{<|G|oQBPh>r3zR}$nAd-P<`Sf&_d#LoPUdFX!r>+{f&NsL6-A4A-CdF-m=s%+4UkIRw8ZLxL zm7OUBv7xD`-9Tx~yY~4r=K0=69GYFKs;k}VOSmpfG21kddQG56#nhsN93f(=R^ZX0(|2fRY=+p0GB*)JiB{&;SoKMua-LWTjGKeI9k^#6HX#T z)cl*O&Gyh8{FQ(>$BMD3%g_?Wxn;(fGO-U5jIF-#zc0}J&u$x9oA!A>0h~6`(A2Cp zKkp|B30i6%lPn(vC;;=mLk_Bwkr5dwNKIn!eG%3*(0*AWC+8Ydr&|Nr8c0|1c_$jMbUluM9AMHU)b7T{2Lq>9toiP$+T?0chfXUA_ z5q2TZNe2TWT6X@XSS@`*jewzc_Be?FgC{_VP>2E>bkGurBI9CdJ`5n?r=Qy`>)W=JgI{3+xCuJgdw2NegT)t%Ty;Kyd;RMnUYST&k zjtf*_{%pa_(VGlU^+?IuNORAgJ$Zf-!h6v9F?xcu#gINy4z=4)T!@;H$d+DalB@}& zWrPsgt`HCiv+jnb5n)WPy`GJQVM2~ zBnk>58I&N=vQ!KhFp|WG3IdAccq~B#6-sxECIp^x_9ivZ&7~vk2gdd7Bgp!+3Wro6tUo~DW2}ZL$9NSSoH%GtB z&p$^PWjYSfY+%~XDPA~zAH%uGvpgD}dekL(k)K~t=W-{D+*PQtQR?_|QHpUNBuCG& zcSyh8ms){gyy91lor~3m)P8)pjE>f6>+#IehjcS>P)tF;!RC!8q36_Qz`u?tySJDu zW*`zYQRr5KG1@uc+DhH*j}f0Hz}%7E%#&|DWJ=13Q#jKm562Ie}RtFAsT^D<(9X0{C-ywK%)+ zy$Zp{e-)>)&@&yr{xhr>zfOit+1Vk4yu~O=X=63GzzB}Q9ZB-&+O?2&iSB0mdkP+0 z^hA|;(~Y@3rr1U#&UA(2a}|^~r%2xeL|O)wh?2?-X^RE|(`~>e7zUaD1u~#u z*xoq6dP3>bL)7FaCACFuGRhG0H`2}_aPS&xBszdeD8|(qK~;MOGd>{?!bino{9m$5 z%M9o%tv$L@D*S-(Hf~i;P0&0mE&}A)y4CZCo5C>rr}6LJUrX;myvXmIHZmBSZQ9cP zo5qSRl`gr>dhMIc*ca^V1kmr$C|*&}S^*C0ZOr-E{JYuzvQCJ-&Kc&8FRu`2iw3U{ zX#Q+oA<$$YULnw_|6I;rx7z1FcjvEL!7%?>JO92H|Jhmpz8C+AJO92H|KE?w>t0%q ze=`}0&s?ID5a|Pi5K{J%v&n_4SA_xAo`ex5W>lR%I$lk=bnnPRA;Q%b13~S1_k=zg?y^-X z6+OD#L;u5Ot)`;>e?JcToA@;W&UTC=Rh!}Y{VnA^W>9CR2xP=%r3Y*u zv2^#t6YaB94!G+TbfsbheOp|T| z`tGO6cn-<8*yk4ZgInpW5Wy&G`@4R=pjBm9(YqrU?bb`Ld3-&e3m#3aEjV>bRdm=d-r?1p3Rh_k%0N5bKx{CO6lZ6qeT02 zw<^Y@{N&cKyx7IAT(3kWVo*2h36d;oxDzILmH=3+yTTjZYuFztszqz`Jb+*k>eW(Z z1B2h8yQ30T+jK>Q*9%mF_@Hq@aQZEj%d})+OM5vKAN3rifJ+Z`Kz{k<7XoY*nm4~6 z{Zt|A+4fMNFIi~onF8db3XJ@b0AZLZdBe->$3O4Fb4GCB0ep&BC+Jc+FI$_i+W4(q z$HxSG8`UjT7E*-*eY*&OH`Ek%bad=I91k}lO?ZUUV#8EmKUXN>t5Jaap-1u@HeoIS z5n)@8M5sq3DxsMLXKr0`93htvw0z1NihsNe%#V$lC(Oth#7aZY9!eNb!&q;t(_Zoc z8}Q|8VRL^Q>UamxD2SBRaOnB3zy2yME$s_Rjw~2kJKd;c-sL^e;R?eITJmiG9I{aZ z8T6#aw`^7rkd=`+jUi$)34f-iOx`yaf`SaA+gUIW^Ts}K1Je)uKNASK1lnTvSIl>D z`NJ+N4QTxHWp%-ms2)a+tbx%N)q*CnQc_Z|jG`&Mm_H(>?Vm||m>e6qeg+uflpA-* zGeJ_Dyqz47**}LDLG^g=?log)tVndo;4$UyyR$Zavn*B?{d;RBJ`4> z&`2U45HbMS{!T1tDej7fZ)?odp+d=vIho-1NRUA!5evv+2(3xGTL677SKKx=&T@(H z8lWEkaABhfRBe%YW{?T1?qz&b-$?RT!p~(nBIY)c!5!!J%(=DXnksRyh?W9F+nKP* zolzI;q$_^#&8lK??{m`+eb`JykSx$eOfj>Dsu&{7T-99>HD6$`PJKuOZ`-Yy&Hk$0 zwW&>0)+2`qZfA9&lDXHsdEaib=<-P7=k2o&nJC- zz}Y^;wi;!`cLr`_jJEqrZr-$M0{jEFQs0@J=|EA+?cCWBg_aaJBfdM)?^ywYk;5m; zd)tq5*o#rzHPDC&medw^{L`kYS7=i^fj|(f?y%?4`N zXkmXpQQfjY9DYJ=upr4q>t+f7nPM^!`r!{A-;$DHA5OsVbuDHB#%HgKBnT)ER0BXG zIi1o!ycU0L)V!$7x3fRRLQuWG)%qO!KXPpGe8_9+hd+U1{?9AK?(B;nxqkr#SYj<% zm&7lE9o`IW|D~VGj~zSa7teDzja$#8UIpXA6y$(5;uF%2#uNkUW@aIze7gVE?%0NT zlc?2oyM@KjV^%(!z_i>Xm>Ou%blRoXn3M6%OYxS;4>u8i4V2|;wWXyEyfc|7N*W); z`^}dGJf9&mJ2RX8TAd3_;#6v1G(@GylA(;Y|F-AxhqBWBL_V9#@QjwYv1hc8)g!cl zmErwV1?%4Xi~A3KWA`GMacdc)*El}7?JIb$_;#Cg8*csHFnJgIo4*DziGcv_pQFQa zK(#I5@b`wLyLn!6kx4v7wkXumHrO~2={0oYsNg9~x6neCaU0nT^)Z1qol8w!ac>xV zn>^ZxY=xMsm(`07ezo(LypXfE3X%I9HEIZ%b8~a^Q<`{=Zm`$gCl>xI1+s7LG`3wIbVqJ-ioD8y__Kd9 zf2AY!-D>i;uc=%kxJ;6|K-OniXcMziUXqbb0PtrVC8Ik8ucF;o$e{3tKR1?5WUjt^ z{W`ME3mK-U3#KRk_$N?-&prulq5{_;KxQ_dwSWANz-{sbI5lM0qvbDYl1#2>3o-Qe z$3H8b<}$K+u!X7~K=1GV1u6E=xUp;!bF~5UKK;6iqD?AZkTv8Ff8GR-_Ic^q;$Crj z!@R9-Avt?zYx@)OH1!_OuSgQY$AAkL?3g?Mf@F?t7hD0W$$sZb*xz5Nw-{EcqAf#k zx3T`)FN(tA2}b*o67Adu>`0uxIMOI8>j$$BR_MI0cmPpbv>4p^-Th$}cWNbUH%0sFVn*X5X1Nnb>mn1>5zq#wnFPS}%aO zzYv*>F3h=Io8pRMR?K35gU)5_XLK~e7xR1Jztj0l&^57iVph!Md95FlD2UfmTX8Mm zbKKPzdzT0a5rMuNmdw);!4`XTw^CR95{3-B8L;0U`0JJ888e%_T8~O-Y~H;2%na4# znEZJxcNB7C^1YlaEUblj^BNkI*Aa?|c@=bY(sFO@!MuS|aB#+@k7s`>8V#u<(FzdC zSM4$~LMwu(t{U?$7S9!k!Z4nRL;$<}db`7d$2{l9je5k#Bbdp(lxUCSvW@v1xnB|v zj54};U;_J@G4AUbqZ8;isi4z2iGXEax$LxpXsa>5iur$JpG!CDg_xo$a6Yt%b`7*N z`Q^!sLu(TdAr;N{vp;ubHC|hZnRTbo-dU@!udmTB7hh&vDU&;#^(%LKkM@bsf3$lQ z2p~&v9(*0^ot4gd1+!Fu&wdKF1gQm{Bg`G}^Nu*4Q4orNu;5#J`y4sBjWgL_&QTL$ z^td?%G6KIgyAF3Q@QRs-=ip+V347~F0Mq@hEE-tGUSuEDPZcPNg;0K@a@=!sy z5^`GdEu4nN=hS)ZAaP@v<%K4`ccx$ln@(Cya~6Ubf>G{PZ<#?q zU-0DCo{>;jGc;p=?VDGlFx3_khpP>z-g_f!&Q$(`%DJD>WR5cWPf^~JOU@3SKPpeHSv#u(WUWmcA@JK znrH|97KkXcqT9ZydH_y|asPOE$Qa+>0@w92PL+9xKA3?=(7_XBo`UQ(GGZg-dS+-? zaiil)BqFHd^aEKIb&OA~CS#OEzQ!+davr2cDGzrgt6B={y6kjvrPC}X>K4vn3Z-%( z{6^TH88`=?{OvB|s{_&ZCf&w@Xc=9;bh1@My^vqEmwm^Uj^wXAfB-Rt>KsavFLy1N zT?wX1Ht0TAv+CKe-v3pAqd?*g@?gYNYH@B*)#AX!)d9MM=O|x@)31M>{alFDV{{tN zB^$GpsxkGTY%ag9zvN(NLdIH>41JA=K8q}OpBuZO!UXzL#M41`({-omH)Epb8ie7ljo_*Xug#OS?6 zTLvE$rxp$Hqo9GRU9$Bl0r)Uk+RGa$#`4)KOxfJhT(~WGgposW^~>Cb4Jpq26nnoZZ|Y=WqZ@orMdr>skh#cw!O6uVo@ko}Of%D*Q=OS} z#%!sq{H&l^2e!-)c{@6>YTBag#iEz)EEJyl_?WZgLw;N7UnYo(1@#Rsw(DAI<1*~s z>og;^(C~X--19J%S7oE#=7IbKcBZ#!HLnHSjlVl_{N3>C@7m+oZY2 zR^R;Cbm`)|C7AC##t}a2DP3na_ zfR^~qK#){fe@afojA4|9?=l>5M0nxO^MtlxFyISxx3A+K2q(SFdyjz;P|nq%Qh0%; ztP?WzT8#1@;;{5WFu(5GJe9A~7;dY#OKc5C?3P)u0ACn`{Er|2pg(yqXLLm3W1Wz| zUsO;~gJ}^uC_CVe?=hG7rg-)8v4c~`9BTw)cG_xqKj z6B_g@=h*65AcVRCMG68QD`nDOCF}&d&bt^5y??;&EQq$m%c6+`u)_@$vrU|3m)5Z( z=xIfmlhQybQs4~`hS8jq$Di1na<_bkwDYi#n*d@1AmSh|*xFmCWpmNySD)Z(BQrAv zux%++8%d}yx9IB!5G$01v(T&oq6e*2+2~J}*8!M>a^1D+(ir5ilRBYaw5Lwws#LA(8t~#7H z8~q!Rr*mJ53=_oBJ7Hn-K=pFD`aR8SpcnIHYEad_0E{LNNa#ahp<-9zlJ6zEh9dJ_ z0p`?zvSCTwNZES!(drYmc?VymWIasAscRn$R&oGfQQO2nj$=4Ya@kCK!#$rQ_2H@t zxX2&=>Pycx!4DXd-*RXbDe&=u6~@wh4pS7+`*+ zT!iK!0QHZkm{>{U?Fac+J|z!Nv}`n!=-U~U*7-@?rPRT&gD0X&pN;v6QK|>xO2Q?| zWRpN4aRgDx0z4O+5l1eLKYqk8Un&P~ve%I}KHS=8ZG3y5dQ+s8OzaBB&o2mKS_V~? zN}M`t)iLprwpq3}B2aDY>dD#Y<&X5E7L2BihYod&v}L01-(Pog)5kBCsuktQk)EF- zF5W3Sw5Seg_eEk*;b;>cWaq}x!}duqwlPD4eRX704ZPL~4U$?aJe7V6+I#x*t6oMR=!?z<#_Z4g<-Oo^#&!#wl0gXH zho6E;BQD<{DODS<-fxfjnHN&wx-1rHBR4r!!C-`!`}Z#wkO|d+7?_W?&UH-l(T!x^ zyp<4-*zN;3^a3oa5U@~Hw7(%(e#Xo5NYVv{Ay&5(VrGl|xiFvB+S19TnDs}TAyiHW z0ft`2H&`T;IhXVvWnb+h>r!96k|%5d?iUq83}LHjDj@cQqK- zpD>SH9uDp~NaaqIu@hBh-+jZ!V(j-YM6qT6(|_*)`8Q+N|J^6{e=g|92m4Ps&Hs^i z=-us)<1QUV6=@EtDzF$GG6tvr3+X6r7t~A?BXIULBF1LfvMX4hiBe2z0N8!!!S6JO zIx_(6FmT@d|Jsp#U?N(b3vvE5pRyLnznwUIBR>O3&4tUgJcyx<2x7(_Y=Df3AIZ;Y zaz&$Z2~I)^oLt2q4p<02?P9|=Nn5|Yj_prpHH_lBk0e35UrQS4Y*5LAK>`$6y8q3N z4mP;M>C|Qtk3oc18}3!|Q{Rql+pHZz;yVu{>vV%ZspBv1(fV{5 zr19-IR48s~qj?>l$df6SgicpuQh^4LC^`v!;&!NHm!5DkJaJHEOs{RT4oAm5HbL*D zCyjn0H*uP@fIeQRN84$WS64wT7e|9BXgeEf_i1`B=pKpWRxOBT5fo#%&9}H{&qb6( z(Vbp>lm3U^oZofH*G`e4uM5h%f;#sbKe23vzW)WFy7MUJms8lv2S=Q8fc53DX$@2&mOaSj{}0z)K2Ng|Q;NHU<@&-y|H`?cx;LdALD(Lg~_7NQKc!y@y_9 z5`@1r1wq!GedICL?kXBgBE0)C0^-%Gk<%~H0RX##59Y_bf~*(3D0%xj-7v<)-95fv z_kAfeCQgv50TmIi=ROdGC=YQjm{{iRr1wA%f&Z=`anJAZfK4G#t#oZM?O9bMoAj95FcW$V_9xV9RY zLTo^${0u;xjN}iI~Vf6kZ62c(p zwB?9q;RwvY93)Z0Ql3*KYr8XFCEA+vNPmw$Z^53{gtRwyXp%uHdj-1e#iW2#>wSC9 z9NBy0hZz`EwiT*R=pH`DzSp&yVP|a(&ZN^fXz}Y#N?m_J5;DqrU$-}f+}<}K@$uuu zICBk2?@wUXQ1`hZIy7~gBz_Eej8D{7MZQW*K>6%m(YK4HUepFTDoyFP5p6(br`GXc zV+|U3ucXx4PQp#ZuB3J-11N_D03Q)3r6@O@Jmwg&Eyk;U-$W}9$XB|Xjh2PXeL6T)xSLn9axATTpO>-^GGCqNibDZwWmi%)}ao0iF=?pW+*;=e!_h5 zQuOs{bbwpsk&)cO2IDtE`%3FhO&zpZkNZVaq`Z6YdFO(weU(Z`lc5e1C*qif-nKM; zUu@vL3)30ZhI;brfXlo_bLf;C%P)js6xZkr_yFIn!T_-FW!)vq#|GV5_H$p6_dpRT zv%kU4<8#GeQ^mIj8$B05%D2$GFUSUBDiSk)!|nNu=1x8hoajh9S1#Lgx^CN~;V#lKq4n z)z0KeWlBPk#S4!)2C}}CIGO!(HQ4S)n2g*Q>!Wf!BC}6S~OrPKq62@8@{= zeUlj3$zzHEr#aziQ%vlEIwJ_ji)q64$u#efwgiL@ODjgPpFOAZ=0biBhCVrgY7vS~ zBzF};A#&9;VcSG{vV^`54O9$;U`tL(na*0fcy8xt6V3)ZZ!IeznWklxBI5}P;sFtkg z465j#XEM}VbowLDWvh(gtK5MZH>lMWd)YUTDWT1?=@kB}08b}R8t+n!P32=_Z%q7L zzTNB}^UvT;!XyeGn2>xOK}C*e8bri@XqXW7(T07O-sB*l^C{-{wPb{%@K41gs-7^4amJ09ND_fz#TC$ttGuxRZzGWDRZSj1S^KhlwF_@c8!Jp_M?M5h>ou;|MmLTf@ z%Wwhh^2?q~BIH~>bzwi-UnCVatRVuR#YwU9|BOambMgqKtpLf|^B3iRfR55Mmi^;a z3eWHRzW?T?{em6HVLU1=1MQ~wFPc2&bvy2=cPQpt1OwRUNy+F-As7Wpop*|=*&yG) zt#!rhLB%Ha$N5BU?^I%xEE~)#!Y0_eTLr3NztgBg=x8L`kzGA@ONZ!?rUxQ_a{^Is z9|or{gMow6rzcNn8p-Q6;1Di{7qOqvse6sXI5x)|3`e*p>^)c5K;v3gpptb%B^#8D z$R-cESMADH`p`@vtvi4qBsxbuh>p&Oz^%}HXHs%%LB)FMu|`<@eeP5NVuE@Im<`Ep)+lbtAj(O)o22u=1K;1yu1y;xJ`gD&u_*%G zEtkK<$EEA@fIN>prSU~Tm9|1>jx$RQys`scxV7)zym|EYQ%BJnKH)Kpu#aKa-}0qXta(J^y}D*a(CY>CRIeO z^YOVFxceM#uLH`4AiWy@>l|p@*@vJUI>8msU<5~{?^UCw{z<_CnC*qYH z@`@%n9pzw{{H8{hHx$Es{Ec1+t=uw{J&>g(+}R{OIVHq@35HA&S6M{$@IjjI)acB9 z3f%WeaI$U@! z+}o1iVg)&K|7@3HH&Id1C156!V42%@L7kEcG*-fuof|XO>bbL-Q~>+72TN>TGS-M4 z_`)3zcV0lJcQ5AmVaIKt?r2lzj!F!zBYkQ;Vgn8P{k+k;cPn0f;%NnTDA2~pQDy81 z{Aex}o_VdbW%|3@=ugxu@5b*K|E++;e5zT4;0_&aHG&X1p`aQtd_d>Dl zhKA|I{t7pLYpNNKH=}0cqP#$5OX4l#Wr&Ck()Lw~LNLYC2N@F$i_17asm>Nz;c5>> zo_?d^`gcgMui%iYAqN43^q^r~$m5rxTk!<9MmQyF(T=kgtRL`k7y4$2|Iipwk{Oly z-`f>AyCy@&OebMR3yR7lNMD^$u!e<)A1ImO)AT!?w8-kz2|R`^V-RLQIu|*^*oa&w z)KD$dz7HKdNXMDYM@vh>nwP+Rupf1k9#JxgWj{Tt0s-9#-VLA6$mhMFp{p3;WhQng zxhJ=618Y^5MEq}Py96|qpnGG=zp297pV}p%sVFMaq}mY zMT;PFeo1~L)TqaVvEs&-NC-5^F9pMu)BBq$25s_GyGr|?srRpeC1J&}GTZBpD_Ejy zPG=N)i8({%TMoku?lX47OBnAt0y)`>CDSzGNXeM@^Kzgwrn?F5{#`d~+?4@oASL1M-NRa8fzo==@d6O)SmRLpJD2N4;R`zt7cETHCu-ONk4q$no4#ogxE zHS`o(^nT1%yMpzn2qIMJjx?>@_vGOD`PZLhUqIg;e>j?sD(W*7M0;H(8Vapjse?NM z391SmXte0TJm&L2Xj~#X4FE6NCfA42l)$8~;SsPtxOxWwPRNJ)TA6HlR^+;L`hQ%@ zD3?p$z}j+&cy>LK7~dk8%}D@;2gd3(eMnpX6tqi63T(*#nm>3_dP+zL8LnZ@UkuJ@ zm#>4<=ks3U#h8p+4#?+nX<8kTUdeO~vqvdba0Alsnj0H>Ity)@-tP*LY>Kj4rUV8# z`JDx*c_z2YH6AqQ(Bh^9j()rSQo?;SFwmL0|@m({N-zA^&_P##Dc zU!&<;*#f)c^ieY)@gh#y(kCLV%I>DD9UhH?Bn6-P#B0UuocD;86cU2yI z8MGH`A(v09l$)LmHq1BJx!x-)2~$~rbJL5p!p4_ijhME+!CD6N;9N*{0}(-GqZJ@h zCw8Mg%)_o0{_Squo<5H$y#o&@ay_Kvu@>5j9Q3>{0!$Ko#?e{c*I7}xr=l><@WfF# zXnd=d7*bw;Wnm8d=mG&&S*Hjij{t~F{T(HleigJyDff7Veol;IO)d#CkRQE5E9o0~ z6wnacd0op^T?)_1!Sh=+XK93%#5c4V8 z6+f|{P(nRuH1rK#>18^92_5PQeS&WmEW*Q^hk%q1*TYzS_v=_q0gKHv$p}HP2!4#x z>X_fIm{8zP-DVH42V3lQXvxx9(P*LmlBS>Lr~=?@rxgIqcq9D$?ggdn*1{Vn)^bEw$Ive-yKjg1TWTR0(Mu7g6p;?}_FrkIzqFVT|x6cT;^ z{tHCY3&e6WOzk2NdiBjW{X^>w$ySP7PXd-&zMI-o!Fw941XcNeb{DkfOL#<7E{^hw z=KkyM%>gJotWH16&_N;Nh@;B_C#?iv@Kfyl6?$Z`u$+9K`3&oR7D1rM=7U}Vs^w*XAeJwT9Q;Zt#$IiPu5Mb2#>all4q(!32{T5FrBDRctfH9Lxu z(8+c}x)DH2(sQ#@mgf{}lqRzxijC9r$am6si_6wN zHF)J2Z%KFp6C!W0Irh5@&XMS$)$y+W5GGb%2hkx;B?Fi*=#L$1nv8kxz-HWm021+0 z`^7mC2k>I!Eq#dR&Gue!191a)B>9fB1)N(3-~8dBmzMCl*nR8G=FUqz2Z8fsGP;5_ zNwHwvNLWxoD|b-4X_%n$OdLJ+_Jn$;;B!8HNa_2crT%GO9PIhZ{^&p9X;~z@(l|=Mi4=H;CO*>>c05|7D%0s12`S|n_!goZ}8dKn1 z6ur&!f{Rxa;tU|lEI~+Tmw&x~X4>M}bg*Gjoc=h!<^Wt}r{|Hqv9SROX};PIqC4qy zwQ%T>Vn;coj@N*fIqMG)uLgTuA6_^qR@67OTe7=s%Rl{E?LT2|BF$x&Bk>_>3GUTv zJMX@d+BU!rHj_uGeZ7A>2J+jlf`xO?=i9R#A54_`a7srH#r& zzDnJ9OFow@8CAMNI~u4 zrr`?Xv*e)to}(GC;*_nk6J%~g^tcaWz8n}VXPD$qh5c!7cfM5}+20;4TmKUy4KLh~ zO6oHcPYp%Qt3U-Ac(L_!#sx%V>Im(OihlkyJ;5k-(&t;UHFlaWQ@Y-(hQ> z-o1O5%z#K9RPY1^m?jp}fek;+K&l3bjzZy-97pi}*C%=5IV)&OkOyKeWAEu{zFILg zrT2h%qx;J&Hn_4>il1Zo?eRI!h5s_Rd3cyS{AilG-|kk_eB>HeC=Wj#(aB@VF}j{Q zU@Z4%sw?G!#$keRbTW=;NMZ zqtva*sZh_(Mr|w-pynqOcuHZ_F9n>|xS^4#8B`%c&s$2^(xUYxTA>5p%dGnZ1 zZ$C|GRted5*Bpj;DDciX_*Y$O=;#O-UEJC%+Lu;S74ohL_5vrljMNTrT}{zB5{dW$ zMcOOpU6kk+ZdEyxd9CFYCbqws7|7)Ef8aN7nP;gTp5YO}Q;i0;mgtkc7s&Gp_0zR8 zz%aPfaO{}Q#g6D`-G4oh=U#S6u2Mgi4L-G*0+nMQ+`sROqcjV9We)UB@M4hECKf*F zh^Ha5gj8CYgaa@_BHa_sBIt+q$&bjvNNSQ?kv>+_uka1rdPF9_#CuEY;LSabT8aW{ zVq2ud)`a56@-!mv>oUq~K;@WBbP)}W?cH4{)qMfNNMd}4BWDmU0BgyO9lg(!M9|y&tU$+2Y0T4nN2IQKr!O z4=b=I!1l&6SUKwx5}`S>3xVhih(U#-gE}=h(fml9PSZsak&nS$EaL#bedf^kKgNkH zk%SEuWNz2^gKvKgitj}kuBa{1QD6yu&HvLE&SNY%pK~r+{dSNvHspyQXtml778upY zO3n~$0spb+toD3$30yjKVnXC(iSEdva$peMsLLjzsb>2y;{054pmt1qz|VmWe|^#} z1cWyryXTiIGB55(~HLrnpP06V4detTOKt-5e6tsXbG70JJef68* z^yQfVM;nanPW|i03MB16lyc#*MHg7T_my`qLclTrc620)@i9VPGlQaYYlMQnm}HThX$<;I>0f}Ip!W(to>IoNG{&7Muxe|V%D4ON$rDcbxZWz>hAM6K0#oy$J^0{V~$}CLasR;|;6?VfXMnpOy)knnx;F8X%f= z=x!^EwcKjpe!rz3HV;M1`BdIhjen`(&(B7#_<#4=u$o zJi$?>;02i!3WtFB!+SM7kK{s=rV!cDprUR#EHr>F+2K)(>_1$u1qbYX5opT?jCSps zK{(I59d=M!ja*TZ=wSBg>je=c@Y+e_bR1jgjbv*J7Pd(kxQ3)8$1!XfL9*hHa7W2i z9og6H*rxmAJ!T+nvmZfhoYUCnnwb^%7`dH~X4k^lqQpg|&>NLBae0NYXG|5U%NDO-+rTfgO5%BUe}CfX<|=Iu~%_;&===fF9) zH0KmD_8J3e@bq426W5^9x2eKVwww)_Bu!xQ&U^P<^*#yC^^6JpUSL#Jfxh(6{=S|M*01h(K=4L+G{NZVSHL}COO-J3LII(Ah z>N|Sk>MSGDz?Pvi+xdQmi{w9jKfF*#{wog5XM6sFH5_1tC(&n6C4))wEfP$k&o_ku z3>gj$E5s}w&lh$6AqWf8(dOEiREKZVUf)zP(Cjk52wvqEmIMb|Qr(-|L7uiS&Mf?L zsH?Gf5?9{R-1GgOy5~BJx~dS?^9}rouX5~iu;XaVfGqFL%;>^ut7A`!q zUN%Xx<~sTTiigWc|S-|%qEE=b>FB$EK0HfX@)FimKwaK zQ?#ZRI;h*YfqpyWjH42(PPw8({ncm)Es80W$%316ck@?j*SCRCkX(LUP>Xl{FZ-EK z86(o(&m&71@)43XP8Od~6{$8QF@0l4#e++d+EAruLS-oein8UmzPAU{zu%R+Yvc_! zVKo5l1D6cQl?z?SJEcwlAC!KHJg5S^vKlh2`%a!X*V~Rt^xt^IL9ES)YfwT8TM(B1tkk$6*%1}`N({c(+6%_dy zN7ffmRzeymy{4|Q-FJ|ua;@G}#xt73O|Bu|+Kb8wz_Uo9r-_FA3h7e$h!aq1$>@tLP}K%b`)-2V7 zBL=mf@x?{7E6KPfSCz!8$oRiL`br!i8uWI_-4>J*GBVy%;09t~!?@H6tjZJHZ@;6> zpaqwxuSOLKb|xeh!?tyPq0osXLVnk|+DR})^|eA!IB&J>D$iBEID|X*Ffmb?42^dt zIqm~1O?D6@K~=S`r2H(%(zni;kUDe^3R$w{prC4s-vBUdVuIOw<)=` z;)u@Mo3eK&>XRze3nyR7raa73B{4k_@d$IxMlPyx8BZYtgIrJUz(8bC zPwUK2Q<6+-A9C^uaR-zm0tD$Sb?zLf_WV+cAvWB%;xTC_*#Vnr!#?V`aX4xt&!(Aq zHGt{AkUOF2!mT@ZBx%MPc_|qke7n{Gddn;_E{8qP?-?2znaDz_NT!u!fn1&Is79X4 zuxxkCO{2v}1bJ>eAz___7!$)J#gKI+Zu zUT!_^eo^uyA{v=nnE`Yr3*0Yg(9_;WUQ-Q8#A#|C!PKbWMj#DGq-|sSP-d?Nti5Q= zQyZx#YtqS`53`}FX*-b|l*Z)2T=x|Gv#{l8(gOJ9tJ03t|AJ)Ck2HDDrwE?sUCi70 zITG6blB89nzzwW+K5F3!G{@?oq5V!;fgt#h4ODl=P+!L3uIQbQXQRe88V7=}7w9&~M6uMDoy!4)S;IM(54rMMlL0-VDU(QfU2%7#-4^ z*c zI3vFYn~(PGoqgdBuy3Q#;!tGlqR?CX;4{yO?ud+S5o)dQUpZvIk?z^|9L<{Bv9U|v zM?Rfph2Tt*espI-*8(*Vt9gZIoedndn$Ub~zVyv`uQWs9iEM^A?0}+6@lyaqA}7f= z5ldUN>DAE-yw7e5KZl&KXAi24ON6J}zpT4XQTsemMR^5<2pG>jryxAkI)2E0odpe< z;QF9pi%!)uKD2#~%e9cRaFw~HV6}tDrKC#$jJ5oWJeYN+Xu>~6(~P_kY3km_HTTB- zEgB9#7GOKmaQk>Zy}^FeoLM*ns>v|q!Pa}vE$@X~$(j1cc~pnlh`qwNcgFYvnZ+21 zMSf+Zs*ATSo=D*ZkCaSXZXxY*fOBCsTEwD9M~pi~@?^4ynb**PC-JbiYq1#FCsWt1 z8|T2ppQbMKr74jlh~&<0LNZ?$MR)0TkFIBt?$hsT3*I~c<46MiPt15FXgoKb{a~-eI;Hkom%MBlW_s6sb zK9xxVJ`u!$Shy=ynZ}?ZP5jPxvtmGsUrKu-61~%;aHg|{D7Es%;DP`6XBoKOQ^{2v zN84OFvtR~zU#Qp5*FZ`j8a!NL(mW??bC_o5?CtyUt@!Sz0zM7)h}v0n6qDaNP_~G| zH+D9Yeho#;P_DVOwTiSGjU@?kW&>=NrTyNCOcdb_+!2=W8ec&jPJ=ZW1yTaIa>`Dj zQBX$6ttLI^-@bc~fRET0nzTx8V(?DykY2d(A+G$s>Znw}gXERZojHlvHnxI&-GC*S z)>ULb59U-R2u{_+74oy>6ddIggwEBT$g@d#Fa7+0fY10qHiaWOz?I<5WQ*r62T z(^FgTFA4sEDF|6_0Y6-Weg5;qKY%s3l$j}`8HwYFS=o4>8JW+ZOj_sv*#}oZUr&1U zGt*VL28BdGXyu_TzEI@noOpoW?SSJw8zVWVVMbK=;+}-V6B2u$NNQL8wK8d2VF|q4 zImEsJdxiNbH60CI4Bogw5MI>Kl`AM1}uBXs?)pmc;6vZyl5{&d{? zVu(tnk?|1GO*e1bHd)(W{O57p@8?=H(md50tBzJ-B!by-pw~bCSvhYsb8i)Dc>3{= zA!vj3%|XAMjKA(bnZyyr1=K~oOrX_E3e|snJHrIbVS+WKg6&sRI{=;EfG_A|{_6>} z3^hXPwvUJ-ZD}o@au82l4X9=Rf)}H}n{Oq_44FHUOC-*zAD#g3>f?O^`xo$YbnajR z0Ku75q)>Jdy|_nd`vg~5uy8XB$SWwd3rJ?ak++Ze)LAa+3`rdPfru%)2)=7#3T;EA}FRD3c`BceH} zT+1({jbcrL?8~_W%CRVgHef{hX2~r8jt(?FSk!7L@;TDVb0`fXJ+5Il72_bMF%S+Q z1W+g~AC_G6h#-F|_WKD-sjx6j+NNLx{hu@r(T) zwSZt~iuk&{VcfXB!Z@XZmTeU#$iuOnPXF=jgx)c)6b$3ww9qi4wxoPdS*n^ZN^Lv~ zW2k~r1I_B=h(OGBMnj5^2K<~cKMfSISMhlp$(8Eg?1nn+Ms9dsrk+`{b5F&9_dR49 zAOcuyJLZ{>(iUfg?WPKZLkE=9*;F%-wJ`CSPNGb?6Fj1y3O6bOpbvoE+nXE9**|LO zIKIkr9+<{EZcKmJm_EhtF5p_waGZ$1))EvA%a8s(t^hnLG8U%AMkGO3l=S0i<un2O(bTnX1bYzVHv;-X-v^}o$e+m zEI!xOSv*QvvlZu>I)tuOq$r5o>UVXaKE@fdZrS;{lpLaULz+lzIP3ujz(3~6k(#78 zr|OMne2?6qj0rS{MyRl}pc~7vK1dl!64QFccL%`frDqn-*aPeYDh4&S^KsrcZ9)6+ zM*VlJyTUs7neMM**EGz1=s4xyp*jjzm(t$SQ3nua@2%;q%VrMDVoJ|^uIr2bp?8W` z%q-FVjUAp=P8DKo!%)2};UTRvaT6F@O{6fw)Z~)X4(G`&_g?*dgVM_PM2x46N;7_U zqE|`isM8scT{7_ms|fPY&;a3ZZ=wwQr3-2-lKGa%saL48 zZQ7XP)!$gqAH&4_%|>dk5Z`Y0$Gw=%&td<|`L#T)PG;umziB#fZ`fb&vygXzF#3P< zwffHmv2XSN+B-BKxYq|89CvYQ`Dl?7GXNP}Vdivpq&aU3D6f&+@z6#!D8gVU!vR5D0A+c zz_g-lBjS_PSoR~b--~bHlM3~4a+k`_Ve)>fhLv%o+#x&)6i)P3EX+EViCg!1f`50%VM+q{9;oU}Rwi!eLjF)?hS8PaNyBn>%0;0|hz)Cxz*&x7; zYZwkZqY4!7b9iqS$~duunwYFnMHbaGB^K5as2jig!kHl(hDo>3(YH)zuRTVKpRaN` zm=iSOt@xU{w-*Wr>gf{b9Q9aA+yChDCqT!*7@L4;UMqGJJA(#2&{WhaVzR&|wf<2r zyMC{HAqm@Wum!3yvRtPhMw)(Ta}}U)n$r3D%i}_}FVk_w(h?G)EdgrePuyv* z(1a+#&vtw=Pbr~w-CTkx$K9fO7GxbE{Lb((bP;Zmu8UmK3Cr7;bp!&c4$#p9F5FIU(KD z^a2^%94T3-FJ^JCz*G^daRWP=H%|Fprv9kp%|_$2yJH0O)Vyh&AiP$&fF3$nqLll8 zDrdWFGCI+)J|OQ_VB0`U&UK>!CvjR>&UVw6ge{({%C}wg9ABH7ocC~0<+2q)h3FN_ z5hR#M{U8*{mYyfrTW+Zz(vtJKH0%_x&r)(){0I#a->lMK4yi^*#gFDtvWjGu(0Q_T zM$f6>9%_9AP2=h(I4Ni-a$|W~N}*_+&ZwwGD~voN(E=qSbUf>`i_M;Af+JK7#?ynk z*X-{;AL*#b^pli;nCoyVS>rc9`SO-yUR~q+oa^7sr6$HeU)MRBi-DeGH43HE=mcU$ z#?w_@@kH6eS0jyIhNU%$$SoKcOd!(jhYufWn#Ac0FZYi8Rt)6S6b<6V=*iL86!MNA zS;kKDn1IVpe3f(8U&(}j4~`BKXO@}%Htu%g6nxVhQg8W;t& zfe4!j?RjMpejO7SxY!dS_8IE(N({E1AP*(fuE|;*Gwl%wX(X)|S}U2*kdetUV4@HA zd2qn?U>bWHhczXe9se%^cG+1Hkq*BXiU@wX{%rYS+9rS*hrG$EA;MpUg%~P%o zWPA5#6J?2Xb8T>&dXC=OWEzaVw{M&?fp=6I5=Q|Hzbu0K&>T?NUFCq9o)`#i0Oc)W zJlWqRIuo?b%L|4*Dj0&hI=QpccoxFj;GjhvBZ|`j2cB$(luwTMiQzMyIv#KeD%fQU zqje>C45J6%YFZQN9g%ifh}GOZ3OW3Sgn}>BeWe})Eiw806_Y}HKiot6gMBsPZjQ3t z`5?gS9pELDNgsl?%AY4hfh2kSWYN3jQd?J(<@)U3HFmQ;!e`EgJOLjx%>W{1!Dp*% zC%_@fL~zyw*T*k0g))~ATB6=q;(1W76tn07JMjq~bF=Wi@TQwmF(5Oyox=BatIhy8ox#hX3RU92kZy$IcO2BD;^)}W+ zWyGZgIOE`mzRv$nxjXwmebgKCO?9Q{z9k}m$g%&6+bqUbqim87`&aHZnfPCtRM~eD zhB-e&7cfoF$YCv+^%FS;{VJ{WY@ zmp4Ye9>LLvv$#ekG?~-I6s>*9q{$@`Dg-sD37O%<0lU$IA^b;w}n~dL&&yV zp^~bGcenMo>%P8(G5k8VT1li%y@$IA|WTjMykeZ+`n7W>S6Tb1K7{ zbJ92ZOA@(}n*GE!N@}19$CROiKSnGuD0?OnaVo9FdOi+9yMqIu=-akgupiKQbsIIt zcH#3#u}-gmmi?|nNWUgipNMqwh13s4j7Xa43N{uEKBuWodS$C|YO2zh2u-sZ9OE7} zE$pB$(-Y6e1B4bXMGCodN1@pD-k`X9(~wD-dpBb`GSOGF`+M4*tcZ02GPu#?6|iuo z1pD{jYX|yakK*J3zz_pp9G~p%a>R!zH1J^lAJt=v8CT>&MEV8|!xyo>ZWlUBXJ7_% zxXZk{T<(;Q*a6$gsYu^pNm7}i&TicnVV z#r_!|GsNxr?9Ir?-g{`UqcG;J&Af{ziF5{TL!ioI7wr6$vXU*E?K=mPi$s6&$3Prp z3Q_uf?B%_C2!ZK1LF8nj?GE3*UXo!n$AL&k`O;U<+6axOC*xN@h-;}8Omg^08}JoCE#4+KwjA8ow0zIE4>Ar7m24`LPDHj&{4@=4 zi`QH8oLd-9t90wZI+u;4no@>fsR~s2*O5fBOp;das{k1&;;n^3T>ydr-oFA-f*2lh zs&iNu#MDbMwrgqPHwlQ*Iu9_6z~*=PrIm)40jbxy-XBzevxs_oq`-#(wpMKC7xssI z#;k<1e{z@BB5u;`4}%(!6XK5Rpy#?(K02Mi2qFSv+Y|YL_(>YjE+1?zT?Wu*>adZ5 zXTT0#gbLGeA4~PdFz?ndM%m;&SXu#Jf^$?{q9;P^&dA`Ydji29_QF+0Eh3+Ox~1;37zy`I%(Kn^}lpPbL>f`8y<$IDHyw-*=7g| z&kEETP3~ptLuJ9d zwHloa)k<9flI~5SMkUmG&oKbwc6@xNPajWLywk#F0h5QBK5ZEj65$F!HZ_#d_v2Dd zA<(VZSd>h-Ge*lhpd}|oWCN+8G)bMibMt{TmneV~#0wUYAZ-vSU>D65MezSfNcujNHv~ z0(t5A$Eg(xlhb_qXR^cs*g1*l^K>5BwJT`>pezNWc{4_sP^%kichaSaj`M!fmpAB% zjhYGFd{v-TR8CPh`x!6Yx+i_){?WLvRI6o@q?~$JsD4ZnX2w5W>5L6a3`^oYP7gFMc0SyhB{RGbzF=F14KPPDK!a^O@<;hY5ic?i2Fbt8~ZX>h}XLX-5 zdv!7%b8TibdCS2J;SPj{Cn%eCO-uZv!rpG z3I@i%m6l%L`T9)Ri(B)R#f&3vm(V_Ylw)u5$ScS1mft6y89086#ZYmcW1G$DK z{}7h2cJt=9GmxcTQ5#6u(^%44Jg&MDIaN2b@WRB@hKJ2CY>Jo`FP{9p^W^UyMZ38K)?(eli2I$&U?P; zj0JJu@Hnt)WCq*^vMO*1m)h>cRJyHkk{Vm8dBBnaI@ zvZDI)=hQFf_-M&-|6QI#a_oJfD zLJz16YZ^1`HDU*0Bey|ns7g>UnDSgGuP`Bf3IVuwP*8LAQ28qCq-Um%0LNqtVENl1 z_=0WvO_hxrGd7!6rL)r;hQXLao|YUk9(D*>d1@3-nK*N;04MZ8R8$_1XC5{otL=ChvzxYsv-wyCT3C7B9RalQQ zQW_f-9)1cwY?+l$k5)r`l~c!aYQ^&LS89^c2{oY!4!;GSN5`!S-~Hczt3+Z*I43#9 z&>X}3Huf3&@!V*ipf|W8n#fHo%k=h;mZhQtiq5NB>7j$3``1G+uVpXB-9wVhAV2hJ zZ7_DrA^{-IO}nMNk?yPQLDfPKp^1bj2(ln8ZePaJKkpOavzJHBJC8VOL|vFXb!y>h zuQ{UQj}+m=B(givN(-ZmgX(y)jz{Vf81Ky-FfcPT?mV+NOh;&EaER`6UlxaFPt-L!S7-uqDG$v|(1^cssxw@&vhc-R20ci;>-_g7y!UB{0zDI7xOmU+ zzfA+_miWqUo|MO&6ERH!~wZ_Dy*2e zJzw1DA8tJypRO&n+(P&+`9}S1ALXy@4u5~+68glAs1S< z7_=4=%B%4@Ppi#j%Cl(zvMUHrM0vwe`fl$iBbP;(9}m3)$uz)onFcdKw;&1DBljts z%jA)_eU|^+^<3^O8Zd|d>kDo_g35{o7-UXNYHE&<7!6=s|7%T7aaVDi^{7--CDULD zGZyB!Ks*DZdA9lf;rx}8iO5SG05Y#p2GZ|x+Gox!?3>~VuJ99~#^5w{FAo_1*O(n- zT|Z-RjZt1p@FD3tXe4>gs6<$N{Gw<^C>#o@C(Bi=RqaNJZ{Xt)|ZUbNBNTMFcl1Sk#}i5!u;@D?L_UI z+gCDfhgB<}PQg$M$a^bL8{*MfHNk|UcX&KtiT$Pj4CW3>UNogRvp4@OZ3V2e>V{^? z8!xf@;gx1ClB^v;Wth`>pzb|dVQEp4^*qw9Zca`;sg}sS_#K7kMDp4@N~%1_qM}0M zc06JJ#nTr1QQZq(`8n&O>Z|#>jjGf#tU)EWHw_JX^{FeAT=_F(+r2X*4LE0B+$N09 zB8-j-Qc^b-;AHB_;z3s=`&w8_p=u1dE_Xo0$)_3s#=f*%l|sNQ&WX1kv{WV(|En@m zB8$TtgBQH)UYU=HsKBv+ePw{dvO7kjacMcemqoy?u9`|T2Z+0Ha%KN$xTNLL7sTR{ zRJubm+??X+GI9q~xw`0IF>%N!sm*PqCuc|EU0`>oBfL?G9R_GR+)xbHW=z|PJ0jFm z49SB!xD_ZnXCM7Y3l&%BUeJTqKT&dR#GD+Aw!p%tme%vCwM%aNeGZ*knfk6&fPiSu z2`B2=legFZxSVj*`s(BdQJg5? zH;lDC?;2G7fTGT98tNDO^nliLu z8P(^H&f5=s^;^@}wS+SQu`-?nF2saSc1LGwBLTTo4rww(a7K znu0n_>0crwIAC==%-?D}7iUicg4jb);s}4b&=n4U1HS~zKe>6vf58H@&g2;#5#V8% zm>wiPh$3)?Xd{tn=qad1O@&S#TAR5UAO6Zm-mLX+yVMn!DPNF{W#bHAfb2S=V23EA)}TQ;D86aUmrN-1mLR1W z*xad8gQdj%3+{a$&zJn08QrD+Wtnk)-@o;&f1C0zys9vK(3e-z)IAXYO*zp5L6!r9^WzM!= zeqMd}Zm-^b+u!?Bs-W5+y=r!0eM~}yR)zQL%DZElJ?b5GsvGU)?nE_}SDpS(DEwQ9Yh;=5@G-%;rHZIzihrk(L$@o!!N0RHuyS| z`3LhOZJl4MZ$Wqh_V=`gk9&0w0)ix8SqP#|UjkB)FFgPT(G=(>D_FzDgLJb6H-2qp zq$aaJa<=_oadTPsHU^dSZsJZ6#N`<`y)_oAgCY2TyE&^{7Vw5tprnr#GcdxB^3AA{ zKt(Q!6$JrgNy68ZDZP62ngUrt62k#KT>AT}Z|~W8)QFAm+Br9{1xuyE@<7PL#P@1y zRAT4^A&F5s6&}eXd)^HBeFsV`4}h&rR7a63FDPDq(#4NuBIM=+LjgV2JS-0CQUz*l9W9cT;XgR^W;Ei^0i|E_teyO!lvOH3du;S^d$ZI zvbKt;8|$k;0B?A=_}hyL{V(M0St&dew=FR3RH`WQ!t9S75Mo);1fbdhK&d?e#&e;P z7L`A+jAv;TqR~4JtT-iQjsh0|7&)gJ>qflO4rK%DoG-jg^-)!2up3IFda_V9T z8OgikppCwr-2*M=%asvW@9|ixCU6bbH_G1Lydw-M_~g;KXtNHBDlL>?qPjy_qo#R1 zdVFjVPD6qvrmzEI#2#w{pwIKQtO0~(W=xn%QR9H|>#zo?eLE();S(WEL`LMB0f`}I zfkV_$5o_v1P&D#h+`0_Az!R59G)UAfdQJTNgI-k*VUv(w%uoSvcqwH1rtfiTUh>N? zzpye6y++Xk+MUMca&y6Yaa$)+rDXuIaxU7mgcKLYfdzF?YN*#Ia0?=dQy|Ma!L$r3 z&lGLc>5*kY$VK;&rKk*KaK^1o%enQ?$=k0}^Ry}438^PaEI3=kFK=x+U9Lh{HO4dD zMxs*doWEZft2&M#EEau&%m5M=L%Jas^~W4D8@z7Hfq+^wr{pw>)e)#U#Bcq>Fneq2 zTr2#)hQ&zA57A%?b-V2eW=?NM8oRLR>!M8oP6&|~pGuxbYTq3oaK-2oY|0P7>vkJ) z$LkF#f#@m6iyCu8Yf8M)eUa1Jeq&|Dw{u2t1Kc(xmW-aDTs#F8BhTHqVd2y;Y3sY6 z_%5LA^8DpOROcXU+N^)6LiQQOBdP3blFVK*P-WYESZ=;kSLEN*jz%7AHhP;iOvMrv zmu?7LC8yKO%W7I=a>E8Z@Ifki5-$}SMHm1#%WFvzFWvkxq^~>D!J3W1`6aZlJcqJ; zrDrPOYj=P~?qSEtjjiQ+x|e-8>O?(@WsEleLfk;5PX%g#(*UiyUWrBc0AQM>g%t+? zf@32S+zghLRN8MX&WCl&0ZffSrXtAk9toCgQ+W25T4nw#Jq2Rxu(OzgI=Rea0=fm} zIK{75qAx?GofF5G)!qONouDa`WbzMy0I&3UfsRZ~U3#=n2Ja;fGpcy2BU**|@QR#? zp2CHBzPd|xb?D{>48`~$+I5o$T>!iFZ+@KP=3zVBhi}>r0#Hvo;s~xKPC~anA0T}b z6WYO@2(=BHhyje<0Wh2?4vA%_ZQyzU$ouH^*HMVq=GMvo2QTTMHerVH6D6{L^9BsH z3t%0N-LcPH4s|TLa*0H6pBEl#*_$VuIFO@_8r+&~Ysc`!Lb>j6M#TkXm}shCnz)x= z4?`vDaZ!TNU37KxQ5>38vJAilpIee&lg+Q;QEcJ>=`OI5-CuYR#02KjkSeh>H!eYa z-i#mofyNCTXSVzr(N|#IN zNsv11n^z$SuBWk_r6?nUNW`$1NcWmQ((c}c5L3@$j;oyJRwc#Y;I}wgW?kzxKvPxG zdOjM6>~;6F8^8N#>Um5?mrBY3&Oa@2X;pCfQrZ&f5tK`GCW`s<)*5fV*AA`eMH?Ck zw!qeQNW;T>G`SGhoIqZAm{~ICUdf#B3y*N__AI98(SLcvsQwzh;_FkRP1R7RYUJfoBs1^Z>TCu zJuj1FluQq&4jAuE6@0Ixz(aGw-`173cJ^Jg*F{A~Z-+{cN)@$uy8Y`-IO0t_gaowH ztZOpB2hk5TbpQ^FBTJJ*Oea4MSq@yab=2gG^|S4SJMaU+CghW$0=YmI<9sGcbk)r{ z!?H1hsGCK7r=e9q5RqGazndkeNC>z9z9#*S3&&|JIM?TP3D6nWC~cF?aRxh^5~1O z)09+57=}V^1$Sn!y{vV7KW9QE8^m0F`jWDRE&7%;r$?BfopRAnFuyCnV&COvNL*#K>6n5ch zIEX54=r{6wEe9Iw?7ad7jV(hUn3uJxVx~fLPx18y;nO`8NSSZ&fmp6lMTC^_#`<`9;Ysm_{7`;eC62pW^y*Z zU2|xTbyo!)uanwtQ!j=ec$nNc;bJ%hT%-C>>BeL}wlXrStbkxFSU2+9D>+{rsvFpT zw;WMWUHXnab2k0qRUCq4r*x0L{}2Q{!K=lZ@k3I*0Mv*mu^Q!8@FA-9PITNB8ye8K z6_Xba`6y8UZX%>5xo)exWGk510S&;6wXVBX+TY2VHnrZhc^{~4lj**WteD@qhd zT-0)lu%YZ0X>B~Vf}Ln`oC~d~gRc(c`(DSDOPBUV$0w=Q{+SuVGKJcSpU_4FsC<*N zD>UchDj+o9%}3*#7bOf#*Rot7gV$2MZK{@O ziSdmW8cWHQqEIvrvmsTkkSt;2^V0R38(?imRESryMtw)>Zu7-^|zNyEm%~O$I-uJPgGu3To1CKJ4DvqhR&R;Gg9Z z|K5!G!ey50Zli`ni300+Kxw)-kl3O1>EU3WjF%F>eR+cC7)~4?RTPZp8_|dwMpWzP5IoBmqE6! zn1)RKM8yCw89aj&uS>m(+w4>u70!|Zg;$U%xHw?FyE2-^nym=w_wDV(l>Z`}ng+h$ zO8tckQ_nYDIe-{#Xd0Dhk(h4NtT$)68I%jOwmBeU^K35rB7K77sOi~W$fB-eIz zVpKEWpsI2&D23-U@#{#+1pp9;zT@TB6Pe^UH**Isg}yA)eTtTs}x zhc6>gmuPkofwb+S?OUH+cynSIc0RE}k|U(e6|0Ch1=K8`q&rZLzWs4?#Yxy5`#VwY zL#vp!qwwl`+!lhJmZo^WF51RW61q8lqyi1f`Yv%q{V0!3__P9iVued3Rd~v22r@F5 z;83K3bXk_Bm%evYKR8^B8`{3pJ6e%MJQQZ%C*K7@)#$XB(r>j zmw3JUn*BP|kx0f3f&f$PJi-uigP|MbTRt}eCBDnmUeR|DIp>?{)-N-ekHUo*o{Q4b zwM2=U-x&)|`u8Z;+C#E-en}Vt7gOwem7W!iWlp**`ej(dE#}3BIAhi{KmqE}YzvZA z@c3d`QOz{w?1my_;jI2udRnQPQL$`;ZZt`pSIE#dAgZot zJL<|k>c#40cvSDT4WW}t?+k{{=aC=;xuw*7Jew<7jd;lT$b^P5z#Yyi!6VORh>i-_ zjyYz!fCLfjrM~r@<%w;|U$6iRu4`jbi0RWKrPB6{rHTkB7$%_WX7{9P8A7&?my>gN zEu>^CA($K+1?IBTL9AZ6%CJz{1oNqrGHmdf)m^kD02=Pb40_!iD3i|uyvy&Ygi0WZ ze?&!CIhN9}vP08y5m9IpJd1kI6ZQJjqK35)u!^2%cj*@v`GL1~!Sb69tkHD`E`xro zE2D-pl7igGXzLzEQDlW{g>tYMS;Zs^9Kc$5?8=wAgYpcb>lV|e&D0ow3qt)UjD>!g z$Mj;*AY350`*xH3x9?NWbO<&c3Q~(H;bg414Vbk412XmngppIlsV_L{M#wU)knuB0 zX82E}msrMOMR?Wa0>`3-zM5BWCtb{eky{^#ku~>$Sd5v8hT96vi2}q_>ACotb~hzW^yr7R^UG`rK!E1IFTiGQ;a-$=xa-Ipq9sKWMIWL zYUZN{0aV?!B(rbFM@ZQ!E-RM8L|l#ftIXf#6^hMgDRM}A2Ct+?m!kjL5)Ti}R1Lyp zDVhUE3gtIjC1G-|d$BoLQ5k_;Fq{OwM=JvHa;fQ>N2|<7wbC%ZQG#ZqZ!8HyKpGYo z+Cblx6+nu^2Rr^N*E=bUmFqwX8HT|XI-pZ9i-NZR5~-a}1U~4UsyGY|A6H2&8fjcR zOAMRgR{b`D;K zU}ZUSV9h7XFQ$_s^F>5~&Jjq<RvHs;F}TYh){ z4+L|M|6p%^znPY?`aUw>=ghaO$NBqeY8j62`%KF?4E(+Ww+zJhv#DhqzMtAHQDe5a(~*Ru(=-k?GE!C@q|zKLSMHYff1i(d7;lP?&?B=B;&eSBTZyU!y#{k zu>9i|rwlf1*wBC`>_H$w;vt6a7a7@j!#5Q82rB7&!6%9Bz$N7;-Y$n~zZSSCkq*+| zex0+wm;uq7T@_ z-nIYsfQuK0jfwpHj4BVN5aoFK>{*WwA3l`BL}O&D4#+-0b%OJ(p-@LH6iRB1$d0lJ zy?r|#sK?#_UaWi&EG;c<1(3o6G<@^@4(aT_b?X*cZ=}`3>-Y+BZ|5)_^Q_5FCkw#e zs_|-F-T`G3(CZ1K%#D(qsQQ!f+$oSIlp!W@gpVxLQdHGaZPkZ=!2+no!@=t(Li@bn zxktzNDUiCde?QxJKdlA4G_3O=MV2eF^WY(3Xr_10Qhmjw(8rg7$Q^uTv75;2_#q%}7oXV@kmu8&e2V@{Ke| ziaVs>^e~yC@KjkDu2n%_W=xRc$&P>Y19d8M-9aM*1A}o#BoJb+K5{+0FH*bJlun&J z(!@;NG$Nduh=QVw1c+64wNf$Ri0bK9TpPI#93*NqG0=~!`^P8D74;%Ub~xXx=2 z%EANj*3EAE1Y#$-Da|vxoxNqY*S54}+V+FLeRgNRy+YqQceuXA0@z}>y?~lEkd=#C zZbzLL@L$Gg1w-{VBiL;I?W)fqyF1JDNrLS<+T4envOj3My1KHVKBf@kd>}3^&Z11i zhzgxFhxSeatx|v7cnR>=89R*iUJ{UYR~#5~SBX%Mt0kVGKv03_i7h;Gc+-nBU-TsQ zm6p@5J@Bnmq`7V54I{l3?Qb=|$jInxY+pY0w#@)HGUs3(ade&;{ug~?W6|Gg5;INx zF4wa8x^*sKLG|__i|gtwOJD=X!6W9r3T4z^M%~ngdeiO-asptNydczp{3X!fwrVs( znv#-Oi?eKQa9L8_X_7Z+H>1adm)w+(k`SVZdCHAQY+Qy_wjyc%qz@r?8a_SoziSO# z^X>}L)FxWy8olsdgQJUH8xbE9VCS&lg*RU}Iexp%ctBh&y|x;7z4E^mnr@_Kg58$~ zVDg8j_20fbLGC)na=I2)%Q3@bgp*tU{{459jFI@N=_*oVKT8qdhpE!b#{)dc z;o&2-tFfz&T4Ol@ZemwA>sVypQHM6~)u?LH{(zgX(GY>LM=!O-qAU+m2+16pXGWI+ z$ktRnlwj)#KM9k4Q?j$=fTl0qveMXC0nAF}HPtwII~S6J2r$XXo8g9x0`AuW0`uGB zT!8-KpvKrKdC~r({%0d2wZT2eeQzln07;|{^4rf8MQiu}_CcHju-v*Wg)G)0uLc-C{XL1jJFUK(wGy9IY=_tYY$6@;^h}UC}6{W z9Z_OaO%i90jVR~+MmjQLr~0j0;@TgZdE+2*sdXv@MRUxyW}L2_3O(AqnpIXx$`&X{ zK_QLDb92BQJO|MKv77+|22kc`3J&B;6*$o8does*0-5p76RY1Dleu?Nbh)eLvAb0J zQT8&pYi#)vNMPQX8U%YFFg04M0+5&!H|@yE0v6Fm^E5zW)KI-pB8k*Hg>YpvfJldM zo?rWz0P&;B-^v!euLaX)_%@}Sfze{Q_kJc&7=a=6d6Pt77ZX*?!N7XNmUnT*%0r)q;9~7$msDuyaL+( z0aP+u<}!U{u9it?RK9xkqx0(@Nu$1BOCxCYf>T?Xuc)c2_Da$P<`p}|@XD@x{h!tQ zf41@8Gi%a_obmCY;h=}m>&iRH z5kW~D>{a}4Noa{W|Gh9POGdbB2Ds(!3ZEaB78ezfi1-xo$XkztQkxMMzV;qmw?r&G zOmvc_w>0#93HG^KqS0f*#EH`uE?oHD4!cwKd*3oRKs8}MI2q+@4`_4xTi<#QLAZLa zy1kIn(;h^WH5HLk!m&jB_kxKcSvj`=M+-rH2glW5_^JVzXos@NyW4GZWovTo=CL+K zF4bx{C+^!$$X$V3p}(gle!SHtPOQpEo;8hU26xuTTg~7WGc#D3HDAYZnBaV~HdhdK z?6mAEoY@!!9*X$C9~ao|8U%RMyALCUlqYWQKXevyDzM+lByHGWcd;TcuFR!|U%$>E)FD~T#BG>k@ef;#54~Dw-mm2&$t>WyFi<&?9?D}!dLFWrfyHfoN zW=D;0PE06i_OY?_ReZfC)TqpJw@g;7f*sJp;YO!H)c5-1<+{l}5;IzF8_uMpj?Nv* zp7aoC+6_o-^pj9GH@6z7SWP-FsbF<^jMUiYVW6{|+Z>6NJ*@h&Dy=LggvIME+7Z6* zWrVSZOFz@Y8 z!ou4-?Ckt5T{629IIaY1DzH~T`UoKxdBN))7wo$3%?VpLIydmzZLz30Fr(o{8#ZmC z1=m#TVC9{M_7OcRx9z$9g=E{}>$mfO_OJI9Sz1`QRaI3zD?FNvO(bxIqpYp9wKc*` zlfD*h1=aq(m=1;?J=zFLr^$%Qw8u<&Tu{+|*X!o$4theDZ2`}2|LxdRTR0(Xx_0}R z@QTE{q1&Tx=9ZE%j^+Ph%Lf8Qp|0AkD0`YJP;z93ytih23pR6Ib3+qDGO#;GIq1}C zLA{z`eRHit^E^R#kq5@jg3dbP#Q;{;*LzqsHukkp<3I3B(g!eKcNd4(9r|nhBF}~I zeg6L4MyE@9UgNEenZMo9Idwa{(8rF1@^GW#l9Gd9FG$zSk=PX0<2>1B0SeXb;?N(L zV#n$OrrW4&Ug~UU=madFPSwxz8b>7deV5e;&c;E=-Uf&&5fA5x+Dhzs?%0)!h&D91 z)AUHu_n70}91ne5=7M~##k z(A)E^U*S}ds5V=AG-y97?&v`3_1W5Pi!X#o+B8|m^vsyBH%IPQ;_z50DIa#DbK>6)Qmfv%X%w8gU&$omLXs0+c<1y>b3A@4 zYB)=g+~2dq5t)!pI{UQo`wuLR;GnvYC=t64RFE30>O4#8BX)z|UY0;iAs)F{=jzp6 zovQ)BRfkqzr|M(1j>nUd8vc-YHODZKrC;H!8EI5jTIvQK(XsJ%DB|Gdz&An;^6?iE z0#2Z!(>oy0DC}lP=JDLXXOeH%Trf4s^g5`(|ck$rA6|sha+hi+z`G zQZY+9h+xSv9Ve+Q%T)e4)i5_1VdM*%UY+H9iL0Hd!|NLuRi9JVCqS2ZCl>M5BqIo> ze8x|>4vYfSv2FNk26sU;x(a$C*Ec7Fx@=q-)=lf99`;7v)MiV#U_MPxH#llcx3UNI zi!@DPsL-aaR$>UFM)9i%aIe`E#PAAOYX7S$mY~1iuOu><$<_;xHMI~6G`4(y*v>pY? z0l1}Io|1t+vc1~Y|JDut9xV$PYP;;^mHNkyte7lEAi*T{bY z!M0Cn*xM7!^Pq@%5IMU2?c_!X^P3`AEk{@{Q#uJ7dmjEI`d}^brQ)TfM}moyYC8KRG7Wa-mT(w(f<-UdUG={PaxBqD|^<3T+74`q<9c*rCc}N6}_1Ri3e#wOkdGT`d3oZE=)NLejL3MaO2fDoxzqP*2_X}`*HL&H24 zd+`s8i{rn!RY5p25A*Jq0obx=5D`m9Q(yZ}GhgQ-J{v^KQp!?v(6&SokPahLX3u_d zCi&qT+~gXTi#Y+U%8>iyVH(JNzJ{%aDjD2;cIik2YtC^`wX$V|$11S;pafG1Qs)av z8ZbsA@oC(aHxGX+eE!VIFB@f)%g;5iU9;*%Wrf+^5*HFL#a&1U_JhDTJc@bVmZo+x zMn9o!zZF74caK%u?QGp8J`qM;+q)^1CjkRD4(ZFs<5er%hVm`E?iX*M?W zZHydYCQ++NQRjt`wDhNVI@#$~I1p)a*kRi|6wk6z>U^4$Gl1Ga$1Oe5Y1uGeyK)gl zfhg2uzG>5dkNv<@o=+v3yW!z9{Ux{R#O8$(Z?PyRrt`!z0j~Wgj3D)ya<3%jqJo)E zx-dvmgGrp=*^W?j6r_v-S+Ge;N}~PJIe-6=^Rz3U*D&o&txrNWgX4L)GZr7z0R*067_w z6eHn(uyOPqiYR^=-$4znbMiZ=p=BVxgBn`K;XA0Ibzyu5HM9)G_p_;WLVU+XwhY8~ zTx82Q{J(?{dkwEfe!&8WKk$A2e4jrpBk+GTf4bt&* zUSaX1@tllR&64RS>;F+V+^pKGq9ilfEKaRnODp-1 zfsW%LQLxZa|KAQ6e<}T&AOCBwf9JD5cZ&Ju?ctB^KebyW`8PB6{qQeCjv-T|`bz#k zJ&sO91E!% zg&JGv&rz9g=&2u_O%@96od;dHdR4R3>D!G(&mjaNu#oLvS~N~j+WGjmZvQ;9_)iUg z{$Fh=>sAy=31=?6L-ifLn#FB&DM<=F#$$XSU{0-|#?!5V_)Ovwd(3Go9Fye}^o@Y% z+B`UypP^UBBcf~Jn{(sxLKfmn? zx^d=Lh@nNlxS)e$)7fqgm)oWa!rO-OWiIE&$7m#JgPRINCX(Dz?f|6C(1FxhP+pF-HSkW@vMNx>{+@AKwI`mVMdZsb5ytXC=F>3 z5X~;=t$U=8-_A4)fKV|p_kd*Yhlo`?y~2U+7W+d0SqZO{Nl)>2<~RdreaAixSte{> zk3&D6t(9jNmesZwj;#!f#sc_cppVXyLDA0u4`ou6pAAh@z;bMTttb&kviz8 z3dP~xLnE8f_1gzOz2jTk3$J2v7MWmwrYkOcKBHFLRV7duGW^=FeKi0a%zt5EJUZ9C za>#TkXVnRps`tpX6P_(zzFZcxkbQ)B_fcLc$7Wm!V0UE|n(!GQ?!=|1BC)M-%~5q! zbhB?G%(`ThD~nNlwSr^V?k0Ll#BMayM>pFY^{%}#-(iGUO$~z1uZKKoHalzAf=MoDckA_7}(Cte2=|431v_MCnX68+|&}VadJUO!nTl521j#jqf(8 zROulB6ndJ(#n1va8*uV+fVtIX_EQ{+XIF~c;)L_<0tqp3Kp(7lK7QU58W-o&B@pfG zU~`+tYQh;+!)Mqr&BOSpo+%_u)D;IFx_kHT&fJ9t1~SIYb?G$DZ5K)W!hO-$tA!0l;wVaJa0(u3fNheK6-Hwf8h_O6928 zMs-!Erb4GUbY^APLNDkC3^&z2A1pKT?hPt~`PFCwQuOYL7l(88`ql+x1ux{O(TTf&A4$$1X?|teenbm9YYE_jJ%W>c@&^LG& zH~^0=^+#FmfXREh(EoW&sVtD44XL_~3yrouovM-Ca2ppmrMYcAFv34u8{_*-fLwVB z1KIY8T?ADHEEYv0S&Y4rW9{2^kxoQhLszlS=dQx58nQPi(S6j{4mT7JxWvmhg=u@a zHh!}xlg89I|JqJeztSEElgHUAK#%e*(%7V_=1{XbR*8E>HXi4JZgYihJe#0+K8w*?v-lkR_!pKs1LdCVOK6KY+CDInb{vHLc;l z5VSG#W(}S$wIgu@3yet!VF z&{yI$#^AP9EfZfyS`89UF-QnLI6w1f9&v^sgH5POhWz^^+L6Z^H#{(oMbDQ~gGt%O zoJvifPMQK|Mps??_$C3byQ&`o8NO(A_n3aYBiA=soK=oeDvLb|y z#LAREJ>;lrEuz;i{3pn4m4 zUiXWjJ;ahqMe>bUfZhLK#Y&)F4pN$v-EyG)A7_VS=aPHgBnBJ{J zJcD!-Iqe;v|0>2W`+z0T<@-vn>h26rpG2WcV| zJ9YPQ_B9`y>kB~%98tMcdJuNckmG-2EzWpC{Y9*-eaiN)J8K+JsTDh4W5cI6c!C2Y z-}e(<&xtrqG#rB$ax5R8d$q!`%~(Ni@J2XdHB}lnPq0p=6Uh8M<-i;cEC8k!hza4`4u>A;}mVdL4y zjSO4<3it6z;ZZo>;s7Z)9Y)pmahACe(?mmYM_Z2-^Nu39tMvb!0`)uq1G>SEi11m} zM=KUyn&+yLq@Mp*F%p;qfH3>bEagG^>?3_fXbc3WkP($iuEYMhg?NnO1LEWRV+xIV z>_8TibyHjpAdr`zRzJjR8t}G`uSpqo5N9pCjZpyJ8?P>{g_Y6M)uIvU;8{^Ab9^-^ zI>@22hE($qSM807EeH!{T=Lnmp12?nyQX~ICO`dU&RAH6w@eU93c2%9IT<*gu)K{x z*Zx&Z9ppl6U~_jAg2ds6lSh&IyXmIDhs@ofhzshOwrpI#0`Fr~PzTsPB};96l|@Kr z8hNL>;yWch$D^1I;V?@In^}eoX@e1XARcyG#6rOfHe$J9`%Td)cbWetI~c&7h~$$@ zUmWpEgfB8OJ)b_%$PROa1a|K?xkiOL!0)sRlfkD38n=EJ_}1>2)`{7{*c1Na^YV1l zps7iL54MipZ%V1YY3+dEg|=2Zvl-r`ENHpZQt}QGD%*7E`es`Iw;qGD$f$&PKWsqm zdujD!9SLFStN#9-x7c7}P%PHN4ywL}?qY^U|5@Uosn-)^v?}TTSFe83G>DQCBK#L1 z<#WzwHSFQvIIC3B_ku=|QopyGf=^f!c(FTkyWut#v_4T^+IJCESm1-9E!=hsx3W*E zgfnkDXWl2e^dwYTCu`q6Q|U-32b??;jzPpSx2sntdEc~;?$dITX&7Q3DX0T%zw-{K0B3WUh_{PW5N4!;H7kyb2rMP28=AOJfgThGX2ofv z0X6FhOR%Rb8)Cn01YMsDC#{Gy~A4K}b!dN}N;CQO)M>pdEiVNj>~+=qK{`;W!% zQXV`7uP_~WjO@(yEp8x#<+CGZH#f)Vh9}Vn$-1GU{DZTT_l~bd86b{(29;B}?E_|f z4jhB2o_z#!7wmm{Bk;?DsP!8*P&V7cZVYHYVkb6x?7<7(RZnxk7I$V1hu!=P+!^A* zI~rf@1;ItF`)Y)CXXE{sztQ4iRX+K7=O#dc_5YQ-|F z!;jw4AB53|apKKz!7q=~VG`mM+|~{bPyf6szn>9krQGaQFsUn-MYk- zhKWyoMwHSa2;34XVaYco{ErWvG$(^`;)iXBi>#yY(UCqsob!bFful91QeDvN=kAA` zlC$+ajr7Qr^ROeH8TGIE~hQ-4lkP|9+BSpk^1W~9cP^6;%*ZO<0Fq^ zoeX^L9dP@ z9d@OVO<5DkT%=bWCd6QHLBqBq=*h$UbAgI)dT~QDCEqy>K^g8zBZWVkCklERM{uWC zFr0d|wMjNnJwZHwl)Z4piUD+O@hd%y`+BnYTI*DN+cFg~pUncW{Ja#G1c+afsxA)a z{j-%LRe3;gzg%QsU{+d2wOE)XS6>c|V(%XVv6~aCJOa|Xt z6Fnno(D^(qZEa~iRhp@F>{oV_qq4B1I<6iI)Y)b@dIG8o0`x8+SDETDI9(e@=g7x$ zg5K**nKy^hDoh=*g=a|ud_!owLlY0NWkj|vb`Cmt9{;JNy#iVSgD;URAG zsHaaTb(@c7Gpaaop;wt}HEuyD`%Szv7>O?92zh!g;c&4}o&9XATdiK7PUjO@8wW-7 z-q_7N>fPkE`!g%Zz-`&`ows~ZD16Bn;4(O|7R^-j?nVCx961voMRL>Cm{pm(T^Gaq zaSTty_K$mK^eW!vJ$Sm?>HwJ$OMeg^&j*~CjDG#ai;stuQC%GfeVKJ5gfntT@tn6X zRC%UuU$dFieIFQlCOFV&X1cuX`IXTx0;0I8#vl6>slSomrz4I`l+x8M%InzQQL?UC z)j=?y#rT)+$HNYLWj+`Zqn}N|)D>?6Gq4FfU|O4QWIdNWacg5l&?Z2)6P7qE(im&( zZQ%1V*Wb9tDp)>D(Sv{LV^!QLP0a>eN$h1*Hz0$XctO@X~N;t!*F}>w?@6=!JQF0xDwHhFmuW;iCU7Dz7@qPib6~|-2to{5z3BE8Yt)mf8CTlb18_9Jw&5A2cO`{ zvNL%wpW*0BJHO|AhL%YRF3iFt%egr~zW!qNaGN7a>wZYg+IdR}O2!D95{*Qlh*`DA z18DOBO7Q?GA=DZW+hU0=2J)bf?$~|U5zLvendRT^`SM_&oD7Qsb5|S$7=bmn`aQPb zf;vP^2UI%>3%cTZdKyQur>52d7AsH3CPp(3r1*m;+I!tq5w{TA8MTr6voJ(0hlzZW zPJKy2C8|Cb&Q!yjW{kCVy1gJQqqSw2BQ*X8&Be*u=F5<$sDi$yK*@SPocY!w3O+y$ z1DWWeUh8g(zo6n|UF*vg4~!PX_eWVf0B?@07^NnUV$i=wziY&uOxpZPuV4r1^pX#d zuMJwf6?i-G0Q!%wb|_HsbqTXBoVI37d2_k}&v2%lEe~PvWXEyD?1zmMN~mgJw%}MG z3QBP}yHAD1cbJ5zo9T>oB+mA!o)YuZs?QjszI0tm5{*zpo_q&98b6TUrh1k%bD%0- zARoOjgb57y+Bd(0t&II<+x<#bUbr*t%x7Yz5%Iwi@7 zu0s1IAFTp{y82AKXA8QdFc9-$qRq(r!<=ObqI zsAsH4lh0XAqB3rLj-FX|ev7`YL#-7sLhvXiUFVn571)gm>OjBkyhRzCB{S(lH4%^a zsh;fxB^j=BIjr-6x{Q^uE@EL8q*Cn)g$&2qC&p|=9Z+31k#9>Ou`*J>6Q|s1adN^M z)|voi2uaY7V_2j$sSOBV*OYnyBz`ovqYyF*`&^1ff^3|pF52x$&AX@~%9Ohs)_jWDS!s=I+z&oasIHzC#PWbR_;aNdNkS!tOA!ZK+7KIXx+fH>U7zczdWFfY;YEbE zIw)722rJw_GC=8>D%SjA9FcDs%1T!h`3J^PDaJCQd|E*ix&P;;9>|-lP`BXlunm1N zs^W6V15TLF;!xoJgmj~x@DR~@%`JgD*4!=WbJcQsb?7Fq^?C;rc2s889SO%_UI;+` zA+S@{mLfKtZG@LF)$>O|NsaH+2nXny-&Z1cB}a+nW{>*1st>XUWR%_ThGo{>+{4x3 z`S^XLK6hGkdGYCa7G{VRNT(CDc|w67c|*UNj2KjWq7t<69uJ^|JE2G(i3{fovc+C+ z1L%#6TRdhhqALcnhpDG<8`F6kEH1hSARbhq_X3@kv(sV9(CQ6-cgE4TjAP#qKPfJE zsmt>mndXT&2W`aFr5+%#VXk+!^=@YMovzQ-_=h(Q&K(8wl?6%OvdHlcL6;#8DOsm2 z@$hCb1wEM2GE$7h>?~-l>~N@QBe+k++vv3uGvFCop#cc>w~}DyQBO)f*({ttGmcJR z&H9=CyfSILnax_9bFR;^E}>N8=pKgjOPe0j}eZVutvt%-+q&5jSg8rEyK;>A2F?I0KqV7a*DrpKboBU+A2G!@bDu@g^<>zkbLR$8 zUr8Lpg3+#+eH*JqT(N>wN?v=_EtP`yIYv zIPI2(nCnyZ=ogVDt01Jl6(dtNHxyG?mfsHe#i;;wSr-sP8viP$JGFh8ooK_yQN9gt z6ip%3A>CwMhC|pnM76r5iJ$@s&W_{8(N&>=EUE1u`?RbQ^+hU^4AYp6xo}}IN~vFm ze=ape*aTUMupzRFeyntEM#g?%p0_6Lu}m;2Nu7IMzdWnGbpKv-TERa}Si4mi_={rQ zs=`QEbn->;AL(94UKou@*?r%)53%tihAO1<)7K6h8qq5au}wU3Vjd*6joN~9+-c~C z;OQ?tH=QyimaarFH(LK$gD-5hwUf9bq0OsxX=3-H~8yWD5-6R^=ju z6yozm4+UZFc^qRwn_u6rsfpK>hswmGFeehZPz;GE^S^S1jI+80m=rf~@>9YnGFQHq zyx;sn-R7`v+XUxf3~ct##iUl9fU#Pzkt^7Cgt*zI0nV)p8Y9z@CU)MD>@3wL5B%wa zh?aKdwh=<+Fx@JH({{OX^CxANH-0O9u3OzCwE}Mw_{+P=z*2Cj}M%9nk(ue0_Oz+4Pn@OD2J)_ zs2!;D3^BtmDy+}4r*;nQr@32(VY|SJi-Y^Cen>rF4t+@Q5-17%mX26Q(i|Y=S6ej-A>P347>}s zE-J8LdvV2bP|Y0BrhS)vNU|TG1(gTMqD@RaFoQfx>;>mNe7M?{tQX&1iwIAMU--2d zXSg5JBy0a<1JqphLP&eB{rJpx5Uqo^Z(y&m^a;yoa7pGGb*b?Q@cIeR_Vp;{&VM` zbIxNQp6eaD&$+w*;$1J+2mQ8bX3y)l`fNDRKlMyE*Urb+&s{%9I^)>$ytK3dGCwW) z>(AeXWm~fs4DWsTciEVJ1-4H!nk$s8lgu>=b=3YYJo>S~$gEWKV1UR~M)#k=ozcC` zs(=2AfBOD6-;T%k(fDs3jZOs+Sa5?QuzA|GOdTiSYYgA*u&qWYFdemy{tflXr^flE zAj{^D^AF>YtB8NjtYXm=`h!`86@%T>2QlscL3I{s%XwG*1J;iX2XWg3q81&$h?hN! z5n5rW&O6CzMxQ(UUI`uVddbKrW?vp_0n2gN`lagl0=*DV5i#d!EnlX0w%-?Qtot1Z z08wpHHUXWfJ3RJ!S}an>&Y7hC*&E_C5umny{mxE_U%xXp2Q_O3P3?nOB!x3y4~s=h z$;v%;;zVhMt%HMukwfK+AoMMM2x;Z;c6#vT;{)44kMAe6GBW}nVb_#l09F<4>upgRtYNvA0&_vtn^w;Yw_~tsuv~j$g9A`PJ%`3DF9-!-= zvr1f{L{#6y;+Q<^Vg3Pkuim?c$Q?~z-67dOw%mkLuQsb%{^b0_aBh!3uTYnog33|P zjYoA+_udDxbKt#eh^NOv_hWVE3k&dX`K*2H%7oBIU#cVZgzSy@r`JxY)-y-%&o#1w z+J!8qGMH{2RLhu$p${Aa+o2h)Gf}B+n^i3rasJ^Y4pT~e_N%x! zUdTlfmzK4G{QY4W!*Y23F$CR}NzGQaK)*i6`LENfR|=#oO%ch9ui%3a99ouP_clVZ zhTge<$zE7)di%>@ty)KVNA`DG(K2wt zt5u89u0MYKI39bf01sw6ica>cfYj#LdlQ?ZA-U%`&A(6 zR?HZt%diih**JCsJ}&lK9fN-sD->Wv2*lu8M(~t;vMv*$*%WR(&|^8k_{s|UDG#92 z>xYorwm1tdV6oUM!b#}@+}oFtcOG_i8J4}n+1ahbpt=TwaYF(HH&mGoLRVYHxFU|V*BSrg=m@_?S0jh;kdNf^)*OaPft=Mi$lcWRd0be|BL zEK$=RyHKD@%tL~80EtOKgHg-3p1I*EbGP*d^cEWE>mPn+%j5%jp5l(RlTo+}=5`rp zk6MVWb~J=U>8h?Ya^wLhunfGEFWR>cTOvgo@~M-7;^EuRna0#SI*0F*UW*CIVSDrT z>-T-#Kt5fLiqb(Fucvkea72d+5<52+zk(9Q7$CsL7f{_NH!0xi)&2Brv6WiNiC}Napq@V3Iv-^5BPAD78V>KA(6W#ae)2HlX$>)&&>cj0`!KuM&S1pQ7pK@DoX~v1Ko0+^TBsY;q zhb2>`@==WnY*DGRi4b9#j{n;iM~2S6Sy0@hO@}Q&v!vFKSi=s)jmeqflzRl-xK! zvwbSIiXb4zB7C~FTz<%tuRDzZ*x-qAvapfgId_XC(kAXB2W@pMnqBu%jdJ{2HW>+8 zQ!bn~Wo7%sW;A4$rP)KE*H&Ah<#OMQ)qVC}km2^L_<8c4AsNG}sWn3>?KrLU+aISj z6!*!7IMnKdWUK@)Uyt)~xyx?do6vHZ&9AZD_+teh5sY*#}!81H&R zF7~*VPx9dMUC^`T!vj0Ek7@an(DBJcVa%8@Za|4myf-n-V4u`x>}qKd7~w**VOK&z zR6W&_8%8$8^DfCTu1$Wi%*48y=+UY}5n-QG^7hs3g&{dg~F{>y$W%t%3TJ0Fshk4|;#H-5;yiM2RryeFWM=&&+L z8@rgwS~@DTrm9>x>;l%{hTIH0;+pW&Rjz#uf5%V95z5NRo@%>gooz}o4o|Se4zx09 z0G4o?J$7`a)x<(PsjW@Ru-i})*{0=F9lEwz)$%9jwmi;F(-7SfX}fdNCqfOERoF{A zE6zFf6X9ZY-o(71>uQ4TN%^Z?-QrM0`1EY3!k7K()vMpXjF>wQ_?tIxLd|9>uI0Bt zO{jkNbTFj{l`C^4$&-9^3|xq$m^FKLK93R@fBy^+uvh*qV{E~5(<1P$&JJt2v|iNL zaBIlxr^GzxJv8G%HAvu#PRh2`-=&x9U8W|l-c24h${RzH>%s=z-2t4VOwSJ z6z>kP$FFl+uIg;B@+F{}@ld>d05Rr4>ZgIT%Zt&JWC)P{eSjxjce zc2NTk4>xQCcM$T@wc9K?7iBrRQy)UjIUf4#)>YXX|ErlHz9Ogku-X^6-)ps)MLpJk zQYM6TLtx}Y7AH}#6*u~Mq9e$!Z!E#IQ%5s3*e%?8XqMdu+yS84L(2xVj>PI-y}tw$ zG521j&ewGX$Zw#j4q)zWv)(|8FY;!Ag2QM1U*}dWhHvwlHEXP}@x=wK2&WJl6_Yqd z5lFJI{2Gt@EkU;cOGQG<0(8E3|H~#jP%0DKskxz= zpkVvv@Un_-x(#DJ2DzHE(bICY^y^MIxohu{OJafT=tZnJ&uL(D8!z~T0$6$qu|5SV zZQtJoyz=suE00d8O}yJ0@^>B8RBPP&ux(e%3b)t47}36~+$p@1SryVTnW~n#S{S1| z_PW`#E=Pqk7O%S(WR_l@tgA(2qq!2vUc}Z7CEgRhxorEGma7UKA7X*QIXwhd#y0c< zO^Iu@*qnNsdlD>{` zGO?Qk!o}G``Mcw-nOx!H*CIAQfO;S1ycz;>vH5n$#?0~gHgH(zi+_Aln~5N0S;fXO zfcN;L{;}_ubmmPaav!)y=$NitvgE|7)2mm955FA{Q0g4fPJPfhY{DclToYwN*D@(N zaiUNP49-@BbA?|duXdY$-SNz@G!s3^#X39e(YlgpFY%^_JRefcrxZ`}Ejv~siewSg z)MwMi)^tYh)R#3Pd@6y2chaeCnAZT{AH&_CMK}l{*Z6|BZ{K#j_2_z>MOF>~7W0yq zhizF?lKHo4_o0H&rGi+1U`5j=S4;cBmkL`Wirr@a+?lUq-MYAvl*!$2Vr|jon(*#bv`qjEN&Vi$ zM~@~70fB+Z??=ZF8m|SWh=$!tu{T9SW0_O(sguW!#X?H%XmAD1)Pbf+J{8_byeED< zhqYP7-+6PBKBr6$E+DMu*SSZy!Z9O~Pnm^hR{8G$Qz0Mikb^j6HRK&@Ub7LF8615B zsoR~;&t{8L-)L)s?QuFJC0)CGdEe;ew-CSJ*!J>n6~;cl_n&8whS|vm9ULmlWQaU;M4ghF3ai=Q?n#8RXKfwGlD7dq(6az2~5nLSQ;a$6)k3NWnI*F>&6HlQTtek{yP2UOY z7jb%F$wYm&e)8mrDeh6M+=o5!rlSqA|8ivVju&!W`)O_8j6gHuUI`KK{Z!Vz`K;A) zp92ScoxD9ZBaI<~e@j&an!12AtV!}YIUm3E3(wt}I+v*KMxDV~LQV5}z%v;&lLGk; zy$BSem^6bUlNN*>l7UhKg>Y$T0C+6DI*f}NNKUe~wUx6@7*}6!PtH5Yg&q|ZEu-oD z`D<-y#zU%80*N7F52(KJTATOnU!lFKMIy|>S^z6hLd({`VPT5ntNgm9!^pzqfNR$d zqRXXr3NSPs$B(-d-ZacY2YljUi99A@jutyS4LJMCH`o_2K`4$7xa1C=E?AiNMk=M+fTxB-y(I^eFm&wmyAZ=4CZd+TQVI)9FXR z8-%)mvG{CBwlnZTo<+bO0r1G?P5#$_o1;K0nHK>EJu9uDof||k#~=inIR&lll{(`G z+`|B}Del}_VCxc8Z+D4mF9IeJ(6CSia81l3V2RQRT1gB%{utC+z6cC6U?71SpKibo zGk9zUIF9h}etlPW_vcIR?au;-sen^*HxkMYvWg!87K5`qpat!M0(cC0oB>vAi}vi< zb8ro?83YU_;Gm`*@NSnR;7XMp2XlbS?hS#77%`}p9rprS@iNHRfLcvGH$ekJEVGwf z1~#cD6#lWU`&024+IFz;*a15kp~0p0vGn~8(6+ew=cBh|2mLFF( z1BJ(I2~f+qz#G4S9n<3Z=evP}8Nj8^pg~TiEm}Rmq$-G$+^vLfpd~QC=GmNr#VJ>>Uq22kGJp-mdKI;Vst E0D9wV`2YX_ diff --git a/tuning logs/2025-02-25_02-59-27/settings.yaml b/tuning logs/2025-02-25_02-59-27/settings.yaml deleted file mode 100644 index d100089a5..000000000 --- a/tuning logs/2025-02-25_02-59-27/settings.yaml +++ /dev/null @@ -1,335 +0,0 @@ -control: - longitudinal_control: - pid_d: 0.0 - pid_i: 0.05 - pid_p: 1.0 - pure_pursuit: - crosstrack_gain: 0.5 - desired_speed: trajectory - lookahead: 2.0 - lookahead_scale: 2.0 - recovery: - brake_amount: 0.5 - brake_speed: 2.0 -model_predictive_controller: - dt: 0.1 - lookahead: 20 -run: - computation_graph: - components: - - state_estimation: - inputs: [] - outputs: - - vehicle - - roadgraph_update: - inputs: - - vehicle - outputs: - - roadgraph - - obstacle_detection: - inputs: - - vehicle - outputs: - - obstacles - - agent_detection: - inputs: - - vehicle - outputs: - - agents - - lane_detection: - inputs: - - vehicle - - roadgraph - outputs: - - vehicle_lane - - sign_detection: - inputs: - - vehicle - - roadgraph - outputs: - - roadgraph.signs - - environment_detection: - inputs: - - vehicle - outputs: - - environment - - intent_estimation: - inputs: - - vehicle - - roadgraph - - agents - outputs: - - agent_intents - - relations_estimation: - inputs: - - vehicle - - roadgraph - - agents - - obstacles - outputs: - - relations - - predicate_evaluation: - inputs: - - vehicle - - roadgraph - - agents - - obstacles - outputs: - - predicates - - perception_normalization: - inputs: - - all - outputs: [] - - mission_execution: - inputs: [] - outputs: - - mission - - route_planning: - inputs: - - vehicle - - roadgraph - - mission - outputs: - - route - - driving_logic: - inputs: - - all - outputs: - - intent - - motion_planning: - inputs: - - all - outputs: - - trajectory - - trajectory_tracking: - inputs: - - vehicle - - trajectory - outputs: [] - - signaling: - inputs: - - intent - outputs: [] - description: Run the yielding trajectory planner in simulation with faked perception - drive: - perception: - agent_detection: OmniscientAgentDetector - perception_normalization: StandardPerceptionNormalizer - state_estimation: OmniscientStateEstimator - planning: - motion_planning: - args: - mode: simulation - params: - acceleration: 0.75 - desired_speed: 1.0 - planner: dt - type: longitudinal_planning.YieldTrajectoryPlanner - relations_estimation: pedestrian_yield_logic.PedestrianYielder - route_planning: - args: - - GEMstack/knowledge/routes/forward_15m.csv - - start - type: StaticRoutePlanner - trajectory_tracking: - print: false - type: pure_pursuit.PurePursuitTrajectoryTracker - log: - auto_plot: true - components: - - state_estimation - - agent_detection - - motion_planning - folder: tuning logs - ros_topics: null - vehicle_interface: true - mission_execution: StandardExecutor - mode: simulation - name: launch/pedestrian_detection.yaml - recovery: - planning: - trajectory_tracking: recovery.StopTrajectoryTracker - replay: - components: [] - log: null - ros_topics: [] - variants: - detector_only: - drive: - planning: - trajectory_tracking: null - run: - description: Run the pedestrian detection code - fake_real: - run: - description: Run the yielding trajectory planner on the real vehicle with - faked perception - drive: - perception: - agent_detection: pedestrian_detection.FakePedestrianDetector2D - fake_sim: - run: - description: Run the yielding trajectory planner in simulation with faked - perception - drive: - perception: - agent_detection: OmniscientAgentDetector - state_estimation: OmniscientStateEstimator - planning: - motion_planning: - args: - mode: simulation - type: longitudinal_planning.YieldTrajectoryPlanner - mode: simulation - vehicle_interface: - args: - scene: scenes/xyhead_demo.yaml - type: gem_simulator.GEMDoubleIntegratorSimulationInterface - visualization: - args: - rate: 20 - save_as: null - type: klampt_visualization.KlamptVisualization - real_sim: - run: - description: Run the pedestrian detection code with real detection and fake - simulation - drive: - perception: - state_estimation: OmniscientStateEstimator - mission_execution: StandardExecutor - mode: hardware - require_engaged: false - vehicle_interface: - args: - scene: scenes/xyhead_demo.yaml - type: gem_mixed.GEMRealSensorsWithSimMotionInterface - visualization: - args: - rate: 20 - save_as: null - type: klampt_visualization.KlamptVisualization - vehicle_interface: - args: - scene: scenes/xyhead_demo.yaml - type: gem_simulator.GEMDoubleIntegratorSimulationInterface - visualization: - args: - rate: 20 - save_as: null - type: klampt_visualization.KlamptVisualization -simulator: - dt: 0.01 - gnss_emulator: - dt: 0.1 - real_time_multiplier: 1.0 -variant: fake_sim -vehicle: - calibration: - calibration_date: '2024-03-05' - front_camera: - center_position: - - 1.78 - - 0 - - 1.58 - reference: rear_axle_center - rotation: - - - 0 - - 0 - - 1 - - - -1 - - 0 - - 0 - - - 0 - - -1 - - 0 - gnss_location: - - 1.1 - - 0 - - 1.62 - gnss_yaw: 0.0 - rear_axle_height: 0.33 - reference: rear_axle_center - top_lidar: - position: - - 1.1 - - 0 - - 2.03 - reference: rear_axle_center - rotation: - - - 1 - - 0 - - 0 - - - 0 - - 1 - - 0 - - - 0 - - 0 - - 1 - control_defaults: - accelerator_pedal_speed: 3.0 - brake_pedal_speed: 3.0 - steering_wheel_speed: 4.0 - dynamics: - acceleration_deadband: 0.1 - acceleration_model: hang_v1 - accelerator_active_range: - - 0.2 - - 1.0 - aerodynamic_drag_coefficient: 0.01 - brake_active_range: - - 0.5 - - 1 - gravity: 9.81 - internal_dry_deceleration: 0.2 - internal_viscous_deceleration: 0.05 - lateral_friction: 1.0 - longitudinal_friction: 1.0 - mass: 700.0 - max_accelerator_acceleration: - - 0.0 - - 5.0 - max_accelerator_acceleration_reverse: 2.5 - max_accelerator_power: - - 0.0 - - 5000.0 - max_accelerator_power_reverse: 5000.0 - max_brake_deceleration: 8.0 - enable_through_joystick: true - geometry: - bounds: - - - -0.35 - - 2.85 - - - -0.85 - - 0.85 - - - 0 - - 2.5 - height: 2.5 - length: 3.2 - max_steering_angle: 11.0 - max_wheel_angle: 0.6108 - min_steering_angle: -11.0 - min_wheel_angle: -0.6108 - urdf_model: /home/jasongao/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf - wheel_radius: 0.33 - wheelbase: 2.56 - width: 1.7 - limits: - max_acceleration: 1.0 - max_accelerator_pedal: 0.5 - max_brake_pedal: 0.5 - max_deceleration: 2.0 - max_reverse_speed: 0.25 - max_speed: 2.5 - max_steering_rate: 2.0 - max_command_rate: 10.0 - max_gear: 1 - name: GEM - num_wiper_settings: 1 - sensors: - ros_topics: - front_camera: /oak/rgb/image_raw - front_depth: /oak/stereo/image_raw - gnss: /septentrio_gnss/insnavgeod - top_lidar: /ouster/points - version: e4

dpCr>IG*BdnA0iT=munpH2q$`UGD62YjKT#snbgq#s0cF5URzLcs zj>n!j0`H~$@=zFE&-dR=zFm3nlPqeSZMbKasm^vrd|#YnOv+;ZYxq7NUp{%P#A?O5 zcdBTxOy%@gTIrmwgzdFL*V=YT>+~d~he*8exe`{@M93W?m;jTq{pbv#cJkH%mYav< z9#EA96;fcBCdXhG5-*g)Fo`{AL-}ZR3xO(L*!Nu4%D=rE-g<>U)UXZi#A-bLfbtAe zAmg>gY|L)m*u2NBY{I^*=l;E@U6|Y@{M8}u^NO$+G)bM6`a*gU<^|)d{p!Vu*OhMJ z2OG~BneKY&y~<1$DIB?FzYxap)j7?AM2~ zI9CP%GLsLj0gqcdteCkIVLvZib$Y9xR+tt3@AtpP1yz$j>wlD$IzB`DmvyV!8tzah$Sx+Ea5{~SW!<-6-RB@_>V}Pr;HkR8k-4=0M-S_TG zk2OMcM3brG`o@t@7lvxHe?#jKEP=8^{Z7oTV-Xe->9?$BH)G~Y-O=&4(RSv`-LQDB zDaf2I)ZeJ_sjQr3ChPJJzZ!QOLF-gU53TN})Qq4S8Lsz`ye&+v)8B9PS|3uwt9AIR zmUBjrF>Rq3?Y{6~?SLUx5a-ob-zVcI`2zsBm`Fx!1L3a5-Z z*J_^pl^}LVGsSKx?`$X-diTe%V}dnNafdVcry5>@|a%cd80gkb&pJKpCWy}5Gm zpFj7!+Nm%1s>X;_{B~@{VgaRbvc0xrw0m^TJ^A)zQH%U!H!Wpo(LKtRHVdz3-eM-> ztvGc{Vl*iY6}KlT(v0(Y{&-{QxRJEw%|@nNa28Rt$R;jl*vN53HJR#V3C5m*>+YEI zopHZCD|-+&*%8X&XW3L6e4XI1zs$+T(L82PaicMwr{gBGoiaCcQYMdZ9m6KKU`~}z$eB!v z9BYMVEm<37%bn<7>AuAEiA4%s4W85q-?fA$CQ9xB%q%>MGoNEby2sZKC|u-Y1F z?wr@M3C`SX2x;aYyRwnnPkF)jkmfs%haKL6DJy5V+i>@>_RM}?TsMMwu|{S9OP&}A@QB!j|&X=o|CcOGwNp^g~CfMsPiLPz_w_GLFTR~Y%3W3_PH-aXX|BJQ!$&&sSUOP6gLxiZvBq*wtKSP&Y!)qr@G+ic)e+SL*JeHeRPnH)5jj53^hHp|c`OFF@)QIoK1T@?O^F~6KGJ|X{6mP>6 za;4ib1?~V?a~fOgFlu`V-xasCV!YyKplr_GPpq%T?3DW#Afd!6{_k-#747F{DN7&k zr2G0|sn3t(UB*vBJ3L9gL^$}F;DVO%?-W}8(kSt#SQIVq9U->}S}`e$fZNGsyz$C`zb8YWsm=MtKdG{j;_lQND#PA0%%AtA+#;PS7Ov` z+vR+xGUeqh#@s0`Uz*pT=b<HvTKc+7pr;V#Y-gRG<#|kn z6--C;4mPo9#axF+D=W)T;q|6n#gfG%<0<}&Yf;dLdA)1R`o1Z1Dmqc+K(9A^rHM=5 z^MciXbV4Rq?@#*Fy3c=CD?t-ywY${>k&scDL0(cy99V-6-qwSpXtbQ3u+&@YD(pdV zgz~{-h(A~Hv#eh0KgInjJ@mnRbjnXzhUM{>Pl^~=eNLDC-&${qT`d` zBH4F;VD32t=i1eK$)&!&04usD7--)ZoWBaU*I?o%S)|v#qP^_5Vz&EdrwKrA5tzh1 z{;-G=imn>6SoVX#Iz4wWfhuGQ!i>uw5vZ{yQy4b%QS?q953+1>zV9+Nl{-Xwt8NZ) z7=nh%N#>~tES1>@E<42V`C)8oHsvTxz3$5Z7HT~PZ@jcv7it);cQu_E+k_c&@yP)O zVAlgyJ5CmW`?`_R@`T~7beyWZmSKY+6 zvy4UCuoi|Xlm7OQ?PMdbJ**Y4M$awtf2i~0kYF>mG}<%ooHc#_gwzyw9jaZs`4xg1o|geg=65vWIRmFCQ|R_?D}V6Ous2!tcc ziw`*up_?8#?>Qb_1P8>~`W-@>(f3;g0VKVa8E8;L1mM~SQRn3O?PRbzn^K378P5)g zsrvuBZ)cLpl=zv`Y6LmcTa zuN{14l(KO}<{Q+zAmg}*OjsRj!nmx(IfT!~E#(_m|b#y)LhYhlRBFlzMQEL2BJ z8w=FT)#2AGgu zd?RKuz=%P}kHM;_EwN`XIR6hk*iJPa;uNe>F)oUL2X4Y_WiXDxAPm#O+g7C(S}{*; zNjW-Gf+e0ekkF#I{SC@WD!bVc%>4r)*U}n_Dj4Q>=iVr5C-g8^!>|wE|AF7>8r{Wo z!RPhUe{{yLQ}f@odxrl&?rMH>Ogm^Xt$ig&)bcL;Oum#i|Io33;B1RIL!k%RA?TAQ7!B)_AaN5Kz~^9AzwB8kfQ{Tqp#JLyQa|7`uXUg(4KS(uBH*Fe zS!6T1In#0uE`r@XCDw9`+it7G?CwMJ)SJmL!}}Q%v|p3XXY3q!x2PV|Qg;+`Un4l2 zXSNeZab{Gyp9yh}l^pd?^2jpmZUlJkw1uYi2&|5D4nSf$@E#6a`V9m8H#yVsclFXk zhVzvxIk+hE-vLbuQ7F5r>uh8xzSPy#iqIe?a1;g|Y#=}@P&`zMUT!EqE_V`gffliL ztgB)jo4RT)#s-(l?%fUN0J4Ms{5xPSIC(g9JHaGwEM~h@_&&o1D_at{fM}34rt~|I z5{3;|^xuAsU`0Zl0Zon1^WA-Z8G-!eCL|q~FGA0Ai?_lUpxUKFLSc1w7 z>+r4L0LHRn51Ni?=gi^8gU|vaOTsD^bYlv^#=!T~8MiCH$voAxBWoWM`Glw?7Wv~D zd~oOnUqjAZR)wrUp&y_2B-lOuc** zF#p4v&hRE}2I!3KZ?d~&M(@I?$=fOi9u8_S<9%J5_953hY|D2qNR@Ll)R4mh%)?Og&BQk6h~oGD)io5` z!?9>;>;_Dh8bDYe<6DuEcf&jT!~Sj9!Z#(I+uZwh;itC1 ze6j6^Ml8@qx<;P|zQpeDn^&k_E_{v72fVjm9KXn`=1TqowK zNJW*5>f;RNpp9ox+BQ;s+}0?exDx1*TqSj`CL3Q;5*P2tam<`@94;ko3GDLE;KwFd zamYQ7)=$?cpO9N!!;4WbeUauHUVnS2z~?>jX-N-2=V6(FD{JXx>wCt2 zatLF?cmbYq6Ev>4Jv5nw$M3kxq&?w1&=+?0^8Xoqi)_E`6X{SZtu2_qUt_VWmvAF$ zea?YRT4Kc()(Gk_4ZB(vsweQG9XKv9#`+W*=l<*m+=@BkLO#R5<>QcnEo>yo?8NbqpCewu*N@D zojG*_a;R%3ne7CD7nh7MtXstS0az2nihq~vGo9Nyf6q1`8cI5wBaP#}X5V8&9kf%8 z`kuq$Wo$HQ)Waz?Od~c0l&khw4#4Yu1`kPqz>R<-u;V7?`~ZKjR^0~R5UU;wse52n zsDJKX?8~%wqtwDVqGsGM@p+z|X=@`~><0}puvx{LZEoe@u z8-`h^ois_~4e-O5`8W8?VRTDa0>HPf>}4-N2HlJ-qrl5MT1(;yKw z4pouF*`D4;!Y@eXu@2zKtxx5HdnQB!Y0lV4{g{Eg0h2wMPRO;knOt#MVlhFc)>8cn zk&tVbnC&QB4X{>6-i zzdf?-jGt>QDh;&I>*vDy_@Nb`)BxtOU^&v+ydI|EAcM)xQ04oaRd%a zYEMaberx7=^|$<<9T!%5s#cso7^H@8Aq?Zw^%i`iE~9eI zGX-*Cd@le5GqdN==Y^#MUu59c>snZwDQ<-UyP-`u8bR={5h!?8FNoEj4YRh`KvIR% z-UXc47~wjdKm}fG9WaTmBR{&pz|0eP@Vv@!Y>=hQj@5T${-$yjE!D%(F#O;xhd97T4i2|N6lp zHf-uQt8~V>GE>fLWJ=ObI4A5UM>rk2o}yCz+m^?4yL=03Ux!e7kpsc_EYx-l!PW^yB}sADG) zK@s`Xfz4P>{eIr<1ghknm$f+@?){w8d6bz`+qO-oCrE=-rTI+UeKw)bcJ)WCpLwL` zJ--x4ZJVaP)8EomjWiMC{-sAj9MQDEBImWtScRDZ%>0&N-CyH2^8}rfB6_94j@~6v ze!rAka3w-%eWjMTZ@r!9N_4MwDw6m78RvQHu`PV}m1*7*tu-O#otooooq@>aF}r{+ zp3gNb)RPBxVVDK79_;m1Xh&Y^1P$2(`3_5#o^LjMuf8nkxsbQ?n7G0@txTMj`RERW zT&ulJhyHcZCkjvL86NdFaHM2x3fHisgAWRV&m{(6Q%$E6AnD^e1ToY+d~fmcN)Kn$ zn3qKqaO5jTo9Rw8fB&c)BnYqe#-hKpZqWhOkWJdVZU*kAOup6%F z%R5>@*fqIKw!KEb2+$i@z8d4avf8!uc!{-@I8QwuHlff1%~mjyR1j3y;FJda#orqs z6qts+FF_MWP?|>PjZyY`4u}XT(f;ZruC%c>3d)@2g^cfT%6c?yIH=h;*^Qo}Y_KK; zEYR&E_~}LU)n`96%bXU7(n`BE`3e_4I!MdnM%48|bH(;a!j^IXo|^6o zM)nOw5m}JtV$>bL%?DqxP9j+9nzGZ6$Mk86K;@TYsf9rC!st$zSRzS>8YG zYdqi5cEy?6y*m|g^e};B!jeprDClb*<)-w< zl;R{UugM&jEq3#)G!3jNGLel}mP-&E-851-AaI2(eh`(M|<<(`SOz8>$;~; zKk$=cijGx%kbF7__$^E=c{yYvyN~Z42nU>oytc$r(Y^%A`tIqR;+c%TN?+(a3hxv@ zhYmRMOyso%_j@hO&v4t4Va!7a4~h6->CIB{4^cRN08Tn0H|(@%!ON#ykThvJ$xzlC zOP0<|?*~;miBbgRkKS*U$bVJRx(?ri^DD03@!O1HmN=Dcl7SON7Z;4TQCf%|g|c^$ zvF2*E18{L>gQpJcZ>@Daj+IOdi}cP%Eu`yH06ekiXu?vmXIrFZ=zrD+BAse%T%S|# z6N8c!>RkTP@N`D6SB1DA{ix@sq>`+s7cu;c51@Q(NTd_v>yDt@MTdoBAJqiDQp%l& zoE|Rk102K)#!WH2ZvU0}X83;CP)nwE7I$I=VQ3g$hX(X=9**&Q7`be6{4CD2pOVy}GX4+5YP&-KJ~M z@qWeWevRmV*BFF5rTnJ(q%~i#F7<3e+on!5X7D_x)|&K5z#|M(-4Ewvq1y!qKKTO- zk0Lv0d%igG0Z6CUKS(cc8G_zjN^I~Ty60kj?0k;nKOx^J{Sn!_U$xG{0Cc} zh8$qso&8VV!Z40L92t|U!w3Ahyo(lshKNybyh@bmid1Fi*uBJs;?Mvd$!Gz*+(I*K zWZc^hbu#9}9EcyX4MRrGX`zNriZ})tnSJ6s&_QZ%$Zt#-HV--l)LtvcII+aDVeY>z z;12H@Flx>ymaty>9ka=S1EOCdr$iB6%lOmzNV9(F!?#N{F*~jE8LOF9RJl$};mDjK zm^w2q@?q4iT!&?>pdaNY_wE1kfDu$JdaGtg0lcz{Nv|b)eif_&o2g1Xi{&22(e@C0 z#K!M9R_kh#mI^O4kKW!3p3)T5MdnU(m5;I|e z#Ay8L(;s_SU%j+L!^Y`ulg!Rzn251v{>`OLSj(SyZmlvy8ScyE!m_22^;N}CRo36K zk^jtx0poq}KG=R^^#zue`ayN>dZiL`#X-}faI76^HUQ3ZwplA2_Mst;x*LF9It-jk z|KdiNbQ)9=8VM%0QrKbZ7%l7bjX`_lVSYjm=6GfoImY6|G+5QMI_3m^67-IYTLNHk z;(32b?lrv##_shu?cGSx_cyOJQ!6=>_ z2VBs~W3nGBE4GAk+pa12^hJuod>)3?hFA&F=X4pQtJ#&?NTC-rUhDom2FxBPC=+O% zCCykNen1{pwO9F>Ro}wlbir)%m$z|;zJeSYl_#XTr=MkK9zxN;@RO7lvVrgyfA0*p z&sXdyxhD(D0EYJllJtzPpRC|HKjMrTumm&jgu~PHVM(ul0P{QL2*VVrT%dRxGI9^} znCwEuAPy;pg%5^b4Sk3dY+M(dzXd4b&TI#7_hMs<&XK4OGdA^gKS%8|Z|@OE zl+k^earD2&Sjt#QCzpPJLU8eC2Dj}DcR+e@1#sez_o%par=-6KF2SfD0zj*OhYX4# zL^K6iVUe33vnHwgVb>3!FN7Pl*6f`C-BJIoCtPB}zN~k%z`<_D*$Z68{cSDj_K z-6r>*1}vPy+7b>rCm%j`abk05F+xMC&px>S-pAuC)S3^FFJQqZKXpAQAS~5bT|Ngn z$13IT#Ws@@lp5M zVZ7>n)0Q^eZ`J7HD8^rbAwC`h8$27}HFTzn4Rb=1jgk2dja9g`l|HFHiRzFHbLtl^ zPpf1lS>M|boebRWXlZ}4$xkH>77AQ04P~!5c=WJeV?O1%v)!gzeNsTf>OXT9dmVGO zm`M@FVKCs71nrX+KZezmLxMSsFYK>*+vw&Tnnao`mBzrW7&SIz6faYR)j8{TWD0_x zzuG`zYe%yM-ff!_W&LZhST?TM!&_S%23}F>xG7s?%)z8#*AC=8vA-B8(6Ncmq}3_p zn!RHqi46`Jrn>J#X7%%J!F&cDqD*!IQLye}U-e8E>@!qev5cZESDGvH8M{u3XM0H= z0F1zks7(wpxT}Ngd~wD5Pkm7I{*38JXQ6gwK)Moq2^3H?YhXSMY}H&aTg@V_^}*Lk z^|khu6puwB+IZy3y75o=Sj9eA&;F_Cd0}Sq#!eWV`O;os9U<}Wz~o8f~~{U8z8=i+R1x-2!z)A6dE1o$$rA})l6B-dX7 zH;mis=jB$k*jK>A#KQ2*UBTiEf%>0CJozayd_k9aD)FuE_-ACj@qeKBnND!N05fSJ zOQ8N82!|P?FQ&Ttc+g(UvynHlGMLcSI;?B+4T&F;HV24$?I-Aqbm#^O$3 z#jRM6RJ0QcDg$)9;x9`re{cXACV&o{tOr!2)082Ghak0J4P!LInI8%Qu#FXg&}RMX z2p}2A@a}iXTYZIlOHyC}T7>(xk_hM*4+O(@z%Xk#kJ1oP*Hf3yP8q`E$|UE_X{zz( z6p&~!8gK0>Y{CmmZj(`!?L1|Q&-)>qJu^zv;Fs@4=(}y~0agT_2OcQ15mGAVITfIH zgpO`|vf5L6t9*McvXBZIsJ!SS3V(Wu6myvEA{nyC27*Unn7JQ3AIE4J zc|r5cDm{jjL_Sb$#EyzFc{;H?z{w_mx9z&&#wL{&dFrr zZYS}>$9t8$Sd6@E`f<7@Y3Fk5z+RWG1N)$brF5J!;R(6T1VE~)$OP*Z9!~RdyemD3 ziB6&l{z2oR6p3qsbsSDCS`Wf$Azwdxcn5%kk)IJsfKbEQIe4J6{O`|YT;Jf=h6vO< z?COKc8P=x?IMn$!ql0eljp(IL>CERxuu~%Z^htH1|1lWk|K%2&de>Zjl1|gv6Q)?8 zAs~VOFCzeY0KBia#T2MI;0dav0r(Xs%MUx@S^1@IqL|ELbo5SIODJ%Bjv-gn5>A7S z9oZi7BFneejnr;qrh-|q1MWQ?huo5isLPIgLrcmCOWLn7Wn%)avxOV~m>ASGYJXa} zx?Oi;)uEEwVf$Jgzu*3R59df^sR9{u{muOl$wRy0^8;Mqx56L1C|X_=-dBGczCVMs zL`t~Gt*pFbRw;7skbvZ5d72rnH@-WCLOuAKh<`+Um_bnPF`L!{n*S0ymf-BK|4LR= zJ7a+n4u5C$7V;-WxnSzDBASM7`@e}A1U>6dMzGEftH+^EQfU|NJ=eK#sQje`%GF|X z--V=v?`wTPQT7=f6x^0B**kgWDV9Kg2>!#UCv{osrA_d4C(&VvO*0~j894cUXZPNT z=@depa0r8iTo8h9fO-qDwZQxiu|#b&-+ddP_WwSY0c2U_g39eSRNm@@A1z)n+#-O3 z)aN-&4m`<6=xH~a4^`~@5KhC{=aA@i@GPskq{MFMZIZf8lUJ?u{e2le^du{aF7Cjp zrP7R*9J98MA-2jGrwgIa5hEsU9r}j>Gj;?=LWv4ko&nJ;A#wK^pVe=V@%V zHSHw0YK(Al@A9vnz1YlJg@p1c#{=-4Qx8bbYr&$JS&c41@plV3tB2*k+_8=UXqThc zO^GSgmeFR0M_>=sTCj~~K3tWzW#sSglm^5S;@z=0CFy-=KL-5$frtfh4|!LtOy?QR zjgltJ0>(UHw@8M38*)TPcDiiHDBS6O585Ye-01AXQiSkdqUirHR?2M5pA zpFD1-fN?;yN} zbSR-5x1lK9C*R5Z!o~3}<{@NEXJ9|gvlMCScOBQmed#Vjk+zIp4(aJSuuj*86SlIt zGc4|rybB}pE=<+K?G}uHtmu}LWBFW`XRsbpWD!N(8%K&yJZPEqMY(4>0HIqgiw~3eEEv86u>! zhM8pIjIQK_obUhjZB=tb5iu(8Z4&F!@MO#;6PXktT}lcpDx9=n&?t?uz(h}B1I_n$ zjiK$dk6E$TSs;tvZ%oerYs?Rg`i2Kcid+eLZDlbgJQnrL~@B*YF3*T9ZXZ^ z&By~kfFePXzXOwejmK>C#j?8Jsr~7kw66tz_m0N&Ek$u&tE3jNk~^&aQ(C__QmzN9 z4|rS)Yx>tcz{(2YkWtx_+W*)eS9`n&SS{F!a zJ?2}D+CO2~pZIaEsga90ogrC1J4;W&VdDlKFhT=J^>P8&(r~<{(aM0&TIBzGXZVV8 zJX%3lPC$40wEw-+MDR{oFC=BH*Jq29>tEs3O6?}ijX#d{LZlS#`!QJIJCH^^Kgue( zVfq$|T|6#xiY^z_=0OuZ5QVrO@sQ@4px}3cbZA5ZSG9xFc{Qvko5_0ux_Hr-$a6v z;4_WcnE!wSiv2M1hIzwdIu2(@m;fcLS0RFbeciGA1s;mBCsVpv*(h;&%>bZwx6hca1PglLtJ@Ft z(5C9Tx&Hotn?u`(9GR>GcSD$Ifvn|sPcMG-OdbRaq`xsGnNg@EXk(%8)FJ&wl;EKh z9)*g0FpLX$?r;f`bGPXqaIFUpr#c{^@HCdGBiDaOBnVR=;DhvGE56AXvuk2l!Ztnj z=_DMQ@_zyEkO^X@%aM=W$?)ie7M<);j; zo79(&@J+4Hc|92A+Hv5(f#n@L4(vanv{xvTcfaP2M-@l-{r2glXgt$8TyuZ@U~+!b zb$}BD56F^V*!}Iu*RUrk$BiFE_p{AaMDf2KlgNr`pDL`6 zf9*0Vy)xVI!{yJqN9kL|mwpohGY&Hr8r~FmWIP$33-`Cq8NF>UiPqt#RnMi|i^)c2 zp>T2QP7NGYx_GYM7@p7cdole)-b2m(ZKuL&MP5No{aj1J60pGPQe2)C6A6Vcy0beE zXGGp2A$YpHVyEThUN(zj+9$BsF0J1-Px<^tp#sJlcLZ~BC^~JYI8l7Mo(;<_dmR+O zR&;!Se@?G{11tUwCr>4&ad{LbuJBaxqagC3af)lo^`y~mKDuDKv2y6VMn% zC&}!@^i8Ambru>yP(+=~ApHby$^nBKnd^H&wuxbgCanl?8WI;E)BQ-zHaRAH@C3bD z>3bX&!4ea)smq!c27dJ+!Gar zym`oV!|fFqKX|JTH`6X#y(JTGKXnX##jUisCY0`UU4!@NM@$Y)lztt|>wzT-mYYP3Bs2zrp0xrkN6mk^k)0>`O1^1WdQMMmzqq$KUURAxt>V*%}Hl zcbtujBYnCB2R_>x*N;VCd@m^}$Z>V9dfnLghDUAe7;;vhG(XZV z%(P-r_xQou#$)iPt~+9oR2y=Qy6htm@hrKOC~Sbu4zJ;w3<=j;>rMe_$Hj`IAMoOs zzCLd|hnpC-qE-9jGIcv|D%#%BzuTK&F2sAEnDzb`8I^3#ebaF30fUEOYFSF$e*Lg? z)+2Yl#Oy(lG=_Nme6^GGqUZ`ZQ@F6Bw0mV&AsRSe8ue>SUCUnLK%Upq8r=0I}|n^D@z&>0%AYM z_nSg6`Xm7x?x%WX^VD8ZN%GSb4hSBU{dsEX#Yv$V_>`&rX3-~a0@}(%&17&dk z)al`spm9kszt2X(Zk58+>z+zsp6w9(*%d4pQZIXiyKrfQIwfXdAW$+(SnZ( z7lAL^XC0Kkp)9tsZCO>>nam?6U243M?XDsBtGVjw&xx@u*!=8+r=GxpbO?pO06V~X z{-MTXJGdGV8zBibicgi+aN3e@ek_GvBjrFb$;ky~ayf=e70r3|GnPJeq6rd@vsc;h zXje!+2e1Ky*%^EIM$AI~W;cZUYJcB1xhyY$bJ=K>DU1PW6qZ`|cKTo8gTy#^O$zbC z*>2*O*;<3Cp28%5So}*b{@Sp8B*RZiLeQ&hkEAKGSeE;ym;mBr%Ib!$tiR;(%PgT7+?$5qxzqPukD&BTW%;-X`OS;L^08gWPHg{qL@x+3^%6_{g7V2jD%yC zqgwP^X~1i5U${oO61H`&wC(;{>;`Y8vXA@cVfrXQ+Q%y_kqYu@6S zaD!eL*7a0(5$*kbDvV9SblrJO`h1&#Jf^}-t#hsZ2$uFm4$cr+==y3Tdra+Yr6i92 zVl7So@&-i1@tWPW`oD8+Bhfi)toXJvf}Sk)#hG6u?%|umN}Hf4Pg;pFSNQ3e!{YI? zq9{Scpz6h~d6IH~dd~;Z-Tavx8Txs;SI2$qyh9btxsG8S9M6@M$-NerWh>|OSxsm%G>Bc*`&c*zurdk~$}Xx)zw zJ?&nX+^D7;;F6a!_V=x42-S}C+|W5_nFRKU*&t=z$tu+^$Vx-up0^S+41@=g=dGkA zns-+~5HAcxsn{TTuY+?Pb&uJ`{-j_2?KR1^tvmT_kFvYW1Db8y-!X0i^2U3%9Tohq(?(1eN<5=rXy5ze7 z3^{5QQ_7cn7Pk#z?y&kX{Pyf9mWLD$i`_G__v6a$R&No&FS;U!o#4ACPll`M-o09g zBk9KiTF3?}hG2~s=jJ(EnWy6W>B;QF7gc*WzckbNrKPqu1xAQ?HgTzB4{GVYQhP?7&ELI4Xxbd0RtlbH? z9*ctxYg(mAu7;_aOtvfS9Cy7kT@6PqKA=^NP$}VjmtE471+SS4hj8;mcx?vESVr^O zC1HI39L#R7M5Cmf{}hZFfVRNl03nNxPaQBT1m>4d!RX(@uyx@e9G2(p~@i0+10LwYKKoEmJKp2;%XJ;01brLE8NqA zjI^bnBn9%f-g?GFe(G(TD^ObwS~;3+F7g4^J(ZL9j&({U?d230jz4@^?$<&qUb@CI zMT|sWevBi#S_iQQ-&{fN#}Ec0%`L=iOQH!{oU`XuI>f>=HH~943cLTc2Gty2Uol-Rd-I@cUPXh0mLw;$hAW7hRbwe3|q+hq=Ud4BtsxTbfl z-kugtxz^3w6lJvVN>-dzx4f>w&Jn)gt$GJ`?8oy=nBRqqx1iClFh|#dYHXQi!pbVd zJpOuFuOXFi+lOIE7yyK3SydmtqeBPNXbjQNwYe{}o~LP~78{>=(qpn}yb0aHnp>b4 zddy^p?4|pwN6mhlHnWI`OAfcK3Rb?9s;=5a(;YWy2*+A22~ekrcas6Fmc>gDijd(W zBruk>#s3T!jFq978>ICTM-%?UVdI8jOl080f}@JTa=~0LYDZi*>!k zf^@^Cw`Wm$zfNPGlYU-v%%joV0$H0C7~r$ztYhDF8CN%ZLVuT`bbE8gd>J~Fv1T>k z2$*l|;DOV84}zY5**szn%O?Nchj-^=5r^zx)ReWW|JS+^?q*l)P$bG z$8y0I9q)rlLe(%?%6zSVKc=s8Qw*~v_Ng%p%pSrL{f=xLt!cNZ4=Voj?g73n6Jz=V zA5I%wtBBEMY09`Ahj_49@@@Oc{HI{%!sIn)&WOf|A7( zcJViP(P*xG_}jyv+NP)DIuV}%&d74GlnRr56AvWWPsj9iF+$kSf!H$QbZ%N_M{Qe5 zdS?f`+O3ETGUt9ZjvFvwF}FzAl?QF%rg;Pkd?wc9W!X=dt&4>~TtKkm-DN-5>~Y6# zo$)-U4yO&`obBwFUHJUykmJgMFnQ?|&$U89GZZO=~2rj~t?dz1C-WZNp?sNrbUT!|LmPIGZgOYs!BoncAKaNaHVYD;MUV_Y0nz zOZBS{u*~gGy=RAZAn{6xB6%6LbT)(>v+LNaFh?|c`#1|)rOW(i~&&rpq%uS9xwNUEe54jj^f!iQodym8cOEia8! zJ8=m8(zyv`uXCOo!)(>C#dIK7W<8{&w|4Vdw4}?hd){JSFxS)i`ucp(8^k5&&_r0P z85H8F0(j%UDM+`kG##-H=y}qhI2!eASyA(W;^*Y zp=x%poLOS?+4U%KAv9_&AB`1-q4rPr3FIHE@@M=RM<)JmyKw;tL7>T*oC&lT)or-x z;-~6c91ws#S5#nU+n(S0KF2n8BY@YnQ4YC!fl2Tj(M6I zl)h_SNNXHt+<4@09Wotlg}CFG=7{K?rxr}!y$>QShahtZ2=e%CXbVG#Ma*1pJD_32 zNCS%44xuoeB%y)dXAGUQ6r7cOB8y;_j8w}>NJ)EAIuKzhyc~c@Qe}$!OA=QHo-MP<{;1tbBv_A*jEw##`~(Vr2SV7lXOb>A{uLycWc~ z4t86Ydc-B%I>;&S?~6n@(2#XB*l=T5X3G#wH{{syh>XCadZYAS=AqRSL;(uyc9ZJ2 z>IxQxB^UR|!HFXSevHyT;YGPcX7ywGsLNdbKDJ31W!jB>^8wKqm3%N)224h-LK-wE zX+p#JEW2l|t*cp_bT($Tx2%6eiV1E(A|uHmy0Nl<2PMXY?1Fb*^#qZI0?WB|rISmY z4<+2B6PP*f;*9gCvDo|QHawwlKlXu}Tk(KlmH*RPfg-+WnD|EgVJv-+Qz6h|F`LPt z<|VJ~LY-JOOipA#PvxSPj6aGUs{!!xKD?>$ljSYGtIS*{!g`^!)c5^nBa^JPCQK59 z$5J`^o5mR}^!tS|%<=|!s;pLZ?aIsax`)stPNW?rWKiKNul$i07o{xSUN4>V)7#+S zQI75zpMY}xcEPJP?)Y!rJ-cQ7%-&S~f}$P=6TP3I?V3LPxBANVk75AN*m5c4=x2&h zHyE}z%x~?Y6qnGHeM54tLVT{`Ac{3+i?`t5ocIpyL)73DX?vlZhw1T&3G4t@Vgm0s`Vg4dczX3BULRlj=dhes;H>q1hzO12yzpA85;$siGw%SoY-`Tyy+f$Y zqmNPV#nKgXpVc$;4QKq*>IUBtd;1q&NU-v;!~3;{+$%TYoqyZ2gAmqok+CxnNS-!` zpg?%bq39K>E5bM3y2VV_G{}P&6ENumArcxF;P56L$B(wF@Yruf{Nb zy!X=bp+r^1*I{sYIS&|C#`{)kQ%78^PefivPQ>-TaX$cs_*S{OWE zwhk`@$zCc^ujbUQ?ZL)+IdNBTISc>cky9qnX2l3c!no*8-Su}Ko}eD=r)Rw)C8r78 z?+1;emWwRBGUk5dWf(?vnA!|nG%Q8fvK#PRG1+qA>lB}GZ-Ns9pWkgS^wrx^s(9Qk zm!f+v@$Iu0LGF=0X_$$c;uIebjuw&$gXRYUI53m@XhUNKaH!HgtaSfexlEArrqgXk zMCxj}tAIzX#pDaS*7*WT{sV;6;zSBKQQqg=)+Q2$A^!{n?_4!3GUSs2-zL%TF<(IA|ll>UJ=+QW%(tSA5ze1hx7W2 zWJx;+Z)rwhIy{ni=z&4db1)Nk(XDR0DGo0R7V6In!US;jF-CIi*7yr%4$tl6BpS_U z?o{no{DFZZIuLQsEkAabp6+d2|#Rpa%ydlmGT2U?I6BO8D&Uji9 zt!7|xT>z$H`1fq=#!6rP-k)C4AstktfLqgFb7dkhW`+ssvBG>@uLG3^84Y&jKD0qT zY@Xtvr|9!zxB+IgBI!?O7|hDKT0U{Jpl6hRx+pyo{Oz^ZXSl73=c>eEUh&xm*s{sH z&aso1!Z_GmBALlzKb*Vi*>(h#5)3Dq_G2Y^_WE**n}H-5B(P@O07Z{O)w2}Gwu#hz zo5$vK1n5EcXEgR}DH?!_2Kyoj+WGu(!xAGNO1x{)Y-JDUG8_(NFt+2wS~S8a2kLsO;RNNX0ub^r*spYE%|tT% zck|4`pBE_k;^%A!6wf>YPBuh2@ApWd`FCg5y5;B_m_&`%cA+C&&(j4ZyHZ{5VmYP* z`76pZ1-~8^Af4nWudUVBV-%Q*NTtJVwud)NAIi!7vJ*v~;PCu}HN{CXN-TDoTd~DF zWc;6b);Z%T!GP{s1uEz3Uq~i>n-qe^;he|P!Ng$tN&{QN^VUv8(eT@QNCmTflN7@U7m^=h#8#uC{1j(LITJCmSjOxX zV^szA&2{K2s(u2?mOVdZTxaDMxLV{(p$ya(lZwp#>QVBF{?e6B;&hVGoO7mv@pzn%Cc9*7K59X3y?`)_-+xg@lnO9^4%8#HUm1AV@{&4fS z;bs44Xw0J4?WtS89F2%6{2w7a$M$l^FQ$KYlKV|;qn6R0eY`#s*dGo#OE$@~-WRUD z@Kuw>8IX-59AL%5AiEf_EtB{C;u_S*th-q3RYq+~*L!D{8PeT0{>aWiVma(1vvCik ze5F0^t`GSMR)Ibn3rv=uscN_AA_qZE!D=MpAwKd_?MwqL)QE*`G_Jn!-xKq*gt<%9 zCC`Ud=Q6XwU0Om{&Ag^IVi3Svjx44t(luXSe{-((3$!%=gndyf<_f3$G}mtIEEm5{ z{wD>Myz?gOxp|-Y7hcgy6ZMfM_!J#+dTSe{!BFI*{K=n5B&olB2E=KE+?Ic%k>3U| z+Sen3z{%k``xpi+QD6ZfZ^?)eLyER;6SKa)8o~a4l^Gs#i@o0xdv_4L%@-QpUHh9P zbm_ok%x8{~4{LxTf%+Jj$>G15u)@q~E`XctHl?LsE%(FNW0$N3J&&bU3U99>7<0`B zvOkO{xAT?BJ?P}~$Qp8a&|aCXgP8srM$~T?y30zwEEZwC+Q;N)=rb<3!F&&n9REqv zHw25f&$mQl(f)MZ{XjWTQ>u-E3;dh3t{U=B(+?DVC2G(dX54wA|5!lUURU(UMSm%Yb1IW_kgOb~z1Gy}3i0lH4T zISm?g5VmD0S~JNy^ms5~ov?uARJ#b=tj85TU^XL>+Ddq)hs9ox7w3W}eybO=_KpI$ zl8UI)hRuEk#nZ72E=3M-6++cVQNDUjYV_Clkaf$0ck^xTeUKo>sI)R1$p!+8Wv*kf zVVR`&Z5&`US`d$^aCmT#aPq5wn|D;*PJ%)Z>l@P_>wk)@%f@aK+oym2Cx(%@0BIZ2>Rp!{ z_UetTF3%((3R;BliIrYLFB4*6BK45z{@bTkL~8}+9S8K~M@4CUp} z@MEd1Ua2jR#y%6U3p;J1YYwD>vyAFZ4m-VGV~r-3o(z|vvq*IhcoinxioBcVH(?ME zbhf%TW)8sK#|Heub1A8g2My1&08^nQ_JCZ2S`ZpI?#2ALTrqfYH+c}_Sst2m+E~O)B9pDEBED@6!>!fkFHA5^5C%+7uKnw;!>v+VQ_UYcbB7Y=CdqB#J~} z)$$~4>kBfq48v*~Vo!*&^lP&ez&y)p;ubszr;&?$1N z`jjYqEfhLRDA6KVAj^nvbMb;iO0nSOmPjbD1W1H1(XjNCL-0U`qsR)tmd|_Bva!-N z9nU`xe(#oHFDPKEp0w;>c+RC5G$-%RKpWEj; z^{i?Q!0-m?ActL#f+Xj^1zZ^Bi-z#-S>0<}&2lzq4|e*5Zq7c;T#O9-eha2kzuz0S zSv~k|d|q>1swPd#_pu&Q_AXZGr**N+x#kz2(9ZllYjYv;N)5#HAF1lV(Wnw?x}`Rhl%1 z!G!U8GqzC^`DSif!cTPTe7GOcOW_YAeW_c2$AkRD9e~se_K)w8<&3iVy2pccie?@> znBMfylI|E#ce2T9KpI%D$MPPI)F65Jbq}kV&nxwk0$5pW%O|q@*xntO*-33ss{wat zDZm@=bv-SUdl@n;AEaOj*;ap)(7#+yi9veX(l?5R`ZQWKEf(!DOusQ=AyTZR1CEOU z)CqKS9!&22Acc-%utC$i%M_m_5eS3gV^F)*+V*kf=%aXOUj^|y4^;tcaob|2qFF$K z&jjs*jjGHh8>oS98_LA4JHTZgs3O@QK$tUPx$Y>%&-UekL5|^m+2UhnaP zoiEr;D}3qZN>)CnE98qR27eoQ2o3bgRl^4X~n;k z6`0SxGkFExOE&qN6Id-B-3z}*Ghcd$WeanQ$;p%A;4TwOMv0@;)U$bB>v?mJ**1<9 z78Z);t~mNYW}u#`br|VI4R`l%ImWa*>gAcPTjznalaTcMiy$g9D^PUlt`ZVsacfCb zMPX;yKJ~hTi}6htxN``xi~pkod8TGW#nq9&el*7d6F{W_1Z|BcKJP`kE;aD`eRg7M zg=@ypgje6sn7Ir~PXxu*ZfX9KNKrB;pMTu8Ets~ZHwzoQwibjQ{`&S~!4=^UpgP$h zKKjA16r^5e=yp>A>)|DJ*;KPI2A~G8+dh(sU($#5*Sd;(2ucEp_BPGe&O|oQUy}W< zNevF#g^Yi{J$L-h9bTc`zt-kE-kDuwnq}=J6Y1?GW;yu=#GX(x{y5?%$P|eU*g^78 z5nDxxF}#eRB>cQVi6y1f(e?nt4GXV<1;DZksMvd-QIw4=PJgBOju+kXKjG5X)>eH| zy}_GNc%PhmU=Nna9)8Ab38U7FFVS#7jDyl*ds=WKl1uS7$Z^?DrRK@MeZEQCb@St) zb_nbQ{!*CXUn?mJXTl*KRh1o+W3V4T67R{J_^kE-#e@q86UbION>HE8J=C-?@#rE z1MwGckV8NHZiZ3aL1-SrHC;L+?@@^WFA$d5-XA9)Fxj+NWIB-Nbbj{Jz49R>4G&V0 z$3VWI^g_chr1_&&{TZf2F-S!~aX(yF)Z3%TD;KO; ze2X|doLMX2htzkGI0O6z#>JUZsQwL6!tAN%w12flO_^nJ1~Ml;MUH3SyvI&i+yM9e zeO|NW99ic@b|s+U*no}epfokCBg;Zy`o9^Y#MOXYd$D*Wl-lv9i3IjNI>#jCY99rn zHYgvxELQ=F?+8bJ!KLWWEGFPhn=bh+81TxuI%`k6vN7WyuT(>z*QN5JdF=}GL#=Q) z^n?d5xUa+lz(U9k2ZBwyg`K&C;PPsO~(%pG1Ezg5hyNwo{=pZlvf^h`mlWW|(}>4o8$-pQMM zq0CYc@ECA?BmLUKws=oP-0k#@%43NI+4sm3;Oa%=axfLMtX*hMx6!IJ3>=5o&-ULt z^Fmnb&i9Dp5S37mCl}D!3V?g)k#u>AcDVFQAelZnBaEdh{lucO3g`&(=GzVL0$Zrd zZj?h!R(F3dc4zr>VH7v^o0SA7&Zp900$S)7RqnxlHs6JMCx0};eCYFxhc!}{nFCcp zv9yBG23Flyfy>z|AfycWCKvkA%_K_!Q{oyts>k!hO~ww#Vjreg!=(hgExUy1;UZp&!Mc= z7HJYe{9#5?D@e=r1(zt$J>IM9gs*YG5lR^{x3tNCdw)W-tC>3}zxZ)0g$d8|!wcsb z7*B?yHnN@Kx(kAA3AuM_p&D;sY3j-t{+H%PpE< zeTxOx%gd(PQvG7KH^ywYR>!K5#t`6d&hFFZdVWwI3jYSyjc~kyH|4|*O>tn) zuPU$uVX~97TeVJodx6`+M_u;Usd2O)B^%)X{t&n{nD9X|eXTAKyu!H+;a;oZs4q;- zKn!5WXUSimgH}G$(L{k0Z^ELM_Sb!a{z$~P)B6q(#HY0Wvv&|38=a@OHD4|-@f#AIxwo_)C#-;Sfv~RfK0!c6p)d)A%nI^vlk2I6pHE*|bWNm`k_mPLT#6h2GQ1D|7*LBq70|jEBS{%-L zQ1=W_PIXNV%HXDxV$21L)9NT#J#GLee}3d9Ee?JkOO1 z4NW2l$M+~3 zxF;wBR{yhepD1PNIy7;I2oyBFh|+>w1X5(568|}xXVICN534hbw9$|NEINc5h4!ZS z&rQ>1Mw^RT#0dUIEuU-9u|ymqA68eBVo14y;M;`P_+etO?gSIze8{~QawF`V2pe7o z@s5q4qEyOoX zmcZ?qL-iJ_e{OF?K=KqM4bUv&6a;~~FA_h>Cl2`y`=6~(9K06U4U&@v@EM$G0YZmy z#jor75P1s$wx`mI4=775-GZ*8+b~pi0?Ykg+qfP%z|v2FdLWwHWtQw(yc08v&lhMN zG41l=Y~B?NP~_|D1{CI$ttCpO1m8KR`%%;FZ#2| zNK3CZ1yuo0EU$BRCJbsPAl4lrv!Ke=%wDN zoUjn0ih^SNw2eS`H<1X44BC;oN3`z89D8i5K`iv(5aj0SlG_^#0q#YXBfxeE_^6hk zE~Rk}1eBe-yZesFz^_O;XO&erSH)}ywPT>5$AnS_l#>w~_*TN1Hv1YQ0LQJfiUinQMKWf>E;DNI@@Z*l`4CNp)MD0d{RTP$UeqCe$_24Dn)^sqy?DlB#t$UET8%c4 z(APvl3@hp~U9YmHL{itZ0KwWq;ad%IdR@?-ZTwBDzzfO5TSqVz3Qf_jyta$Bf16_} zR+-qROY`6n3F^%|sLMjfYaY@9Ocn93)_w7EmpR_{704g>=hf+Z zUkTJ@bgHTl$zVt@Fr9MrgJC3spA~#bd0@mx_f!BA2f8&pk+X1v>}Kv z`&;JqiULiIu|aa-S`SqBw&m1fNZVBGJml6W^R7f)2w=6Pwso5%f^MV$H2aP;NUvK| zrgy?>3?YOS;Yp}>#vo#L%ihtk3hWBeEpdJch)5m+)c51y4>FTPgD%Xb5KmWPm!VbG z7Z&v|H6~jG*k*ndm|(-@pd~r9fggYjbcmf^yJQ!-MyVJOfcTV?)0g*?R+j#zb356tpmHtEbvl1>Ad|Tr3`Dnej!!@hB_|RXlZY zHm;kl6YB?eCvNC>{X3}cD!T&&6bP{;t-;Q)Ixv7&?L);&UbP`4-Ur8x#rDfidc@(P zJZg=Ya7aQA>C(jkbi252@*Y&#t3ZSEmMYN+oiij;>z`GB?iBdopl4NjphgEkg_Mwa zTMDtW!Se{T*BE}kBr`bzygax|g1Q9+d1i9v>7T6m_t=j@Qq?X;UB9Qy4e$HM7m7!IyeB!8l7;XbsR+*^iZ8u`{g0xjJc~8> zs^GjHq}R1qMNJq)XsP55*Ev8dIV)Ss8p~oI43GV4x}f&Otq(5cdVx-z^|4>v7_#;T?L&&MT#cA zf*-5;ASK01i9EnjU^G1QEy~JOPf-0a z$_3?Ev_SaIpl?SKq!$8q$v!^Z{-Mxa_q_$?sIdcU(dm+X^aK^dclntKN~Dq_()=0a z0Du4E379DgzQO_S#RVMN`^34usP8b|76pPZP8|*}S&T>8y>g3eYb@h)eGQ+Xk2VMN zoEh6L(*!&|AvHxEx9J@4{MNz)Z`zRRFB7yo%f_k$nCZ_N*ZW)McJllrLL0*$F*yUl zL0XlWKdUrwpHR}P5%!F$dwur!)`;HL{j7E{Do&8w3}le;bZ_B4P$6b*8yxxsndUMo$_KPio zmx^5$h7jt2L^f}nn|RM4?M^&WUWVEP6xLld#jZ<}#JM1^qll+x0Emy}FYOeF;x0T^ z1tVc~cNap_-MJn6JytGkMoTSsa0+~0Y=*r=vg9ZWNbFa$*45QTMTSCwXAiTddhv6!R}P9b_^mG{fm&l#bN)m0 z^AlD(@%(ifnn=!Pr_OBRtb0uBMoC=L*~BYd>p(g}c*t-|@5Q)26V5awct9o5q6q5TfvYAkX;<^l~8 zke1t_{kH{Cu#^PK0fn>-oVomo50P*$%=gvGrf+hf?<=?a6?Ub88by2tn@Q9%ybkDe zjal04AVetjV;0Drh=ymzi*cN!!NPBPzCoAx0ROvDBEm!<6}VsFrN77r9%aO>25|a0 zL}v!XktJsJhp_>8Oeq+Oyk@=Yk7u!N=+*dquqrXPI%DaD*C!4o*&Tcfa6d{2ESDpo ze7KioSy*QTJmt9&K`)oAb{)^v5zB5?YT3Q}JP*zN+y?^N>sbOPt+Ct!I&3md<;u$I zzlCJIO}|PI37(RzrSxhw zWvRnJ=GSls=sW<_?)f;@tl{cBYBm(Zsely&#ur+9jn;k_pv_t2Qab_lPzZ9Qq^)|b zRaC-5fwC}vUY->CNq>&Q4qON@Rp1C zfU^wYfQ9;{Wot?TzG(}QTb;!YGJFxEKS*Tyc2GYA?F=XhQDk8{<0XZ#kYv{lOKUgn zLp#zipaaa=^ePwdu!xOjL|g8Nm9pPrz9}?pT!vq|c_YAY%p4O>VN*rzzRxNcKyJ)M z&BWsn`_rbGFaGGAWdjvGFVq7a5=CF6Tpt9rXL{>MOKWOgpVkr)Xc8=dC^=mk?StG5 zC3d%~H-MUJ{jFz7MId|_Rx#z=C?M7zAxUJh)1f|-o;5os7OEt3#|P!Hho|)RRd$}o zy7w?+1e*45G-Zrze7N{1_U#ST%2loJg@E?CgasvA#h&T~uYNm-4I(A=o9%C$K`E{q zkX)FIZ=4@SkQ%t$2R_xtfFA&KVs3C5%g$-G(N)e%%U6<&`Xezq2m9W5RI}gil&Rch zdVLH#r&%TNS@lGqi^(WW*;6+o`0=v!M)`M|uY!Io_S~4fOt!la;NxUgnZ?FS%;&a& z7_7eJd>+&TO1IXMs!>@amare2e_PK&@XB3xer3(Z7l;k+k(4F91G|ot)cT=`Ve|FauEF?I0QAz+>t+ zUdBDp_=4ZEFT|b>F(V?J>pNM zABnf-3PM6?%Hpq9T_1pe7yxjZr8)Sd+d&Pl&nCQG2y)y~V0C#9Z|Yz4r!aYP4l+&m zqW=C*_bwq{I#Ro!eVEwtN6e6(V4}f(g7kFY? zv63%0MXEgqI=5N!%q#rMIhQ3l3~VN|5^6iBGZK(>n|K>gKl&#VbrjBNj$*SNY-V*m ze{bV{V@86nv4arTC_}Guqq}F9E?p9mlssx$^}MzoRa8Gm&Eg?z4?On(qKAnIwV}i| zAcoxnSTRuClB%JfKsQ_!(7iEco>suqw-CKj5f>y~sJ1{uON*<;6M;^|4DMik2>Mm_ z*CK>X6YBTKh8Rs_?u+Z3HwyH9e6pl_G+K~dG_KAlnCx`dF-$V- z{7FtxDN5{EHN5FFz$KBp?y>)Q9nWdOT-gv#1K3mM$G81J=z4ndW6Pq8_C4r>+zwI( zh-__roms0q-*(vG>%V(49H+Zj0vS{5)rs&Kqt^o zpzs8skujC%zLKExmwl6tRv6R!C?QPecdBcC@Z32?r-Rr$avmZMSUrOlI8z%VeQe``Bb4k-i-yb`~qPpJ--bZ7{@~q0&J&Itt$o z_Fr#H)uvB(ZA~5;li7ADUW^yCB)aDmj=%F8irHR`VU})y^H|(Fldhd70BylS?*`>{ z%{;4Kn$nq>9d*ICmKLOFdId7clA}SHs^tDVv7HCx*>Y zaiYx6(*E3)Y48zu{Ezg4IWe)y#W_P-39RvrjveOW(AXR=#92-ZDCe|YVA$5xE-*9v zpcSo|@wN1|%9AO$;L`+Gd5xSJ=Z~N5)iw?F*~&kWR%E4^T#L0cw-_mSS!3g@`b_SDD4sy-pawg{12r4Q*^bP0pe1;V)9R zZh-#kVI&)$94G-U8uuq?ON8u3p&&4ne{af!JOZ=^D$sQu1U8}GeO%jFkW>fI-HQ>m zN+oAp8fq7_glmD=!UzOci_Q%=kx&u-%v?2<*}BnqO=^VtwO-b}_c}{6 zUEO@M%j8@;bN9)Vh7$cusHt=|S$%wheZS@ITZzb-GSDdyTEZGvVU?z>jJUex9Y=&& z7D~-IM-1frJp$5i3RFgjl)s)NLsy*x;KH_kwfxmoy(`xY7RL(2sHm$WM5b4Y1uceL zADf*ld_`d|MW$ca2dL*zPP&IBUffyD=5?Q&$@Lo?oTL?BTofLQNpBiOXRG7WTi54P zA0n-~1~br2KZH^vI&hwwdwrAy$}62aYwsRG_g;n~%+sDi3LysddP$O98eD_zTh7g^ z3=r#Mc=AuZDmKlfnB_#C!u7c|$hg>jz8=HsR1@!cWu(kNFnfMnanzxVDzfjsq(jE~ zG6l-oAEpKW8ve*;9u1*QQ#!5i?FCVbj{PWYM{(@M2UEZ*6@xAQkQd)4I{nO0cX!|< z8|Z573MHm*ucaHp_ME5Mwrb!_h&r(E2%j%xU_s}W;kPj5ES$#b?xb+TsNb!vR}Q5G zT3@fguw>$%0`;zZ(H6k2;t22GO$8sEQwK%vhME3Vs&5Cj4u6pX} z=^eExBNGA=E4qh%p@jnljsz-Px|9O?vGWlCutHwg`J}5YhdvcPbsLk*A+rWEUv-6^yzYh5%cg zKe__;oeF~Jz%SMQ@#cKq;DRLlnUJt>cHPRpCl_G}G6olZdV&Yc>kS-xa`B5B&GobF z-?#3z$#~vu^~wt#QZaI=$jD1zICwm;L1z~hXZKmi@v-7^e|1^DZ9!pJ%;{T!zJu4& z85v}xd2am3Z90VYR*URwH~nRaGAFUxZVUSbS1NQ79XbeIrwr!m@gL1xD02dZlkA^3Oc z_Lf7WlQH6-+CpV0>>lm1Fk1Qb$-cbREy($zAg!T}iCMPmb!Z27VxGHNQhHFhHCRTj zCwiLO=cuP##e&m@(_-yP-yujBUo`+T<|UxFaao7S%3kI7ebevkecgYMR_fPt-^cR{ zZoj?8Kl*lig-?k1uz1QH-7Nk{owS>9V=#i^Tk7$W!*eYiKFY67oBr5NTk3geS>Y(U zv-ibk<3EgmJB@evJrWp(xf3SBuv8)^bm=qRw_f(QnzZ^kTyZeS#DQ_Z^>M^*9}4|b zy9=8ElK)({BKpKDgzG74L;?;+IoN+B;`F_Xt;5~xvp;u3FDK2_J^P$Cd+lXU&U16o za91}ja1|_0XT^mqQT3zub&+TPN7Z}B_1yOFp>p3iX{$MZOA#a=~) z84jCmSbzSM&wvO7?H{LK*WdVXY;vl_dZ)hZc8a>{W6^B>HfBxGW&w`GaMLV3q+ZH6 zI;^2@Rms(`z!Bbc=;3iqYxXxwx3O22eNJZ>z#o&GAN(}1$8Y*DZbG$M>rMWh(%8@|Z zPA*-aeUbiZW7O5Xy)}&XK1z$gJazsR5pIW;o9f<+mvJzcRR`D~OF-b%PVHzl{ZZCpG`&_&B^4kv0<{8sl7CYTj-|R>~1hH*Qsi%hr zC+`xyWP=lH)@rUjk%kf^wY_y0q56w%h=Z7m<<*BL!1J;$kMgy0%e%BtzN@d*RBctJ zdN%*j+A|cr^;`(4BzfX}ZpOcP%0r89A$0VuY836y4#qY5edZ9m4V}KI0msvXR7BG5 zxmy>e+5wlOo!FF|b}8lhV~OhsSj_QP_H}Pj3Mv<^3jk`+oWyxj5>=wx*>ziJn+4Wh zb6568$@N4b&5lZEXQAYn%32s42iB%tFHpGNOR$HJF9U5UL0@wxtb*G_YBptj_hx5_ z`Nkz)_sE#)EB!UiBEVi>Kr;p(2m?>U%|d$IgnQ@GC;~ek%Ns1?>a>Q1MbvCTs~nu- znNE8gIFH%`w?==SFO`}fuO{*+k+|hlNtBurQ%8P`XNu^meMEzBVVpIkpu3N(zd{)| zwJ`j|BHX8B&|7BX)IMDvcNc5(=hfYMlHONa&M1&J=KqSst9dGTSA+7@i-c6b9%f=x zF8c0_5KjB6lLL*!tN`I5&}H-!^Q%RO<>Q=O;*K_7e+BAj&6+jEC6Bpcy-abF*}iVn zb*@FfnE3A4_fY#5SIbGBy5V?Sacq-Ud_0uOZYS|}!b+&$u4Njf?fSPIT1I+4XZyaP zHvms0kF2En$)mr%bRul;U~(z%Q;Y7ct!S`P$%C}z-U9xBJ&Sf6WONjc>x|aU(>~%o zA$Lylhyez~EAq1;C?b7>JRL~n0Mt+y@`O~#+|nYs-C9H|^tKjrNc}2%J8Sj-DC-vC zqQ(zeqC1!1Wf+HtO)$W(M8A@opZ*}Y^{(0%vX7)eH+Sp|<%EB45Zi&6(qW`Hj|z8C z@S4&K|FGqTkk*tid2hWg5v{_nEoE6;9CFL~?x-^J(E7QlNvrLYFe%lkB;Q929jcro zvIPzbkAyG34SfCPe^|iJu)k*oy(O06t<_IpEOkE>qpqjo${Ni1qE^^Sz8>KaW4t~& zQ;uDqXNJxcgcB&D<{&f)#tn1S)pH3LZm-s#e{NEOi--%U)Vme#vVHtl3pQPRNA~OP zGIq+%T9=>K)yeg^B7XyYLiyt>(H=@_bDb3QU580{iq)U*JC%M>Ud3m}H{r+l#Du%* z$!UZwTfTg`J%lMuX(MP;LbuwqJN3tdkN4Wr!Hz!{KBlYdK{@9w@e9IBJdoj$sn^a! zjY)qPK86Sf&WpUYr4rB+5^qS0F4NG=be6)#CF@b#?d4!Btc(*9iF$I6_pgX6H~I?W z4-IyHZ78Pr3Px|%GTWsSVIbHiwqA|a-q*-S#HK)7ZId<^JNrEnq557B-5&GHSqy{6 zJI(DBx^=qN$~u+@jW;RNV+`FEXWPZh7NCfV?;9bcR`LCfT%xiR$MeIO**1_5of!%O zAS34-v-8|#F*EeiTH%2v(=nlDohd#1+4RA=pJzfNYc~~N9Ey7Wnf}Uz@XG2)*EZ<3 zSf;;V{cLY&z+b>jA9E(mFQ-74L^;jDGsNO!?u0G4NHysNh-K5S*m&Cy0i=z)V#E04 zJfH@Z#h%D7?5qMicp;K!wtYW)KG{R=Xx$VLypO(*cxawn{)><2?O#=8J|odh_?T+m zeYu=H>b7Y9_zITNdbNxKZ=TGB!9vSiH-e&TQ#;ytcCdZP6Pwfm+wLr%#_|Vv-6C4?fl;_6xj>#-3+)hWh43`wz zrY+98FItXINQ)KwM3~TNNbKH-6Y9y~^OMa&UPpeth%p4xm{?<1@ikkHpipEEDZ8R^ z#qJ5E%UqI~t2EFfTWxsT-p=n!evbYIZxE%w%lFm#_r@z9 z&Ym6}cr%X@s1t50-V^=x8SkVP26%=Y6>2+)zK!6db}#!8tR5-}<)!w$KwVXTE#c(e z%@5z!X$}7#zgTeuiVbeo7US81~Pqy0HUfHjlCY&a>sop9m2=>{O2cNt!R>sURs`Pc&zi3%~GfdItv|uf@!wq%<34 zr^Z_$njbkcdpRKD>BQ?>$sQK}qQirp(ej}7<@ZEa$Ftvt5^r{m(=C}Osd=B@?Na_) zls!?x_M}T++Sm`zE#fjP0SEc3j}Rog>7t8oK3SURI%wJnJpD1SpY-gX3D!i^D3(9+*b#(Fpm#6)-8_k8aU+Ch)-D+Ne5{$*r*0@SMKoY^L62#DLcGKf@fmr<ZRqNa>?F1)4e=o zCr&G-@C}TA3#>o_yl3)90~kI zy6Eav+jvCz)`3A%JLLWnNxV;#5;6-T-lZsXGK-SQ7&PhsN65O>WD&7eX}{i7c0iv6 z6H%vkf|9yP{5K@I$FP$=AO($z1JdgpUKkqw0q&w@&cWT(B%lQ1md(MlE!_Z_6WHw* z@X|4W>V+&=Gk2J(;_G^9)~PT^1xoKw+heQHv5Ll`Ry3;@yXkQL@c(K`dZ~MVa*EYJ zN8gS2A0o#17{@F@dDot5B;3g#^d8!O&>gVT9^;T;Xr~B7@ByPLY$gG~Ki_&di#;|iVXMSAVB9n?91au-`p3Hwk|CV^p%x;;X=r&U7pG|YaBPA10x)HyO+?}7htmTV;bqpK7Z@zB7 zcugCtc^}x()Xlm}Mju4#buLVekr}X?jo17?VAQnVZAjx4xQiClpd(0vl0;%Ga@7kD zUV^k$P(n_EN8lEk#AiIsbA)G)awVq+39(ejr3W1C4vEu6h9jNJycOh&e~#oGwEQJ_ zv&HQ~=l;@xjd>@WR|CkiAqg2fK(}=2dOWFU`1F0|meQ2E%(&izA z9s9;>BT!cDU=i=2Wd}JB8PQj7H(_KmneY0v+>e~p5C}DDG%oVVynTnqQ)@GJ{?c#i zT%ByI{Y!Tz=&>ix_bK0Oe^<*K1%x4Bj}22tvc3vwVi2@)NwD5w=&WH97DrmGKVggq zbWI%{#eY=>ZvhP?IWUuRt;(U_aDINCsDjwJxmj0OBon0%Jv`Cp0{b)zI5DMe`O5}C zgc$0Nz!$RaZjgrNGpMIW5>$l@>XNeT$D4+sMXE~{6iQg3U?G}r&mufH+j)UG={-RC%)Vfi>Xc=lbx2_tZL zqcOJ`IzDxh5o=Jl{*f$&B2rwdQ4YzWS(+gFH(sZn&_NIPj0H4`V}Bjl?rrzFcZWq{ z51A9{=^a^=8N6y`b$~ASgTjq2X(q{nE~O@#FcO_{1d74W83O;O`-MQ#M<(Dw11l7p zLba4@6!30V-NU zbW4Du$(Rm|b-0PTj$mygZ`kto=uN)!|9~*x(6@z=rgaTvlOmPr!BTkQRWzK7$7^nO zKJJS3{IOB9eWU(NY*D}cSya_AUl_>xs-&N1!2(zHt}<-j7hn6ANWQS)k!?8C3J|z` zjr!hRpFf#K*XlvTsI9s??MMfWktn?Zk!1;^G8KnN?nhio#SJ@tN>~XUNb<~`hiPVh zm#VPe0wVNyXkuAT@4rot>+^14%=^>Wig^OjGRMPv%QsNGAoK9~Jyv(;~}p4BSK+ zmxa8wEA?QV7(iM)sCu^Zb$D#&-Ptn<{kOne@*lFN1WOw%uPXl)8A<5+1S|hjwu#W1 zA9s5#hE%4{m0PZ(j_4dvs}^k<-AM8BcUzjXQPehcR;t9uA^ndY zs>L0ra}j7B!+I`x8Ls9LzGSjz*7RgArgGaTai>)>ew17a_aPhq?BEo&GLj@y?~oO< zyef8y#Azy|x+{v&D%wDKBSmu=4U^V2L81C8XJMDNZQx$kRYYc*7PF6{{SxrL>aI*y zq)TzK_0U5ZU#f~FJ8b*>dc2p}BT6ERlyPn9)#7_FdGNQl64*dA#bFTfe6s3X3? zu@+Hp(PI5N;@(y>KLx`)FG!N(Ptcz_3;RsEc8gA2SfiyMTlNmCWpYe0-(3@H^=?%S zjl5~R(C2iP{(|F|+flqd`-?O4=WGi}0T^|f%a%H8U}l=Wo%kAj#6`y0-+%*U%+5oI z6!FOyU-?`#ZlXvo==T@ekxeWn7vDC(~k0Pl&G`?)e*@|;4>z&j=I$=0ui zK_5pitHpz#+RxDO!(BEv^J{kH$`R*8SOsP#@@NI!j-qOY)rl5ghEUngExsK2`i$c0z^oqnmtx8&B+fJ5{< zf+^eE1Zuka$TU6N+O6Imou37|<8Ve6aXxtXuzu3G@(j9wm=l{As8qS=bjk`ao`ZXa zxXf(ztU;^Qt;n)Hq$1mooj8!u{BMJ0#>!U(n$cm6jHDs}I?0i!b=Sw`ii5k3T4PdeCUWL9Zg`(@KN^#2|Km+!`w6{^z2X`lAnLHA}3b^Cb=N3*{`rgR)Mw zJWF0?6>XLQ7{_|gej~TjJ4@{2bB9w$-mWF(+{c__$+epvjaVob-xE>B&nP092p>4G z&hl27_O{l(qpeUN5UJtAm?f0)JI*DA4noc6rVc&eIDV3nGrY#~7q8^4tzvMDW9aDY zK2zpmf!|AOIjyyY;@wMp5`OxEs_C~}oV0vsQ&7`;U#m_n5i*wwPh)Loz({ zi_op<-ht5XU)PM!TwEe2nY8u8uDlOs!{y-*THoPtg$67se5=2AOGbOm3z?fCeh=^w z)Mz*&pY|xa5x)YTfJ&!MVZG16ghsE6)j;4P zwcKl&_mAIKaoI*p6Uz}$mQ5cH{&R*X#VxK}gO}C0<4hfoO;mK1USxEK_4JP?tk+=I? zCo!P;0ouU(-XaS_0g1W7%AG;OE=CVymr}-0Mo<0ne^m2ldoh!Kvb%026E%=Kz(Y%6 zLMIZ^W&eipckykb;it-+J&*5PKl9+Nk;?rH-W-)RE!A+!~4@9Y%Z2a{N+70lH*bAWUoqs@CecA;h_xDVyBhs>AXg4EZ zG)zfx=h?klP*$jXu<^BQo<%n!Ey(BU>O6Q;H@(b}pJGj!7d$!O2XQ}dEh{Bh{P4QU z{YA&&Wad5eSM6!<>{i_Akd7zu{Y*ckk>rrtgN2H8W`!-cuKIXYa}-9e zXs6oU-5>5Dsnl8wP5kUi+hcS&~^YNLHzsWL)jy zk#~o@c!|0%Z0WW$J4(_uE(y>9Z<$`|OuZ9uhm1dML?2Dmu0P0l^{=yqXdlTqDS+V{ zbZIG}`sp$&;t@nN{-2)hE=5iLwxFPZ->x!1B$j`SqI5%~0{`qxTS`-To#QMo|E1v? zAIs}3C2lbztuHNhI=}EE<>$Y=Fy5oS&ku3yxCqp1PI;tkt@`TaqEI~Oe^TwFmhNfw z?VDb4;s;a^CgXu$iTPYDT|KUCzoc!nl9Z+NQ4QGNisgTd2jw5G8r=)zj7Pwb5?6NG z_SlSvph~cgby>O%fUS4y@)n7}|K-DDRrE+N7*Alb7<+;6;hPQag_PMs2(tP0hGLpTgd^7uUnoIAOS;m)=l)vN{ z_%AunSP&3ee@D6-njS9hdgB0bwJgW^rmDUh>1FgZ*Ja|8-4tW)lE^VlOILy`JF>wC)7b!qags+ezF9E+9TaAM_U{2toi zt8D$^@0MPfW9?eHpG4hk>%U!0#;`;9F6Qx)_lF(svz5QzpfD&I{=pZmkKK|&EK>aE z?TsF6@7!J3dmyBwvDE#e{9nLUQ>KpfIoC)Y^0ofuA9nuUKjrit7h~M+yjx5<)nLqh zalF6}L+l)$!yMgtPI_l}zqGNVvIv0Bb3$Z}AXSz2xlw}hf2Q@fcxW5HK47eopvI}T z5^(6bfO&~@x`RKw?Vni&?MSwHwMpNu`&*__Z(rt&dwzor%H-5=vq7nlqA-(ySM*oP zY{aG4Q!aJF-P@a+dLs7W5r~*ZS2PjUQK(dQ`h2M`!)u^gce+oV<#jPIp9|KPs_HvL zQI~UUsR&bDI1k4Qq83dfwdhWyTKkfve6lw#-5dJSVQP7>c{y*mqR|2U?yj`zaYR z-Um_#`j60a_n>X|-XFDsFES!<-N=8(14MQCAB=>4POv*te;ngIowLPzjk)W&%FplH z{1!4rCue8F%a{3foegAnb!`lGT}re6zG@TpWb3<}?FsXx_e$NiB;QmokK{OwJ<^j{ z#PW)gvzfSRW+JLumjyPKJ0=>}K&&D_c;POD7?{8lM{g+iw65q=eD$JhG!1ee@%_|8 zZw)4}*n^qNfGFuP4<_&K?oMD6^v?c0gM;RF_o*l3_fWR)+UJ7r^;dXDJ-44x+s+{? zGrrkQo`Fw6s<_~iO3Bo)^$9YP$Q|>)3w#>PAO%TAA=Hq0(=b+vfof888x9J)(z;Qi zwyNqJnKK{;ghc8}EcrG}IWc@($#5C#thQEX%&fazg5$oKWIJ=u!fLrlB}p5G%*cx$ zh4aH=kymf26-~Hso^BXsp?d6Lt?jp8do$1!6LeeDMD5G6g2K%LzKR$x+DHVpL`6ng z>e`(Qg;8{4!i|s3?oEGPjO*w31V1&48>1Nbyqym3;{4m};e1W{|2@DV51FCFgeH>{ zD;qDktj_}CHS85zkNY_aYtEWC*?thdKmRsSu)A-6_V97TtTy8XDHJz#*-3X<1?;bqtm^MvPTev%=r$&T~m^88fQH9XR_GQSg9 zIu_*BH=n{~v>EJq(sz6Kcb(rO&+3zOpX8kb?0Whs8)ggK>h9s;VbA_?#DSCV&SUBI(#pB+ zs;9Q4j}6_|N2GmPNXI|nN6lEM*ReWI6MfYL`tTA=kR`&$@}fHz6DqW zECHbmF^(^oiCBLZ$lI7Xx6-*IE_wUKg z4|boHP)+CRX2t8ILN{Vkp*m7!3-%>~l5*4v>fMOE3?k5*(T^3uhCg1fPn^{#e%bDY zrS3eHp0J0JnUTE)3$vN1kZt?F@W<4QMan`WWYCp=vSV_ETMh9wJo?MtK*;5 z21Ops@q%yTVUk|(aLas;LOe{jjl-==bbE+ay-i=xA`&Hn`z6_9{*xsBYB~x}0VsC9HW{L%K2EK*ez)4KhI(#MM@R=6}wyt_B zweet+(N>HSGhDXrCS%ETL=CLwUe(~#*PX-!KrHt=^G(3*AE2ISM0}%Z08RmU&13hm z1XMbc6N2f-^}4yD{n4R}zfT=;b|g77rjAPTM$_)kJ{U^Ye9z{1rX`rAdF#B}Ty0g= zF6=Idb2NAkO9dwXSw#uIpblh>Pj`BkIztpM{`1LkGJkAgcVvGCGRkxzlgv8et+8dU zgDGB+2@Uc~#zNOx70uIzI}D8qZtHCkL%G0{eejYcGed`U_+fXTO}0ts_)fE$^Dd=q z?|JiPcg5n{lx0J-LTY>`uNsh>+Jp_)e}s}YSz2T z-3nqioMufWt00HOYn?SS;e*VYy5=pm=g$k4%(p%M&M7G~tJsn=*ng9fV~cuprKq5-t!ar@m zlF>`o_XXbvpikb1`KnwCj-}Add(!W&7{DO*NV2! ze_bU>RV^zSO>z$H_-_SeY{TI%9q)L|fxXO#1Jyy({T!>G6(F--R}b2kQD(R)CBlT% z5+i>q-DO_G>ZKF|(yU~T)got!kWS_S`h69|&Y5uYM04#WtQ@=Cy;}J3>1VsrLbRw5 zbG4K29t(}DN$bEd1UdBM+cwS(%-gR$)CbUTMw#I<$$O$-;{e1syiC;CK?~hGy^m3@ z&5;~Ya)rQSOBchi-jv{X=^*50#v=Hv0wPAx(h1Oow8VDC(y96teHe}CuHqJw$z2rR;KR+R=U*&NfLnegcr=zQcr@x7je6x-B zTJ_}Y2_*>rQ#K#BxRheRgP1LdL9#YK2aV5;^bskru0A zKgn`4p@Ej>W-f9TJ7J#o5U2as0wU%tzdv547NaB$l(Ytd$U$u z6U`1W*SIF+e2IuCZ{ntq5=1FZ*tMCSYDLXPtfc8yD`2;ew^$W1ldGG`)66+$TF=jG zFFvAs4`CMh0Xpxbts;!nk>^>ARudRcLM#L27E&D^#Njl!|9X4zar!xq^rNhHoPUl} z45-WVQO3x&MG)ToO2n^&g5(jljM)M(lSl(l>vV@gpPfoSRNQAS z?8Elvb?mr}3#ppp4KD;~H|eo;D7QP4$rd&ptE0KoAB5VX+qY9yw*|I0masukP+!H6 zsgLjRF6~svN^kBf9Lx3utW6*sgs^yXCYncH!)z`GI^{_2zsARVk>vy?2+(< z2?mPi@AyxwlVcP>@_7;p_L`?|Xf?>Y%Zau$9wPux4x3Ce537oN7sS&< z!*;UqT*HM`BZQS&m@btqA-29m=^zRv>W=%u%E4o46C*s2n;R2($~Uf;f z7bnsil@Z;#jPOYY;4jsS3SZUa%nsLGX^-!2li+qC`<+N6$v`39TLS)mnYRkWDZX}r zu7R}&HqXZJwu$@9-~PD3i+74H=Ru<-hu_{Mg(PGkIV$crzt7Q{n6`#&4EKXl(fGJ@ zydV|Og^~AbxzLO~LNQFA;c7<-(n-9Vtp7Ax*f+0cP$;%pk|SxFI#!8phaT#hF?T|e zb)P7z%4?tLa5-zNyD+-|WXu3=uFZC{=rTZ5Ty;RTg7-D)PhzeXwELdix=O1Qk3jwW zCr2EadI|8t3NjA~TWCV35}Ouc<3%@ZBvx)0)6E)fN{05Z<{nO8GdDRtUQFbR! zOSsy8dpH(xwXIvf9)zR=-Fbm{y&;gN(+6DGIilN+T3(QI+!yo@ncyQM0^};9n?Ii_ zl#mB`woAF`&z7asWhGzL$$D0&Sh5E3+ZB_a$XjBPj8p~)FN8_?_zLY**B(-aBM6EN z+Kh#@DTiP&HW9PH|7S%)Som$*JUl(=^eS;jd~@QV0q8CIWlh9KsWsb<_%~gInKsni zMD&h&s$_bk6Vp})NCu$uqZklMhO0_3e2dAjwB?A(3d;5_%0utXRK=v+Rd;XDd$$Zn z9GYhf90z|474q^O# z5*xk87TrKxBszdb(bc#_y0hu_>4l75$j_-_@KLJAso~fa#QvGVx8Gvu;$P~@VMz(f7%%@cr(XGu)sS7vxP6IV4?uwOXL*7THjN7;0&j zCN`=cM!U*h>8ytfEfMGA@hgB~>K|659HR(nYWpk>m5Of#T`a!(Dhnm+{FpAAkn4wI zobj2UlifJykj+{a^)obSi?x5qB1$g|zP8zWyAo;#WyLN{HCZBc9i9ea$Ah5YQZYqj zd893BPT!8%k$5`1Q(c3Lg=3w>0hrzf)y}|I>GZHsbc~(fC`W^ii5#Q??NYe$lzrW% z`m_OaCtWwc-=OvCgSByzb3G=n4ZCY1&b)jBp`QZL$Q~I0p3jFpNs`q_iK#R-pk#Gp_IBszW;?Y%vb@jg z9e(i--YHeuSFZVqKy&L1dw$q0_s2*${=z*QKgL2?=^dW*f1}RHNb!2NVYV-%7jjtMN&8c*3?H=o$ zDpWe5Qq#3K^3**Iml%@5e<-iup#?j-KXa1GkekX+Qx$SaKP^QYjfY>*ND z$7kao{9F{}GQ#C#cPW=$tM7jM6go!gra&=Ep)mc_&_+kVR+++_;ppSm6eDjqlx_UQ z^MRz=kKe7>7tkJs+!;ER&WUAdLYz1nQW!qo55-MuZVtf(T zQap?AZw0RsbN;PId(*x3+ke_?n>ymPtOFPL|JF@Mz?m_}SI4E6qKY{!e#i#Zo;w~b z#=`3f5QFw$=TDYG7YFi*v{TIm?ga?6j7p_Y-ZM#9b;!N2U&^;xe4jp}*P!X^*{R|B zheG*18NhQ6GqWGyi|bE>nw8hPG|2)NXi7`#g49WD*K%{q2RLcm??k@F-5dl?issnK zpX_ofy7F58W*;(h6t&J^c1hC9;-#jM%&olil8CRw@v-H}aml}Tyim_yiM6|22oJC0 z_0UsQeG`3Q^n%e{Y)R_0{86fdsrY|3Pz+L1oH8s%q7KG;(H`BBmwcm(P zb5i=nG8&i2jW7(3H|AfD*GjX6EN?b`uqEq4V(#dJK~ro#c~1Y`^p~>n7?mkMDf2yf z11U)FnItSV^)FJAKIkGsK5x^r4^&cjw^BcJIWS=Fj47>X)o{ft?RPFw;@qw7D%l8o%%*7GpOtp5Y;M9YdMbzW ziZdkEHabkTgk6t`$7ML{>|2W6m-|;YnH>MS9KWXHTsY*jh zNtvw_ZCd?&#Shlan*;2#^HA3Om+$H0vjG#A6-m4ml-2CypxxIKY=7d-o70sM+*keo zKX|JxW#8PuApU-*B20-$guFYCtuNjr}=1 zT0ov`-4XnWnAm#UBXGq1co37^zQZ|ZO(x{e4(N`}K|P*&v-4y@+W5FFiCya(JugAc zHPLtDTiEG~^(snA)y!fomoK_w{P(|XK%#Que}!8=9!C~``>ono9iL%Ru9hbn_OMSa z;c6LjzI;JL4#gc;yc9=8y6(S?cm%nulqQC0vTYv*gLA~6(8e@VfB5wsE^>k`cn#L% zG#T%VhZ#1f*F13MROcy+=BX8Y*_T|OXz%;Geplix+w)`8_zz9pe7THP)H**EhPm0V zNs~CweGSQm>jC#uwATL%be-wKxoQjR;dMn^edQ6;JMoY}@6HrgkX|#+_N;-G=`j>kj@e-+l z>ngFN{-(ZeKZ9hopw7iSRQEHmo~LDe1$B>U&eeXo=09oO%l&|3;HQ#HteHB384INh zpxVP;Gr;0ROuWCt6g*OS++)pGgkWQFncce;;HnYDqn*+U%+`1IR8vnT+4IY11Z-I!XHh_NT5pcJJ=T70K05 zLJVfeT>H!lVVn8-MsPN?p#NJ+?HeYUlJNQYl(6)_e2NOJU^Dfn-T6EFSStKT{(3|!@@!BI(z7cfubX#cs>w6Rv%-`Fvx@8T zJZ^y6fI{sJ!0_*A>y{tk?vY4%~8 zYhbAKtX*-*VxSvmq{8ek374Lb_M3wKN=l+bsz^ohlj>SpF{0*8#z3px`g?nOn{scZ z;HDZQiAtQ6D;INS`eJ?k{4^q5Uk{QBO3&@jwX#xXUa9FoPtm2O_**w{Q$|%MGP@-% zYfZX*JKeH90e(h8VR?AB&)H;p|CSLrT~ZC8I|TEwq0gNc-xzn7Q&E~8tJWFrlc_45 z8VjFTO4<&DAp8FdLDR0%=L+{#)NVc9-MI&ZyssFWTqXy1s=Ry)#$$E+wT) zI4k2jgvQ>hRJN}0I$|}H}keVrQkc51SHd>$O-v= zqL6Xz(!lO&6d2ch;p5s^q7D#aAsUHqU1es z`WoVE`)P3w(MuwUu~8wNv!=tIrOlL#Hk1+cz1g@gSYU$DazZ)=3lCU3maV1YB zSSCg{C%s(@gs*ar-ey)-V?d7A+TNh~bZ(!rP1<6Np25ckbNTA$9#|9V)A6Wv;RI z`WRFjF(Dy^bw?Nvt{x5O#i_hv4s#Fz0fAL^N_f<+exPE-H^;!&5K)b~jx9L!) z@t#l=Gbe0y)pW2=amxHzw#ewna9PQJ&3aayzCn%YGJo9G`QiN8v!oP@a~Nz=M+s|F zc*{j5*ktzzue8(0D`N$o5UV#x=pTS+g6-SQ>kJ*((XJ3dg<1d)4AEKY5DEV~YF&S> zp2>uo$=L31Ln5m0c^5ka@2du_i9WhJx_LM(pnQ9diX>F3l6N@iaZ!K;g756}T;G)HtX#E1W2pa-b$H0;4O5|twpdZ6@VGz+C z9vT#3#}`OgzJ{GIqnT&?AciM3;R;lfd&>s4*(xR`CIW(jb)m;SZGU$hC0PQIw;Ekq zQKpT&D$xE~(iU00Ulya4788T9HGJTw?^Zn@pKh11{&{b7Y%C1~TgaWC0G+FFG|uD{ zYb=cn{$SGfE-mnEB)Y`*R|86+)wTYFYM?$jUkGI@t&N4 zA~qj3Y4(6-k?fvG%%4%jt?r^y#5z|URQYkO6r}vEJes(;LBzPK@b}S`_;+R#J?yd3 zWAw^+r2K+Fp3TElvHF?hp>4g-O2cY6RXuM{4)52=eJ^`N!>8rFJ!QXKjD@1DDq<_p zwbVUp>Yvv7ci+a1%nVN&h|hIv%LZ-U0%ak2^IrA+wWz+%l&;}8v?D6ZV-1G^=Pq1N z{*HLshe()v{J^c-*#L8vcv$NS`VSQ>y5X9JW5|Vmby4~S`Pj)J42;X8LPF%whI|9x z6`5vQAHZ9mVcBk@r;U_nLS>@TB-uTD{`(meF4=IAeI67Pk3viQ=i+1^czw{07s<*j zz_zd-G)oO`(P1u?#Y%FDTZMEj=KuK6I6S&6{xCCRp8j^6P#(Ykh|cRsUOY$LjP`FkZx62tE4d1kP>|A_j4_hp9C9T_58r~D3rh|qkqz> zJ$MsU^2J%?@ecV|F3ru&fVBVKKnE5&kPm7rf+U&yky6)YOI{~W5_WoH(M-B|voI=@ zGUqjQ@Iq%op;Tsj2LCw$@3npmaqqPePl4Vk8`Jv}fHrObCjnz};pMM8t~W5!iR4z< zl<%4YF`9dikCI^W&NVNeJPE<0&Lo);qh_sK$K)&Xn24?>hHv98h>zIwQD=iB{3bOwlkO?bZlEDq=f47!+ zw${p#9*`<#4X*!Yl~}pe^LUqi^)~!3RIy}=SDufsiovDG7X$y~RByp!-#byd_LOHv*!DbupQm*7L5(GaKEhW& zu9JqI-(vzyhNglS_j!El{pDQuE>)?_MBDU(7q88>Gu5s?@xk}$(@mRPP-Ez zqW{(8JN}b=xZLP<*~$dQq~XBM&p*JW*A6!2PfYHCfAMffwTOI_XF z{W$O*6WGBDWQm| zLECTM`0j(HD=eHg9im(&Uj{lcb4K4t>yxmae$qaoEt=pTY;^SB0TekAYqx#;@}&kt zYUU;tq%%ovgH@)|m@gSdQ||9VLa&-lGJmD4d;*KNjYcnR))nk)D>jnxPxIpI`fND& zT*3XHA&UFhZaGvCuXN7#zhCYx<|es~gn^TTm$vT@-s3t=6P|T2TDa%}hH~XLIyXpt zfBNj1q1Ki|S5KW9TP`73m93EnL+6NzFJI0)=05TbcbA{GmIxx7{E90k_13p2vyRvZ zcK=iN(xYfMbqV2gkpkUIpuGhCLeC^_%{fil?PJJ(B z?=tOE?)5!hu})?;Jw1Hs`t>Wo?4B_f-8zWB&^!hTg9^ zF>2kh>ie*3hL{KM3sl#%X}bZ1Uj5c^yWvKOcukg_@?V+bu$a_3Ap)3cEnOo1=sIs8IYbyDVXH=nEa6#%h5N@rdw&z=(=))K&h$4n zHYzGB?;n$(J;g!=)OCtcX8%=Y1^UI8GZx;ubq&0g)%RoYQff|;vF$mRW^USczX4lJ z;S6bXx0ajMVmZd4{N${YbQt1(>iXielG5RLCMO}Xy-svU&f}l7i|XekDd#xd7uHN8 zX?#yXKk^OT+`ZVlA!zGTTHe8NY(IQWlPLj{BF`%?oAxT4TKgG)54VraVoE&KebKGR z37f*MT%`WF$>V(2SroNe9{mHYIhyb}Ne1+y8DWQEbqlRw)WDa?)iacRnP&X^o( zjm1x#N25k!iK3$7&y>)c?@`p1UV2yD-1Oqkh|;7g=QY>G1KU~ zA6iM8$$Ki!HbtUo3M&;uKse%0!*%qn0f&vedS3u;ZFpDrWb5%WjD@6EbekJdAe~Uy z9~FC3k#7LrM9dlvgk`PQZ?VV#TONw}v=h((J{S9EZ3DAWrnnYI&?l3ZU+YlzS+>gz zwioE5V0f3?29#(Vs(JRhSHRrxt=dO(BOijTMp*;|?qlzomM7aE58Ita){yn=wE>1GN8-!}4->rRERjAH+|fUQ%%KioU`MF~-?f{a3}l*v_gdMx5PVtox*Whnw;7qV0;+@Mbj?))#Y4lw!VV=GUT@ELZ31U`r8U7* z?74bKLOl-s|Gv8wo2EpFPDle3EPbI@9YZ&07qP3>~{=cM-6fw(3JyDzBLp z-ARh-DrbAmb!jYbBCVl$SD5EAdWNn@a~v@!vdHy$j$UA3z)ZXT3rcG93ZGZ6VmIy8 z_*dA0obDjX>ca%er=HO=A)%??LKQWK-aa;w780r)4a8+-Rlt9k`-O6U|I>A3ekH3G zGpkeD@etX)hPV(jAb>M82=DwkGY{?jR@{{(2KyoZalogqCB9nQpPDi|sY|-; z_K%cOOv$e0ly%F+l%|NZ=f5{y4d}{N#_l}6=Q*%eSS&jtV z-V!soc9Dmx?9-=%@l$=ZN<^7yS592_j4EFTh*`ew%|Es>VcDve>#2knzyxcN?c??G zvU4*wTsl8aiM$P}v23{L8>^xI{^@o%Wc7r!)C#1V32ab~IwltGD72>y-vUoAxvQ~# zJtb;t?Hd>v_vOo%q~WdX^nQ8-(clL`o?$s8Y|$dVUoRKqg}XVHSv~%DM&8nW?Dc$8 z!TX1k9sPS%e zgMZXS{@8eY#>=)*ozNxoiLtAust{ce#t2Z3N}P)S-X)27%*Cg5M zphhUXbv}6?C?KH6vW#B+-@+dbpAuhj{>?fgPX7jha0mxvP_!6ECq{b~ik$c)W682MjiMju=B$KnitYKxO*#NUe>GqVf6<9O67NFmKDo6U@=-*1N%ru_yx7W|jeRe-9k9s@!5I~fo9l|l>|Nn^k z4tT8F_WduBRcKHtp_C$0l4Q2D&@e+r%N|+DPNkl9LLzQS_9`nYN>3hCWN#W|?~(mK zu3PW#@AJN&r=F+o`#Y}dyw3ADkK;H8#DhwTi-C=DA~8n|d9i-^xpIIZ)_QOXb;VqS zF*q`P%aDG!PWD`*!O(|ZRrUDK8Bs;J(A~yVUC)>WHi_>TQj$(M$4P}2#wnZpIGf{K zpWRYVI=_95nQLoO-@N&d{f-9@3Moeb_XlaT47`WYs=fRjkVy?V8vZoeKqeki=R|Lc z?e)b=tKNCIrQ5a|^6zyl2j-EC4qO}(a{IlDZk_+?jK&4h&*R8&s{j}WAZRu<86+Cz z8*bV(&(ZmupH)#|iMz9oaaVM78}`KU>nvR4ORPNhf^&Jfu!gh1+4rBq|9)n;-wq)U zue_vZn}jJiGyngInTk`r0qG8gZ0@#rR(M#G@F*tdMg5A3Ot6hxdA3*9&7& zv|b$xcr148D9_b-F4YZuas!MTth|F6D_+)j4wLXD?qYWoqvW!lm0M3r7p~@ zI+^b|YsEDmd>Qq9`HSlWKSj-@j|(lwgqu+qD8{2Qj2>Uxc?FdX0sk>Hlz=)|ZDQx3 zPN7bf)gx&Wh{CFl$AO89o4o= zk#+*$vc!Nj(?#^R13%TqX&uKUNhb`{y*`k0WkBL*(vOhRi!*~$A3l6YNnHD&ycenq zb3HGRZ>@|p{4#8s`2w&0)H-%7j!(w=k}lUu$`dAhs`FPAoO^X~01p(ui35{0Y7EWp zx_2F2pBW1Plb-@XOShIwJ6!!g6ao*+)p0Q;4|4u2bAa<#II=QxxIYcM=0$%|r_-jTdsEp)GzOpD9QIGtp}u>6uW>o{*ABt*jP?lho|3Xs%BVI`!7 zz@RYZ_I%xy;VW{}v@5-JFG6gxk75vLI+`G*Bee{a;9lL{KPI9jG-bCtMXuD_UAHk} zM(Bn&N)7R*Vz2B+dnvbbe^c$JU;-8WXtx((GsXo|to5)uu%F zo@+m|UTO)aL#bZHJkzrEa8+{fEgJ8tJWS@6O6sSfVd@$OEZxKdA=%{2L?jZo)dZ0I zke$JU%tSizaHS#E9^-cj&yUYB=b#I9`ftbg0gmcVn+R+MGqC)0oH*^jes!Yze>Yf! zgSi4EGPo=r(93p=MTB@s_}@6Gy4Ub~Z<>GcJImoW0T9}=Jg}w@9D={lX)1_Bup66I z6a{V+v@a2&dhfSRkR)@*haZa=@;Kx9z3DT@DdiY6$5ne~rze!0ye1=nw{W#G8HIyG20JeUDX-1h6}_gMIo@wqztS&sL&_^Lj*bHis|ag zyT}vSR%E`a?gUq1RAgi)u+wTBa%o74$*dxRfFxTtL}0a$tW}-)*@*%6-ZmB7)xG*P z)B{q7^)MJ`ZodtkfH#PYCk@zY=KJU83N9zsU;cBC#?QjBly(o04OREmbO+U&%134F zqLbAIQ!y2foT*Xg$&@+Pz77#UE>U9$zH1iG%w)mzOSQ-L-DK3AJ9m7-w);I-ADLD; zc0955?l~_=l>VLf|E+eA@&}yfA2U2iO%W{3cZ09~$7P!cp^e{eu`qb35FB1{PNUkc+aunTGJVW@m_bQ)swNFGEO(01s;42(ZloNK1@3I zOr4AlyZ^VVih=5$=krVi`(tXnZ|!^jqfZU&|3P2Wy>M!wr#~A0o3K7mE?DU*5h&cX zNBp?kJ^#o^;YwFwpHfVy2{Y-#!P4;h{H;FAug|0o(;0^?;Kmi|g{L^h5DG?CbAQTb z{uTRkA7+y_z!XmQva5aY==QJenGZ|DZJHtf5$gN*j&ieQJ_NHV32V396XQd3@2LGa^UmwdqYIk&>(?)`ws1BRSh6cfd0O%8>C=7~7Pz@`2br;b zFuP0dBCkQlhq)8GU8{VgBcar=@Sd7vh}y@TMPucZnrn z3{4;>AKoNsUA=lWYTpc6Hu63>h)rAM$fFv@qe5pIEaOCR{fthy)x4~zs3>vMZ{Hv$ zb{veYa`4PgI58n>R7#bm)@}4Ea=mxLkdG}2j>F_J?a@haS7f~=_I@sZ`XNuwSV5Zf zl;`~AM!Ipb@R_-L{jXiJn*P!Rx9Mlvga%5Swb;8^PEKxrj%+3R!RPdh&^f{(a6N1Q zO5q)ezuVgnMaso!U1Pk9KfiQ(J)*Rko)?yq)mdAT1HtaoDs)6Rb;1GK?u_IK5aulA z=Vmj?)^hpC1~}~N+3lN-SrOo&k$&>`I+RdGkoBgf<)73_)YBqs*hIl#-dbRfT|o-( zKUhT|CfVu@fS+~485xZ+7aq;$qw4A;BMP9=k|8)b2*Q}?fcT-C0J^)#3PN+a3U$M9 z3*P^?_c-x)EFT=o78m%z3Be14F&dA&a&iYB$R)3}fmwLw)YZa9hCNHlipj6N z->!d&X_iggq$tEaaxHgM)(;C=89Y@}5n9_LVU+GiM~PiUZ|)bq#@n z(49JHBZbS}-L`zwxv!|($C@0DQD`&f}ZJvU)zaLZNn$Qe1J+kuUz%xsGIRMsGyZ0DguFW+3oFj<_igrd$f zGTRke13*4@L~_pa?fD|kFEF<3oFptNXsEt8LhI<}NH|5{we2fgyM$I2Oh#+tX&mxOnLk&!l%u=3Buo<=}J zF<7!859%{*X@s~`wBAh>ErQHl^Y!SOM44Ri3S_1Bazx$IVwcK6n4kbKb(BKju0*KmPWBuz?pnCbC@#J@XinfNHs`* zAJ&4e7l$3*Sj!n$KY&Z@^Y*I2Z6ADDkoeAfPr6f&HbJU$Gx6^}6hriX-{GbPs@dZ{ zfAo}Dj49=&pDJ?>j%J!_w4{-F;hs14NTE}C@O01J{nx?8=5ARj=?3HH{WK1hMT^Tz zAa^{9#Apga(xp9+-q(CDyoIot9^Mg;lY-DhafTQiI&{eQCk|f(sFxULphkSw9Wj}0 z3%U_8(qMzXBy<@BqDrs%X`@OfpUW5qDhf#i?rcOKuyzfU36W3(AA?l-8Hf%qv1G}A z2WI6vf+O7sZ*r*x7vUCRGNN(A`?o;rWt!}+69Nkw=doZH`JVSsq>)^iTmil>uE}OX zmOdPz2gYCQ7GCcGx|FAw6po^I#rFVh{A`f9cDapPDZo>k%;;^GlpV19@sW*`c$nf_ zjiYns!Byx=MhU^_^K`Nq>Z9tI;>m`&v+r7`z<<5uVuh-G7Z#D7wRkuh9i0FvCiF|o z%4$J@TjcAUNTwh9qY@=4&JGxzw~hkDjlVL`V$qn9h!p;%zyHd@A&IAA#@@a zuH9w!$Ux!;!mHr;AlqUdZ4hGp0|TSbvWX)Lx;81aA=5Tl;%xR7Y3cObOrUAK#+GI> zDtoD0+!SZr!h!R({qEy37NP8fi+z%dy?;*UAt6$h9nzB%=uBVtzbsfZ4Yk^VSFb)z zND2!JcM{Xzwg>md23n0sgWd^`B7Y21pgRd3fWx6N{C6*kgckP^wOLs8(^}iQx(K!d zGfowvT0+Mt5_!u>^!raD+WH3v$ALTzP~r#_I#sy-H1|n+05+u+1FMhd=>-!GXQg_y zpX1D*%NRv{7`uSYq6Mim6F(K`*}ZE9YzKYR4ZHYdtQ&R#byWkWQ5y;iEr`&;r8rLd zdZY;e8m#5q%p`&Ozpo>nrsObaSdR~3=bcBdn$(@DMJQ>>p{N1+r4!~-$KV6wfGOjh zk_#Xj6hfrK*><5pOBx9e=GV~Js9P}?Rn`_#DbKL-d%*qTD16{k`4^P})6ugBw%lpb z)bp^gB6927HKS>k;37(}oF$cRegV}oo)V@n!_zI^0OCYO^l69@YpT*;UrKC> z)oSEwRJ_7Q(k_adQ}N-e@9Sy6snnMjkPXb81}^Ed8aG5YKxQhJq!=_~PandaR}yAh z5zWUFvYH~Xc`yUngd4$7RL|m%DqW|!KesB)zXF~8vv@N*=2LF!U-3ksJs%Y_+)Qru+ zGJ-Iv_ToW_k6gTXv3}>n3oWxU8#f*}o9+0TE+0GcL&8(j3`f2qZJ-J&k=s(dwtqMz zpCR}?mKi*BJvCtQH-j3Bd~$!Y-bc-3!?Uj(YRA-JTCq?ciPeZ=~IS@27iJ_ck~_Hby?~``pDzGKJ>8O+j*0dc`i&x^_O- zuF1IPR;_B>Hn#WNGmz;jTd_HS#PC;6b&^iHNJdY<217Jh`!?^vd4CG8MU||c8@nbD zRMDl>KGZzWdjjdu82Fpy_wCsafpM5aFMsSv%7kYC(&BEMTWHkZNgUx@Bkz(zP7VCY z2E{8#7sfz-k3o+mql|w$*g4PZYbtVq71#1#X)^IRU~&?YYN9hqf%!!;$|4L|hzHfM zAW)*;8G}o|d?AhPnHoqCoKO-pyg~l0e6Nj0|W7;al^ z$Bx&%A*pTnWi9U3ieqn7RFnngb0QUg4F08U>GL76w@+l3uBAnfmIPc6Bb3BUh3AI6 zq(N!YM|iMkm0KB&#Kk97kS-bU&s$B`8oC@C#!WxRC%?1M%>f)5(LX@25wTv&Myx67 zU~TGpJg1@TS84IY;s+( zj!qz>1Rnug?FLg#ioX&QTUh%(1!GmjVyj1;AMb0_iAs7(;t6KN9m9}v9kd?4VUjIs zj`xp#1Bbnq1g#KelRDw{XrL_Z59@I}dh{sJu^dO(n9?Z>KFl2CJOONZlr#Y5W~U*> z0l#VaRdG*&OfnCm9I53PtcxsQvO5LXUYx%bxHB<2&xTcqX8rzxN*h>pT*K)QMNnrV zSt44YQiokubtm!dPYE^_16<#;DCp+B153?6?G!V$moRHqi4SC+o2Wona;(2uZdC2& zJ|tsRIah3va8EpMfE-Es{HG-sO-&o$*`N{{`z%#v289tRR!5;?*a{Sg=!vj5G;z&H z?bgn%`36cPl$e261&~e!?{$i6)!V<{2b*8JLmH2`WCf`ssgK)}i{52f^=-CVK|8Vc z&4Gqg715c=bLGQc`oS9@LitCX^y>q23_VH6+Mt@0KZ*lkK66lwqw#`=Y%dBH)d$N4_a?(mcO(JGx z83Y5dU}ze8GsodBbPO2M-N6TVy1kHh-`)?jz6K6H{s9565TV78JrETca>EigOT08* z{R26tV9C(4s^ZqfahA+LbG|E&jM)4Z_!1i&rIgbg_N+VRxL32AZEkkU*l-JWmEe+X zirnR{m^@fW_87&w1yKg-^Vbp(S`D`xtHNKoJYopllmSwkT3CXeY0>{@g^qePn-IN-#9x-Ae*Vd$)bWo{gBIH{K@g35}tx3lkST6 zAE@1lXnN;n!VBK&wRGCrO$==VyvI0H8h3{_{$65X;P)gMEcrX(5oZ}Q9+sN-<)v1L zlP_cq{+ESOuaD}r8w{mCG)ge+kj6vSco>)PVOY;aPfGwhI-Z`MH?FMoRC(WlZju7# z4=!r~O1$tG+ShTi$Uv&eEqa$<>GSV5wsAWr2ki8t#g=9)q}DUH1G!k+%eqZ(o?g%b zugk6Z%HrzID@Qqe!2yJy0)v&Iim|t&?O{{DCO_Ftp58WC)}rP@q=e`fkLi~}NqOng zr5jh6@Kx)Z{^dF-YqU-27(3vSORs+(_Aa)1E_RT4I&wC|DzqX|P>#y^(~VEQcLq1N zz%A_U7%A?SmCyXQw4IG-FzOWjn<>kPE~aB!-2Un72_nT5x$pdRatib^%i45xFO?{iJL!|1#rcOemG;qQhPb4ixio)98b1+AzLGj{N5`xJ4 zMqbgf<&PDDiT9s#ucwoRuX@zjFscbI$VDk`DN)0j2@yg`S-xUL+0{I-u8`n}-r}#f zMcz*O*sTrldKynw{+s5I*mesu+oSWmrvF{vc+rO109E# z@ESlcyq?I=wq;MAzS;bBb>}GymUTZ>?fxtNavy7=;C<_r7su$s0w~ZgU8y>2K>xqw zNG}9;)Eg7d)&_D55SY)l$hZv&KDHru_CG-tYWa-O_-L*ZHC_kX z#35Pfvc|1#Z-wt(TMtxaNLY`PI{e;L4A0}^Q*z(E)4x zw}UGgj6d?ECgrO%d)@EY<2HjH%;;FHQ4bksG^U4i8|R;$DED(bQZUtJLtk7e76UgQ zJiuAs0Pr5y59bmJlaS-A4pw{CFQKDFU_}fUza2^`G>IL$zMZds8M%6O^tmsCj(Q+ux3yo9 z!=?Xz_a^0wJiB=fU}<>~4==9;9Mz!fEsm`PLA@H}VT~7UI6DdSW}oFVO>0EvoQP!w zh1~Oo(&E-l1Wb}eY%R0uqt-DC@tj~~Xj4iG`1J_lKRxT>@8u0L+D97Jj;{Pi-NuTE z(&XkmtSLXTk#`doYYx5lSzz;m$@^lTLjqmbfQ$5&Rj1(}RK^DC-rE#7G((JSj-y>K z%f3C9h8#RLGV<5G*CK^^*Y+2fa_nB|j?|x2>*)H`V6U|NQNwrqeuI_?v$+p}nu*a&-S`<8Ubq(n<>|gs`kKr0ZrHThiH`&}}Fz&}Qr5N5WPw+6@GIsE9G+0F& zqf(Gss?-kRqVU5l@b(Te3U4#=`o)p3pj&zxtgl_DRge0C4TbuHkbm=q+A8N|Pu8}+ zx#6?P91WX>e6M-gBHFquQ}QVIPC|F3>ILSkT_AV1=juDYoL+{R=|gP)cp7E=bt7RF z{AK~ZVJMdcIp|j+v|7^6hq94Eh5VfRr_i3m7*{fHI`H-9%eemehxsB>Y-i3K*fJgA zv+XFweCD9`Ap=jdcpoh>?R>LDcBexr71^5lD_@2C#AunPpG$vxH-eG=s-$ph%UH!)f3Mcazm_zbO8M>6WI0GVkj=YvZa6H%i>jW4HmuX%ek zl2MWhuQ8VLO8IQKeb2(mwb+-y?7GCE_Vq8Xh5P%Vzp|H`zR^Gj+H(j*l~FQ&b(jXM zj8G6X=U^Op8X6sit{~(6@1xgWv7p8MB*`MWOdS2I7^(2xso56ECNl%CA1(Xg9NdF` zgw-2HJAP48Av0%sov;f^pn4rgNG@7%ZXc6(^Uk%@=Kme>$E|jrVXW((y@Y42ycA9t zGeG}CQE^3Mm_yufI`ZEw+qVxy8rxmIJan{ZGJZ;bOzDJ{^h$$hb$%kC0r@`l2bdn= z&acxLQ+|lx%YPVxUjY8g;d4G&JKu?9b zy_?DVRL@n8uBnQMLmcU5-}XaLnCxziupWS?JfDS*uSFTpf3iypPXceeR2G&9j5a82 zBSk&B5Y#&Q+f?~(kyP<{XrGPMnA?Qq@a@Xt?=Q`TKTD)~Bk&q1DuMT-UU<pC)B_$OAl~FOKl+*$ZwL2ZqhNcI~pkmAR))fd5MDIpF;2^Qw zui!+u;afzh!+tp*47}VJM6NjLrA zmD+E_P-pY=Zw`m=pu7i#s3k|}U^tc>SgAWJH1Ncm%`@WCkOro}}JjiTZ_=~fg=?T|6^4ZuF z7wV6Yb6oJ#>nGUYkPAr~jcrW$`Rw9Os@JdCuae-o)SU3*%Xw{%4if}=;T;a*qC%1> zt10jk$7!8Ojqrq+E2ZR%oNPH6;XXCEOQa04bw za*yBbzP;grpbxhM2?JEYG2cn{g7uX=-t{}#$rVxD8mbb%?KnuW_05-#FZ|Hq4w;)- zVm9Qm`5E4szx4ZN&iwyUF5r&1^Vd0#l-`q&p)VU_p@);{%9;Du)cIFN7~U@e6KuDg)Lz|xoJR)ELeqmkue&t{ZzJjab(ek= zZRBUeZMg#c%1kNbsnKzh2+J(!08r!e_vV)<`(k(;N;`A5tVTy>cl$e1a zQE>(wbiG#Fx2wAO%ynw;(F3*7fp2*+a~xF6*}BgHX&;$J211`K1VF#*PkI+}eq3mQ+i>TGbeR$0c<>U@v$^{o3C zs5bpb0nX)zd}0yOi|W&fJ;#R9^NLjOj{~Qi=syX8d7l(@nv)PUO>(QSe zl`lb(02e(D!`gqm>R>fj>(4`j4I6JSy(dxVh3!LLQ5-pF*X`5X?{HO@JYVmdKDs$0 z3$~9qeY6kOoJhzS_>W%|Uwv?`^Yq5ea1OE@?feFwKn)o9++AGj;LhB|5)tM`R z=nV?|2q1^$wW!@^W_A3YGiXxkZ&J-sNmLm~a`9X~O%H3@>_1GrJH)6EMY3i8{xIFA zB+mt!tk#3D2MjKDCm3a*@tWksa}DFo5?~E<7N=S@`fP&Hm1lZd@V?x!-mR{N*D*ar zFIoK*`Rp5qPoHEkhGGhcug;1^idntRvjtNQJDfijBzK20hKRBM5tQOs} zrJR84Kzl6FaEXhNG!oh#2yUYu@YYZQr2)*2$;~zJHDMas!~@?9)3NJ2HcW;uy#j*E zJdgJZlBWzxz0+a&Vj?r&k`+ULTVl+o80sWHpDnWAPQnkCSVqu;dB1tw@WRWh`KQ3L zT5u4jk`wV}Lm!v0RCZg{aeqIf7ab9?pLCQ+mlrIzZp=;1G?1t@AHYq=Y`7gK@a|u2 zs*dL*6=Vrez~@tQ>#_F+8haFSz3@#b-1N1BUqvukZoxmiwOFZ*9g)$|G|j#Y3##T) zYO&;!K4=v|$UBYPjOexVz$e?G&*Or$m^i~#!`Xv~1g3z!UtH~5)|PCtIu1M}rb`^S z{vF$rL|1)7EK0uk{LOUV&m(POc&ag3#z|Wj?*2IQYhJV6lNB2yZuFp8#EkZ&P2p{ z&d1GjyvnxXB8#E`2&6xU@wEJ5cK%Vm@| zZRpAl-3P{^)C#hNyaRl65&t-;k^kXkfho`FG2pk-GV0(n9OK>OL!my2lk0zb0Q>@3 zac=#y${A^CngpmIB)?aYkwmCPatiXQz=}H5JMlOYz^gfEM+B@T8Vc*Cx2GzKzqiB% zc*b+ciEQ3XdKlz}kcWJj=D>PPwD4eVqZkV`ab@9);jPbh)On~+B<>>V{tvdn%R_il3|pb8Jcc> zk*I}9gPSz7z!3oz*8kbFHGWs+Le+sdYNIaJHZ%-_aaB0j!6jL1qTL-vd1n%*$_Vg^ zQKt!@d&vnqV20nNH61dulk2zpXmvNKSKfMiVWLrF$88Hdcq-Z+V?QVZU76yBz%kh#?g+Buo%9c{?Dk_>lO ze$s0SNCr^46~1QJ{95Q@i+Kg_wvK~U9iF}BTwR}Yz|*G)unEJaMDqri3d-jfP!U*w zc|$@81_-c#S!wb6^0_cAEgj}RA1z5Yn8-*0!sV+BY$OV<;Q||B#3L?BhsiEWKvfrc zPMhWf!S$j)h6n#x;i`4F++Iir)M$+4W~gx9H(Mj76M&H_%WTx^AP4dc7m$gYfY=DH zf=}wwJ=p){cM>)|ScmERjJrl92V?vEh{y)Gby>yLFxLlhBSSUG+2z9+!uyiYajE!TDn}hPB?6R}2lBmMLJS3@{SxgPaPK=Uk zLRNX-tYlurm0Y6o($|dwmtPT34{We>^UBR=8mObh+>^+d^5xPKlhq=#&l~y^jnuqy zLl67adTKR7l^p?5!9lq9Y{UQ{Wx*eDjCMD>4m@YjqAopKOL>PM8vZVLYV(fUmh91u z-Ik<1Q)QvD`tO#)?`|tQ($mN#cp9(B?C>d!ZjL~2lemRw;I-uW+HHEq-cvIw zQa%#uq5z5-X#&G=jhF%YVay-oq&Rft4xzQq*1DEZ^ipye?UA&!IL_};B4`WkbeY+G`(R35C0C4=B`u4eQCo2t^&X7S#5hM|sRDW{Qt)TguJ zb#fagmOOqW7%ewg&b*KvY(0S^$U#oIkF9t0!bv)~-MRMUhAah=FvM^&7+39u@DsJR zKOnSMSX*?`CPWGJc2tpomwaq;=1Ds>&80JY*Kv}h0UU=)RCWF!@^)q6Gsd=YQHLcX zes6t(3ux@q2E>TSO;|o)h!F8OVdntttAhR|^lHa5;+uKH z>i|ln$JF|-%XrQ&7Dez-zs_EO{6teYd1=I>LYw}Mth?l2P$_;zR#e@5;fVUbsegCz zIgV0NTitd-&MZK%Hpm;Dx+*r&E4@o=Uc_u!_5RVFBJ(M3Q@j#RXK^h2yL*&Bf~>&=*6&%#NY|OmtlC1n!t}G z;fyJT7hVxdL7pzlq&si>Xt}muJ2^SH7VSQt6li00(jmW+8y$xrwsW6U)Rx=Lw+(zW!EA{eKA#-__R2f9*Lp zbV11hgM}{hWEt~{gK+Y5W4fg2fUl|nrEA)v5!{j(khX4JRY8bXa-K#U!`DUX*;+As zH!~RYYY=v)Xx$g1jSrZfFd$c<2fEE-)Y^Rp^NnhTBY5=qsZ#%z=DS?YVW0IIDB1Er z53bH2(H)!JBWEu@e;qkgU00hWac-$$6xl=U3rDaTTInS$!5>W{}`R= z&<3j^eO=b~++qJ;&HAM0+WLAm+J5LOYj7||1@e%*Ts>y;BsWLX}!*=G@omu6!PC}bqF#C4_ttlYz5{r24<7hYZO`LE0iym6XWE%xB0`Ya-^ zAgqqY-IsqH%rcND{mM)!TYs|g5@c;}ZzpE~XrOT6%RdVao#}m_U*OA za|#R#Lal*X@xiFS_n(66RVR-lEjfYN6jtfhsC+5|bPU%F%O>chAG67vNIxyMr~sxi zQ&5{4SvR6m8!Hh@)^(P^B}g$AD05rQPoJ|`t-**=Mysp9 z;dRf@UjrsOs9MKCAg<0(fH9ru_U)OY?uZ~N*8-Rq*#&oh*eUX%K#PLhT8~K2QVleI&l;{zG0ReGdDUe?OmT(ALQlAu zM(c1>eeOo&ioH|bc148{*NFUCm^h+Iqh)BAL{cK89-8pKA&D0hl!iP!9ph(?oJIvO zH+V~lUJ9a{mjqn}^9TSRix;5NlD2Mj2CRH7Kq%TbYrV5nhkA>MQ}X$9+Ne8JdfE7{ zQOGeuYchxe0NQx)E?$p5$ISvRzb2@;bW(dMqg#CV6^kt{*xE$33iXKQq#pQ;>g-HF zX3t_dWV&?VZ)|vh@f*Wz$ueH*{Dv{*FGT;Scue`>XRXE~ zf74Kt%kP<25yq1=Utzm_7fB~-jl2@Cj&zvAAq!{%>}2v`RND=?SjU%;!+r#YNJ3K_)jO<0d+rfgnPCvaZj*yhM=g*u53+7_GB^E)+moExiSE3ba zD!Xn5Gcmo5F6%JVk^IAl3_1g{hJ)=aJ=gXQ_^eIs&YG1Hy4Dv#-X^!$Ur{R&|J3N) zLQ9oJOyBbU{J1O9_igkd>MG)U$SYwGgL}K>@`>8-yNUnCdm@qpD=fJW=H~OO0iMt{M$(J9)+Z2ySF|IS7OGxzS*F0T^_$d+kEw)_PfR&7h&aUp z1*&exDP7&p)DpWG#)66yTHbgC$Cb1g=w5V#*!8@0bIPTB#C%KZoi==&(Yp*=xkN%# z)UQZmwnIDQ3-8G-e=uQ3@AbKx+DQhnq;8?Rs1SDHVxJQ;V2ibWXkCshYlR6`;!kG&-9(M1bDsvzz^LSi+#u}pSx$?rKFlW6ZQpMwa<~T_Yyj@IE>j{_A9K?C}5e+xalllyY;|ED8D)9VK7NK#_ zNaJH-Vj41tBR{dv$qMyxg5@e)r6>@*<@dO z^h8E1->#9B5CL0P#qsUc1dRY_4R3%R5ciRh&Ev8bMe=V}be}=RD zcd$gO04UQPS#xunEb~Fb>c;4^C&XCw)@A3{Wl&h7GTrMk7!EeLBRs-EnAr;2Jwh79 z(pq4dqrWc(2H&r=yp-FgX3B2s{lGmFAFkSQ^kqe@94_ZH1M3}ZfX(V4BwvxhX<$be zRs+0f$Lw#V`EQ82`xWu*f50MZuk(_#gdr+qhvz2MTKg1PNuPgomK(MZX=_Xxk2H~84T z+rM)@YZLC@+sikLN@=`61?kft2zNfLdgbZb9Gny$;~}tSSnoc#50&PwZ6ibxKx$^3 zeCD`kuJMF@ci z*3H;JM52R0(SymQ<-iEzp#jmeZz=bD_aXI>{ou)eIwW)>w(H18OIy}ryQqn7-FoWK zp__zE3)OhKd87K5#`Id*-(#m}bJzWYd0S~BH)@fF2%z9jXvjeHCXzub2Vy^>rLEnO zo`)u`5bXe2u2A%KfkvN@0hb*kGA3D>8!=QU5GNwh@rW=xp{8)n8*i|TI*?6X0*9>k-}eKQu_5u&2==0Gho z!@_aJWAk`tis*}%@(u40W(@s&EZ*mbMx5e&(v{3AIFc>LZ_&W1nNrX~qo4wZFNtR6 zb2_d+1J)di(>T29tn*EkX6L70_vUB>new}0XMoV+m2QnYA|{7G-E=#CIPR@R$^nC# zcMTYu=SZAt@}U>`u#nEc1u{hUz7pP7cO zIoV1ksu(URz{o@5)t$zWNBOZVRm?#5Yxm-Cz) zl(2F8PjX4U)ouj8>R64#kS&toK!#V_dB|up?HM2?AHyDLQk;ik_9zR*Q0r8Wu%H3@ zsr6H^9n-Sgc3H6zq;|XOg7`LG_qkd0MEKt`Go6rWF)Pb+n&d*LJ%yeXM$tZTtG^wjmmg>!gU0rdPmaGxrzy4d|gi@5v0k1@_chj$H2a{!Zu(k@Xv{Y2D z3QaCrpNokA{=Q~Wj~|DI_N5btQg|asyiE&X~?7eh8V01a@aDq!? zm{_vxWBScX{`V{ic+!IJR)c$BQ;76b^9p`XDK8;;Ac>AN4@~_@hZE@WvK+waXW__7 zC)$haU+StuFN4%zq_5V6Oeyd|9>&`sH&Y{&Qj7uE#-FqI1-s!b4ZMETn7a^HugZVV zI>8%{huXf1H+K5p{F=M-u9=?(LQPh?PSfVgr4MW`4^&&bE!gB2Ufq<{_HEmil*$vg zEvVu@TDk!-cfx4HTNfo>jKUYaxNrR3W?AC`s`l;H??7CoMeUF~rQ77e)kBECtlgV9yp|+UON7(J8 zw^I5k;VY6J;{SkFV6EQ}F^s_&iJR#WW(gtaT*2!i9+Bi`-}A@Q?q_lyyfHo+Ch@0Q zyy5M|Td#ih*JT`%G2Efq!(O;HW(kkci{nT2U;wY%L1x7gTAN`b4K*p6G&k@}eu@1T z{OnmQkPCg!uh^ckX}fX*;%7aQ;-r8UBwJ%Y>zp}rMlA|s7!pCCV|{^OMH|<{V?AJ> zls`9?9Ps^Iq2wsefF3aTIg0^J-)0kvrL1NjF-WbUoc|%W8}!L{j_-2amwYb?87(^U zvJBOXT8n7rh@=8pKQTOT<9>lmp5~!AGkDxfw?L@aME$a}$*ftYMn?_qL> zFcPk-1~78r{jzP22ZoHW`ND~Jr0(k)ER)JlXJ6|TCgp3qI{ZLyZ$H~D&h_P?FI6nA zTy|-RK6%HNy@05qp(V`AfDOz6at8+#AD)z2a)8j78(Q$x>-VS38{-5IeAsou**T-@ zJkqw(l9Du7Yz3>bA?qvhIwMK#i|=QXgBn;!u9dtkfM;-rMb8tiuEY%umCQruH}_@qSZj|JXtk~C3q=C;6?mc+(Pm*hI)ZGg4QaMsS7Cg zf#N+0FN2_O9XV3qG}g%FhqE2hrC6|0QFT8?5+R(~n1~qzF(9^MnoUfG*%v~$A|Z`< z5rbX7@5}5zB4Opoaf9U{Jo#^!a69Vw(@t9BzmN+JdtLQN0rrSWq%y zbf^bczgko>*Ms$Uk^F)X0q_T1`W(P3B`Va)HKxyB0LjG&z8ExOflz2cQS)wgTtBP% zn$pa+AGGB9%76>+Ga{|!?vBmdOkFQ2DP7b}0~wh3{e!tqZlu>a$FnKND89x$IiOYi zTZVW@oPy0j|G8$j#w`j%6RRv0yI8xMvQqKqYRiu8VJskmGDMEt3?=xQ3$cCjZNv?Z zp^4~fO$;-Rd<~(|1pF?0uthQ2q0IBhCF3pXTPVXB*@r^|w5|TB7 zDb%iWA6Y@UJ?;l*e?^j{WTOXvz#h9fBDl!l--q4@cmDc0{!UVl-&C2$`@Gi<9(2$j zeiRgqkX>Me#0MF0jRGGU*|xB{rP05Ge0tkaG3^AR_x9ma0{x887+US33cr^_fRzX) z!32>OwKDF4+RAlq^0zc*($E-kHysZ&gNYIOH)>_Gcrn57Xe(1h@>PWxN@D5cHeme~?lrGqZ>MUu$jH7rcFFb7G--I)j5`MD`P; zYD6AZov2?sFd6Y#kj7i&zc1GvLcKR-#kG0Y+S^bJ!~=yzN<>Bxfd(?-+SEEXE<-#J zV;tbak`?vP9P0(uX-7KaBm(sHU?8FCJmd(B%PE)x;I^L^7#m8AV_-S@(fg`|>6ETR zI510!f9`a;E#`fE);Mky4Te^iJt}G-zFB{FT-b`dJAjsb(WWwr_FW|Ixsy5gU(|c+&er`2QrPS+}|0_W+uJ65WaZ4Z`t6VXjkWswNtKL$7mjYPkPL{UrzJ{ zD#;7i=V_)Ty@_;i{%xhO!zs#htmhQpl_K$moZr9LlWgCEw7^am?rfz^q;Mb*t^W=ovEVxq>uBxc@oKV8}<_+6}$52bz zVgDOQJYC26Llv;M406SYTXs;|6`B#+zP+EO02vCuIkuXr?)T`2(j_76!cC1 z^SnA%a%TGj<`osFO9wxhMAQ3*8~$@-Hg>2@{@x-8$Peetb8t@bJ>V3xwyF+`JQ<*6 zcY5=8J2SNTreLX{dQ&Q%m>Q6pir~wN(}bTo?DDzq<|NX+ybSQuiSAjNb3QB%Ik78n zBe)TX9xuA@j}>+pH)B}v-AF2;dqjGUt&*0!V!U4|=5UzDH&fbZnx@BG$4GX2twJhsx6RM{9vKF_R#I{r zt&Y{EBN|$+w(xu5dz`LjMEe&>CxDmD_fnBeWW4?hDO^)1yA1({nPz3jne+$G(Q z7Q*lJK2!iF!5L7yZ>sWkk<$x1C~Alng#GC1?cIt-Yco2($VTfZaeiE(Vf5|0-$uj6 z70Z|Ja+@-8@+`Aa%H#fM-MCpT#BwUXMJsP=sZa3vG_3ux`t^6pFQN)X&GS1Q+2JRc zmH4#(zVDCHYO{e|6U`0JWwP_n{ ztw~_K+3OAok6d3m_9lLfD4qD|hSSEC!;*P=pgdH~Wl~36Wj%#7x?lr} z%k_m#4XYP?vSZFdTG5rN5JU|g;8OUNIg9Lnw?dN4?hrC4^EA9La>uVixyHCY88tle z62rz@Tmm*0p6P1HlHf4u|LDFz04=#IRrR6U+epprd9p>Ov>Z>l(}j!2mYT^M9p5Xi zm-+2a(W3b)g1iSK7zc3_T(NG+t+$*;tttZSt!#Kir389l@ax?6J+#x=+X8zVWZ^0;2asVt?G<gnF{bX(=OuB;*pVQQC(8i zWD!CXy7o%1t0Tro(xZ-uX(vlbcl69p9znk5s$^O?73?yRc#W&mRPFbV`HACBJ>SFz zhawE{B&%`6CHHCHl9+%SCfXEDmTpAFfo9_IvNh(I_%T!uB!6U3^_SPotd~oqC^hXS zfRMl!^$ZaC^vqM{MJG4HEuaFb*j*+cnCh)EO1KAq6+h8Bb?OBic1mp~1j^Z}5X-z8 zERom+-si$>F3B@P8w>Uwki10g*Mw&S$!4omBiC~-f8_^fq@1SQTX-lbw~JXAk;OG` zC0Yb-L)yJ3o(B9~XTo`pI_1Q*E;oL1fy+L=Z~L29CMRkx=-mzngh%TGzJnR#E@P0<4%B-zp}? zv4t|g+d{{_)vz%&HI>-(Ym7*3BxVQj_^cHTg>BQbF!u^C-DVxFQ(e&(A8@Aa`?8~@ z8HzulwQ}7`MjY>|pZpwPH%mCH)L)$`ma9YwZ<0MDW9V`98wFbV`VgI=m(P$8G_@(lf1LOEyPBe(X*kwL z-4p5cea=L_9Qa&hC9r7yGga~3Cs59}p3k&y>`2YCFce$|(5EZC55wZweyXb1;s8pv zCU!gkAwKMZdf?nDByp=eL8p z1?z+)nAU_;#?7NvHo&V$?|2H7A}}c7&$1v^W=-r=meUM-=(T7S_xI|!b^GLH|FkE| zbX6Y;8S9StGGzsUiK0QrNE9jA+X9Mvju2YFg0d;x`RK7@!;K>49$_@kso1h{0^c*- z*H{6@=Hq6=S;OUMB|ygJ{izH2du;|fX2fTL!@_eY0Y#-}yh!aqRrhx_bKK>7INpsJ z7Hj&cK#nllWW|uwW#B#;uq@u+BHfP3dlm2*z>!E42yX-*!$%X*M2uB;O9WtyA-XSH z&(A7I3MnWkbY6W1g{U(D2rO{~G#BoE+8z07lCzg(co2Lc!O86$iwkxVk7}gGPRJYM z!^6Xe&G%KDFtTg5$t36|fGnVkN6Et@mYD>GL8Wie^!7D&8~Q{M$WF~Bhufz>kckHo zqvXqLt)kR=E7Hx~Fb=X3mS-%rE*9ejxE9O4UsLc(k?dXXfaUxhwzrcTF6+iSKX=zi zwk(~RYSfaoXcaDuBaX-6yCo-;2{|%Fp}d*izw~}{^#2j{9q?4X|ND_wwK@gCfOqs{A>mOb&1bbnJ~EpN*!BZ8 z9Yli7PFt)wB76YlFGkK_G;SvUUU7-&EDN3bn~KbhaH+4S63|O2s+O2oMF9bos{Ys9 z9Mz%xT=y5nRUQsAnDrUpByAsAXzE}Q8h`7h&kGjIDfd?+HLljTWL2+yLsZL2fnb&d z=gVDF`9)=vcTtF@SRMKnE4M+hK07@ldP>zE%NWu3`9M1FT`rW^5 z5!!h`>)zZkC&dM+Yk_ci!Xn2dpeeP}Ir)gmr(@poLZxjhE(mSlz>-;g@AvJpNCbxO zrYkUa*ihyzAG|tQ@u;s#PWKg6V^(1CC}}l9)-Msi@ ztsNork_|lMHe(Dm)b9y+l>~jjy@eunWR@9ukG^xdr`raRz-a#22*h%+|Gla!RPU+$`(tSrcga@3fx$Q#t<8XB8L;w=!^uS54QX?G!VI**PQ%-E zTIF<-mMCOAOrjTQGF1N^P2au8Kj^#;L(>U$UiPP%ncga)6HZSE#HMF_(Wae%A|s}b zAx%28%(r4n?>)WKvrKO;H=-}330gr3je&8$q$xZS?HilRO}F)7U{-LX_zz}!`u=I^ z#uCM-oMJipM(CGg*5Dp2+44|j=%biX$^TvU3Y*2h<6Nt2Y4yZoL|Hq7TRh}wc7&|D zdhuezj_81JEE&bIy|JGvXg5S>K@3`1{$VK%X^w~W{&YMNB{ z%-eg_&w<(S+UJYIEzNS;Mf1nEo7vtwQ-HP{~m)X{x78Zk=ST>*;w)*i-Y*3DGU z+_v}!ry-@_OiKRI$ck0&W*qQd-}!mr!lL@m%EkFC*iZR7zG6t{Ab;khzJxfC&OQ7aK@I*` z^#h2r%+C$0rthj3$({(>96lu%{_rkkdHM2X-%AT1{W27|7!$L>9DPo-0)HW~@_I{z zyU{>Jdo9zQM{c_ka1{Y$M7Bt=tQw$}PyEqYDcL5V_v^?R#BokX_AxXqKaEM@_?D>dSiX3Kv1(oc^+kzd|dn)0)0C`Vjk@ zB3y+)rv+@3>kbxmwR?KA8E0|qJ{p&7Ivyy0fsC3*^kw=@i?A$6C!Fw4L_z;2Mi#~3 z=Z`nAva$x%1+Ky&qNQ^!gpIdH+0$v%g zdg+Onw{Z$-r?}Xqx2MlCBx7eX@b>Ng$Qk9bJ7P*s1(jTPXa%o+eq($;abc04(E(%z z$7u%+F@oFji#``Z3U;L`Ba&7_>xBj6fF`%R=@5m?Tgf$gthU0qU*{>wp3_orag|+_ z-zUS3RcyEN^uP+zl2;P$^T8RPMs``X4_vY935tZe{0K?%)Za3MG_>5S(nWm}_XUx` zk?9Kw=r9pmiQ+)zQ|rb)24o2K5q{Z!*ZTN2rb3n zb_QwiOO-8~f!{F(e~Iv0NI*pN!-&WdLXJoTk(_Q9AnXM{)D5*+mT{+Op_a~}GkL1d zI!gH!0bUJ$_im$tq9i2$jR7*MNZcT6N22XhsBuiY4}Im(`GcbRXstY?WeD)+&y9O( zN=gqvi?gilzO7?Ghv&b_$R3`XSwp@`FIk!X62 zxGGFuUULmLXJvZkT{we#4M$hRd2OK5UPn|L! z`G#IF3fvM4MD`01md};IeK}_ke#qAaLJ|p{Sp0RY{vivCD55xp`T*!lrbNyg7JK-H5qV5I{P7P;nzi@Z;>V&}P8Lqdj?b#o{eajfT>I1#dWsVm*@}G<^ zrlunD)8V%=8OSgb)D`ng9Wc-iz>&|d+s~@~Ym~s3g#hJ1#;>8bR{`W*hnPmn)!#?g zSJZbv{ArZqdILK3Sq2MDi8Mu`xnI?&@ePez(PMAml8+wIo!dlFH~FZ?ni1%}Ai(%Z zwEBqjIGRyU0#L$^Idx=#)W&5KJ%!%w)7rJEQMm^eo?@uhGit?e#ym%}SSPBm(#l6s z$2l|4YtJjPp{XX1JV&ZJm?`11Z}`;iUdz&M8}92iW-o)u2J`L6s_8hSBAUZ83e&0T>=_V3jI zK#}=;=i)D+f&RW$p1?H-Ee>dY6t2hKCU%9lLjYR^VbK!1WspD^sL4QWo|d=xd30Ci zscWYxc__63ER&X)ceKJ7b!Y~U!hIi*tBTXb{(hwlo46)4IAOqfY?pTh&jY>JlU#e1)RDeH(ZQ4c8|y^uO~&vBW<*z~$V>pR56I;v}+ z5KZWV)-!<;ic6NX?jC$&FtNm7O)ZWtMZ9BE7Hy zir3zJjDrdgHSq#L<#)mi%GqAOdR;s;j}t9ka$D%Qow@wxXuRIKNvQaSb6rV0$y2O4 z<{z=-$Mx>YqH;&a^iZ#l$jsGR7v=y4jr4zT60)z^>5E zVgG4*#qI6#m2c>5cY>p#@e%=yr+hMJoN;WyA#j9%t^9#ArK)SrP7Qai>h}d;Ub;In zJ}r@B&6>M{JJ&8DI0EE6VT$aH>`z}wT+#Nuw0Z_k;hDddqWO8Tp<3;aRuSI|JY26W zQ-}o4GDZL~roB0t@3?gL!acxw5MjRPyk%VCgdI6E*YoR!@9K)6*@2{__4m$M9$w2~ zsB`Gv@#6wtv=(q?J*w9-U=rAFrSo&E#R}__R)WS_!VgNOmGi}_w%$LlzyI<3gKm6_ zC3|kY=i_79%O#Rt(Z_y=Dm#DXtc|UWi$ZaZx9o+A(Bj9z<^JJgX(q+HUqIfm3kRUG zWQuVi4rZVpSLC3!=B~mDaa&(f9`+{ssaZ|KR-O$U%jvnqsd2Tb$@EX4~9;b2W}1 z&Td6XD-MP8bLer*0(5=$=03h&DNOn$RE)in5%tei6?C=?yEjI1J~%ks{L-V4{bkGS zm1awg?y5*}1!wn&s3>=b$czkaGUTSv06}*ICnu*q4~B{mq^{7=u{NMn%Fre@NL)VU zC{K5{gl393NK8yDEGkNcj6K@zJg@}BwcnmYp{jvV6GI(&g-lC%WUGhkRb&UgB1_1k!P;Z&lCW*%GM{yQz8LVB-NC!L1f1Z<;pL&pOyGA4f#-bIn<;AR;#n zdiA-0Z4@OeczHG`vyGdDs(dA(ZNu)Kfk%j|c~S*kgxP`NfmAI_WS3GwfYTzI(c zS#bfG1dN^RL=c@|9`Q9x0i9b)rU2OYpg6c$b{6DKUmlS_So33{udZumTcf`JGN`64 z!*Ozg(_Vi%CS0J%<+oUwf&Hm8*6AO9(P6Pc4a4J~cAca&ye?nXOyr3M7l#l~TQWK@ z^S%V4@`1hOE3s(^?Ac&8RUU;1eCtshTsqhmB>!+gDo{!7s!NJ?9`p`0#%>}kNcOZX z>y~0FPt@f-m4pd|1jIK$=S|4q5rG!tC6>pJAFpq}w9Ts9db8kS$`ZrP7~T=~)%2d;`;d^s@c)$nY<;x1nf==fz>W6RV~mz%Jaw-1hHn$M zc80cqO*t%SW$xLrKz@kf(Fxx^5v-S2%uk9N{1|YY>B~2akqBfgf~tK3a0TYuVnpFN zCT3=n^EkjEhmfitk3^tT_xZ-7c8&n!uYal3TTm3Z+thSdj%zOanWLp;yQR;z5Bqd< zNQ++=7hG~XO6ybHS5vShoC-sx~GO`7&oTHxPP$xYFxlNUrk5k$-kvtq`Kbn+b_K{3oJ4XSck5JTdKibWJnp6&DNxmx&-*I5{ zF@d_lbhZYF0LpO8nj0fYvYTd5r4@4Xdx*SkYi}&ShwLduZmT;6fv>_bE_LDU&&hd6 zzRQ>XfT17bryk$>JvLYO1SeM#VT?pOB$Co3l`H_Kl`la5w#jZId+bai4cLu;q zRXZ!_K_Lt^6kPU{-zQ(eujc_4;HxH-P+-tv2)ia zyL9bWGl8LkvPQK|9<}m5dAy%=+}K9ib8Vhsk4w^DTSp?Kt%brgACMwZpYDX5mlMLqHOE;3N%ZhYh8uVq-@gP@kyjyJYxOzFCWOX zl@(XD@dmu;ALr`ZS&^nN$Nzi4>%*+stf6YCO*U^fgGw|zN_2Iml>i~A0RmlO@bD#2rx!!g02o}^*7D~|jY%g39l za5_-1BUJ-{jg%j8?EXvpcMY;;HSmxb`v&O6~pI^`*Sq6 z?*9qME~TVVZFoh8F^18aZr9sBBG~98ig0u*3Q0nxVqO5?p@C*zVAKdjW>ycpNuP6p zY{+aP?Q|MIyAKbmIpkh~SD6G|qPPF?TjUl5YUu8e1}zpK-mW?FSa^G*uh(#7qQf-v z=9b|~+f18N+1631GtN$*x+AWIY&Owp{rfmjJ3`mmy4K)#8~|rukruej;HR*Mhl2@%q?IRh2KCgTkWxAtp;KYUzp? z&zRTqA;&pm%KhiR?HC*ursOhN7D%vbuOOsr4;H_geIxu^bmrVl-{oJ@2}XOoCVtpv z1fwdlyIG1rd;kGlnYbln2mBa9-BN-Gw5U&h%J`Cm2q>mSk*g$?)@;2g@pJ_{3yj`4 zExhir!w+Da+Qz2L=gg7{!UCg>bbh`r+hSbbW_o-PO|a7?DqWy?KsCv%?3_>iYmBP# za{sLqGb=Kb7}%xrNLxZiu1cvKXgI_pDZuRzsZ-xPIUWxlyC#M$A=mGd*^HQEXdF}5 zJwgbw$4u*Cx$_+5UXALQ=)_C{$m-@$ALddFDuqw~IAXO86ZNM7nTq_XkarsuuFbdO zv9lGhvs=cS*%_d-G8mW-!S2#Wi3z}5mgj@(fS02GN!0jaCHndmD5BlzFsq|afFsi_ z%+0TAfv8}S+{_FPHw2Q8m!g=x(`_i)W#$-awCEnvT8bOgi1OtqQXTP=h#X z*C6O4u*`LBod3i`N{_VA`A?OD8jVsH?`J63+htof*cpXo*!Dh~)bH3O=nzs6e4vW9 z|MP2$%mGfhnbbU?;*#T&V|}}$C7jLL@NK5qv_3K;8Jfc~dlC*HB3vb;E%Wzd8Ih6v zm@Bkn$D;`{IHZj8tQSydykpfEbKLPU&*LK4bgUimnk9K$?o6PVf+9FF^*vXNZAuO0*DVf57zN}$!RX)>%MgVI5L}zCY;t;!OzH2z?*H9>t6iZ+v zF+Tu12w4zjD?9W+4gqKG7qhOCbYI%gHB3v%lTFmiVa7q*X`)*dxq|;NYA#!w8?6y1 z1oAjx76(ehTl_6=k!e6s$4Ks&nsL5h`FUYtA=FfESa}@x6~4)A3*DrqE2?}85$V~F zH@ngU8Gy-t5&SLM#b52BQVlaMwvFh=Y;3H>Y|OV8Wo&WI)FE^v)-C?8!^5}Z3d7>!P9c{=G(U+kNePJI88`kx zVMBV-hMP3oG}G-9kgsfuu8JUfV1N~piQ?A^_v8_2GN8dOTUe+&Ii*7&e+gk!0!FQR zBLJKMvf;UBkJj(jan6wDDf`dkm(1}FEobZOp+u)xwT|N%C+4iDmZD#Kl1y49>FPcd+C^Pv9f=SI;jIG4&nd#z8!&}E~(q{dJ zq53G5{QII~wV{Z1mLhqqLIeFSn^(U`Tec^)1nDES*z;}?6+D;{9=4F2?k4WQ;!r>U zx&aM7i9;4Iz%p_lVLHzq#z{$mu0-;{mtXaT7S4HbNcsgGAs^(`WqA+_L>eYqF(b!mQ;2h zd|w?xS^hK>rVC|Wx75#hGHo;}eP=!a*josBqrry@bjgx#H6!XMXU<-D2Z^9=7|3Fc zaa;6IrIio~R&ERR_bMs2@dJ*TR3+yo0_R@*4NE?nG41&4M%lBJ@%lcQ$@M-uw(*BO zWD3e1vP<44Iwn*Ft*?nrNvR!nAXQuJt3{W}PDM6Nps8)P-T}8Fq|JqpFiqPbAkYtG zI3!92Jm+!5(0?%&apN(f9^T56+Mm6|d;->B@e0)$MiXEB zDqz78L|_3&ZO?(sMG_0R?gha;6P_C3_>;leclQUGIb$=m?cTB=%UzW6bCE0wVAc(= zKpC#4S>nb9{ZVNG9$1*K&luw|Pbpi?o!J;&rXoY9ED>f78NLa`QBkcUanEGf4q=3W z{vk411BB9K-`wn#3CE1b&Qa^hjwIrF=nIO}sad`2nRQ$^+-Q*DH(KnI*IIJr(yX$? zg&Q~JR>>5ekx(wXSk++InV#Tq;NihvR=cgUXbd4gqNAcJiOY1oWc@xRMH=Sl!`E)W zc;hZklQ`z9>Gg%$f&?y1hWypHs>%-BF%Ptf*<+CVhp=E{^Fk`MUftiomW2a&e|_Tf zw|E8@u9X}zae>FY3*`dO5Y*#mhC>yIEVd1(v){W%cven6(_eIR3{&$+!IRWMk>2|J zj$S~~WDSEx_$Pcnt)whI3G=wWTp~MVLTZ(Q?Cf(!`=5O4_WWO3o_&dSGH1u``6@-e z0|ttdZs5~xYQx~R0;X-Q8KZl1SIVDFAd^12vv&|Kn~nvz#P)u?YZQi8HdHUqZ=0Ds>r;TU8RIY+B0GZXIsIa5) z;_nXA_P@20vkQtG9M!)o=zObpD5$XSeQ+*Z`i+}V>lyV8VS#g9N*5eQMxN&h3;bo1 z>VN!_5f4|ttFaE~(8k1j^@bqEtQ#6ZR2nLmNSJ7Ulg_7EoK3bP5bs^Ru?o}8?AWq# zBSWJy0K+9fR_hn&UefKp20Pti=lZ@~BkulzLrBtW_mW3yDLj<8CiQIQ58=mebz2DwsiXop>FkOlG-% zl!}!)!XWIhVdcD#t>I2H=5RAW8W^O6z=R1`R$b_L z0R0_I$VCWcYXYtwbtkJxpeMvGkvn@SV;e<877uOeT(}hTIbTC{CY4OYP(k8LKID0B zSY%}RLJqChm|ngw=)@7CenZ%YBtU}ofJ1cB95Ta1oLu(}5xg^h6p0erf}8s^Tboa; zpP8slSE@~|3wXfWHWi#1(dTG=zjyrWm0`cocGKv)CoV>)3v$~2_>|I9>v!75uZOWr^=%LC4UdQzDR!9^>AXQ0O(fvFx&H4ElEqxdbevHWj~Oz13C=)BJ1L$)!wWHQ zGzyDdq)ujK24oPqGr$`RyN!C!BJ?BngHVRC>w|~@3tieFTKfYcBh+D45H~!`-L|e1 zONPkmRV6oC?h%+7xxIZ4!T|`XZT>L8KyAI&n_SDJ^%e$vawu>v(q+1pm-s^UNR5(B z^y(kM%SdDlun}iZTnzdFz6sHQ(xo*Wq^h4V>pCpRy2M3el;@#arWO5usmoXov1p=9 z!^i4vYT&i{+1b@-q$1{RM~iD)om&14Qa>W*AIKIm1C>5R38*wvc%ezsG=h#=MO9Tq zZ0t$Y9%*Mv*J@#s(Bw? ze^fZ_D3$c*)R~&Y>oH!zVdy z+RueYO7CsIk;hY|RG=Wjp>@41paiS;eRQ=xsrygZ1KLn)FgKc%X+EHN^5hf#q81R# z+#t3yn$Rk}hH5D89=Qy@Ag8=za&X|P0$5@)2y}aUET{%yq&yP8Nu5BnpsG=&Gj?vj6A8pH_8?P(1lDe*|?1#tY zH!v;x3lgw#cSs=#)80{)Jgt4>96!Cb)|QOulEgj`!ud9OdL_a-kb_<`FXQ(88UD z=?_$xrw>x=EIr|m0F5UDBZ~Z`)JTYS;6TpCpvK#`vr02``+*}MPrNbI;*_B$@#VhgT7T#yj{3BL615{^ql$8b|l+$L0_%aI*ySvsP3&eUD|6L_S& zzKv)>=`OP9&^&pNo_O?J(i0Ni9_=VfKZ*z|nKEGA){6{tbte!+9(w$MVQGnnvQxBFNhrO(WvF(fB+YUzI%ehF5~ryA zWtnirG2h%&u;?dfOHJ9bwCSB`{B^Y8v!G9@ey08Pt!gH*jg?kx78gT4fDbh|b$-_R z1sKQg1~xspk0F|S4{eIATKdXtUb|{Xdp9y80-*~Id}V@GD`^C94pjrsb`2xojqDC% z4G>xFTYLKKSu*XLZvFrf3E^e};M6Bx%ABI=zdm7Zs)wXg+p#Hw8M1UgSIWp69n5O8 zIr6`R?mkBO5w$7uqA^~zE_qkorYp!9*<%35>fm-x7aEXFg3L}_Q9;2QX?lQfG+Lyc zC_EMP7-H!RWJlNyOQ7MAfTAklR-OW4pZyNZf+Pze+o%(sx&@PH}pFHQA%{E)Cfe>wPZVU7}b z8wQ1M;sG7$f^=0;HvK}O3dXIw?jBJgL-qS4N?~uvCCW&`z9Ko)q9hH+1-KSuz56=* zF%MpFt{>SUlQ9BMiuUWxin1#Y@{iHaBzDYf(f3m;JRIxZz`Rd>W_MmbR87J`j7B8K z3ux^Zh$DkfY<-Km#vkCE%2CdZCenN;gmvE>Te?A7^is7g=+f>^Y_5Lbez;4u`>u_4 z&Cx@?#&0lWnT@%R!w4*LWk(T}8NR&;>7)JGYIFPUIic|y9u`)D5rAjZ)Pm8=AteCR z5?uWiSrDg*O5v#Lf2}m6Brlio$XDbg#$F`p9am=R`4#>1YS=|fhZuA@|1G(t@L*;Q zf%yWOEPSc14ix##M<}axqlQ8ezJ?3Ku zk2lDu6CJ8yZ0}rdes8F!5r!Xm(6zOiN~f%?hi>*{VKeNN=13)_GXxf8AZ%%J%beo*L*%<*jJiGW-FQsT~T4fLjYyNWI(Zr?g+-(`8 z=Yt8VOu~<< zIqM)fL6^<86EZu`;TU1Xt6KcwW+TGGzyIhAX~Psynf^IbQ`0pzZ>k08GMkugFH~0s z?8|GM|5I2+UXeek$eh-8gm4ZY|1AfvvI(~F#!sp~EIc73@P?zN0Zv$w@!a?Ow8r`o z(cw4KM+ES8^&{Q60S$>~E64+<*! zq|*9{vXo}aTBXwaHqgB@_@O#O0j`jCJLZLtAcMDrsk%=$zJ29a^SE!7SG^v+^Ot)J=vtjl0RE9{CdE>mxQ7oH6WR&#z|(l1`WY_S zcUVc{dd~=^r)eo^lLPsHPKEi3;Te?H*2wj2WC-PSDoV>l?*}z1r93=J9g$7T9(V40 zUww_ya+QE2pn}yQ$N+F))>4)^tAz(jeJ~r>1teR&*?T1mpp~ldrr664tbMo z$nxpkgnh(flb6c3;g^q`_Go!e=tvf}4j4mr1rqX>iJ|yOPcgt3V_EJNz4(((P|cNQ!|9|63ue5^b4W*wv}e%PnPQ#bXP~7*jnC_aP4-+ zr99w_-H_$5vrdgdG9Cg!+nm;-{+)&H<*FTtND|z}*|OBLv8nks)E6aWU#5@ExL-h` zPo4?7dL=%!iSN?cN67|oUQ{SF-~W5WQEBt0A_*>k(f*7n#!OJc_DbmCmZi7U+M_8Y z&Oxb^Q$1t!`7ob$>jr(3I70v62O8B&g*Qc4t3sWNyj=V5pWcoCUtNsLmQBscKpJxJ zk$U4Q70H|Gz`E@fx|}h>zoSr`+TqM-`6MtGxWv-^Q)dq|rL|`k2eH`JkS$NUn~?QB zZE#SA{+Tc(`{}m)D&)U#<+n00R@+m(ac0h;-YQQ@?l^v9@sba`-}0`(HPq)kc)~Pq zF!P1CM6oU2m$ko0)0ZBE3+R7h@TFI}u#acz)7tgp7Wg{k;#=s;oTd@fn3I!%qAzM^ zb2mNvX4M;kO1OCWB@XLO#RXZ*9-E{vNIL809`%Kz;VWC;H}a|E#JcOT;03Y(9N2hKGkQW1UzAd<4N#TUl8phT^(< znvO79jxuJESgJ|DqT|x7XQpUUk%fgAcveho-^+4(Nfn<%n^|o9?dyZQZ{*Lnu@yc; zsNX0t6o2(M3>)F^L|C(4OrrQ8Tb48VhE_x_z8y{z)R4eG5)nbLAfV-)`n(j*mE0{}t;= zE2F>1r|{d9(K4G7_8CLt;3+?sdz-?Js-1fCi*Ub_xyi}n>SP+-ZQ%*GkS+e#K2{TG7>nJ6O{XK zAVMqq_xn=w&o!61X%jE|&IObw&+M+EJDV~m`mBYsKUm{81az&uK|H@7d z{E@F}K3a6Xx`{F~RG|E07^(}1v&eVC&F9dUlaC=siyB9xQbie;jMwX*Yg8Uq{_i1L z9b1L>Cc-E#8aPsuCWxDTey?ye{1l>_)B@`lW2*W;D4Smi}h}NyS`;Hc{tP3%dNVXdS5?oaY8r>D@$B08)gRHO^ZEeB zPujQn_m#$_YA%T4lq_Zf9sW5#tU5nZ?CY(A~(eV%Uu$E#oL=~fcr(> z*>_Kgeh+cN2T=7}o;6-PHSvlCU;ghSpC++o4KQXoFCmxYxom%!x}7Xf*~a+*59gD) z=}(p4+<01KC_ej3%h1=%EuVBG&3fgx;DQW#(#%b-e!4G{OPhK-nEJTtSovbgQ)c`; zX^2dGgAd?m%WAiHthiDun}gl~)7qpvm?F5EzD;RN$`o`s066}+t2h5D{P4_eLUc|RFjT5pxt=`cQf{D z^O*g(Aike(EfShHZ{FPLpzk%lxh2Ub;~Fn6xJi?Z+`vd(Wns|8Pql545T&^88TvX% z?m5XAQ?nU++jH|4@kQH~A9A*?68g;2Xo?@h>2Pyn#xKyuy%y5AI5`bt4gEEh;8( z3yus;2GTyRbW9N63U9WolIZisX`}0NX>I!UU7!)4tw9;B z)cVxK1+p0ijU334q4E2(P<840rW+}4l^9o#f0&~dnUY_GyKbtNLRloMN?u#Q zY4G_+o4e&&seK8@A1Sk~n6P&%Qd~%$q!yxp!Ksa&sRNZ{egGew*gow@8kA(gcs_6Bz!kxwDcrP zPnDbd%wA3ZIQjLX>qENdKk~hG;6288b}|k^Zs8>Qh3H^E4Z;`E>N^_5I6NFem+{>+ z77Z^}nA1A!WwZ|hFTa}=P*dVQupb|YJ-P-P^uTvkF4}SNPF$biu_ul7afWpK**?7` z;zu)Oa-R1`3mkgvR28hv(}q<#LjOi7JT4$!A8>MUiI60K#+?&TvhT+d*PL1mL^_%o z5AvK5(bD%lK#vvRL>QX5uTbK3Z?S^Qa&qR@w@TD}q)$wEoh9VE+38b5V)Le2UMkW2 z2tF>25S|AIuOg-tl)d7@l8pEgcporDgT$5~K4Tip+}Hc?;HKJmBaiF7^{QdQjegIgeQ!u{heD+ z%Jv6&zA1TL%!G#t5QCB4VX8_0bIj9kQx2bB8-8&K`Tp2=s{lXu(HX}>;|>e9wc6)M zfkw;ewtd}F{1=X}A9d?(Gd%G+DEp7UT1a_%&wI@|$&%S_rekbbu{nF4qg}tkO zR5JWSR^BxoTKVlr!w=ouo6NfO9i+5y0Rsvr>N3}Rj!ejr6E)gnWvNb^S(%VM;W&Ed zJ4&Jl_n#8I&CoO{%49PTBxVzA5N<*+pRaUDmI z=u`QEDiABTn20Z>xQ&vID*Vkv4V9LuD)JTEQ!;l~K7MBF@;Xy9-o5W>0^joPVf#|s z!otHLRc?|Zf%Oz>2v zasx~eU33hA{Rz4A1vLS%b*!<+;ZX32rf~c)KhX@;eHVWtyGT}i@{O{j$5Z>77uRx8 zQ4g+{_?28%^75b`TeVSFnl0vQyppl~9^=4xk?#=z;;Y>fwH}Syr(>=2QDVvZI_fO= zcVee?U{zw$>GIm=K^Z`bMBUT<-m%D$XGHF0<`z%RD2c1!vAuAY?%JA-9*RKmd z#^ z09u77CaROlxogoC8dlsBBO^JiI96G@qJIq|Mz9+4Iz2|1L6?7KzMSFWzZkaJ&@_xe z^18-7va(H^Lm0E>gUH3t@d#d>d~@cokarZlxvlu#P zf^IZF-en>$Ok6%SFJUWalL##EQ{(0 zZvFfX*#JhprWwdbi*m~KFUr42Nc5bXnzOSfpODH^tXCA4<;d*`&f|)@P~CNpq{# zd+{&Ky#fF`T&9x-XVe65(f#cHF2TDPootw8i8DJr?yhFNRH8X)+Oc z6NCPC?fOCXWKs61*2+RBe;u#ma~~`oPJT?^IAT)XfOFb=v4lf-bpo-RvW zuX}`$z%Oep%9FdEybn6^bUE>b|1GZclTQCHOm6G{WjF`+ruXW%njZ|Ts;~camqbdT zPmpy|`(~}SQ)UimRD`rx`cpAAYY~bpXJnu~#`wwSZ%=#)GbO2b+s6~ZVP#xy%ZkL~x-q04O=0D5w-lM7uj+;9y{ujFn;sa^Z20`Z}1h4O|*2E#ZLbaCy zV3_Qhz^rQ#fW5QY-}noP9S0sV=<@!r-u9zEc}!|^ykG92H}yHVC|Z2I1DRYweW4#9 zGc#&*C=18Ra)l{_u8&qL7BWkIb55pLx$!>?Ddlwu(0hcJfu_7|KFU7LB*a8J<6nAX z?JgyJ8(yA^Ij*E#dUtyxrcDr6&mQLO+vro1HqkwSoVp` zz5};t*OGWfDob$bP*F;lo8Js&`Q`p9DkKhTn|%M7sZR-edQHnchrI8VUAAU-bJcl+ zo1JRw#ITE~wuid6JCj7WCQz1XZa4nj`(}>lR1K3sw{^_W<40xS-c!ocK$b_fPyroS zpm)J|c?}X!2($z{(Mb6|dJV?t_~G)fn}0X_IK^n$bIeYGK^G}VM+;YpMeEqh%MsHj~9@yNpSB-c=h z4)yPGV(!DgaZK3h0u%eVRVC^o$jH$b0(3?{S@@<-XK9kbyo0o7RLuV->+(ftr47VA z6AV7`bjln5Xo+|!YhlYmI;aGA=nH64RG?#!fLR|qi&rDQYu2FVt2Q!B+$q=3#avEp zcZvD>B$nLO!i{LfeK;lUF+T$W0iMytvgEB?t8q56{(H+raXjE)Y5+Lc8Hi{y9h2Y; zVSM9d)zFbG+#hdoIgXcZPeX|n;p!hV3BkQRe{0lO*Hc}M>&q8j!j{FhjhRNkEaYW* zB$tc!7tmP)z21|qDci|=4*-|39$nilm*YCK2CVfBN-Vtgv!ZVeVnf-_9~-#7t$$(_9P;yvd&b>{)zDp&g|#5`T+ zzhSk=Qpf)8dwRwI{-2wIam{CS7Ye_mKyg2?X6+lhY6AOO9~@cTS6w|)qzB;Vbu&j? zqv45|hT-#^}{X|Umlu9~jrr@zz0*AeiMQTIEra;-dd$yUJxsDaie&&pmo zdV_0O%S+~_`<+Q&Am=izMXC#9e;T4r3o-(bgY`w zTAp^C6TJ2<)|xhpe|EfezBxleO{o@{#tD^d1L#{m7a)q`1Tss$6wUMt5Wf9-bBKiz zlUv1dUhqBm`&l0;)`}c{e(m}FP@30QvA%WehFE_x|L~98-5b^`to*$hrNVvMEaJY> z=_Om$MSo1zG)I2?M85!vZ_RpGwLLUb!GB{&V2uZki{nhB^BuA1ayCPD; z#{R&=znNZNuHxC?MLR%teDVI2TMqOMzmhGBRsaB#Dr$9QKs{l+1Gobrq{mFWy`hg9 zgKp{pdF0fqm}oQV>VeqkamFV?k6sXY6Us9_C0&=-PQT3n;TkHf>WCa=_O56l{i~=j z%f6IHdD$;dK6N9Lm74g_bmbYalLhR;6Oz17|AyhvT!=EE+!JAOU**olqh#$ChA2}dWiqJ6qu=D$cW*{)SA5a(LW zBb->1c|-4LxL3n(Z>qIGqBxam+l&}>Y?I+-*S-;%qdE2;D_qZyzQ0t!V_sKwEq~y+ zj(Ar^Mcr|?_3r)ihk&X3_^SqE)VqG`k>)gBZ#R{7?;8EZHLUsPe6y&(jNuN zkqo4mM|<>a?bJw-g<_ZAFLyJm9^Qx~zh#uQ_XZp;RVFUwR}H$pEdRgcv=rW_JwbSk zWo$Ejl}-`YkguR36kfYwXJRaaij3b zBgkvtV%c7|ts1Np*S`ZarhNgHhZ>Nqpv=bf%|-RQhUw+UQCx?@gb$>0=wTWASE=|(T#|41~gfAD<(@2AF+r|*4#Jy zt%|vc$)}IL{xLTlt{m(T+3~MIIk-nUD4JcfWKX3 z+eS8ETcE5twQNhW;}|`-$ya-B5vQ0;o?4Ure>)hO%DHIU{%67OKjP4iRF*qR&jOeI z+ffE_=Oiv(U-alWGpROnOpr_AGvAf5;#G0=MJ|M}`_92guM1oB|2@G&2P|;p`a{9> ze%KE*>*<;Rxbt^NtcgYn(1>Two(%<=4Kf*;K%WxbHv6&O52%fqsji}$m_iruUiUC1 zorHOd7Dw|mIjpgGe&1%zkl3a4eaqA0kyr*|Rq+)fT4}v43BtA($FXCxl(3oFo{INfX**?OoyPJ#TYIsQs(9ukgDoj@*Z@}T{o-!~9CJl46 zbHzkO-vdAfd>@2#$tVFd$4~(a2Y+#Iotn^AIv>fpU70Wkw`Fcw`GAbVA{aUVT(m)u zJ19|adHaV{2lpbQE(-#D1KaF*=_g*7=~%!mTYBzLd_18GvT7_S@fHcXlLUj2y1GK5 z1{X+TX*f1E`a!_O#rdg=p}T_9+1!pbxanW#L@|&_Ysr;tGayxvspGt0Zg< zfTCu|AZ)^vfg)Jlz4h%L=wq5-I$;e&U*6{8teNWTI=DgrpWZhcAc1$js&n+jA}0EB zCl^M!mF7yk{ZR03^6!*(MBQb3UuHG7tPocm1ibcbhx2$@ynlh@{{P#pN5CYgBuGR; zjIjsh0(1WMLI7~g)4H(t$Lgib1kH|daj{=xaW~y>y;Vv<>Iw%Jm#9aX6lI z?Vr)nxze3XraFS`eX!_-h$0kc$ILg>eE{Q6&`0Y{NJxm8>O$(2LC^*P!Ryf#FU_g7 zB#3ESYte>wk}flYE-upN{++ij@>|ob0#~!Wlk>-ke#Col-XrCklT4zo;WeDniX^(V z6(HSQqP-8A$7?bh3*SGv@n)l)p3aWU@~@nxE`I&MatkUUe)Nrx z{U?I0*LIm1VQenRIq>$ut&A{cl`)SMS0Zocox_+IGDVyW1R@F=M05nKEfX}2w>hZ? zO@I^JXFP7J0H_7VHvti=48&YOaNx570(ZcZ+(Q5Y)||FdqA^7-V+Z*|RM>YokKbj+ z;+i!f$e$?uE^ne|5eMJWmciap%Q^du9!24r^VwjXW8;jpo)$g8jWzL|TCkOc;PT1H zHWa*!2iv|8=o6rdOLIK+)(zUpx=ug2)>Pf>a%xTA%v7G_w8$9m6aWnX6tRPEt5Qlh zFNAXSrhAMnPu>ahYgKqPHoa<;BsEGSE+ci97F zJp$kn{enS&JbmumHX!`Je?LkL6sDh-$n>QJlOqS);E+9V>+@@3u_`JnYbSmuX9I5| z<}y2Nrpiba)}_`3-HhiVc?Ea>*UVnrgr!X2-EMCBEnU?r<1xwOJnw3DddCYBpN(@U zE92Glbm{K2>SU|Gj!}@Atl@s?csA zS9V-($^+%=>N>&Hq6$=cF4(^NElqy~I zf?@r-)vG!DX&eWQn0MPVF6(++w`PU^wAR4(tt`79pIveAOW-o5BYXlkV_cnB1vV<# zmUf1xxa`w^9^NIt#pZHnns#xShteyx4o8_U!(n}6X~hme_Pv;0FCH;Bk~w=;7K#~X z#-sr5YQ;F1$6!ES-j_$-Yz3P7Av{A|m$Qf5sD>6u2aFrKUdMnJBMEZjcZ)iBfNoh% z+MN{JNaiNd4|WvwVN;-LY`(>_4bX|9G#_ z?eHDtA(6jsJXHD7SdGU7kUkJSHyKS-LCjZW|9W5A?YE+VJr3Q#r*?_nNLYHy0(XS$sEncCxz_NPG{FU$*T6 zldBqJ<*5np_1xI)D^W4HQQ@=<$UF>Aa$fQ3)vE{Y>0pR_Ws|61PC$kR;J&RHON9?< z$>E)~R1T1pDj7Imp)gaX@Rdl!U9Tfr3Q!Doe5J_bxli>lL(@xS*DL=voZZe#@px@Q zT3deWZoNIJ(+IPeYn&fCAg@s?QZj22Mc_Boy8D%{Y?X!zC5c&%6QBxTTVhw|`Ab>1 zK#9BN%^}<1%R!AFaxzl?CZ1P*B`pRxBqs#x9z&mhSz-rt!I4UYCnPC6GEr`AP`+MBf@W{wlBS@qqgU_b+D)?DF zNT36d-%RaE1nXFk@R_7NSoneh*3@t(HM3>?_H%Y^6GLzAwoj-TBeitDQ~FGw_s_Hz z=Le&z)~`s2nniuAn9>fZ{lM0Ks&M@pS${z6ma!U~cD`(nJLto32cC4aydKb+FSfWQHOHsvwXF6KhVzcytXQ%l6I0o z;KZLt8cEyz4169Y$Z2O&mO7^|Q)?+^+RL9*<Dl>%-Iy>WLC5dP56qNYx)CeJpdwuEa;Q(k|Ao{8Xq`gri`$v z%x-F`;pn?lkvf_38U1&6e}U8J{mCGRx=6oKDljmP1^=RScfAdsXMol3i+)C-SpT-=c%t` zn($YBE46jv`gI}oZhAE!fq*9Hzk(3wT7dz5OgJf4Ef2QjLXU-W;)7YxhYv!atgRr! z;|yT%2KsZ@F)wy1Gf!uxLdSekUc5JHz@ct(3=yVbT8CWUgI0H$T|8iH9(I-yQ`@?_ z1pv{glw$CG2J$-!BsOiXXlT$*V36F@0tK0e`mwoep2u6D@9=21Q|GaZNgM3{pz)~5 zXc%sE=z3n1jptj92?mbecRns{Rc2{Q?tyWw5f+% zm8Ap+&L0mWror&-UEZ|km;M~;&c$Ey<2DO*U=Xhxm_6oYx42f+eQe{on!j=2RiERQ zfE(>E#v8^mIQs0XQuP5YbmN|-{RLlbKy_|d6+yD?7kGRw#9i))DX)}J+$ZIS9U*v- z=ixjY3`Ofp7N34Uw}TtnVZkf!XqN`V@S#(xShDr;I&m|NuYUmqRj!A^gqWO>$kw%w z27=g~wn9HJrYLcAbkrB%;gC#Q>iCDL-%HsW{xCNUGUy`a%+mFdrTk0wK?~6>W8_<7 znb!q*|(vZTj&^L_gQ$N&Db#pMK6&xMkYS@S(J0Y>dfDRf6;iSN?NK zSjcpUucckD+TGn<5^9jGC~vyKJ_-dBx%q*mqL@~dH%0`y3hCbzpv-@JkP!N<(%``pS{<9ulIVd z_gY^}T$vS3Rlg7XQ3Z?~_-4I=Pd|W#k2AjLCQB1UD}i30gp&j!%fYUw4DH)eKUaMK z))BeG;s}d>#W|&xH!i=K^YPtJVzg_kK>g_EM+Qji{OUaZoXr4XY#v-E)OR)Qpqa%Ewr&};UD3ldLDfT!O*bMQkRM{B z6CKADVA^W0)pqvU*+7#D{Ga2v?HfKKinq`T#FjX2LzFcTpUt{XW&80SEt!9m5G_bO zF*tRvF%>qNfvv)RR7;oQk;hKPoyCo8O9Bw2_q9_$v0OKyGXYD5j!!t-DuFc6Wh%A6Q?AKpWsb< z*&naotb`jq{aD}$x6Tyo(YyBJ@{7<;%mT^3AeC3H1(kx?56{rrdC*0ynRS?8)NqX6!7Y z;Q?>JdPss`pmp=(Eq~b2l}r$`T!1JZ0Hb-A`;LynZkn`$;I*(gtnAGK<6~Om`|#2Ge|Szz5yCzEdZp zUIP~TD_Vd>RH!5milA15PkFaal=Gw(i^6FQUM%)x{lOu&%y3m0yqQ;VcRHqx({Z!pVtl= z;VWQfaQDzV%Um#ih##4UI`}=ebtr^j45ebXVz3=W!N1AySepLSNx4}7OlrZM&?Mvh zn9#@auScXyzW4!&j5G4GN2c6Q3M0Cj-0_%mh%9r=8s&W3gX+6>?%;UZDwRC)$I#!k zFoy0GK4%8RoBx_d$nlq3X`20sgTIeHw$1e17ZOz_Tx+6k+dIcT({Lmgc)~oPSCJdE zHZGT%$LJ(yRpJKgI&jvL2lijztleiKdJjQ+kvd+oqmn1jNG#4PxAe^X`sVBV^|IiU z`^t%}L_jVwDT}W@s3D#k2O33OxJE{9Z+pNCVPI{4ecXlD9;V1%p+Sp3c+xgl}}hWj z{fH|auv)vr?=#gu$8)xZhKD~E)L9pfy&PsM7&XGnz3 zPRJ{cqV8jW4SMqT<_7%@e`_S*CI)2bL35i~6nz8ocxI3$*wtU4DF<5?qi@f71;LO- z3=Yf(m^t#JwDTvnPEgAYVi7*^m^R5PvvPi9Xb7fj$d`c!--+?YUa^Q8=#1>Y#IdZx z5b&GI5?2*T8!{H7+8h~oteh&-E(FI+cKmBo!Y7CFvc`1%csPnKUt^axFRa{#WEBNu z>6{d($e!B*fQeV)v!j}`4LebTz_r$lT&5-J6Fs{){IRts%!@XQ;fa5UW4_| z?+Ej?w^!0E#y$a2IlvT9p64hIn|)o@MppLMQ8}tf3qoIxuh_kb`NdAZM|m@K-d(9v z=yYCw&y{-})dH2ZJLdI)JhjV}t}M_jyr=tqEy~+2pEQ6Rf4!!(ZiRcv<(Tf3)Dn5A9Py0DDYixNW6gX3&+vK-nP#6_S<20aNnqP z_rPnBgWCwF02yAMOFSdE>o^ETO18S*s-XZ=7$he2ceUJ55DX-`(`OnzR^MK+85&_a zBk866JZFVeQ!tnB`!&`aMNSp?N;>nGMe4>f3&sez6&`iVwGcvo6Lf5zx3-4;C9plZ z_&Lg`m|C>tHY!RP z;j4P8h#IE4IJv~$RG6{ZKQfl$6>9D74nt=~CM4DZGjD%?D=rEi9MiPVd=A-P@tFO< zkpfWalVDc;YN$bZ>p1VVMkMju@k)GE6+)X@fP5G0tcZPt=-XLbZsTV=j}A8}efDNS z#JHCy=eRmZ;YlTWp?}Vi&Q(98Y|N_WC68>~L)Xq*#XQ^zQKorigvCH+E74*QwxJ*N zsYn0)4~JU+viCZK9+n1|SVpnm4hXKRK(_7xB?PBCJ-rZ7{kd}9H@&Mxr|6K30k=6QHuglN>i@E0r?^keSMJat`n!Q)UnyWq(MgK5=VR|6`L zOm2z3UA%nwn8dH|+9!&@wf4FowFbZ+ID!gpHfo^?=a+>XRKbQ*Wed6f-_)Y% zZ;QPfE8dmR5M~HgSQyuYOL@BO=8!7-aVaTc{k8MTa!5CGh`RUS!868JbSs{RY0a>WUk zCdq3}ByG?>pZT1<@t?u?rDWa09LoV${;-*iy5|M<#jm1_eto5pZh8&|Tt zy);dlEhc`l?xcTaX`P;wc~t)CELqZ&@qgzd;q9H#oMPoOif`GP2cL#~%bq*dLGm05 zhEH;x;E8k1>p2{#!{0h|1l1eBOZs&+P4Yk@UK9bnuD%~l%HA~v#l`J3MVwmVXthe& z>kPh*KXqb*R+mBX-rEo()4=Oh9A*~${a)wL_YX}4lsR%-i<6R0_CQmy367I|xn28U z>~hZ^M{k~-(p|lN$2XMqYl_yaF3bO-u|3$G$=UCpdDNU?JP_p}TJO^oTVWW2xna ztxSeKf*L~X$ozUm`*G;(weVOd?By%8YD%~<1yY`3j0i%1Y1l&Qc5cb>)DT z)CX@6niP~Dd@ISKUd~*qG7daS6;j>09*)RPZGzI7q8HsU@-k52O;*nFhAZ@<|C|s- zb45&Ua_x_;P<*Jsas3pWCYhJFdB9K5-O9$TF~ShabQqMe%{9Fv-)+_h8sgl z^O5T;#Kx_ZqzTfDAJepC2x?SCZ+C;(DEP2}3a01=Fmn;tI|0^q+FKu(02Kn8(S+*q zm78hq-J^-tU^U>GtdoBRerEjlipd5=0XZ9+IaZa|e3TIi6=6WFeCh%&c>o-iW7Z9#-h3md6pd(-z9iwO1Mu4U&1wAacxG*&SAi zfsR;JxQ>ftU*)wedgEW`itIo#`{~g=72e``!U))XJ;4qfV50X}sS|j-Oy1oRFsDnN z_89?kj^gF+K}d7zgwQH*xVg(C06C;xnY zcQk~?k><=D?Gthg)f?__I`XJEA3HVUUpb!kH0n#-e1x$nbFc z>}U-sp6z44BW(5zxFRaSYW0>~6i%yQerZ@cGYCi29ao^j`#vej^?{}am?d^WgX-N} zn53j<2h#*wU1gDDOX&NxTn9`4xSoHu5(BC#8={8eTVMksK29^LbP6JV8AlM4hMWlS z+qwTTwuF@;MXOfoP${w0@cy6oH*b*LCs?V9fiuB7JJovdax}@xXeO<&(jpv_kXPzxk-AWX%kWcpD zYc}$Q%JhK(OR%?)(m%^aACP_dJctUSlaur=Zm83H+^hMWd zxpxZ>KO8s(W%OV!f&q1`{e|9?OP{qTGN%?|Z}LL3A0tf8)W%eFM2@qgqt*VMkrJ-< z?a@>7T3Mzy+FLIJ3pC>(oC$uu>4qPyWXqr&d{%M;Y(g|0SN@@44{yGU`% zk010v>UT11kAzon$d*iaRyWw_wd+S?<9@KEa%fMV22S86M=m2cdYr|Gz`qk5p@WB) z2J52q9amtA`58%Rv|}#D6kXqs_-UiB$7o*h>hc}pEp|IPa5na>(G9bUUAMv+i}&}i zZS;O^jX%#02zXciT!_#c++!2%7rPVDB^8`gLSkXF*C}eA*Q$ZQ#IX`-+=9-7hT{kn zCr-Og|HAz42bH!nmYI&D6Y|YcrobN&NNI(I;?|_K`8*i8AX<#M!EhKQ6Q?o>Nghta ze)LGCZxnjYXGR5rrKha6c4u6M<*FVxSnoy~?LGjrYm*Ds;Fk2e_%2=dpV6z};@S_; zC8YrR+GRqAQ#FuS1a)74$Q$-vfkUL4(FxPm)mxg~AvKPtU> z8V;IGxrTXsp{b006#z&Out_m3%>z?L*5csoa{UTYL z)%3Uv_)g~&PBsYHi=95gOL7qcXu=9(s4*h-~n?pGh5Qx z+|*(Fyhf8Uuh(x1p#`}m8m(irg$Q-ND`$F7lj-qAkrO|XQnHQb^g@<~4Z6;VTHu*M zZuG1r(wWzp)P3?2Orp1oH_15VI+5OxPh>!Tz?@NTrj)rr_Yj2Dy@0z7GE$iAge_UMF*wm4!vX*;=uq!1O7XK~e7@c*S35m<+sfU}w*2 z5i2Rjnx%(%rx(EJsAdiYRdJ~3Ct62IdwZSIEy#)+)PX(Q1$zi8v*00U;a00929}=R z*4L^>lB97tws`?a%7ONccS!tYBxBY5#G#0Bv(VeZC=5s&nSrJJ&Sb#!Of>WDjEG1* zq)3mf)7a7V85HgjAo>G8giso6BLx=3ulaH-I(!M2Vud1(J{9Avm6-XiMDhkg#|X-A z5hXB*b}!5y?1!;$=eHL9s9;q(*=<|kC_dTJDbfLS!~g`&D+{#Qd7?!>X{W#@?HmpX zP%MM$%@lZ3f4Dce3hEm@M{Fw34wG&Y+LvIkU1SU`*+^B&%Kk85ss0bGTxOTmAZ6Mxjxdmos1pb_LX73gz~X zsVYk{!lEr4_>8$~r+@{uo!c(&KE+&Qw*nSy{e``2){wS0_jj5p;A&bkngmPB;yk$c zj8+$?Iz3Y{62b1}x4KO(TNzQCx^)AqW7P0A{?=dbC?Q%h;}$a325@$$9&_DQ9^&&6 zmhl6I5mlJr1$vqd1Bm;9f;C+Xz{x$w+`-i&-R3|62El(M`@5mg9oMP{4!KJ2`T{pr z%JwTimu!`(y?x>ZK!cO1`F~!EK`DNJklkt5-jyCET)rB3#H4q;uoyxue_r2%yy{yZw=tHXVHY`MCbSn3jSwvGlarspmH@d;)Tm;Nu=L{UrA9A1^XkJ z#&5BUHXsv1(F$|GShH&ZooPW5Y6X-5KUk)CP}jVR95LH7{T{1Y&Ky%h!e_u@TI}b) z`}=`Dd@`Cwk^-~cDa{fO*Hy6X3WS26cK{f+p2KxPUl-vn?J*1Rz_bG=l}fm52malE z-E`8q#ii7TE(lBrb4R4Gzk5HfBs;ww#I?($)B?~d0FKk!&8oh}JG15rW<;XGvKq?; zL+=A}Mh_wJH->_S-QSEShM8H1BSp>;cXTq)lFN67{W0qR)dqFMJcClnwq0WYBR&Rm zqAop2U@IHy92W3HeQM}f5dR%YO$<0lyA>g@CJ;}D=FUo78{5Ui{{$wHnb<#tnU@t% z0WOw%I5Egh{;-DJUFkkS-V_7US-3zBj+TYI?exl?d=?g;Rfi z&ci=_7gFJwj&%%$W^n#RAav`W?;H&!#gl;S++i?djUVLTN1$p0xjb#(;8%lX1A9g( z)h~T%*fMqiT)=U@Yd?7Je48zT5qD26(MbwnnZvcZvu*dCoGLU*reC!+66P&8$xdUKJ^AIAy|8eET#hQMLv{W)W1 zVA}!bbHHX}-ev%#Oiv-)y#G=9?g7?mtpDU#e>Wlp$&vrYdM_Y%$V{fdpXXM$Gbo$v zzVXJF^{&?RmO%mkreiPYHTZC1U1mfbeZ2w0%p6&&bXIyobmVH6mAV-VamBxUxBM2! z-bNLFpsvkA0t|eErGplTti`qK3KOkY1%eod|%J%XgB!2xmvZFK{$o?#uhHLoaT2y%{(K?E7L7&A0}h&7{sih-v(kszi4 z+o~j+r;LEik3?~9!aW7X5D}Cs_bXArB0j&eVe@>zWwtJrp#JQBPs0E5hZIjo+P}g0 z8x|p8G1<73vYwHwgXxO{Fow#nc)sIg;|zjg6RdKje2m!=^Vff^GJ+S=A7Q}@Z9E~_ zjLY+zldSCLP!RFGR@DaqgqJC)bwoj1-QJ4cDs=#(XRD1I)6!=R%-M~skpjJOhVxh5O)%CeRl>45rsFoX@ge#vvL6?e#! z58rGHw%nM%18l(0Y}ePLitrtXI-wlO=|ae|9TzH~G|FcI6Za@3wh~Z?R6YJzd#Y) zg}>*xz;K6ggHIy?T+BhmS}i{CAz(#EfE`oAsV$d6)-x8dU zQ4^by{)(JBE!k`f`2`EH`^k0`42@biMxSGJ3muE%kfBQ7lt_er99)HDZ(HbfHpUc1 zz#Z@A<>^rL0U*{ec_0Ywycnnt01Q<69wjXe%+w*QkV@7oK3`B+2-Of=7e5F^yvsP> z!08{3?1oS;b7UO_T55mng~>bK&^-nv)2znpjx0N5WbgCPB2vqA&&z&Su~z^vI0E1h z5$_ZFN-mCi&%^nDzPyi`*y%H0sQ6_y&1W3HT;r4!D}#mG!tY`nE|!|02LSUPg7VHU=>m!!@eG4-c6jI zeZH2|Bu0$5Kk^lS+U*eT=-(dW4p9N1UV~!lM{H*{Rjt4N=|?FdE+4n_9nyXKSMsgV zN^ku8^P;HmAU%2=2HRWdwZ&#GkXRo9JA9p$7}{gp{^utJKewA(bcbJT@Tt6wVVq)$ z``wy7qi3U*u3dXA#9K1+c0#r)Fh`qmk%5iq)6zZSr?6$7JRJ=h`M`5$1&S|~P-0#1tw*VTj??COsO|50R2c?ehZZKh%q^ zDY}7%WZ)>r(v@qk&TwHSN1iVJCzy^eVGUP5#PBCrSoNcnKwKX2I=AG0zM_coW~jo` z`MBs1U?<|ezCml~9mj|3*dDadi*$~2OT?TLg}p?4l0CkvD0Sz{#dnOG!l1j5d}@M8 zBwPopO4q7)1?%K+D%1wBZ_k1W^lh^c#YII>eBL2`+CJ+qhWh=b z2QX0HHGQy1uK^tD8$^&y=!haSvYr4J7uZ}TFQ6?39oBZVLaA_z@dE=xgY{TP6eF^d zb6TZz@NWR(`wh(Qn5qyh5iFTYu>lJ03oDJ*cR6eBT8c~rTbaj~w%2;z>qlam(ZRjt=vcmw@-WlL?&&$}t(3~)o7?;NMDY`O9mW?3xQ3}ae zTLh$NV3?lUN6X3FtahIY_^nuYspHtJX4m67C~UrnRP-fzS%^LpvmFAj!H8eQJOFA) z$W-!x{V2E6r3i@HGND&HP*;yPm2HE?|40gppG#qo{cNLXyb_9kP!VJBR1OVYN3}PO zEw}AJuv`W+@^W{Sz1;N`hH#$819-}m;lGEVY>kC#(Bq%r(%IQVp(aX8fR4lihp_TE z55&;}8l+`436M(CXWY$mo{8(VzcUDCvSo1YSs~>6fwptm3yeFjbOUc(Du4Nxe&O!g zWP;djlqWFFn467DK{0N}!Cf5xd=}6Xjco*%8~Zf<7uQRE2d zrC?87<=3&V;+g`}?=af+moQ|}*|`!No@a1fik+SwbI<)LHl7xToZ9Z-B0ca$=0)R< zY1PJEtRj}aP%SOPhX>Oq08PDpq211!McXV%hFF%MaV;p9azp%P&FEpsNF-q6j@!FmA=7 zT+o2-1-0EuTpHASD*>y$|M0=6Q3KlLp}ZictXvnDhE+PClwpHmV7DZ|S9}UWFs}LZ zgG}Yg#dj)Bhgd7~^X>V_toq{pzDN5VqE>W@e)HM1r%GQ&re=_QvKfi4D7~icBQ*Ij zgsMHAmHU0z-ko3R%0ZMs2SgrjiaLGe`PC{a@>uC|H4vX5%0e6P4Ons;k6N5=W=@!?tBPcluItFUv}RKEw`Wg01)8Xh#{% zOx@~8(=l}gwwS^k!=0tkI7N_Agh<}L&K4nx;&&iAgDAi;6ebIaftjZ)wk#ClEHDLo<+-f{qE>W!HVjsVz(gYh6PNOChRv-X@_2jfs^`6 zS0!*h^LZOn8StMuX2_ZnUb4ztTRKmU^=?V>YZ@XIS4x3>{b(E)JL^4wG|aU^dYL5x;~uNO^M3y`IPj7t zGDun~OQQWqO+E#`Bt2@?Ym|_v&4g}^um03PJ;QieVak%3NX@)j1e1CW{f*^TBQR*D z&#+pV`17u_=7q(M)EEB<5p23l;O4OdNp=MkFE~J%tinA&Aiit~1&ol1Y!j*bI%tTy za7G|}yF4WV;7txRzaW{JVaWg33x>m-1+?jz*6i)N7G@L2SmgghvmvJ4OMr#^voC&R z$Um?i2`Vn|Wjok({`~oVj*Tgf0nqOT;Xak?FnkU|MMB%x!hEgV4eRd7!nyoh>lH9S zG51)i)_;mi6V9X+UGTj)9-k}z-bVKmBrWZKMFA`^?PJR@r?TxSgCFG1za$ig;U4$% zI6~eUFea_u3o37BIlOzuCv9XEnd;$DwwR|zW@U9DR_y}>Zv*hakt1oD{0-a%Vi)CYZQtbw{Y)98dm6f zs1pG(8)N0v?tPx1wNqSrH}!G!K+ApREo8h_2a`Y#9T@xSJO(>5>RXBJ?_f^Tbvqc{ zR0+kfL-h2xzTO3OBRdE=<*@4*!7$w)Cbry?tf(LYU;F^ZFmpiTkL_x+{+ik$7)x!} zcE_h2CVb^=uo8%DY7j1-3P!APt8KI0C_D!E1x$Fsphf6xK;B$PBB6~_9CjM-F*+oj zo5N6-tfkR-=a<$Z^)2{y#1@shrLd0FU2(6(PiRH}qCC2Voc;<-=_z7c+zuftJ3BvL z0TmQxEKQYwfQ;p>ke%`vf>(V8^cxL<>3gcuIjjXO{2%T)pYY=n0eu@* z0I0=W*lzR599=&^A=8!KKVo`EQz#TB8~KSA)&IMbbsy<&`ErMTJjtsm{WZsayd*VQ zT;61x%qtG0mslb73CCQSQOb^Fb2LT#^IYeRFF*k(i#s6Cv9YD)z>-A-1{$U=escK4&|66+%tLESGGPg|^*duI-1NjfDiQ53{&I-@-^&;K~3yw5fQ zRQ=y~TyH~NFN2t++-8_=zR4<~2&_@sx7=*GJBM2h(|EsbY(YY`s?L{J4V}sY=qwlB zwH%lhX0F%YZBh%sx@ zN_mN4;W?vu*F~s{RzrR+cNA*q zR<7!Q;u^F2@VGon(%Ik4eVie*GHBoWHuxe_-v5pJ ziRhCnvoCAkZ2@izAzBS+JMZ`wd)z7=7yQ+a?QHuAeoj~{2aQ5UarGECuNbv|x*N!T z0M$p$r5&^Guxg?1qdbxqNNvY6zwQBmT~3=V{bxMW(8}i1XhH3}v1|^UsH3W^X2Cd> z0UFWx{JTlNenLsZ7&;F7oA=t5C2^GCgfJW`!IXCfWT&W$F_Mu}==46CLyO{HnL@F& zI~V%4VvaDuzFBJT{0`fY5ld}Hl7cTFmk!>H9MN_i?J!th2m##n1r}*b3}fZn@S%az z`F&5?trPfRps=oFMaFGFFrhg>5L#uRF~XW5fNJ|PLUYX&GVp2l^uouTM2lY3#q`_e zswLz#vSR2j^Qrz8)k6FN|ELe8j7`mZYdnv8bEv!ck*v+=AxfV=ivCFvJZt-B6gD6F z?{#$+tvQb#o`kmCy*Ss!bTsZ-qYh#~Z5NgO(IjM0!~4i<6F09psT#h!h&18glJ$Q9 zICB36X|5-i$8kM1nzzhT<2JH384Qp9rE?lSwCPwKJ*Bl!5-+r1c^hxRlUvAt)3LfX zwpGf~YWJFanMfK=d!e+B@58C5&P7LYL%?Gg*wJ>a?iX4b32s^@Cu<2iI+Jht&ZX$=A&}%Q_V%(wCxNh)GZw5{$_&T$M1Q-h+w~ z#X(Il2pu-SYlLnio&+{UhlUt;k3KimeuvGzbiA`n${7fKs;T~q-*=^Xy*(??UuGls z*ZE6ajfHz??oMagW{C3uS6%oHq3h2OKLe%EN9(u6Npoy$Y)X2)a>Ex2qhc_{Xq6ch zc#zLpbr40pQ($9&G6l<&CUJXy951=cDsqGYRjdSduAxr_BQU==o9Fe z*}+QWgRbEw4Y;~j>k}gi-7(n+z$)gYHM%b4L{a0*foQk~tNnp8vWGe&l^x7fvih;A z&9{9Ox_7ZD(_YL)<0iGh)dR?&vI+BQOLyomozL}1;j8&QiSAh_R#{(5?m}G!`+uVP z*Q{(A*_Y^{1UH-~~{q|{Jb2WG_fqQ|W;(n!j# zM!2;MSEs~&1z$Qr{SW22%b~BEJ^qdTRh+~4!9+A+%T<(KI*hNeb2;Bbxf+2;0(L9> zZ$(+j&duA*``K&<_NI=m^#?lH=T>)Daf!gx5%EpGP9&tGD2jNzm4D!G2SV&|$|2~q zni`beIOhdZAS!{gR27-k9?zDBY{qWrolgbu3q3A?rdXHw5c%mlN{IfRlNS5Rl>KWX zO8`9nDfPTlt?+VdYB{YXe`Dn*=<8iIMeUoZ$QG(X$eA{!=LCNDGHhA)NUU5^dmCm% zaC|u-2FC3JARO_f9CsMK!*`KHpP{tZWxxWfdT?4g1??y2Azf+=|4c=G8oe2+U%Cp` z$U2NcQo_hz-8qvYP7gZ}oC4vyb>4|Cxi4FwaV7Q>;}{jfrrU~-p^pFLCv2DmoB#0% za5>nAbv6S~M1AT|dyc20v-88P6ISNyfs2ZJU1mi3fK^=l!c?*s3PAoiAVfU)fX$y4`(pIl!c4@KGQi4nSXNO4gV}rDFXd|OU4%p@2-^Hl;-)*SUO7tIhL}Cv zfEgD5ww0I(IEisTM@HH$Fao>tbsI`JYmw*pLJV0x1G=kZC+`+={s^HjdlZ(R?tcd_ z#l2Tm+kevjM=4Iiz;pE2X#k9i?R8!Uu!8XWn{%0l@Z_z~!FUSBE8q^)#Zk}-XcpWz zE3KeI59KrVW>~A?%%*!jJBJ~xbWN#++j1i?p$olfyto~uD@gs!eufjTx3N2r3AXm9 z=)fQfE|$c{jE2x-%#NEnZZ6tvjFHNr)^`w>FAafeJH@)(y_)T-@$mD;0u-#m&)mK0 z@z;nW024-c255*cTQko9)mgobsCrGvWG}FMo9BI`rmp86j_%P_j20Y7uQS3j)e3;f z;~Z_^xZr{=YSDF9QtePVb?-C~++f4o#t+q9cbsWX<=1)g;q(LuN#+^(45l4{0<<=QW8H#tt@U`EcWnnbn zQ!TkA!sC!MJ`UtST34O@srzcr5c+PJb0Gd(d8d?F>61fAbrb4mK;pn73|T$Gn}nQx(k zV`H%rN4@^pM&%$-3?x451r$z-gxln)U}woo1uEO=xX`Qr3vc(|6{lfmOcjksv{k*K zqaZlcfD0L-i$&s~r*gI~(=~@`_5a)B#=jCiJoVqU>p+<^u=lt{k948W*VizES$g?L zkRhP602os*>+I}|x42RYWwD=Iz#QryIxEm<{M?4SYEUPYN=7x)S6gH0Upku%%4Ns< zryR!^1qj80o8ymURH4~xCDNYvDpxYru)Js~{`B}jJtQz3i)0$g>&D+?VlpW5t~c-k zEd6ImNl6L`1QUb$AqEXpN+%K}+<``IE>C9ipr%$Qwca(K5bpRl}=<86I~ zG~>_>*X;kj?ma1mo3C3s_c>JUv>;`?4CCW0JV2@K2X){|AeVG0Hw)-yc`%#p0*dAC zuRp0|W`=G*v)p)^!6*{*%Cr`8rcHLC?JlO+=BICz~TzkgICC2e2Q=r zoFM2ql;Dku&~2eY5yJ`~eoEMjYTpy`o+rOJhDSFD(Mr2TKocOGRgEDfP&)&fyUAN1 zddw2BZ#wALGmNw&9iw~(qg){j@8P(9w$InW>@}s+dSf+e<19$WN0PVpFo3TTW)B&H90W@d z%E0b1r>&0W0z8t9XW8TIs-8x{xG#@|GPBD^I^pU986WHZ83?f|CU_5ee2Lh)v-~C? zL(`Ep)1C=qHYkEB!zcw>G1vgDC{BhOSR)_c_G=gNE40031F( z$$fRkZ|qm-Mo_Uk?Mpt%(bDz%Y2%*PCl1!U@~pq|{q)h>OvXFR?)}SnEQ!cm`TQX| zd0eLaI&b(1jb~ds+iu1TlKeK}{E zs_#SRLuw-rDiqeWcUw40T{#M$J?zy}tiCYPL(+e7^|fbERw(T4}reQReaIyPd!=`!7<_mHQPjv`|AM+ce#HsR96XQIV? zUMsylzS=YQmS|75k^V~!IdT??<3mvT59qwqr3Z`K0;oh8N|Dy&{*~J5=~H^AXh=@L zAIEWAfJ|Fo0MCil*eEI#_9g2uk~k-}HYi8v;}SS}Ko~`>8-m5$ZZxT;_W8pzEE8!- zc*RHhW7ab_B~Wg|=AGJ{W{W%U;edE)!f=qnv!6qpb9$!SeWp?`?>WlZKboc+m_`~M z$)5-U)7QjnGWl8eGD8K9=m-r(=ng<{XNiet&?)=ViSI7=Y0OnaV~ zTmh^iu<(dL^!;E=HTi4Y_vb-@bw*(%unV;gbK&dYlm??jVHGfX$v4g*iBW@F#nPZe zhZPul#Ai)n+f6OVe9BwtuSC>JzuoFL8)+7swR)qeUBLVMYLNQe-1YY&q9P=TifLo% z6ClR(eBZplnC9{b=J=Q@<`7)$ZEHE^p-3rp6iKk;^gh^vvWBdM{^okRPOwMvW!^)5L;o0Il`(4VOUhyx#!>Y@1eQ2cmqqPcC!(O_<4KjicON1{ zaHc}DI_FWBwZTH9iLRL=E*~R)gK9c`>y^=sKR)ah&KKYx&=L&zi{pJflM?;Iihgn7 z&t+W1hIpcjv;<=3wNOG|)#r9^b^C^2K%Jg1{v}asic)jjj~+r!dNe!=4mqHl+<1!M z5Lay@1~H92P1J|!o_n@zg|8zvtMM_3dMsB(OtpoI4xDr5jRJf0%ka)dVS01!BM%NZ zIWAD3Vb@3%V>^W0EHZq<+5e2cdNb3nUv(oefQ!!_-}&cnOk2+SRoYZ!ram<~?VC4P zds47%I<$g-+^kAz$=*X;b=LoTz!Zo4dAe<0^KUi!pRry}NnLuyV}q$X=z94cI|m7c zb)!DOg!Ah+Wj)^%nrsyP2?`1P!^K(wrR=^&eJ9J6V+zRNAjy5jQgbqd9JShMvoW&a z)zW;UsK3Nw>Qb7gSJC)q_s&&wgk)prDlE>T)wcrf)~hQ58_O*%n8xUPpW{BiT))<; zMTc4g<{y58p+_Y@<1kT}Z0UB?yY5%tU+I(PNbeK9b`$bgHd-|A*fMiNqJ2vrCk$DeqU`$Z*d#{5Y$^(A*z$St!iK{XBkh@wNKS1)VrqR}h znVh}}CLgN>I*>W4gRbH@af2^b9^Dvt50pA(n8O+xLG&? zyT22QoSv#tBch|&2~*S~ZE`dxf#6aV1y-|FnXJTIyh(CuUq)Rl9_^4i^n0Rs?Ac-@ z%|xJ$=TxS)E)(jzsdb9;K)z?j(#{VfCb|d91=e}e3dT%IKOfe+U&l7}rZ6>53T%TB zQCMs6Z}!7`-9K&jN-sR5tBhI|w+RY@t0ETI2sX&W+(9j&!3|dkSwWfl_YbLcl7QL}Pk9&`b55Iy z(B~|@>@sSx1?gO!vs-@I4i8p*e|$t)=eUqsyi-#iYORY0+=O&CFxfmW5-j zEA0L4Q~g#P#q^}bIxo@emMXHH!llq^S3?%Y2JS{8b%E;KHjk(6mU6}LhVQ*UypfOvJygv z4uzMsJiEWckwvX^@gTSaUP;<2`za!$8pxBJ(B&@bzV4pwH0bMc8fhV-|7yUIVAsa1oCAm)+w#33 z_q&EEV%Ml>$1C4ymfP!oVkZ(f2~Ma))y+?ggQ*0+43>o3YuaLI$z$8F1qS)`7|=w8 zedTreXV<4k^?N!l0LBArikpM;Wt^P%0vK6{m^Fu|Ydmj~#=5=b<@b{{kairuW4IGK z?jU%jMkUuHiLX-o@J;uzxz^%5?t+#a{P$1b;{G%*y;TnHW$l58@#4`h7B#expLhIF zqni9GhP4_7;$!pf%3MqLKEQ)tJteIUKB3F~$H7mT1moMBGF^YX*%*W^Q0@xjac#FE zv6_=5KedW}*Lk{2%>Sxcd@R(5s4W=(Wzn8zlysMe7Fhfo0Xd6#W4h-GA8 zmM@c0z8OChJVeuZR-$NhOxvBGU>}Qi;;@m<_L{r@&p^IA_etQfB5JBd4B-xNU?nEu z)h4b_6*_lH45lVcT^=u3ZuXXvIR7+iZH_L!C0sP14UYuP3qPOBbAVn@`yIi>=GQsw z7>u8*q&EFls%y$H@Q9x*`V#h19wJush}px%o}|hWR1| zDX8Yz-aM<=Yv1$PMVaCVi_&9TmOC1kA7*nA`sCM{;Fxg7;Sc-3y5yeo9?Xj_PlteV zFa0`qmZz#c@mp66?BIUNV>9y=-?K4(gMU!^3+lq+G}UP>4I_Toum5y=eWFGN&eu5V zdNWCWaL;9Tz!Ix{R(OWU+ZMYE=dSKi`DpPFOgeTY&CrrF%crUPU`h*o5|J;v6M#~_ zab~j17Vt}^>;tE8(BP)+Mb?D`muI_BRPzM)>K=qPwE#%sknC;@fS`{JYIVW)B1`UK zVjPyqIb~+@H|0YJ&azisz7#Zq>fNuK zj=xRpJNPXc4(2ux3S<-!T$Cv(1NmjgSpUNiLz;oRu$w5Go-NL2$$cJ9#&sK!Tvikr zHTB*oc8v)gPDv)@4fjO=*f@jZ)~n5D>&}LVMSI*eJLx6-)M%m~FPx=29gv&bi_Sj@ zY^(E}QeV~Bm~`$h4)T!7)+rW~L^}KQ2#EjNM6Z>Gy)P(95b?kPA0t~!eVRh#_*z_zNgJ0_L_cL_sk|i z@tL#ysfpb^TWN^h1~Q$ZA0C(_YE^p4nyLz)(1@CGtR${C41nYB{6~_f<6Vp*- zCww-0NhKYQ!>bcxtQi}RyUgz4dMR(!+8D3kA;@dq(_Fw ztzwD^KQd4pn=e%6a!@c*_yp4}PI2Ln34o4Cg(5b~-d zNia>ka-cmWs!3^ zC>jP3;uHR5#1(Ga6TmiDlaB9%&rC0La@UVP*8A7M5Z)FJZ1vual`{)}oqLf-N8Df2 zU<-&hE%su)TW}{s7P$-$~uj{i{v`U(SDaO!MvdproI&Q)r0d)D6-Ntc9i0_8mJE3Q+{O{M{9aPlOjN?f(**sJYh@_a|JL{2aYM`AKpyw|+u=iXs zK@5J0_wQ?wpAUl|wR)zXhqMwqm7Fxt<-7%nloE5C<+p{-yN>l9g)J%!w~YCc+~#CD z1NSi}we*~;wPCmmfC4^b zHk9ZbS|{}N*E%lDKU@4u-FK(z-X~n_v5+ra4cJP7F)AGK{81@wNMf_KHvKLC=bzQ> zB*VslajeEcB0^jGf>+z0tQ zSOmel`~-lIO%##l;yJxW2M2m@H_QA53V?+9@F6jw8fu-R7j*^44Gx3?< zm4K$=PmPR))jJ*6Ldo6J%lSWlwri!AUcx%gj$4EaFeL`3y?QYu4N)+^WE!{_uZs`lVM=e8Wgb{Cj?PsH8iEpNhoe#G=bg8-YJYwT^&M=pNH+j9=9u zeMXbc8-M?>`Vxq{PDhV@NCdHoD4XYgV5MTDuIqXgeF=Bl^w}^FEn20e@16Ce_u&Xw zY;xzc_WW5bO&Vq89AEk4yLPSplJ~84l%8=6p>32ilRG?s&kTL(_v(LGclMPmU*^Sd(d*iRK<;0~FI8mDkIvSrs!VqrSSgtf%QG-g(xs48z# zBr@-HI>ke34N3r(k3>Nv0PF3bD z+~oqqxCogUA>eDl0%*1?{s?%Dx^~;5#V)mKe>BEIXwQp8K*Cq_~1UtX@p@*Inc_bNS#e*4oExMdkuXykbItN-XsyDXFh7+@iY4W!c* z?UZQ8=G2hK(uS5?;gPNHS;7tA6R-{a&knQIxP4O+R^EpZWc+)6^>Sv1WYX}PifI-cqT--OQvw1dm`Q2P zaij;`XXs?Iy~(-#i0R@q`gnzs6_LM!F^K9Aa?4Hz6MRY zdEVaY2-UZ&fRiGI-DAl&uEiO^Eez2E_(LYg#CJj}Zp>^@%DM-Y!Nitgw(DPxVC)wQ zW36u#5V4`!?7ELjcx`6R5UVdQ<|#omcuR^I&0uV(07qtT~jNWLX| zl_cDJWz_*aLd$i%rp0gT{$gHas~RyJ7WI6pxlg|uMLD?9cP4^>*%A9=pE=%Kb(_ct zmG`-S7!z%Uu1PWyy?dcnqS`n;rz^ZhXudtme%$hp5RWBa?#A$TP9dnL?>2W04|WoY zxAZnP%{FJJ_0gp@I>5+M?YD5nV|`GoqCVpcDX0d^|5RGGK35IohQg~ioktVJi};f) zKT%*D#+3Xqf%j)>PKB;1b1$ty@o~BXX%cex&?btS;GF8j=ajv(s*t0Aqb1Byfr+#T z)zp4EWe8bMtjHgaU^W{u2XoWm5@?V_D%!iQo=^ULh_f}1=LH$Yr|9U=&vfF|JzycTApaXzT5$2F7!BuuOP zRNcx)gdR>bFS^|JE}VVcJ3qWzFvx#+HUC-#aS#5- z6mGoOu!*?E?Y+Z=$)ZF{(S=7~1fQ^j=9y%8t@O@rRUPhK8O+=sbMNT82mdxKK7C-qGnUmK7*55E#vcDS~~eGp3_E^wVyb25wYBzp&_6g;n)-sEtK*+_!(geSv*!D+sDxKfOHOJyr=SBA24KiN~MmZ z$i&0Ww{Y|mHW&9t`7;lBcPgf@Ujui9`|N0N{!r>*B0=Q)Xuvk|z=apSMh8HBgO$vP zy6S7VWap>PxmfUcA(tIFF`_(*$WTGd1%i~Thj}!Dy>%iLE#!~WIr+#3?Q%;~`MSOM z#nn;|z$*V~xB=FN>(rl~7{q0h( zv17i!JMRvkyLT@N!$nsmDb-^FZ@<4>3weTz)r%y3yoH;b^9dsbCu%` zRf7vks!T^=7;V8th=yvKV78!Bzy%t@MY5-%jSm_-Elg8zA8&V$bm|_n?MQ%tAr01N zv5%st{HoD#IMM3Y>4FnX!J~4b(pjWMVI~sy^fC4q;SexJry)Zp*OUpo=!tLzVLP>U zDdhOV3g3)FL3{yB%Y^HZ@K2lqaF#@4g`bXlyZaDwcY$cwU)b$sR>vw+H9;&-kwT}g zz5r*mbDwdh7ECFnT=m`y+Kw>)HYoc^Ud(#&T)%~>BxzF15p0YfZ1In*N@H78dBj(o z2Nfjl*xavExY#`G_Z9i*xgUI%K_l7hn|Dw_ z3f}YqukqTY?FN5-2`WFB$2is1_~$v%?sn72BX6L>sp(8QS2dH*vQrWpYW;;9Jts`R z_@(s^YV<8$I4%r@6xB9#7pRE&$nrU)0aHsEC&!k8NDOBm6>s^D;;_O3wB;)MPS&LL zRB7$5MB@AWk5^H&fo=1!GKV}5pu`V*TDzQs6cas(>(n0woXnaB$B|;d-80@AO2XC)-oi4sn;x?1bso~U{o|U25LyLn=59Z6}ZPMQ| zB1mvFdgd+?#~pr@SmFRU2YIr^Ca9LzfdQ@|;Fuj?4-rdBEg#&)o)M=mmnPOR|uy{s^T*sff6&xF(94OPRHi5u0`R9FxSW8MiV&-b`3FCKK6~cK^z?7{SFR-3ooj$` z!!%F0xx9c>8b9-H9;J$Hv?=ubzDq-g)ma0q4F6+yEZ0rn`)P2VYP*O`mewZRTR>Ki zs8xm49_Jb-U`+S z&JKF=dJ@AHlc<;0aXeh9Z2X^X9wSifg@4L5l&$@UnVh63LI6-pu98?Hb59{t*K-hV#i;K?TFsvwm_(wVTsFqU{A|1c^p!5`9b9ZEzLCBz<0_s%Q(c z&cCaq<>8!Uv89VcC_)q(v%y}X1#o7IlFsEPvKFo$nl&hxFR2CNrKNbfZl&h==iY@l zeFJ1UDiU}LT&D@>bW;qR=;s|p$O$*!ch@a8J|QS{&JKZrFS^1jU(AL;RGMG|B*HdH|V9X zb`DbbToghaY17Y8Fn4V?&WYJ6*=ak*S>cEnl;0Np{5QiGZFt%@ zV2m``Fat5P$fDDd@6MnjhaI~L`1nkP#c}Ys{Kyn!{*5JwA2!}1JDj-L?lMm|-dPCo zweyRW;`!p#!oO=yd$u7r(Sk6gsM~}Z=^U;T8N?M+emnTH(mne;xV|b+EtHTCxIkLu z{mM$%n(w_$ji*@N#9Kz;%`Yypg}ei6W7So=J)I1$){Ywr4q@w#^B+sMr8;HMAGN`)h>Uzs>oXB ze2c7L#zu;d=wWQ?0%*YLL;D|4ki{tU=DfJRB@X3p-ys2Drl0JvWe|!iKf%iI*)vtM zE6I56zlS2|lSlw0A9{>owEd;dBZ?G4cBELGlvNvkedHM2NkUc@Y~qQ1>%C29%isbe zV$wxJyX?+se>BhxG`N5Tb-$N403FuqJGqi@iYa>9(hyQ5CN}}x@s&v>p6+DEZ3)>S z@*_p=2etllu$~6cAf#l-ZnIZs-{OUnkLZ#4R3iEsNDbMbT37gDx+|=FTBxdkz}g68 z`^Mn6GmxV72croBT_S;LkwX~qFo(!YM?l3Hs7*3aZGZc8iFDLeX8`FxdL0m-D0&J# z9_sTy-?fiB(|LsVJ8}ivqpQma-`->!;yxw%GhpbG#FNOPJ-AT#KtKz6iJ!+`ucHDP zXQYEg(-7r(K;sy`FYvK>O99D9Cjr}q4LK&^V~6fWA!kN7eUdSgtyClMBr?SSO(K? zH+L*)-@$v&qe5}%)6!_b1Xb*6Y=*KCN+eA4GJl4AIv9PX*RW^Kv`|O2nrOW!r0~Je zl?G8O-A_<#TC6zHQ7C~CjzSsDNtV3?x=-keK@sIQ1fP^hiMthW2tGb%ou1`0ugt^- zx(`v*fg6$=!Ny>tA#MFf`NMA09Bif}-&15c;{#ugM-dX}%Xv>>zcWgn-U2&x0W^js z<%`#K+bnY6IS@4ECz|QQIEEW-_sE`3(h8J9kYD-F?gJ0GYsU*R*6z!PwtNzIb^8__ zFq;fesQ+1Kz(Q9MF;B!oZBhIChMvVi_|qnjvn~!yn+9Z1=JyG*kG^CC38rSmmt%FD zOtY^}OFPHn-+{jWBVNTzK+0^_aAUf+&N0?N z517D1&+YM2dGe9<{e6f9WJD$eyiQTl84OR+5$*n4#12=ifQ{#IfDn>Xaz9}*YJ4mZ z*xKYjYV>LW{bCzQ@sRYjb2wO!8$PN87aEG|-CZELFpx|YWI&a@B3g3PbEGwhHf^!{ zV72$zj|PA3!`k*1CR*PHCB+GYFTZ)Q+HjDv=VR|7NCSG;JE)WWk4yUqn?>ArBRc0x z1Mwoq=QDQs&#Ckjb@fUEpU>J5ef1dFtbh7oH4tUZjx^2R;Iy4IfaPRjBe#S+MQv=O+8ll3w1LDdv| zrGh6xC{33H6Od*=aIyX76@=r&OzAUpz}7trnpP)KgY>TM?v7FB11^sOWFSFuaDUp8 z+{&C!HcC4G$+|IaK0zx@(}TlK!IHAUW$^DQ!Z3@$kD0ggW)*W)cPrHoH)rK8*FHG% zH?k>7!ty+r8j;v$Q|Ogc7bcP)qBI#peIs72KdA9OK~K<^@Y1g zsSD@Drp{mFT19PQ2q&6Sn}*BXAom#tt%9E8?T_tIX3(S|58C5?{7(X2y^PXEL?=;n%4#mcFYel9PKN6AaE;qb z-gAJU^gaIGCo}||yar1~q-*d}mTc#=9}3-50*{G46W;)x2iCbePs{<|yx{}k#8vDO zlj<a6%si0sd z0{V%usAuvLFX$EVH<0lf8$Anjycib&buNUe8iZYpxYWrAR5|Lqv`;CD=<@-eL{1kg z3hzb^uGMSW>28IuI;1pPLX{>PFq`ojQ~yt@cwt?CO%zL`!JrO*~ws2 z%P#eAL&c#xH+A*F0yNJ*DCxCTFNyByt~5*irjV0RRjh)xPb)Y@Rh=9eP%m1@Ig0Y0 zfNUYkN+nok?i^Wsi6xz+fuk6WT_F_fsYx&OY8(y({3DbD3Ns?5G@~}ASMu0=joaAr0s`e@En2Gw| zMhQG^N{6sG$y1O0w$`i*&O7azhc<8IEanuyGJ-1PVeeT3$BK4Da>9?FQ~?gc2((8P zh=QhSZ&ugc!ScBk2(*eC4NOZFpjvaY>2c>>5l6$VqSzT@%kGYtF8HX=!aW;ap6ns1 zOVsvH(9@>89;fWd>PrVKz@9x^egy~=*C^=Ruq^{!!>qMaqlF-~WZJq?K5s6vW|B8g zB`ngjlU!TADLnr~@M>_kRgHwmYN^dqnZ+=-ezX}WmK*k}c(W&att_$?IcGT9>>+yv znxNjNng@`T6~!-ucPm+(!a@w-I&0G5*lrlbCc0qpETf!-Axl7Gy{J2Sr@eN|o2qno zX?JU;QXe5!tD99MeXG2+o)QYE2r>lHgRdi8a``n*o6$WaDm!K8*|9iq?oy_+#%)Np29eKIPX z0~(h8rp6imr0^5!JecOJ(e!b^GrF&spjcW$es0f=e5DeT*KY(cLXRFh;M{NLW^7-S zENUDTS&x~0r@7m`UYY5^QhOgiAde|qYjQH_|HuK}fM(4tsX&7)k}SB9L9GWl__6Ts zXa0T2>vl?!4i(v2R?KvFuaceXS&P-&=^fm5nQwM+$(oOHraK&}Y3u*-77=ZnEjA#g z-0vb4Ni$A%QR3>3FD!(Jc&k?iWNqp)X@{ZWk()8(l>fp@d;nKFlnX`ARMbp#nb-5F zx`J=RFd<(GjD`~dv!CECHv@7ymoElV;06o4%+doZW`+kVf`4IkEbZI5dJYqwqn0ya zFai+$uCLVZS)R7$zjRE+)vq^zl|Z%1bp^NIQb5Ey)1vX9 z;_iEB(z|K!%=}i1BsTo_@7|%dGFU5qiODagp+Q!^VWB_ZMK#~c0?WeM@sk9bU2e} zN%18OKCGl1W&~J3psPE-I{Ri&&RI}a_~akXE_;Z+VZW+n>g?;&NM>;GxS7K7_p>Ra zCDH3Fg)9H8Ed??qLz+`=0DavPlM0n^a9}m&6h+}*{&-yptERCqNO7b{ zD?ukMP4nckE_0b2Dh$62!nQ?&NFJ+>{j%OsbWF8+`xl`=rD~>EJ{nMRfEs2)tYsk3 zU84m!RdX5+9`TuBj&5CU&X>^1?Yt{oadysXUPh2<$q#nOWSsTHVHvoKV}Xlu_H(t< zvc!!-P-rZGcytgA6?X3Luu?_so zWTl8uH*qAo;BLI>dku}O{DQfu|F2TzreEydPY{`_xTxCu99^!@t^U`l)BPZ&zUehy zEU9_o2@3L)uFr=nr)=|{)BZz4(0Q?99{b2xhqb6N*W#8?a|K+Z@-{v~@A*EOXlU2><6>Y&+~^9ae`7mlVHfOzoJ~#r z-!f#iz+*(oQp!0~QJ|`S(VP_PjC(R`#0TF56hBHp!cRxWkNeYC_;v7_o;x@Yaojh} zz%rRdVsl+TGvCIT>pic-B5zvGg*h}>z1~-TIe*MKmp|GrO!DCOF9+X=i;5n6!Tyid zEt>uV=Poeck^WV>`qJ?bM}Y2;+m6MPZUv|Q{Z>0~Fk@4CTU*Xcjiy8FhS=+`dm|16 z-#mWo*s-9A+8+Hvk)}42-@>{HsVmUcdwc!;$E(*?LiB5F`JN_!E?f>4!I(?mfru|Q^bEAYyE`p#OFJ{FGSsb!_ynTp&K) zk38Stz7FDvVMXK-Ez}69-@z4YK84Z}3&~d1o!O*Wu)soiQ|XJ-^&Z9gv^n>8@mY+s zo6gi%>Ff%PSZTe6s}q-Gu`K^f)ub4c@911XM;*Da-jK}&>INb|W8RAE5*BN z`W~FiFe29kN$j!2<}X0)^61Nv7NzSkwd{1qR0L*2rPkkj*>deduq5wn7!y+kEz!S` zn&f{cLYVDv->mNDhiK6s4}z&Hty(vAs5C^DO@|3<-DrFSlA@(#MKY5TqCaIBP4_) z`W{i5oZ=W?Eoc4x8ctq#1h&n{jRo;P2Ph^+T!I`O;q5bP^zzQ%C6qbvhMFV1${6&R2S z&Ym@H^X{g2|l_0;DL+BUUS`GABb+Hd?bE{~% z03)44{_&lkB{P;cmh`)8mDhkqW>W2%J}L{{czfmNnaZP>5wiAAeHpQ>9sL=%z|{Ur zvO6O&U;Qf$k=XLzjp*P^h>(aZO_AgSI`=M~J7pr@#0=m9y+zZ3sFK8DF9qtTqSF%tl z=_!|BRaV~G=xD3Iqqh(?l@Hp?9BHCkS^{<0gN}g zj>IPPWQ|AFZ-Jk}c)Hv1qO5ECVBeKXLG_FIe9tI4Zy`$>wj0rMn(>?p+yB`i^iBRdepu#o^c0VgmNPX)yicA*4rR4rJSBpU`zX}%1 z4PFDU3>+AS3$|&bbJbt;$Q1Tq(w<8LtlM7{WbC8#nJbZEb9-^TXeC)=a20)O_a&QY=?Fg5Ag^cRF-&w`#q~yqB=@=U7cRFuKeE75e>}yosHl)G628egNr(@_ z{OK{HRuY?UQA2o6TC4KouDb!XzzH}s;qS>{!8y|1?nLt5OoK!Iqse@oRC*O8eUxm# zHqn@YDNVb?Le=UMgjRD(I-ORA17V#zU#I~t%%_x`F--6Aw>)2Y9D_D+`!VL+B`gW* z4)1HXKW~_O7JDR~=jrel6%QVq9=j4UbboqjpI$6*bT!gQ^ePZ17-kb+A}W>+pV4VG z0b5GSCSmHkb6@rl#(NB+w`)>USeMJn+tqRSJJ7DM?-$VdaKUe$d9B9^E=0<~^~&Y^ z!(Y2YqVcfi5KnV^!G{hKzD0X7tddo#lT=^&{zLljm-*58Uil2lgbeu^*Z+PyNf&uk ztd@4hJsrG@rXH46{|LBt$vFN19>KESUFz@hW|sW;iT;!x?9Y#}Ec@#%1^iR|+UP)} z6*l98&HZLwrv|ST7Wx0wF_=s|tsvM7s+E$wySSFuA0DhWW8p4fwl_CEZG zOuMr7#coMsi~8;m2&iK=IWSSpZ)gJ#d9fN&A^QnGr&P85ubyi{QWJg-KQr-;H9ccN z--8%w5uwWTI_LJ;bW)S>7-lN$lM-h#j8EFi&wY$k5iG2)T4r!Thx){g;=_lPrQ#vj zu8_lD9iMi_@X=(jvcy+ISCT&EVtN2b8#iR&omwBx)A#UF56*T|v`%}XExVHSouAVG zcM2sd+=eNLBz{E+W)jJJecY(i{}k2&p3CIAx#k^8Y%?FpKa&+^B=->gF{scDUtN2A zF%Q4}+5^_6g#FxuY4%9=#g~^Tafz$rxC|y; zzyL(;7~1q>i9V6;i5|O09`hQ4eAOPq_7j8|^R9fG0PB)kGOCUdG#aEQv93DeyAvei zI`8R(Wq_;gLN@%&Klq_ZO`SX9(__ObGlK~tMv3|N$}2tX#|7x}?kDAzJJdZc^Q%Q~ zkfy*1Xd!7q#-!oT0{s38@1VKSVJL8vv0q`vjPJByCILAFMi`tC%Q*28M}5SYZlC)X~|&kDanBrBMPC(y&iRXuc4S zEA3uRej^DV8zv|Pzx6x@7OXNLwHJMTWDBhfbq_lx7(qmMq^uG8G-*F=8JF+Am3n`}!sg^r5 zn*KZYas;TA%}7OHr?8D%`3MCZ`oNk_I=6PVw?7AhGx)hJb*TBC&N#a)w&t9m&HxZ= zK{b@E$5Med!=hEGK+EdUV%l-AH~0m5q96tDls8PfcEcUFXXslRm1Ux?{O7oiP|fP6 zjbnmAHXjb6$1i!ScqGj_e^vOrQ`!G=k)AK;2fj;jiM2piHBfDwJe| zKxGzT=f&drib;Bxk94m3`Z`hYC{azMO{bV$?X9Qx-~tae;n(%!(3)bcpRravw)veT z*(ipEts?5=ex8ChS)Zitt2Bn~5!u1r^_k+=y^0`o8}2{H!@esvI<301{_$_h5XZkE ze&(Sh746`wrE-h{0~MpzC12HbtqkCfs$D3quvOsrn|}vOE!Kp_&E8pqD7gjIOp1zp zyKrJ8RY5E^k{p)&kQhqU$wnm`W!kj*SG=W&wsG2gUOqzs9bSmaJA|2xzD(2H+F_*2 zU1dcl@%Nr-GTV0xHPy3Vv13@LBY!*##OD6!;IRbre>%R_(0(ud$8E%NYRCT;RN3qg zA)5YWacnK-Bi;O~x1r;|@)_X>!e$>;%H4@lLIC&;It2w+I)Vf->L8c~+pc+eba#F! z!7$>-G*K4${NDRwR(aRKV&U%+|379pgtF*f=YCA`Qq?&XUTu zB4#>ompqRZp0O@YUm9gb3h|u9w(5o5q}8$tH@nF0Q`2f;@`Ht$=sbwH5FO;i8pq*# zrMG0Q*)fNvp2hG0MrLqev*7rRc#d~MkXCsZxBu|C4%M8_xHSf2ejeeij$4EOl3ICo zKchNs)?58g6O4IE47j##_`X8?yU!#hpa#RaNLi1r2YGS zuZLbW{XI`3K5y_`$cVjbm2~)+q_U+m{%fVa?Mg~`oxQ^4!_IbH@3Mx{NXhd#u=~$0 zCv1!2JIqBsgQ=m0$Dj(&UDI>DXuAT#&!3jzz6+x;@k^xh01_0-oL#RZz76T{a;Py% zeXITZ)I~OS)hjHN>M8m`^9`k@B@64fp)hOgwh!%b#f_Ws0rYAwh+8e$ok>m`Qsr6?!1Roi-51>C6){#r4D}gUcoI_ zfuz6TqAqUB@%Q^^3t%EEQyFdkS)19tKeJyakYI#`Z_N#E(-a^nXj_Xn#dQFC_2-y@ zBSGFQuG=R<%80vMK}EqUlma9Cet`U`lCp;m8Hmc(_FJ9{nvC$-VjgHa0K@CTqD4=0 zFIr&qBADQ(!86CvgHDOTU&Y?tgQ0juG+AX_UCfNmxUFo0+w-Dk>g-ScKi@LUoPqS` z)5DfK1rb;8VOc7!-&#Kf;(qy>o-HMlg4bT`lnwEO%ccH(aJta#&iCb7LpKJ&E$IgC zX2}q;NfQiSb64!fqmlw-O>NU2scqf}(YBXM2fYagacF6?x4!igu0p^`z2KMhs(<7O zL#S-N<8o8gNRp+|wzO+Dx-mri`>~X@dp74gRd5Ol{Ff7!UfUtz&=Nh?Mgl;o32B}v z*`tU0*2CXA<-MH~Tu^?gs7THS?Gmh6(QOjjT1KlhFOxcXk_Y)K@94G=bh=L;J;DAH z;50$*il~6||NGT=*6jevt0aB9ZC8$1C)x`e!X+4eO3jDAwlJ7eW-?6%lE)JRc24vX zw?rey>F9_!q7+MO#0L!C*9OZ<_$T@@pzY+8XB*u6EU}%k0LzM2+SJ;YN_mrUH%9<( zv6s76Exi>iU3um^*as+K+&7$b?s-%Bmct#QUR^(zY}I;MLXt<8|GGDb*nfKjJAZpG zK{Z|>u7Fbr+v;HSy=M!l!b&zxEQ^#Jc<3|;`iY*bsA+f-PkCM$d-N16y#k8_Szl!n z^vQK9xI`4@FDgtLj$>ah)ly)GuIy_q_z>OJgWNT9xEdXyyeGF22g2Be#DMU9CUQd5 zm{wm*CBX1FRtXT0(1oK}PoC&`A^k={q;`4^1Gcksi)L`VM!+ku3#(tT$bOrat z;t;mFn?ieK?np43VEE!B&2)9%9)Sx9NU`e8^2GRjD2qBJ0_Uf5L+=#KRQpJo)gHi> zVrcg%ZoF#DfG?@1l_`Km#PHjM5CyLsb@-CIPF%3EJNTBQL&TlXVlHc4oKK^@=#f@8 z?>2I%e0H|beg>k?F%H{z)9z7vXlM6XVe|NC{rtg0(P*LonC!U5w}6T@+Hl&jk)e zxF-xbuRpS)z_}d|MAB#6oiA*~)3~SHz9#fIhiZXp!aBGNS^kAW1Xn6A0VDTZ?jHSj z0Z}q|2!Zkr@(D(Yu_NPH*FUd;0l@?3V=VJbKV4kD4UuDs8ma8-0jUb?u96;&P$N+m zHPAt2W{DYXz+4HYCR!O9`oY;wiq?hcaeR?y5CIYe{6tX^PCO_ngQAG6Z>_9>^mr%Q zPgh1(zy*xD-i70xsRJiLeqI1*4LAG`wH6J@U-lUqDT~JqO&IYR@nF>K7MNPQve_T5 z@=|H!Nzo>a<_%?I1d@*`hLOgPF8h3AiXsHQ17`H}(^8=2AIRz9u;f^CNkAId9qfNn zC}~I5*R0>dq-ow#$%H=T%BhE>MefoFbbN{X$dy;0@Sm5V``C3Mle21!prVZ_-93U~ z^2l2O<)sF+tjJo^$XdlUaB+pJXamw31-2&L?+BYTlj3x>)P)4q({sC3uz;(NHl< z>d9P_L+bR$iWARAS{Mk{bnWGUa_?w9{m2$|{zI35cLkMIB z6*5*b!}q)|H0J%I~_qBmh&huC4NpkEfmWP(Mv&;lb{?(j|qc54C#Y^Wlb-^ zY~;`xg%42{4Kj4`{t1Q8-;KYE!pcAVvMz{bNSDs|Dnr*PS@)?sIm=W1DnSl&^yB(_ zu+N9U`aXzd+E3stw8z5A4SW8cU-M*aNpx?U-{KIq@9Vsq`8?yl*ilqBqItUVQEGey zy=0K(^RsX(4B05GR1&C(!-t#aHP3I!#I_2CI84fErs!7Fue5*4a~F{M9?DV~@VARU@)~^q*rB_Bg&9w`CF7$4Y^IXS zwVymWpJCKZjiwhsllW2%`|0D*Hc;yj6_xDjHIfZk+{u)X^i7A?thK1ip6}g=WAu$m zgrOAo_Z)f^7qB*oD(DFspST%!Hro$-I%Iz6ByxLLY0L#{OaZsddx}Igv(YrPNzGk5 zhsD6&_b{zXAfRUc*7I}~HcI}X4}36^YcMYL_dA#ynBm3}?1V;;p(gA2=pAUGNQY+e z7<6S_%XE-lC1Y`$% zBQ@oM*OHgY?0HLmd8Ez!B>!WFH|*fR`Nru8=7OtxFpCbhT_q)mC%@KH@1B0am#%(* zxPeW?!ZoxAd>Ae2>4~NSc^5>r8lp>CBxh&m`rsmPCb{W0OrN-j9R0OCr;&rNnpvf!kZQ* z!=mF)UYzX)3wf`L#AX?QN2btVQt8#9+hSN)IKZ*nY{~nQkT(iRHPOPWt-iq$q=6dw4;~F&6QhMOrO77!Ki6PPU-8;fw1`m5+^iVP5G;W9)WZ0vgCLkO z`MT@q*wOg;+(gg#YyDBv=AGh$Z#H?(a}1|Tu-+{I)C26bdwOZD?;M)B*O)u=$Dci|q_FBhz&Cmy%!HOiSv zsT#-{^l*dmMFKsGA*&^5YTR?n=SRcfSiZ~04kQ&*x)pBb7P^TuN{q^e6+Quab7Da)Bv4&=@Xr|Cv_G_YUr|eM`{8GgUo-svLs}EWn7(2lVZ<4kEYsMvn~nv1`Al1 z!Q^Uc)D>Q*JI7Kz@Z{JH<$)VmbH~586cTL(ZBOgc7o5NBN)rXcRD!a)cqb6#dzz^e zF{dirq#`&niX>KJQTMno1KO$cEDvfj0+hU2>j7?yzJ&lia1xl;N~X17SBGBu zfT6LyDjEPeF($Y@G7@O)0rMb)>0vUN>MAdS?JiDWdHw6trd6+Ky!}jDh~Dzm z@BXu|fQdtdN}YK?`0HLXnT+1gp$zG(4sU0X->o~lojdzU$?Fj)_L+`oHq5RXI^7m$ z!F=!w$9IHgvIYmx06#Pt5k`@QqLIPx-@h+`c{ax~yUe8GRMIaSCW!Qg1|Kt#N@9R>~#x-fdUz<+st*;G%!?z(;X^2G)or88LOZVHlFUc=ifIPOv9 zDY$Sa$fDuy{40j7Gb^BQl!^3X{6PJ(ObcL|saB2)ci)h)1)L;f5Ad^sTSTPj5-D?j zlVkP)!5+H@U0!qxFKgdUHsis2Ft8E8N8I3^zn?Enu0@Q|Kb0-kiZG0Z*c-j~$PoFl zLm;Jeao&h_eg`wM$M^Ntz*JwP@O&`cad6t$*&gp#4g(6a3^O~>nWGtx`Ymy;>d-yE zQbdB|Gq=71K1zE+vGDpm;q{?5=nQ)?FRK1|i92u4DTd9q@`0Smgg}$6a8F@sd_H6E z?sjjuf4tQRG>v9_#`Xq{KE15QOK`!WtISy|ZcUg80&Zj6%E@#Dj?>$kI_A|* zKSp=U$H~e`?5{gep_M&EVbX{1jvaf#-fm6z?idPg%@rG#2RSTM%%e$S)nEhAq`Eb* zV#gBgnqxaW?AQ9=4w6Fu`6qrIsU9%x5ua!w3so=<)B2ijnJ`$y`{1s)SkvS(-|#27 z0T@y3jt1UA*XL{f+~}+wU@A!HM9M!YFMvla7x5nHkIpO!_7w8V`?r<0fNz}|F+eCq z9X9olYJ{ddswK##{C8#rqe+p~A=^J2$2!{$GrI=@^b=g6f%sJ;7#3<;j?Upfkqffe z9al(f#fMG8^u6w6v*F5{Ghh-6u0fOUqlu2w`e?%T3xO51J^0wC&6(Vj*Ld&mQD!uB zc)G>jA8T&0D`XeCp4_^X=6n)5u8L`%^zv8IOGZP|#`tT1S_xF;WIU%Wai}!EeL<K7c0A#HnRp19!+Z@>x9mFbunRp=LYmlRYw)VV6&j1eF?1 zc-1a_cl>p)bN|oR_@J2iat4M~nEaMCC@wBO;2pa4#9{0f!(|5wQP0YhwE5;_O=^R5 zm3epWNv~)TeIh6l#WjbO4cmI8@5g6X9$mgQQ<%RI#ipIw3;79F7nl`QURQU&(^PY7;3T6I#oj%`&3aMp3>Ptn*1_8HTe8M?bL8_?TpOuW zgMbbwdIZ|wZpUpHo7P_l9b`1T-JL&7C{Y{!es|B2XAj!i3kvaw%={oed}7SjPt(bk zD{$~_1tnh}!KO;J=ix84lbQ~uQ{dGGoq7#;2H&wHFh5DSm$OjGG6*f_rz#;dEYySlI zc(=2x(39HFLR&wtT!k1ol0H*fGlpqrCm808Ed`Z0X4hwsXw{aXrAvDc#m6i(O@EK! zu80#9p@Ggd0Hl}F&}{7KRox&{afy-Ov4U0&dqas4w$$5hC(^f_8lz;0uY~kNuT#Cr z=5x-SQT0J5(fCpj{vSE=6uLJk~&3Z%M$xx97_z4sVf^7+&Lc3g-F z%id?#0`{Kt;Z50?6L8xnHk$oBh~)+GF2d3!BV*W zwV!v!LD066QzM7(jUK%r)K(_?DjD{sS#mk;RJW|HbE@hTFLs7Uu2EvrnI*5*#sBa_ z3E$=6aAI%l!4BnYSa4ukf-r&GzH?S{CB@IuVh15PG#bvdun@4q0C%FTj701G3!XwN zN}aQ#wV}O{K3F5W6io7jBG>CFj$8?w<8Ov8)v9E3f#V>YJYsh0NlfXAi_1}At3l_T zU4)Pj$7mhwAWECuKjifyLGKW`{`Y)T{+X=BHc$AHe2$q!%UBEzYdbDW{C6uI}^)JnHmra zkaXQ{=iP0P^gaUV_3OK0|1_g^?eNYD1Ug`F)@p|bKS+6Q8nsqOI;6aOG)26e27g;t zGzMpz-F;+vo&<|>f2m){{Jl!OAkCfby;?F^>h>5D!K*`jJgtcMV+&Ltjb3u=xv|)DUeF%vQFPF z{(~S&^*dI(z7$?~}#R`X|}1 z@yWr&*!E@$;6ZMn6u^Ux-G$MBfhN^3MC5wTn~E;yYm-yfXwG*R%sK`rWZh%?fNkxz zUfA38BVbgV=D+s0wnpp*+eHD?DzY#iFzX!?^UD=*%7~eRm%V3!J?=4}!7`$8gmqhr z?Jla>YbUs{lA9hh_v6|Dcu=lB-dQOUm>xlpJ;O!aoIy8mcuzYKtVb>H* zeC<~LyN(7qE!R{91#HWu})qd={bvM470 z4l*oZS6uDom?pebWdv;!#Y6zb(LF>pckhP*?;CD9@{+<3Mt25Dnjvg%xmA+^O|0th z@P|OaVTh4oyy4wKE+97KUB}i0sf5@1K8G5&r!b-L*rQf<7RFFkWrg~!*OoZ9Z#h)o zJ+(U|N2Am1NOiu}ye_ULa%Xfe)?JraOB0;Z8I?Qm)U~zCseC$lyuaQf?(K};llad9 z$C9&)G)KK~OuscW8FvVn~}mm(yg1;f_#~grM<=Z44GTDv-N3dhMwKMn1 z%lXYaB-$>h=oYFJIyoX4st@RUo-DsXSNQ}ZBV!|v zNPhH`^95vI89KY(UCfB0lUIsQ8|cgK{93a68Pihn*|rUrdy{D-Q}C>_CI0He#o83j zJf~1ehyH)&UtNi@;-S8J%}b$#Z0uqPe^}L#)nRJG>zHw83jcR{9m0{hJn#$wqZEXh zs(_k^d3W(}E@wqviP*yrg16S<xB(=^%5 zU#Ruf7Skyo!WU+FL3lEic|6`@me)@wQwqeaYyftu&Wx zs{hJ0nRds4qoFRfjx***JvO&SMHpBV;>LcyBWOIjD`=hMpB2xqW?1@|e98a_WB#{n z&r8272F_3Yb}7$zq-{TVGIZCODr#DSODJOxrv8ZdNI}i-#yEET7Wl_aV5hW>&#;)Wg2kzUL?k?sAgOg(*S}&u=j9Z+{z?zMlyqCBY6+ zpCxm;6?r6COT6Ue>B5BXy#-g@LX85p7WJdfP+=AixUXV@f9kI-4uRQz-%pH?1e)sM{e1xF@PenaZ$ILe^0)2;{T~$x?V@_<7Jh2F7D3LoL1r`LsSb@Umt>;y4v=f@zmp99)p?} z=*L~>ePJRl*L?JMLfkEkZ=glh*d0bt+5dDNxfo)jjSzF>mgoD-g5`KLi7tI`k=E?j zSyPw~nAf)m%P0YS)i%FAE`)F{a1!vR4ZCpQN9uPHYkM1{`C3gf+i%ThnBRNXZ@0da zKtdR=%LFsC@aw%x`U^i=(~?RTN6mKE=DJrquNR(I~fvTkgi_bZ~NC<(lh)dOA*LjY&*s6u8sdY8tPmyy?Qi0b!rBv6~vV40D)*&PG??y zHQ8=?0?@g*pThp7v;#S>3$<*1GLDbGWjnF654#@y(0}H5-5?Yii7?i%#*;H(qDIP$ z>t6Ga_;Rhq!_A_h2;Yc6HYi^q+_)$NFNS${Y1;*=Bz?H+cxtt~y;>d<9YPI!q(P@C z8o-VS+^NkgTp!NNKP?uA*D1f{xT{V9kP}rYJ3CQ8O=QAcJ}xGyvfeRmZJ zB!x2T`}zCq8i1|@WJf1pWg)mX&vdYi2zRzmVH%l6>Nu0srsJ7TmkH5vIr3XDY)%)p z^^>?Sphz*ppI6~tM342xj|X>qy7oc&UDNj$oiPWY0=aeQFO2tpsQ1E5{v}>KKfe?) zT;(UrHv+Tdr^cu+nD17^rAmW6{rh6D#X~{Bc829_8hLyPg*zKc83xMuyJF>S$olNk zkA&I{9yXmS*tQ-6JEXst?m5RFQjQz#u6Q|A0&c(+5BQP37ZRT-4WLph4E9*)#Y|WB zQL9$qO(g_!-nh;bmebpp0AT=_$H;EPUw7b>+&x#|e>11EkP$!&-JH(UL@$?Qkt&F2 zr{4T%(evIe$g!khZ6z02PGN(2!=m579TRH-9x1{W%lX=!v%Yl|z=1E+XVAoVd=72Z zm;8mkr|v+yq}?7q{TQfzJ(QB{X}N!l1Z=E}I}NYL<~Avn;NLK)QLlW&x$hsc4yQt( zCp>Dp4M9uQ5I6S!G4&nrRJZT{w-hZ&ix5R;4>lfB*A(J+IgE)bsg#?)$p0@xI1=U3h4HX7}%!7=G$(wR0CJ zr{N#vq#tEJav{`o*waW*8rkBYwS&C{nV!&H49IGCIkDt!p}(|LF1x+Sw79 z7@J8|NiR%o%6D~$^qlJ(eZ#-_ekdDfMzC7BnqzN-33b_@lPyhOE)a;@b`{F2@IOt4 z9T$J4kJKT|EM45%}A5OsLxtC8@u7N*LUY_J@)GMYybN@bW{)GFc1g#vgvf z;&t;y_HZSIH?`idR;5*;2L&~f^|pyb+MaaY!tz`@ z7&4JQ-V@evb8k@|T*^JkA z+`D}H~A-v%~x>y$Xu8GM@VemGc% zDSceA-u`BU_$nMZj=jBRB3(`S=)0k5{l$Jw=|dxUhGf4IMFwI8fFa*e^v$0gMr1`CYV z@j^bu6vI)s#Q}Zl)I2bdEY8TB?9Io)1QGe!bFBxB*h*-#F?3g)3NV+Bz5JorM1HLA!)n}( z|FZ*MNNb@vW>Je%WBJ58joZ+n6E^v0^U)`XYlCGTHGZQ5o~o^^Ws)*C^t6rv7X+k4 zPz7CumWKu@Sh0-&%`E4k;UZM zi|F$%1KQM<2b-BZa1K*pfK!ya@zxe5$i_C;r9V{>= z(&yi<*xZSB{=9;-n9ptS;PA9|mbKq>;dH@+%1KSHNzG3l^HX+3REHYb?z?LaK$OsW z_K%`GH~;K6MPc6QSL`0Ua6;%W>|uHJfZ zNPo4LgH0qt-y3(jTdbk52iQ#&(3R< z)9c`eb)QjCAifVn8+&%e1i~Pa_TAZwfWp+g(6?O3QNTDb6|Koc}nT$Ix_%Z~hYV%)PqO-T0Mf*aAHo=+0*?Ns3+5X%!>|8&F&E*HKM!7Csa zLnR(dQ_o5GUaLsFBF+TnXpSX%g*fOk`_|W+RFo-&=RgwC&S$n}dqZ z?Y?(*4eFXoQqwSqo4+^GK{?6MxivAXgByobUpHIw|EFE(?uvu=a??3Aj%G$2IO4cZ zFF)I2oT={R3qD|&IF6_@h-4P>rm5VZO#LYi1?29q*r|W$nDPggZzsTjf#v_m5Y6#= z9uaev<}&S+m&wP#O4_AWy!a1 zXK^0LZoEpe6y|9k{cx21*q@g;zpGmx@ZAo8kd3duvilEujptMv4w3(Ouz9fsa#g#~ z+C}R<+ejZ9UTXpfc@W>b^2=eYj;&2&p>q7-lxHLyEd0K2on6N}Oa=|J3o0XDUin=e z#Y2TGW%vD!%HA=HgC-mOiSVC4J*HruEmbISfSD%U-dj1`u_D;*&5H|Z;V);vB) z+gp3ceEI&3ejlD|Y(3$3@QjegKEoRq_tb{IKlkEA>Um$+XB+fRS3I}5aS<__9=^6} z`%2?8TbS9k#^bMRH-if8#9W7=^ojI{gjY( z{TPOkPSmf^wn+?wI9ozk$FesL0IEtOIwoQvK`qU)coZT7Ci#%&_XjoY@jZrFZ1)OL zZixU%;tFg^>-lwwxS>(x6Q`)ccSjE)ONIt~n6k?pN!Tn$p>U1D;5ml>SgUdC&u8dM ze;dc4)UVndW5J(Km7t)y&4-aQ?slPjUG~3Gc;msRtVsDx5IeH*UyVZQpW*{KuK#04 z^JryvKeS?52G+_|ykLdG08S9&LGq*Flzd^Fp4E$X#qw;SKi}fgKA^{m$Hl3a-K2z&rVnC$`RzJ#ouLqq|F37(9({cWJQ0z;1nv(Tz07^-&Svf*y`vU zrAQ8^#7hC*aYCTUfM9k=gh@FM>&QU%!oSrzZ$C~U&Mef>7l>hx&h3tr4<3!ZvLmjw zY%_G`%%k&4dPM!NdEIS_`$^mCaj_fv zvTHSp03V<-9Eph?g(R22Jxt#vM$S4#U`-hq7BsVsHB<^Q=!G|1;L*f3Rd@&&X|M`MLz8L z>^{)Fj6Btczi+U9#R_sQ;|Ope(PCfHE2iwJ8#|!1FF{dC@7&golH+_xip?s3jl7JE z9})A;-Oki@)E1y(BM35lsx{Web~L-=Wa&#=f7Z zkC}M)R@ixG{M|3pxEnA@3m6J+A`J<9RCKeE!$FCu9(ReB;qv-s&Xc1X^Yr{q`iW6ZIV&=51~O;W?*8L21c|? z%Y;r|v2KTvjvF9hDZ>?U`^81iu#s8D5ZUbPaK*OPf1J_9R0@K;X28!o!0P?we>O&Qz%zjr*K&30~mepMFRIQNN zxd?7({mxS>7G|MYkJ@J7|4=>wT_7BwM>xZft$nof{b5e=xSmYIj`sJM1JI;WCU+-pF+qsZ^8_tP ztQ+dSTQH}19K)onzI5WO)4nY$inI+o0Ipm7-y(mpk%MEQCuqdq?O~qJp};hDTW1hL zyn$^Y7P)Vj$xABl`t!kp-5{NzlDi=bGFSKe3tJU5(y0;v-GF-slB>-dp>weX(rZv4 zTtl(@foaotBb5<-`!QRFPwWq1B^~jB)^XkE8x!!UeK;!t`fAm`ekxZKt~}G;KjvmL ziObspY1{VTkio3vN(Cf+31Np&$B zxETnGWRUVVHz}eb_{{}TxO-_*eP<_cGU#zaQ=WkNO8;Zb1LlaY^B%|r_vJ14?Ai~H z72BsLVbw&o-n;6H<;5OM%mjxJesN*F<~W88cph0m30)F=yuX(EU#vVNLZ3YYeYS6l z&%~t;EP0!)4xoJhU(cvZ-TK4MXZ84-@M&%yEO2ah`Tus>BJ4POhsA(c?S9#_#{R+T z))&+vwPU*{aNa&5Np8%od6GcODN*qT!b8C1gia?!(9w0HO1>!`8%H|$jZdeJU^X_T zBw*6YP#3LM#;SMJuOJ%olc0|UTr!i_g_%IQ`)|CmV@F(qKdYO|_;k|D7C=bjw!4Z^ zg@YA6YZ&;$x7^z})93EQLmXoHP4sA|rT+pYfVl4M$#Jr3aeAo&U8lleh|AGTrY3^9 zNoj}Moy(weFfPUXT}epPCKgi06OhBt;rD~y@sP9`8gT&X-C?ZCwnm0ZeZLwCw#Oeb zA!EjeZsj1`k9cR#%93<>;G>;~C!h&l{7?h-$H?pBVO=bskCrx7#?q;zsdyj$#GrDm zcCT=r(`MK#3&oMcDih`~kGZWIz(?45@twAPsd&I%Gh~fre(7VIB>d`y6nWq}Z=yj{ z`N9>fERyM=rJ?t`gu_#l`Uf8iN3^Ps`p|8!L*IyN=PrW_B-Q_8cPN^1}SfDyv zl;(n!>NOX0r}XiIT-7%|c@KWHk7D4CPViD=V7%Wam|}*_)Zj9U4a%7pAKt*w>~qE} zOXqKIl)`Y;rQG`N4~p>{ZdXrbY08I1cQ90A$Qpzd1>y=DY;nY@W^H1bBuWlgiA0yI z+r9X}afNP(7cP<3YS`#YX}Ch_eseg(FX@ifsZ5=*R;+V75ehgzTz2NP!V3~ft~yZ*i`T~ClUm}R zv31c+Y9IWB{t{CKoQ~gqTFGmqJ&G-Iho;?!v*smom>p9{-@tkuh-#k z8R!5_fo%+Il};e3BtDd>!eF%cKsQ@F-D8|#lCS{clK?$aQl9SU6kMi(yIvXC4juET zP-W^=w{j=!^{Mj0JtkO>+6ZUkT~)A<_+4u+rL9CMJPGHdv@*UeMp>=}rSU2QlNW9r z1orSXd|PK#Jq+}ihpg=%+?EI}o-4GRxyqbk4DM0MjWFJC(qJLDbYRAlR9+*&E%sZ= zm>&`1qx1tp|Fm?g;W5RKH`vsUf~k$jEw}oBd5(o*2xIM+wsk5#jj6M3uPb;BczhV~ znQYfvN8`1Yqo!45C-#m%*UihseEq$}aW41`56Le8f6d@*v*s^u;60RPd>5*Yy>f*e zU5VC)&prety6`B1fj(scve~Z6WH5gVo&bu(D80|)4 zmmemksfp-InPOvb>H;tcZyk!18C;H^|MnqpyrdDcWaCb-5`R?k&gs&cd>#^9>0`N< zz%E?Zw7(#vvAC3`Uu;Z&oUA`nS8o_? zO2m(x?i^VqQn9WFcQd_rfv=nsx0gbQq#NA!roZG!z=bVHQ9Kn}Q%`J7Qwqjod|kfC z`?*j=r^d2l-F70}aEkQl+md7*@sL3OlxaiRa$9Vq82o10yC5RqIaMLRM>Dkvu;hcm zjvqVV&JsF>n^z7-%JGo)GN>l@7P^iTP+xMR4gju3M-KYr$TT<2FMA(Kz^Al=I3?L< zZVag`1qi0S5i2e7)A*jH-D935m+>t`dC%)p<_-DXYQy!8Tqn+!;p)0(6s*wHuw%#D<%K2y1SJ|$vxIe6?#V~&=v_NauF^mh>^cIp!Ew@>#SoSQ{?Z! zC{@px3@mQo2f2O-G~2e}$PWg}_{qvs_hhC#+S3I7!w!b8qSH`35SmNp1afis|Id1h z4j%EqfPhlXv0th+gBEzp_%5n)rW|!%&?~DzaCpSpXC*ecVthgt6yuws5S0+Do8p2%=aNXM z+jlgD!#(_^4G-in&4{<}DfC*Le(iDVXl?=sCu!SL8M83g_%)45%D+Gs8zlO)8ySM% zdGTgeXNyy44HF_u?W>uCBNSUUKwCy;zop{Cf7MGRKiO@nTYntjIxSJ?HnY(Tx!{?Q^%Wj_^HmZg(`SqBGoMWT#s`Pn4tp}z0Anl z+k1@{_oxqb%V;nEz%RQ9fOQv?r3odN8SJ5+^a8Y8XvRV-7@o=txL;b=$sS_TE<+Ip zW_*N(v$jede@_)WfUW?Ir4opTA4`mFW8iqUwT^hJrIvy;L(s#(c-rPKuIbZ0AWY1n zCq<>C2>-k(L|ESApECVirjsY;zWvT-S<-W2@6XsDXvYlz8A9WqRn1Bgy#+|4h2Y*( z=a^GoK_iF3pb@_&uWX7UALXAj@=#rbnYe8l+2l2Rs*uI46*#=?Z~Gayut0#OPa z!ON?Z3EDTRRg729G{Y9!{tjfzF;o-sD$;;7-IDNhKtR|1RmBR@g_95vTuj3|e#Hek z;N{g;FEm3>7dM^Y2FdGJ zz=ibGAPwUWd#>hz#v+5pGJf?4qra~;lKPwJPUHKr1dQcMM|&E|ESBXk%KNv+DObPC zQ^tg;CL~A?wA@!1v6jMyP&W)7Y2$)!J`Yx}+c4W)C0RV5YogGqKH4$dJQ_WG)Nc2b za{h>7(dhVjIS^WC_<{*{$TO(A(5z?JsCYv4V|k$Y>`< zS>*eE2|J*xD_=9*KssJ?(G66cUMf>I!yq$o%#{r<&6MyibR!CX*)pemAug8~IN!_~ z;7-F35_>tFE(1TA$=A+;ysW{%`h$7I#C}c2&{+6R)8=N^H($Wn_)S18ET6iCpq8dK z2p};H3|@Y`q@>UOmc#7`{){noPCY>>&p;-?^L_GF01UY~wkvgd2>FLtB0Wt?oY(1d z-pkNSug0B`3E**ZY+^;LCu@=A2=EuUXXjXM3SzmArVy5m0OL{}g;>sHVxd$f{UKxw zUfm@o0^tSfsvqhk`h+q}C&*%ru3r078b?KW>L$ds7i{+KRo^kser=KPs`!bBxD`B^ zC%}V-bG@rEzRJY-3KP(!2nJu_&84gfyr=OS_rtf1zioyjHsEwRN%t8WQasIt{gV(g zQG^sNBD{ZJ?hjsk&0=sJif2n+?L3}lhCSkwR&Y_Ui4supt8xuJmf}q|CPf)2{a1FLWh@cgvP*lKQJWr2L-}_cA?JK8wrHm6GTeEh z*RdiN){BRb&X1P_qQZN|fc~UaMD9X78+nR~KWkuerH_hBY(-V&UJ{~4Iw8@xcxc^gUu0yOdxca^&2$117p=wH84*s)DoKS zbHi3xRK-kRA)hptxOG9)OGdi~JiH@+Kn zhiS@)bdtMuuQNY@KB6xGSTNY}<@mdcxz##wojmg`W+)KixnQ3tI7@?sgbPi|5~tJb z1SHX=cu>PeR*b7Qd9SbaOb-wd!)Dx!snZnB7>dQv;EL10P)1t4nd;c9e|e=f_CV1! zH#{pR^JU`UbuU4tqCvNe|@b(mrUjoPko9 zXW$`d`+H@DLthCYbXWp@55F0C;?m8oC^M7kT_bbLs^(hMg-1O2E##(s18v-yW zWm5rF^!yoHP@iIy%nNP2poEH{jBVB^X^W949%q2V)Xhm2RqwzWU~(8Fb&ThFOD=x& zjLFGWg$KlLGzwXY41(PmQAh?o{Y`GjS163v*^ z1b90@&Q;E{-)}_rZ^nS8dVXh^%HtZhMzyYB5nW1eDKm+KHcE28 zoE#q#6KZDZ95(25?)xhXYeotpIdMl)Z7s_N?1!>F&p?W`=bH&|2)6)Q_~Et5ZhZVk zP@7d{W*k%+DoWiQn%Mf*EYF)h!!r_4G*w5JuGVjvn9@N80=W=J`aVPX>4x8$qTPR& zr4u(GW{CLj_st{IuFjs0#hMGua9P8>CImfJ6|Wpp8q z$`vy`7}2$N*z%-wlca%TBVA{x6UB7*;R?a%+wn%&Dh#e^9N-tuE3SF}hGc-!e*L*4Z+{PU3fPofm=_v~}#`|}HM z@SyNUeK^x{7D&K0h8Q#471aTI3;x)ju32qTO=(=CHA00Y#A^@pU( zxpwkERgtC?vWh_CoxQR%Zb?5EuIrECfzZy0zc91Ce2H7tlC-Dzf4WR7 z%D2ypgM_gyBZEP$PjaAOwN7F#99xl95nx{rutdJ?`i z2{_4`9nvVU4On>ftTgC|g?sugiZ(SCI8G>B@vH{+|J({CWlBrN?o7CZo3R)gKP@-f z;&bLo!)JO~=CWk`ct~Cei-DUBUS*0~;ZLEOC&@+AVFj|u1AIplKxF$E^5Ybh=UKth z8T)b>F%C*C^E?Yl5(kSq4}tgl1%jeRjKP^rJEfbJtuMzal?ol^(xlQ~Ye{P&U-8TJ9B`$`Nu3KL&1>OVhgJs~)!cexq6|V+$ z8}X1R*t6(71g4CE^N>?(L00>w=?b6UOxiGHU6Ha)p~mJFB-WYj5IjAKt!j=LW!A0#mqy5o z`{3C!qc^`d87ZfnPjbeG#H!=KoKhf(Kgbmk-x-w~I0gwIrxT&+SnJ{WS-1EGjS#CAckQr{ z^-QGpp9UM|vM#caE;QCd8)Ts`FrP)q*>>pD9#^&X_~X@AK>qLMP_E(41q5b7NISwQ zs3@)jW-@(8gF>g_7%Y>k6P+nay|=7UCx=xK)HWQZRq-hh@FTL|s{ma&3PLpG!(lVv zTPVSp^Gv2rT#^&Yqjtq#b3^X#qgPo`=u60EVh$f-Xt6)_XP6Ac!Ij&Mkz;6taa2)U z%K_8|{;LR2EudsIvC|KNo+mh8SO*bv;rEbo?`-+P5I$d(vK&vW4(jl%8!<^B*KM1R z73agt`^y7CQ2SZ{<#*V$Fv-D1n`3}U31<|<5Xaai?k1~$F4Q~c3K}9$rDYj1ux<%N zf9*e3JmDrt?i;4|{OF0Y+s;HMFPOud^@y3g;vaW>JpbsWAG8XKEiZM&eIns!sP+T3#bfI1B=~8!IfAa9`DSAg-q`iA6F>dSMd%eC z9tc-NZ_T2=FWAT>pYfBR)e9v)cYegSH{c*vz!6SSMJBDtR+T_ms4gRZe4w4Ml-{pd zI`=|4n2Hq-=@Vpu2~aBK@B`u(4tSaMZmqJpRjixObK`SS#pjZ+x-oAa_Hq2QDzmK{ zOpdYTB7zCFnddVnxmN-ApCj;Dgt5GrN=93MDn!CgfZ~j`(0Xwg@l-P-RTzA_Z5?W5 zAj6wKw6E1gB<_bJh?^dPbznJINFQJjSCYd52mm=h)uW%ywbmnREJ3PUkX+k89iR|* zU=`vy2(6p(lu(8QfgHRz{Nlyo*MO2vN!_I-u0AO_&-2+HZ5POON7)4e{~j)hy{WAN z{J+G(RV1cPpvkrGU}gGngntu^&ud!ZJZ1Ioh;Z5eeF#h3ei)U$j9hV7;V>e#U-vE_ zJ>Qr&fF-~?ntO@g#U#pP6IZe5Uw|abaykT~agUtP7^iHO&cN8zmJ8nC6z$@A{ogqa zN6$4*?OZ^i+6&CKW!IMD^OVvS8mT{O2--0GqB}SqvAb8H5i7^$*zNCMK7jT-yZ5eY zf1dD>iL|PJ%w`bCD$PJ@C2>82{a8tncj6Eh2q&}%v!4Ewxg90o=T>Pq&h{;|jJ7Qu z?K8XSg%7%vESVJcG- z0eMKz&OOqPlT1ro-SHua4$Ma&og6bsP=|0RN37)D6UIyWOYVJIV(@Iy$H04zuoxJ{ zEXRwSX87=yeN`}}rSicc4GcC}1a-&teO5(5=5MffK%sb7jXdoerDH0_zUJx`4)ubD zcS0u~2mw`nuh)^15tawJJD5n?ti@ck> zW?G`vt#CA>b|>5m7I^&wppI|&jy2?@p(0_gzx!Lgu5>q`xz^$cdfjj)M zA8wyTobSad9zl4gb-CTjlgju_14MxpQdxJhZOONQ1) zbv=@}0Wmh=$7_Ixb0&Hh<;VMC@+RLY1zDo0WdaC^r)c(OUdQ6j0Z9~hSLC9#|B2ov zLMW;=%07E0{@>=$rBUhPHuHBAMXMx{8xsfOl0J1sIWxgwKo7LXb^(Fhh47aJmJ1e) z@Q~J@Sjn{g%`FxpGyfD$`r!f3n5<)*qpsBa#Q+-zQ6b}d>!AVg5C4+m8o2ntP>LND zACW{RlBW8sC**2^ zAg||u^S5$#{U3OEllzvbX%I^Z_CsUeYW0q2)pJO;@v1g(sLo8=8fP34Ma+qAqmO^IdL2xsd#uAu$7jIybtQ71F?6J<@1M>rb!U9TbK#c?v zwGiC_X#x}P^0FxyYs5rart7I>3*(~8m$d8U7uF~IpAsqqTfE)P&zF-l3l?XDc~B#W z0G$Bu(YLPgnRgW0-0O@44gzvF20=8|WpU2!XL$fP+xzJ)@}B zhwa4BWRBWj%;X`c$9ZFb53yv|tg@D5LFd401B>LS&LS{_SWDFXNN@lUzet;b{K2nX z@CR8TYpIsllf)LY%BY)aG{kV%xnQP_0bZ|JAox_Ffw!3d##8u{fhj__iC@Wl%0|6O zX#n&E?t|^WN8ZKnLNa7lCe&FOHV0@)R=kRLHLOf7I7(x;3BFqp1M8&?mk-gFpAvi`F{WG=A1 z&QV(-7qJPO1N_na{>f64d#fu53)HmrwS6l1)w#IV;`HeVcH|r)i6{yLrVvwbJb{|L zA>tg)(8qsN;c;gr`Qe)CkJtGNaTcUNIS6-3TZd5RlUyB{I@EWV;?ILXh->d z>ynQ05?&eVzH%s+FyRav`W!pg0Md%4$)`ruY;xs0X5n8%*!9m-y>g6xVF(&)^I|O( zC+P&>Rc*zuAe&D>XNBE4$wxkS4nP5oIY+IqC(e75%ou7&>Cn>%Q;3ou@Ep?|384Qi z>flr|HW|(4AAvU-46apeKAGu(+f{nw0fla7Q1-E|^OzwFDC$0E_SEkM8ZfY$TA&ru z(*uQGG$GAitU_<$7nc9NN?va3eK1PF8LPfrZODP09*l&YzOLG~8YA>22=_)^XfG-1 zAbt}=7>wneJqlX-Q{`P}E-(BQrE31YqdYT;xj6I=I8jk+=b@*EBZLq3GCVl3Yt2Ii z#8_O0hQ~*i)nHV#Sg2AwyV$noQR`KW;5SeZLOpaeN}tft0xfNxZ9j2pe?6E(NHeVR z8T{;27n#^l=Jklk8ZN0St==T+A+(SwKbLlwJ?(1%1zWx79eYG7B#@*Pr`3SX8e}XA z5zsT}ANSq(mERISdlwdzifNu4DhH7~(CWgEp(>D$9s~#TXP&G~vLQx3`kv zadwpET*XFau%fT(m_goS7X6@EeSF}L4^0Bd2!vwF!j7an(_NlW%Vecf6yGJ3h1pyX z^v#xFkm=)(GnI5bjfhdDun1puV%RtV#DYI_ljdPkSx`v9cI#tVx@arvys~fkPOg&p zYP!{sWDc1fiJbrwkSU%0d)LwX%L&4=`SdKbxL}DObpK6p7$;MqH_<%$MATIehh<2* z8GFo-vILC@ZLI%2)q~wY1bqnV%aARRB3gnre^g<5SB@^4>B@~kf7NOdyJ9@r*TCG= zcdb7}AkI4|43Y;pFn+gP!x!5qeCrT}0SLHWO}H7=MSe6= z^i`6s@?r%q6lcmppCnbVlCrE($6LPnA9>MR^qoh<`ROALZjSkXv?Raw$_$mfKN0{s zTU>~ZJdgd5&^Pi6GharTizbp>N*~E>mQTCAYd9gR2pb{zT~vJ0MrD9Id;}j%BhJPc zXM+$~<;_$c~Uqq`b+8iPgF!;6MS!+<9 z01TdF!EAw?PQ9=^X)QetRZzQ$Lw$nhrJpW1HX7(NAiUVbGqs^%C%n$C;uy6s3nyaJ zQmtENX!Nn_QtaBQAA$~-uwMjYG2YiP%A(Z>xVO3L-Gc0-qlljUb$NaymxXnN@qg=I z>>u2m4(%A2$@vR4RQgpMfZ(5L0TYiS0Pv;rWgdx-{Vju_6gz$6;v-P+gm3@Bv~kug z6G|KahwmScSpmtfmFK<}K`z{nNfuR>k9f|gX}a&{L4^=;>}1HHfn55ut`&ju$&SMyqXx=Jjn%56_5*jOQfo)_ zbic~h+%7-j1yw?j{k5!Dw|2s1ic6~UQ_k}u6W8{~AQA`*lY_7$57?YEnpfmI< ze@`oFlRY@M7%b|ptdn)?ECkH3D87)%pW9=y7IIunAgM?V&|bcCmk{TaWM64CcAG07 zs6B7~PcMr4P*)NQfpSs{iey9b$L2gb_V;$N>eKG($#LSB*-FGiB(Y%%Vtril4Cb8r zw?8O1`-0J&tsD%BtG=J$6T}*VpSuqQ&pqk zBQq7Bu1eJtK7C1&^6)ree1ou~dS%lJQnEDWZt$y&gz@=<<3dz0r`cz)bRM%89c;f{ zm$MRXrNS@t{vIAAp$Cxp?LveJG<}UJaAOY|j30PF|ER0mUMCw?cG0@$(82rK8;+kn z`~Ci|`#wJfehQ1)KJPy9>>iiY>!)wJ_U=hmRAqNjCV3YY>RqbuJhyVY<}~x&8Ej}sg|>6PSVj)2&^ts?wm{L=N8Y?LgIX{3XhSYi&aNL1#^PbG>hxno3#!cIpt*v$*_#~*wdwDjbQ$*k z^IQ*1kd)RQ6xo3+bs^A(kbUjGACOi}gqVTY9OLm1OxYQOLS=;7AWPXjIkfk?d936G z=kj8#{eRrPAfvgYTt*wtTB2aUso(G^9zT$~rf>S<#ryfNn8VL-cipK7wHhwH{--A(y=>z3RuXB4U_HB? zxokvbd~Kmb5QJzK0LJ@DW69Nd%R=&Le6r<&8Z%iO^a43MXDWz;KGFE~uTA_Tx@mD5 zU9p%$CBaK??F(q3h=-EEdn3jJiEIjfFOOgG_FGu99uNNE6vc$Z^2?Q5Cij{`jv~~? zIp|?j*sT&!UJ3{1E4+(5Tr>W{fpnBHb^d|`cWyz? zWNlcm-$Upv`g_DTd(1`v@;{Ak!fVf(Gyj$MoXi{bK9%$spc2ou(I!F3((Zs`V(TLH zXxsUb!Nk4>6v>OMrRKN7S4g}&h4sbNcM6j(;H;?D2I`tM(m*Mq764BE+Zjn)Q>U-eroKCo4)P9*%rv*$249D051oaOI2oDn4~m{p0{oFWBI>$Q zpHYX4N;GQEy79k^TzZ#tmWKTbI5YkY#4M`C7{+Z-U>wi>G$? zMr|gj1FzTaQn_tEZ$qScpzQhVGp_sii6zBQ{s3O|9q9-WCW6aq^5Nm2q3msLFla3Ec9FL;b z+YPD-uJi0^skD0_Y_SgNfOK5H=-PGFYMb+OqO01!Hb{@J#s>|Er!o8tRBC*1RQNxw zdQKA~W5mrw73#RA2ct)qifAE_Qy3+cE?`_>~I{L&&f=6ipP zSREFOUg-BWSx_i`ST$Lbc-L@U$JP1J>EYoDd*ot|ZA{;tWw1i>*;d=m+cgH%r1>kw`ZAJTQv)Cc_ndpD zzQ$yn$9W>aBdQphn==)F*j zYrUWP)Ej((x`y$niQ{*G$YMYIUH*eF(T#2VX69p_{83+d-}i~0&B1JG=hFVt7Fv#X z%|dm5>4(n&a&u3mdPu)wKC2BT{moy8*2dUB_H%sz%m_a&i!;x-7{&s}rm?Xwqo^dj zWs;J;B!-cbZz{i3M#rfCQP~?eP8Aq-cq$cBpXYM3K}x zqirnQ?X16WFT?*RWw`Me@U$Gvjbqfg7+4BPP!)Q@-1l$rVmFenfq*_a8>9bkXPTAs zJi)_OUq%)W+E_LX_1u2^p1Q>+0uoFT6gWmBvlMw&XrH9-P?YSN{ilhudKgis{EqY5r|n&L4ysVc!NCxpODlXMr}(L-AH6;&KTo@ zjXYn4MV^?(Cdoh-k)X0LZ_Xmg8|LGCSj|t%jCd*Vj^6jSimN}A!8+5}E6|cQ86dsZ zx-g%1&?Yy5c5v_QUmr?~MW{3NGktabk45+jgkpuCm>%B4dy|hNPa3}W^j^mXp7AB0 z%H=})qpbQ9_rP?>Ol!ayui0ih{iGC!P+YH?8|nc@x^A@u zInK(Qz`YQ*t6*y7oL!5k?bgL!i*;T;7YaR0tkgoyns2T|H@nDI9Lf3HZ}d6~S{Dj* z`40%rRooYo;N!OYX1Im9XqvrKuFKc^ai90Fdx1m#Lh=^6Yf2(}z)Y>AV&sh48_wm0 z-ML?F9oh@sj7}HnCmK7mz2ke2vstcJQ$?& zSGp7Bxp-X{YrFZBS#NJmz4dnA1u0VwMKej>x>-p>CP^jJg%a7H=zWPCS^As@i$x1e zu9?-;Ie=N-zNSDZTII?6zm=C=Cf6YN*~U7w{?n}>3pNVioCO@HgaTn%HE(Q6;Ma2DfF`-4 z&EM#@aiesMw2xMO_81wOT#hVQ~zkLc)u z=d~l#Z&ZIy*dPO!=NIbjf##fgi_2gc#}5GTpT2^@VJXIyyw9V0v{^Wi9PMvaMgXK^ zCBhTE6=lV{;@1ppbN<=kOr$}Ak8m&Kd=^+*xA8~)`oO!NaQ{94yBmjC4jyInR|d| zv_91S)B)F9Ua}ZT&jwecWn>l4nG?h^H2mERN(;B&sN)!r_3?-(IMU@I`XswIHhn(R zORg(dh0R#`qurOH#Obws2F8aLw|XRDfqj#tb3;uJ?t~3XvugFK&UcMa{0&%w zQpf~`v=PGh=C8dS=yi_|9=#s41Ciq|UOXeSNa1X?f7DPNAxQi43Ao13n-;w>V|sx) zPb-)vC)adbqsxQ`y@2UlZk zXWe|4ea#Ws)qK+_N~80l9w%k`Q?{lvIfeL<3Q2^IA$k_eA?EYJoEd%ljCe>N?*lk|Ut4^$ z_*Ll{Ue_NTUj9e-cdbgkIue!`!|!sw_`1kx-pRM#b$Ue-F|+N-r`;z)1Xx_mr*1tk z8ELlyeZb}TYeNloxfveEb{>EPI14p~neFL4>)R;1UEd737{P>@lo9}NlhL2&nr_`J zzCd>$@uD}i3PexnH~vm5qCNArkdsUK8K=FOxCU&{GZ}39YZvg4+mc>1-2#6j1n*82 ztOCF5{BXh1E(^}nZBu@rWrr5$1{2FpWoXXqx+-)ZAu_kr+#>=1`B8XlZil#*bbyp# zm+OdklY4PT^5!aU&Pblow=w=RX(sDD*HIUGy}M&1pT7FYTPRM!nqQRx=h3j}!I^Ng zKN%;PY$pya>Vgs!$4XH3`@k8U1!)fb+bXA>o%f$|(wNyLC2rQe9WJxou5}Zj{SNky zIG{ZeR^OY=?`7cDUVIBEyq_hSpY~?nv#wz1xwm-7hS6r~w!sCKnY`$vzk{;W;dKUB z{qC`_K$-rG(8hak8MJReQ!P?0zQZRrIJf8>P_VnJ!b@);WiK1jT(tv|h6=G+3JVjD z1Za~10<=XHftI{RH-(Sm0Ky{Ya{H%~&-^i>STXbDmj9FnTcZ!rFs4LI4BYYOnSKApXYnM#N{a%xPaOb7|`C$h-+aL$ErVmu|NZc zWN(0vHsb;^E+_h2^_{h?!&w@)+AH5GLM6{LF~{S@nL(U%Ex(Okhq}b+f?eZYmum7g zUS}Na5~AA_7x(m+Y#l|m(2rO{{MfH@dBZ~8b+!^f#XtK$?M}u8-0(9@JX=FoNEXE$ z$z!$-k*+)SPI+$&S$Fe~a)RZl&WX2vfbtA``)srF%y_V^V5}w-5HRUk)^#Vvg|TARu7iFNUEfREIXLX>?R4jkpHUqL7zoN{ z@<+l`Lh*bHz(!jvZ#afUV&Y^%g02-V^RyyP_JU;7GrVB$pNS~&((cPrlTUnNsYxpM%wlaKEFy5@`d3PgGpG@R zo0GRWIO)nVbbY$!rj17yl!&YykapLe{8K|^aGUZbQT!&WGd?QS*#{VhvdT(^drq7Is{#F#*=*PshM#W3ax-a5 z^YRxN6qT}VFp#G`p}o;?A4&)Epf@*^xJh};+vFx^-I8RRW)a$ai&H?3{)mH4i-R{O zwD&IA56dgx=n6%Qv&64Fs5Zqjs@X2C>ApxX4N@o$homHD>jL+^qpt445PG2YvB9K> z<7cF89=lMXsCRy@#S0gR!ta|x+JEzBF?5^V-RQOq;x38uyKA0Q%#|k2%=HChzJNBL zE5W~=VCBqJ@}Nayx_)^>4Vd}M(QpoDh zlt0rS+a-(R2U`awvD&jIRBDi*vil#(x?@hG10s=|IlVj&ln>Zk9ku=N6T)6sH7y#D zd+8)cVpsuP_Tc7Eecsn3HeVExyH|tb<$q@yzrqK!{U3+6q=bs#ZbV;lXLn*G88%Ji?3vzGY9 z?{y#ax2~mzZ1$U=o_bgWRaKt|fBW8tDvr{9wI`>xJ3JmTSR%;R^)f|MZXEhER1VDr z$9Ju2>_7Xa1)ZF4zmQvl-fJc2$;HgqI|%s8n0d%SJsG&y-o_7zyON{@Tms$G`8>ui zH1yh3>a0_XaB*Mb`sI+jH+aW=YGPsTu|9T5#;nw%Klg5k8D}Cf?UsgO9kmF->SK~! zW<{x)Q0)%CwK@+LY$ga0YeGag$$PA1_I0JFY2ND7!PhX**1Zo+bJ7a-La0M9`fuvn z)_9qFHO@bx@jLq(<|SR7A;C4_@AZx1e3);G{Oo^e0(>6E;0#$TUc_H8kUH!$v7DHA z?D^1Ckr%>xa8xsW>}Pmwo1PqqQCWxFbinrCU#o_s1a6du1TmBAz*ax5nMGvMM86p- z%#z=hJdl5|@caB{p(6Qq^AeTlg~)3_CHOs5e$n6hO?2kkl^NNIv3c;Wd<%B8a&nslB9lja`X>lEvf z!)W0`ua}VL?!qxrvXas!y9JJj?sP?7UK9DnXP?YY?RC{b+fO_wny=Mam~R^Zr{|;P z0;mlD#1~ZGQiEd6(z5k4gGTZvV!3R-j z11KVjWJN?#l8EHc1~4F?C^-otNs>rTW!oZ1Qc(ekf`a5El0!>W1SBJ&3Mt8gCQZ{1?NkRNZ5>FY z;4E|h92WDJU7?Fh$%36w0H;esyZjj}OIdhrx)gp1>)*7WpXObzH(J_el*+MHdx1^_ zVVN)CoGZe^Q@>%d8X7C$KBf7~9eVxd+93$oNQKAV8lJLU{j$x7v#tvg66aDRFzQ7^ zFspD)SUo6Z3{zZx0{%)>9-yPX)MV}OaJwYCvmCdl;UBHEc730<7A~cc zJUmb_s@cH&-MZFbmX;l&9lC{2==!U!x^3Fsb$XBHGj{>lzhfL{=KYUI6gdjcvl?>N zMK1fM(-d6ZbL_CHtos!-P{yaf6tRjO;1l6zCt9xB{_Q38-jt%xioLZ5GQfIKBq-2d zfEsGY0$<$P2^Qy;3suP>k_AKl6M5E$)=-P16W_+)5^{&XzY8lkPK`MOgqQi{cbwV4 zEzqC4s3B8PQ6oOAmn{d|28AkWra(-|d$&IE3zHpv?>fO0X&v+RFlb>Bo|}y879S5E z_R>K0Pw?oZ?(qylg2#+g9RXdNyKGVx%C#9CsyKG=BVB)vZkMxF{K4V%BxciD-({Z| z9W)p#?Dc^FYrA9sDqkz0(QwVz%?^qgTLA7K}n4DWV00_>7ORFf)}lf?d@tFznEk$Uv^ml$9!T zAx#yG4S5Vi<~J%W#c3217OU-Q8x|)F$>F(FPYb;)pjs>M^X73t%&j#3lXU+>0^i>e z$5S(JPS`y$+UV~z(PBt9L;)@=F#gRB%!L;mhnv3lxjwp`lf66Z>smwJy@of>EEGSE z$#x29i9_}PH;{_N0d|}R@Y|EaYYAvk#`kZy=Dz~*bxhziHoRyJ0>=Xl8d0!3|I+;lvM$(l5mmGPUj0Xv=e4sa969y6f$8>Wf3!$C^dpI)|`%a?$!MPa81_U z$_`AQQ5uU{=#|e`M=+PjPzuL#_HZFz-pg~Fk~;9Q(!ebosxDJ>rjBD@9pus}pNQy? z*K&jnN8eLW>~KnOy2Sc-_{FaCnV$}^H^?zmB>#OLKhs*4wPOD2Y|B$zG6HFh1k3Gy zAOdS{$MLVXCjqjls9?~eoyI}%QNvP!bTo z{j_Lb_@+okS!F!5(Y9;s6g2>U{u#;srHJ|;L7}4xB>kkb=MG_6J~tWHj%`XyY~__Z ztMSUx^MkXW4w$RUSKk?7KmD7`0y@_gGsblq)UpXLVN5c;3KOthDU9`Sf4@Z znjqeEK(44f%)9_w152gScAq_l-N;sV#3(n_+*~q2INAe{elP!*e5SdkH>hxk>VHXxv^tY@Ce0&E2dAOsnJ4FX`sG~QJ zcI4k%e9PUnw|u#mXw44hL`PfJHk`s*uQimUZS^V`qt^jQfM}x~uhwFX` zsLO%fGZ$?!)!sR(NfDUX_O7ChDqD@Hz@72Dv^ZqLMBS~)R3QCHsjyZHU`U_aFADpy zquNideyT)jAU-w(g=dbnJ}jhHc?Y*(3&KGvPP((Km+dFmVXBa!K^0AbkJ|DosM!L} zzG;kL+Y6*@#SzFpa-xS1LzF^teflcIPIgAyo1?z!F=$ET`TqDFOfB=Z$43GX8MS(|2y(>-Wz0oqG4~Srt3eI{j&0q zHjN`8F6pQ&-4^U=@--VQ*l)y%*Oqdi9y3ZJb4r70$<=oMIB?K%SY0VF<|Q=CwT60^~nh)YP6 z?{f#lbW!HRTWSsifYTbc)=sqcTaW1)51cs*_6rX2Egho#3a$h^rvEWiC^qVt$tm)Z zH!4?X%M5d^s9B5Aaff!Dn*v*e3+9iK4t^@n&;obu?E8S(TPecClxo7a;dl?&# zF+TvZAkNv$gw}r6n*rG(NH)OaW#68`lDN)5LDh69b@~uC|M_Pv{Qi{q7)}4w*%?80 z{#NfhU?#BQ3_L$`%Dz$l$0C9hMacqfEy;5y}%Kuq3a2FbPcLH5({5bT8R=viqip=>B4m zn#>3Ms1gJ2o_AxLQm-vT1+G&NlFz;I{i)Wzza{XKpPT8*)H;^iaeY@eE9H6g zc)1_v%&cM9uUr7tUAr$-)j*C7gbp$FVzeuAO()GBG5p(#0cn#A_E(b;9Hllj+Nj76 zdoU^raa9!-OPhjoNqX;4UP&*C+2>th#PXp6;ul>^oEy7ttkB8>7w$^_Iu@(|<&`RC z)MU|sun?Rpxq|2c+EkZN7K^ps(IDduo|>~jOD}05ftuBpO3oH8NCfg6KJ^=xA8IGX zQ%L=$RTy-4(S(aa&ur2`o%ZHI22~L*{QK7;F7HK(fTU>=bnmen*nzur?S@)N|+pR}`M|1^Oid0Rj zpT8Srb(A1h9JdX`Y5R%R4B>^-n3l!QtPfPaB)++*;(=7iCh+7pzR+@DQg@RtQ$z=v ziu&dtsZe9|&G7e+z%*?sVQ{#vIAxt%Hn8!(_TpI=raxE#FZJ#5Bl*%|aHiIf;bL*s zb=OvmM*}#lS2&b?tNGDZcHD5czu+UV<>&YA?z9j(gK1g*JoamIbT_pJoac^V2C!0o z9sx5QT@o<}Qz3#84lR<^AYs)-w4i}wQuE2i(=@b=k=cn2YofkgNLaNB8d z=D+Eb{~=Nl#B_s0oA<5VHDkgI{VZ&>$%E`kEj~l3wq+8!)dL$su3baPl6PmnDD1|x z&t|F=d$at9^*tia90Kb$cb9V|4HlTM8c}8;@%_UkDwQ<=NG?b0^m{ z;W38@i^4)z<$zX4{v@HnE zM5v@N!*l? z_cTYb5+o;RjJH*Qvx+1otHb0eIZRgS2bCiR_h3Rjm%_M3ZW5Y2S27;Ct`Q8mTpAMr zBCj!wfHo! zHOh2S!Rib_q{W!O+F`zOA@@2h71a~50->480S;<~eZ8>+_~@?VzXB{gS{F)hbva!V zI$|K-nzA6Kc0q=#wTr3r*g*IC$B|yULdt-(ZGd+mjwRbu3^z;_^g?pTvQ z?qFx$Nq--0N`>}CgPku><{gs36@Jz(C%|ReB=ZY&=3LILTR@e;>F33d8>)LAk{4Y{ zCASUv^rDKY@VhU_rVaH(4UG-C7#;onOiYAg7nd1XD5QPq4+YQSzp{QSBrgJ3uVaS@ z;}U4#zyj3>E~q-R*^9VIYAX)(FYjShsXOC2og6(B+mh0G^Xxax--pHNPdnGj=#qje ziNWF4VJnae;`$WUK%&Qi!H68Y%@ypJ(9))kPW9LdoFR0%sfrS5`nlca-qah;_AvV# z6bpJ}mf6!19<)(B?+u#iVsp$U&(egS%@Y!>O= zWZIXY7`9Wjdx}NI;x5h1vlykCpOYm?ejv`v+vk)txw2Y9Qx-p3-DzTb$cqaTd9}PY zM$Hk~^ihpZp59yejpY?Ph}e6Z1lUKtm1pr_E1XKRpG(<9l`G{hu`Avi4ncOcH%tc` z{?ubHHW`?*<7=YDYOZIhlqY?E;%61a@dy$G;bGmG+_UOV4IylD26|J!_r2dRmsD{Q zSD~4-Jh>*Rrb%J)nL|Yzt2GU2bc>J2A%3ChF zu2lPe9za3_{}wfg!rghV&umBL5%hY4FjTqSxzvNmHYJuTtQ1fhqaCx?77UulFUSt% zgeZB6*`#@!e?)YUHYYv0xUZcZr=hng$v)iZ>Um{3EiR7fQ#HRT9kS|b^pf=6&~yp? z4&nax&F$6Kp5Jq!+0S(Mch*|290&4F0zMpa?p$m@La`)6HZ$e*$24`CsG?1ag7s>$ z^@E6^IAHtNR6-tqF&ep552@&%DRqZ1{WllvF=?|xyasr|>YC7-2%wN8;mHfRs9phF zV~3|j4Vf?Cb6xNzBWOW()-)@!#uh$|27SmW#fw2*=0~W^PE&bD*I#|^$``|BU)fDV z;&%GqzE1`6+!dYwA)4)ihhPc0fi(4uTwi{#G&kXt3Vob7W3cmdPa}lm5Re2SL z%bH-z`9{G2z=&a%kz4sAFP#4HCrF1>*mt-cvzPrj&nawIDdhVGG@S%{f749?YfNa{ zrXfZB?G?xg6}Q;~%w>APvD7@veemp>siy09!pKyH4;S_{A?GZ_MoVc5>w zGoWjXFuKh+1yko#;x-&Vzw8z`^6ZmrI2l@2F}WN1;0RQF0ld&q_QUy2C!mc7tWaJs zMo7wYV$=ZP2{;cNQy3nbV1knh1np$osc?s1?yKGlIE<{rr8^$G>5XyuPz%?W&PI34-7 z{Uz|z=R`U*RuUv-m$|#J zuECp9C8kYp_{<)i3I4=xh&FLkR}m~(SiBEVL%;*`=p3ncSuZ9)Ng&IX3if!;+2|cX zzL{C&Lkf>y8W(`*{-eHeJ^!0h}}d!x_=Q9R~wR^ztV)Z2V$ z?WIzC_G{jWt*-%!d=Wk8u^^lKVhudyQSMFeKE_0m2CBL0Z40c8O=&T8ZYt|_P93Gg z{bJpCKR+h5>KogcCe^C3>GKH(W{X`qWe#9<*Fc@g(exV%14w)NFdOYJz+hKMkj6uq zRf=Bz6kAspM8}k=4C%BNE+9t=qOR|KJ{GofKDaY|KNzkSq=f-)?A6WVSnm@*Fsl=n zjbODHD|?8{z1fNy!;8IejZVe#({*IEMW3<>jRWz7eP>_7?2GYafinu481!LUPy2Wsk99MeH;p<;w4v?ktAh2(0AwG5#3Tt`zH`yb)8D z`#gwO*DVzYzB-vX@s`lq3s)zz{+*giOlY>K%9LNEJP3*{S_BHnL+Gc-r{y*855<-N z_Mw|=i%}|lCa%Izu`^d(bt`u2W-^T{x#Ib$>{|(cI|g5_sNwfFd9D7SJt*Tu0>N&r zhBoL=Cua7uhmpO;N(&bKR2WlfP8qqVowlOSdESG@_%7sg34>v`w{vmFroQ-@(Q?Rj zbY(>80yG?R+4vbckly5T_pU{I@uJ=Dz|O`aSJM`^VsvJ=ZXL=fUFh!0HdUVJEfgCX z8Zx6xjb@eI_(Z*FA`b!@xaS0v6g z8(v%WAP273@Q3KwWI3a2`v$&bcK7uirwPsMb-F+WFzA@nZU z*nhy_{x#24B6mn?Mv=gmdjuP)hC5kJavX>X>qPSNu#zJm?|#ow65Ga=)_PT;FzX%gF0OYF zgkri6KtoT^UZY&|0RI(TmFrE5Cj|0hVF8e;C}}~wElZ?4t`-aS={i^D@?%iuS5bp+ z>>T~mN6=qd0X0>Vocz!_u;{a~NKA!3W!|U=&P=C9t9-fLb)|>Eg<2~`L3474^`+s= z=D^35&?IzVBDX0R^`>iD>usurZchbwA#Zx1QHB(_Q@BLL5Zay9ezfVKehnHeru`N8 zfL>2~XroimEXR^czCEq)C0dFm2Qzh&+qdF+fEtZ;K*}u2q`mC~U9P$U0Tob`vMN{K zmh&Q;QDn8`Fr8AjL>W0q61uVtuw=Sk(Dz;%Ol2F-sTT^+Dj8rQL&G9D)Jy#J9my#7 zQo|A=C&`alRq_zbt0X)+I$gG7V&X1p&g<}LJAai7bQT<$KS@`iJN9Cfp#ofYBzg6P z7%H4brwn6ZWA%^FfU9~>4)5DPQABK|Iw=1SZFT;T{Ag~;YMqlUV~!iYSbIZ z^{<_Vdr;3P8{(Fg&Sd*7MpuAZF{r!rj=KpMy{3aOL=mBlGX7{VxB~H;_8Z1!m2!5o zly5q89aC!YfL>#+(BMti8aKZV{S#Rf$jk~%!_d)5vBpR^zt34ucJR2Ge~8a2k#;38 z#CtBmVR-FhtOCZ2x6{Ap#P) zw?3A+E`Xo*l{l~9prMiij$WqE+Bne*`i&_nn5XwbcPuh&gA8g__Q0p(rj`K~>%EH@77W3{%htvZ`!r;CfR;hn z9OfGXZ@(^7I@jXbU~QNiKTXnznR(&5SWMsyGxByreY~4T?^CIf+5rqY`_w?^(xM4g zfLEZIVrSL6Fhkwixz6@f!}*kgfhQ+kmD)llRdP{hsgV54vydv(Luht(R#Zab0BREJ zNvY%x?kro#bAVozLNbjkTKY^1vtkMwwQUd9-rw6oxbf(bJP7>bLA&5?mLH&LUlr4P z|Hh65mY_qU>j&KH`>(32tUm=-wjgVdx`(HxpaVCx;ZU@yd3mSYa&t(qn$L18`H`^a zp+;!cOYMXT4a-GEMVV0VxllEEDYWHP)K+jm`4tX^KsW708N=ef;IQ)5LDcN4V~LoS z44W?@R5TL5X4q-uagHxi``>}RUx=I(Pqk5GpW9rJ2v6Nm4D zp4O=GmG*+80_CsWHO2V(j3Vz{#@nM$dGVGZ%Q45LT(k7qO>^35fh`pp%~W+5%7ISJ zf77sxV{G37#>*YBBctCc;GUr-yy7422xSE8nE5pGYS?_XCeI-;t<%tkH0B_5lnx_~ z!lJ!1d*J1(9d>ISmy@J#*cOc@qF!S;1Z$A@sJ)(_!g7Mb6G6R?CuN3E?{pxrARo$O zA3x31Jc2c0=2d=Gg9IV!w7K!1wAr%Ks^%t$#*eKkrv8T6`8j{hE2Yrm)&v%P>_^X? zUd%{M5+ZHh@rb=TCEl#R9#3y6^BYn{W?9UPtn^w&UQQ*@0_rSt7d=H*r&PtFS|~ zpmONTO_#|xTC1w!B4v`WJ~`sNSo&Zn?jhq7qynT?SG?FIYy)>g53UuP@=0gFSMp2K zTPWj$W2u?Jzh0aZu<&#ENdV6BkZfcEs#jLD)dlj9Cl3(;}(zqXl z`um}Vz(diF1h2*FBB${u88mb0;r!F>#aF=2vC`6`w5ErKeqpQ-kIwe8GcU!+JL8v}o zY`G#_jXFw}IIcrYi|A3c7}@vI8i^|Yk#=QLq$s{Cuc~|**y(PXAM1nuhtKL~Z{!}= zNUVZ3f6^n;M$0W>CM|C-c?A#OD=e7&*h6PPFR87?B!eB8MK=2TW9?ah5h{;%j9CdU zrw29raEHh(KBj!~N=+#CD_6tf1a|#ktjNpT^!qCQngC6xj=1Wlpzeob?(Xi(912qf z!~w_H75z(Ag8Bs__=S)8^HTWMR%Vx82jxpvW}v2RvR%moC62a*gRd+sELiWSCnhF( zSGE$?rd&){7A7BNY+Fq>*;2tf38O3KrTW5_Xu*`awdVBLO^jt$)_Vf%s$9HFvqz*c z_2wOGBE-CVU2sH4d_8QD_N8LeDZ(FZm7iZ_1=X_T#YwnheOD)b~ z-^zPfsiP2KwE|i!H2n{@+0nl(ra;SKD>{5_OMAI+5hHfv1HO#g#Qmbr{fz4tn`a1d z%hGtRKeQ-b_uKEBH?V1Aab3$2Yofb~VQ<0cyx0vrDp3<{uV9JOr>o4u3^ZF_@7#aV z?^=S=yi^(V`=u;3`53mm)}f&8nI%LmeTNHy98#x9QD@saJ8S>gwv(=%S-l|murnq! zbjb%UroU#D+8>pllyKjg;V(wO5v|XVf(45g4#0hY0-AO%w`MnvVZD*Ln^=N6+ao-C zSM$qt--`e~8L;$jr@xW=n9KbbiL&j0{vJU=LB4dUJ72>k!8n+09L>zU2ZyP*IwVp4 zS!P%xcKOEV@rC@MOz-(rB)310f3ojrH#m>E{;8peVJZ4IC$Qd|MR`R}2s8!RIFvM7 zzHv*fIS-37ncq(#O#VKB>5njSp;N4w7PY#4Ymv@*e>M%&%$>WkOnb50G(_%|%PL6T zy0^AIdryqc(ef2WKU&Wff zzFp8UkACUm+3;E%^%RyI3O7BKte_2tTQ3vS?%?4#2~BZ}o5;`y`y}+0j@9vce`fsS zRB)uvhcn(QGr`a0Y*5f0m!ic0{R5^jS&$4@Z~gw0!EWLNb!IVJXe)rUTJ%O3sR201 zMyLCp^xKCaN71qbR zSjFSB==ofn(d2lXwp1wQ#6S=25+d}m{rq8lJAc$u7uj}d2kIHRyW?YHCLL)y5$!(E z;`U%(p4Z0kyWCu{jtqlHI3YT@(n5+b!Q<$T-c?h@iFLU4Jxd+={tI$jg&#&v3aGF70dXx9LSpb3w4}aW zI{j&6# z%eD0mLe{NwiSq&NMn*c^`4ZMYSC-znPw=oPcobG}p4%akgZfn9ZpD4enp9_P=V&go z?w|Fb<0@)MwVuA!TQd?U*L=Evi9LTZsDqbIo*NS|d?15u%n)3veDv~D-d}gRFzLMo z&0!b)qbaPHiiXN=-@|hWS(fK*6Fpqd| zX{f5V@sF6IUSvz81Bb$fzIVT%Pg}h5$*=p_JG*zEJd@LT*Y&&>al@T=LtN+Yczj`a zd9V;KFMrkFb)GP@!QpN-W-`Xmbf@J2_VnXc(x0?`T_EW3PUMzZrjUXVOfw?2{Ya=V|3hw{*t8h;T`U} zxBeWbB##UafBUYt>STt+;fC6*_JC##+sp;nb%(ycNcWeO1tfQ1JAOO;o@~?F;1c4w zgBTuwn^@v;IvoudazAGH!Qxsk^eB$#)G7B~J7fe=HoKEXWwNu&Z{Ov+Sa3&5%xArp zB)vBvLr3@BmIhc{$--1$&+vHT@5y&G4Bey>!;1YkZV%%ZSoNlkVz?vd^@5QSwKIcu zFS6KiU;5eTv8Uq0?AWN}P~NbKW?>|5s}%pim}P0TZN?Pvu%EZ#@i8tX$;p-%ms#c9 z@8ikq%O@Z23pRMincr#TBL@;n@8fc5X=!suhvvuS7gr3<-!9jy?ON7f{VrNc{>#7c z{piS(kHKHBY{6J6q>i;`l;#%q3Ua(n?X>lRTaD!k2WTr2tfdngF396H{+Z4>I~9|~ z@UsF@p}W*z@IhM|+$qS3c;5E?dxVQ;mEW7C;nZ^JwRs)J;~d48Wo^~{kDeYJ7)XA+ zURjoS^nkL2(uY8ffkfDKn!?xJ_wwzZ;@QGXXmGSe^x3rb){fgD7)O10ET^PtpT9Wk z=fvZ5eOFGR{e%Fy;CH^|Z-3$?ZB;UQfr%CGxmzi}EPnLxZ5K19&b5+I_I@#l>sdf@ zLk2yP8|r=TRuk?pp50};6T5JJBa?D-!LRI6QctXpQXY+Ds;a3qJ)OJe2b;#nCGq}r z1FxgQ%rn~spv`mN+q-n9_ODl+AgTr!T-Epjg!9x-yi_B=oxo4%U}xYWp$N9(%bw^i zb1!(6D(I2t%RRq;EH3uAxIB{CSodsH&g|qPQ!W2m27!i^kf|W1#-DJV&{Jpek4kD+ zrANa#6G8$e6U<)}1Aa==SJ+K4u+{yYlpLfVC6mmrD*1^P@E#z1Zx7|5kjA3sL0hmj zodQef^4PkJ1q9)Cixw7{K)*Du|o=f^vhm6dCM z&+P2zP`YyE%Fz6!hV^)Y+YQsJ`llW5pALL~{FVZyDBca^JGZdFHRo<)V-v_VNvo04 zQ=cB|mtX2>^gGFtT~1tg!FIyMP;K)4$a@9Z*WLLGGA>4yqS?9g6C=s#A)J{_Pbyu~ z1>f^yaYdd9!|`3*479I%)DMW-sMvf}u)VFqPPD{TOb`7{)t28yCR=xE^LciVJ$TY%x5d*wHlnrep?HkQ7QqfYA`8FCaQQgecG z?LqUXXKr3C*NZ3kn_D#~!JJNc;tsa$)YUR_V?@uv-{upX&g{GAJhM}u9<1LZ@)QQyh?dUC6LI^(J|clf>&uLH7Q)gv%LduohbEFSjl7( zcN&}mIr^oB5oo?9sGi%FJq5Ghl(;oP><1#x*o--P0xbepv08CQh>4!D`|e)HnX4Sk zaZs7t>;C!kf$!7(M~RW93ssc^9}X(l)JZqNwRt$2RJ$jVi$3S0Jk6?7)s*hK9W~i# zq%{?+J+C5r+~kWT)8nhI<8leQhlMC(5B5x_Zt$DbZviNubw;5b*Ym{FDBU4#^$_QEmr=9 z#usNrCrO&NWKwRB-SY>2{d!fS7Tw&(g{hdX52i*FT|F!wGR3oMjSOio&$ivpwm5&g z`L1T^9cKFa_nrFt$M2AHzg*^9Gh`{BT3=g9$j@Jl>$JAEPRP!75V7Gr5=lt*yS%Jp zb|}D5Y-L@H!dW*)z%6tqy5`-wbJr?{nSt57x>PK9+8(@aK?O$%15e%Gil(pF&bs)K)`;Km`jo0bWBA6#1vbWBG53)s4LoUf9~QU!<5Sw__kTW9 z9^xd8jMT~26#)n^GBNR0hQFG}+NahQ0L6&KEO6w&5#f?RL;n5XZUE|f$;!rN(xnkX zE3c>)7>^fY-n#pjNHy?$t|o-L(6IWyIp&@1p*xo{Vhq`2%~s$khkL(g}p+WMA!i^kv?5 zQ)tGRnEz(rs9l>YRH|WY^9F$AY)zR{43*8SvF1&W%A~pMxOn`7(R( zcrI|&&*P=cqn$KAk5f(mzn6A{8Ftrl?a>7v2w2>{zW9Kit4_vy;k&u{_52&E;N4nS zT8=t;lJKSEI^K{MB~xnNGofAOK0dKT)0#m4MZihcG-)tgvN+xOGPr$$PQ5#8Ie>GVr|PWF8Z*QkAm8a&w8}eqlrXnIbB9L=N$qFcmea z@_XL7?camGKMHn0OQKpV7X;F*@KX5%Z;wmX-fQDVO)}oymPyqgEL$(@itP+DbhpHl zq27EY8&I6*?H=>(TExHTxjAmA{d+hJsGX%>EOto+Pqy<}>B$D3c-{t7s)3>xZo~Qx z)hv9;FZ1Ah#Q^&29d^~y(&`1Ek1uucWu_-zQE~AKhnPV)oz&FS02Iw6MO_HkUyY#I z5nTX>g8;G@BSnp86bp@wjnM&)^sgrlE;yq7Y;9rTC+tlQa2rOm&b~j|@_V~Z&h1Ml z4ND|RQD{u1AU5&$(g@~#{rYu@kwoA9);Oz@Q3M+XvP)z%kux$f3MO*u<8yO!N7y(y zIUT;6g$?$tx%3t|IJDo?VlhBC%s-DY#INZDKIL^9vI7d_HhfY$iwEMG$?+XNGoSg1 z)cur#e_5k@rqSBl%OOGVbi_-Y(8>rrky&!e-NR$2VR=##|NfKOds4MBAt=$IXBPy4 z-ak73vxBU`u!B#&wYBYoz@*k}qouWV03a4J-VkCv@L^%M52X@8=O#@ta8zEC)K%`j^qhyiskGl;cdJPKm3-S0F)W5?-#~$pwO9+#8fy;`$1yNrv<%v#MYDa%wr- zbkRRcLmw)mF%fl90ExK6^zU85OF^{mNq|t%F%)vr&bKwd7ou}f^BU72H-~tCAoP!; zn8pDkPlvzclHxKlgiurmkk&dGyU~_+q8GJml_j&rp$G)P+th|N(^!Z>0z=oGf0a+PFd)&3vnqOH+VWcMb;db^jvkZX-brS48?hNVR#?g%6Vd2t@OC|4PV!?Mj%CU=jYRMBlzxh?@qWw)g*gD(r9Sfi<+Fy}O$Yz`TIb)+BRX z^P0ee*`7-?7B)5w9~#w*mWCpUzU;PjC5|fKr)GXr}o& zHcIh_&O=1D*L5s8>D2CnVU-X$;#eg3_#7=}lYsRA_B@anX)CY<*YW)8seA;(WHTzP zPPvIRN2ZD1tM8&kGZ{FFLkIi8?9CwRRKpHK&0`xBTB)? zTNaR9QJ?kI=ji~|{qGS$S1_{J{q@H-G731vUkDfgsV{65q?3CG{f&CAVLnS?d{ZJ< zLyum4LeJ&O;|<~Y8o;dg2L%Of%WUrIVnyN4G~GObS0{D$!neM}Y5eaM5ES}hMx~}l z$gKbLXs79qPmjo-b_!Qj?pEMP)l7dvmCYbBEr8FwRu(R3XlQ)+@S*DMrBDRXiMmYn zN|H)u2MUP6>^X)>s?ltP`nGjr^X71lDDGI3UpAkvUFPYwI&h%e&pg)ajG^m~M<|cu zLtfs6^XI`o0%0R`r!ndvXz^eaaDqe!^L;EFVC??yiL(O{-yR|5c;{=BRBo@$jVR#i zg8n~t4geB;%;m)Yz6qZyb!~t_{`=qo0sZfPf%aPec?E|1b2GU7zpp8tMWN+?KRk!F zRQ&tzfGX{wG5+s=x#)+|d;a|#Ill?({qMi+{lDq_vl;)lJO6A2_J6eVzrFbXMb3JA zG^~E`OW#&N&mmBkZQc~~(2!f)>V`_JeCaOEYqlPXQ$ct<{-I%JIz)C8l*8WeVsYJ) z1ju*(!;ul=v2KKWL(-(+?>R%B4^7gH%H^e{r5W8zH&ywUZ%o)Z@G~*ri|5W&9@^Lp zPj7A+?g1;j2rS4jz_xr9|34-Im0lD>LZ47gFekf=%arWM{4-u=20ZVVMfq?;h-+7|z)O}h- zDG<38d%hPrSr_W@h$0P;XWhv)w>&r6Y6?L+vytDh_h-iX|p`u`te<~FilG1g#^lLG+$_+5=Wb3so}ZvrBd;Mc~# zd&hV5>g#>TkxwWqE9YPt~f8k@HygYy!N_gjf@FuJb2W7`z3uOnE!Y z(0L8xF@WGww)^}Tve!>SN?nZWfPWW6DVoRO4b|VxV>wYC3`#B(H961bF;DMBB*UkMMeUqs4KAKS?RP7yLbg)G&GO0#ZprB!`JRP5QG8& z*q*2D(K0T!y-uA54lS4X8FU(c>y*IaI8tEF^9)%3)x1GlNPy}-3AtD(rR4KtX(lG{ z_WdD|KoZijf>k;Yp3&lfQUQTpS@V1EU4a~7h2xi4`T5ZDe~|#!Zn-&i^qO;QHU56c z(Jvu+kpk?zXCu#Pw!*89h5Wb=2e8Wsxg>n|0V1nCP&WOjZtz}2$LGO&WC@>H36x=c zTNk~M=LC!mkIu-*h@W*v;ZfUyAHH9$3t@!HR`nP-z{(!Kdw?gZqYYsKhkPC<-xeWZ zXNYnc5ru|JJ6VD2cOIClWUl23dE9728qhfoHTk96cyXXteXsd;hgEWIZ82n#UH788 zU=fZ~4xyL=`6JLna-Bj%h_3@6(KRE@2??d8a4r0e}7)NVJ=2gnSL+06T%AgtBs{ zTpAE$kZu3t6Ji0pTWjLg0Kg%n8D%E2{&1(m1eC8{y&7wJz|i%U{{7|)5gowUv!(-8 z{t+F}Gjpx;&jX1>zSq<7VPV}Fs^q3cISAZCXG80zLu`#`S5n7O)*SMa;%49yudtZ(=($HX5SSN=N0jTD-C(-_ZWxX&G zkF`U@Tk;uYG4a_~GDys=ylF&9u)Afa6$1~7-BGkgVkP_D;1>#|R)H%-Vcj)$_RQU` zJ%HG0cml$8;=MT*C;b&L?2MwZlzaI!*pc|e#G?qdOn2`+7xqPs~I;E-v@^)%Lj*i_w1HABUdVaD;qHOM+a5WO9 z2n_R_{);{v#C5@Zhu&X z^KCiHDb>OzUtSz<2GLa23mS+zUS-N+$XAdJA}p<-X8L*Y072M?+m_CENZR)+*0=&% zGSIBd9i*AA+djSu*~_)?a}&z+k8B9dusJevNbW)T)&l^*C2KLjeB-9)C%%g*g>Z2u zCWJk6U{zCK7BZxJ^NQNd z{QOL|gSwPv2u@XISOVoeddErvR^=u`rZ%oJ%X@8^(qQKu8a`Xey)NRuIOV171m?KL zxWp(*h%)q;%&Sa6N^{>UBt^V8RtU924Ut5^$^uauUD-+>sm5G>Hi9lc&=gH9IUG&w z#|W%XcDjN#+obvl<%?F?^H8&>5KqA9L#_yyo)$HSDT>;3f2hnbLvu>dMswPz+X8y| zRsp1i68rypc#ud-&lq?jqu}s~JSh3FtGcGl`BKz-y8ka%$idIKj!^JpyAa+5_?tW^ zqE{qM#z?6h*uF%QA`ozoP%(=Y^_?v(EjPyc0Qk%+b67+w_*SPV0mFT|mIfz{^SKRK zYH=})T(YbovNIP=8WD(<=9Q{%X=$ks8{jXsTVd7y#?6~%?@*$o;>U2RXf13@P!1^= zi4WN82rO65(Q&fElNMvkKMfmzahp@eL>O!rgc538b#!#}J;~KN>23h41G+DGs)hg) z3J2w)33?KGLJK*f@@AgSnh@?-Rsuj~ce}FQ;D;k&DTQV5f1Xj>;K|_8o9h)LvaNOE zdoD8(#!yuq>u{cGRa1x#r2^pdW^jm5x~mJ+8V|s-zZ9gKrYw#J zc;V%*2O(ajY84A8onZRiJ0E(1P)DYI6=?E<~aUnm);K&K)m9zXx^d%3ja(P{`Hn}wehz@UGAK0@)s6MFaWCh+ z;J{dL+;c-p>XKy{EZD*iB`mUXOWGT&j(48naR-duQI{J#ro!z_xrNL{&@HSetqzu| zlzXQk9s*6xZ_Yg)0ZVOes!vAu^z*Jx+gNps$3!X5MNSKVrY(N zfvK?6uI({cjr$a+TbOmL(zl9&qoKX0TmEs@2Vrh9{8STwUNmq?TuaY)EVq#J;gc09`-&1aE($b@S#;mB=%KqQfsVRQ>&srMn?x>xQQ0(V@AKX5J*ZIS^N(Wq^XXf_1`RiN!G?kRW;{ zH6_JleyknYnyw>n9>-q_JxZ-Md8uW1kXRcM^8ER84yPU1X(d>*;vrE`Tm#}@EbE3D zD=Zc^wU6ILuRff=7*r$zTwBAJZzQ+{Q~whW{G;m_EIU&dwP1g2nEP@phQYkaU^3UB z5-bFeAXA%H!C@Ye*8_5Mv67d5@|_vC244)VauDicBKPG}seF zar=T}H&%yHe4;923{zZySsPqDfNfT9wJQIf^?c~#>K^%Q^edk1wyn#MZs6rqC(pC9uu3Tv? zG-=mN`Y2C>^GyP$j7n(~GLabN*ys-n;2&}s?+^ravHzU!E`L;M4kQWF6j05p$X(#o{Ve2j;*}sHTaP{P8{@6eiO7xfFd)QzHQmH*ftbits@QDn&~UMic|uYPo~nY&ZDjr9<kl^vA z+8uHA^=W_LNfdDA_FA4x7WVvK!5&R}u3>INlhxqVj2WC&7UaC37r z!9Sp-AAlO(&pOL!G0ElubKdw!(U45&ew~{h(8b+R(}Dp z&~nYdfD_fEP{nm79HS^?u~4AsGIE{^ja)jdmNQ`}Gr zK&PTGFta0a%}He|wwF0+FotLl59(>4!+AIf>kIirC@nNgciUKs-JsU%Ikr56?cbMw zw!rRZ0Qw|PJ&3kK$KfgpI6&7&QC*Qg8A-JFpP`gR-MSG9WS^ep#}q}WVlo2BpAO_g z6%5CCSTz)b_c35?w4&R%jKuuF&0~u}p3sUC_vsE&(7{FbN1wA2^6iWoxu<|O`4&io z*l;4i3+mj6lR=9e9fF9n^gCM&=S!8CcaX%CQCRw{HUQZr*V5hc@$S~15HfAF6b8AW z9<^h%?3o(+)J3(5t^rA=OF?{7RnR?ipA1lFT?WEbL_s9$<$-umqXwBXuC*pIkkJ|F^7n zAL-0AGFb&V&|taN-I$rK0LjjiJ^5;ZD8J~PDuAlSXjCyYYK+mwa;L-KOD!d2&ETv2 znN5M&k2}q~pnc%jvGi+43aC3$iBj-cjR50P9nUlbxNHY^_IbHNs$7!+Z^qibiqWB!M`WMomRFSq){|e;TKP?BK0vV;=fFchM zhuntYYRE53xD-0K(WwO^TXeAj$;Tp+w-?XQ+YVj(+7^t>$ph7Sj8DeKK_+G2{`|a( zW4AMSKqxn;$`#Tnum5)`m15Q%X(;4u<(1ltu&@yMWs4WDUM04D->8Q}V9W5m_uqxI zy}x!%Q}dN*8DxeaAWGG$94a|bP$&?Ytw=+vLJy9hO2kf8u3*mozwF*}BxpHLxFNs~ zBJX@d(U8MM?jfw7LA!n3eBYohP{|Gf1LC?=FKRuzRH5B@xOTQsWzK$gthuxm%Y z1G}IUAkieFa_{3#w7-OtHWE&2sQLv7StSsWCU}&ThQuU(W2FzhDaIFw_y9VnyHp|` z1#9PG;06GD4VU@=r#Mp6Bs=>xs%;y__E^essBO6+A2Ls_AnBw{l}>fQDP!i4VBi2L zWGFjw?=13VQTo{j+dk=cjn9#Yt!!2&u`d}TFR%gJKSen&AQ+WEVW?w-goDub*9gl5 z^ObKX3a}y_$eB1Tq>-e0HBbViDU26=T>?|grV5m2Kq75@kT6MvVz5A90REwyH*Qp= z>EyE0^06A($;ZwhgVF`10)a-YhHA9Ev%b3y?p0G*yMKS8OY~hM zV-S*!Wxn2oi;@3G$;Y<Z48+DT_Am&2{JsKW&sVYg`5f^l=WZw$_@?(vT}nZ2mD@0r?OL7tNPxiDZ43^ zAOAo)2u|P*RU+7ykZaP~ihlUAn}9`ikl0t`6mUhT@W_cgFdv2?6)TXcu0B|I3JH}= ze|iByz9&J5{Z7Ih;%t%G4Hoa+63DpmcLP!lg5y6A3R`0=Z3;0R0zh~Lkzpo+ECI<~ zKwqd{_vnyHw6r*v$3%8ziWt}#D1V085yACP$tsy94X}ZBf&DFTC=#z*1H3}DZeK4V zB%?duF7~W4NEu`z+^dGI-_Z%S$N_-010VsPe+b-*6Uf;f=__`*9Niv*_BzI-&<@O3 zOdJ_P_TlJ7gM)+qQmDif6(cID|#L<8Xn)dU#v4$8d|B|*MZAlelu zT)93rF^!DqAIB0`kfpxq`94m*nX2gk<*|H2C}PkEtb`0g^`u;L$c>3z`f6^{nPK4X z=0fmt`2gBZ)tnZ4WCzeD+DIj22bYVbwDBHm;7@eN2p3Si`v zzMU?QeUk)6#|o*4kr|9f{@&z$206Ono$s!Mh0A$3?_xWB45%~~?U%1f33b1?wXXj^ z?Ol01)p^@K)zdU@GgDI(A`E4j7ITtBLenBmh&B{W=aeO)NR}bqr%xNl(r8*piqkZt zj6{p&G*28$6D_hOszWMUhmeWmz3$&Rj+y6u{(Ap?=lhw@j7;aZe3$#a?(4qp`ydID z)TP5>MgF!Kxd`b(ty#0?WlGfiNUC~{K_w_JnACh4gU=_3k&94wc!sLgUn=nZU59p~ z-r2}}ACXf;&DdHDy1%1xHCmMIf3358{elY_*tyXXolP(3Y&a-xg{Mr+X2}ud;YTOF} zr&Uv7n1~h~ol#aHT-4Hfi3G+`G%6^9XIC{Sc<(^)GoX{9jiFz&0=HCfU^2X!4Wcj9 z8vfX|2p^)z@4pmu)cQux}S1N|}PS<@fG!E6$oc6oe0-tycNwdrRzELwi@(bB}R$MOB!& zn?rq1Md%|FP65n-&jgm916_~+UxbjNQ-B4)3{fNY>xV5YW9GD3(x3|jP>f$C};0`uq%RxZ?M8c*$8P6gwGU*hZX-b`%$x73LS0dFyiG`O%~ zY*bGwgH&3GnfEgK`OVdt%w&IMbZwE|EPqIWpUd-EDH&vGDDA5 zqUOIA_PFXpD}YXU;15nYV7jPj%P!s*AUCOX(upPI0^oe1K+-0tR^9@<3jSGJKai=) zLgFNT#Qa5=JZr^_cnX-~>Zql;@ZaL;X#$KXl%@B&kXd zi&ua^L5#jRl;^;->>NV@^)cVfq57J_lN{qiyK8^lE-te>a7|bX+U4a9!O(8` zp7E4BpE#>~rwn3o8F!x2y|M2|DZ{LfEgE$w1HNKnbL$(&${tqHSniO5uS0K86vUp( zf)=O*l^codbJyGJ9bLc{Q?hjimv(7Bn)=CCfnPS_;4IZ=&tnB5K18N9o@0DV{Qj|B zNrI8rE?y46r*xNn9eQQUjTi&a0V*Pkk9Cy}?Xq3ETJB&Y%+@%w<{xHyWW0s=6h42}6A1+}9!ME7#)CtE z0#rc}R@I?HR_(C*2(uZZYCqeK?~mAHy<*u0ENg_B6ADHU`nmBYYnYoA`}hHysStTG zg9{YRqne)_*RSWy;lBF)3^QNg#<{3X$qFBqEdQepul*VnG1JJ5I{WE@^`nw~Li6rJ zxgHO-kXF^8^lr2`ZT%%@*_n^f+9;28nC%r=2g@^)szB0>pow{+43wL0<& zxEYuvSCEBz1_qTOF3cSfnj|zsbIXhf&JFZw+R&D>>&e$Krf+}Q;8opBfdm;;ZYb0k zCRerrsG&<+e@aSb1_wHtQex z?Shebd72wjX8nxxSX5X@B0Ad&yQiL)l1{Q0p~&QyjEuEeltsqS{6g+o{5;BjoSjyq zX1dSgt&zo5m~*PZXPbjn*VET83wZ|gT1*w}lyk4HtT@FV{~WtD2n5u6`T1GSq-&W= z>$#yBm2H9BSNUUt>aOi1E|4dVw>8z*4IuOAnCp#vJ+kc4NRTfjNp$juBHa}1ILh04 zz|MjY#IKid;LoyfZ>kKN>vDS`9K`g@{O&a%T2xKmERCm@eQa}z%aEvdcsp{E56aE5 z+6-(P9HimLO{7j@?<_yTvj_wgx&qL=ZKFT9#oj+|d554tRzY;j(V-E&o~V83F%vkC z$V8vp`d3kQMNh<`svIpX3Tdca=kPXfOc`~^DEa-2As5v}b)M$SupCI0+tKDFoRg@x>peLi9`^Z81y?j^{ z#VDNtDC(GTp6v{8C9Hk-;;!oZZr>H%WB0(`q=Ig9${awJ*NvA0XhBwMW?y$#2}O*A zIvi2=xT$jJCjZbIEWTqFXC?8;%y=`p^CuuoFIQFtD;t@#1M&4os&rEk-3t2XyP^o7 z<1BlB+3ZtA=a(Jyb1>HOyY^r(_Uo^|o+`qdRCI5Qr7KLUX?cfy;J-=G$G@XTQYjx5BF zC{SCxM-!hU#frzHSv}g4dUJp2htF@92T*a>a9m#8J)%25WYIrz3ZfTbX|cVarT~LX z_jPuj0V4IjazC^~%+QU)*F7Gl@Ul=Z@N=!Tk9WgOHXG^A{)`&$hbb!w zg>nZ`QG67cfs7iP^|9(p7YNNiJU>{QD82A>lJIoI(mcBE{cuu}@BP$hR|+L6>v0XXKq_0ZPK9sc;|KV5;gA@vdCVuNE|RpHpId9Ay~z`q;B zfY8!~S2EPa{@{S25+n64gp4;i-qr875ucAQ@EpO%4kxa&w%XfI!JF9NwMuL7{cF8% zrzz;#n(-SzWX&f@ft7mjj>NbnCLU<&l`vLZ7!)ydUxuVh27D`b$_&`(?3^G^ z>M-{xH5$DI(&B+rmDZrW#2Fx#^-mLbf$>euuAgbT@8}sr_f9H_n~(;wgob9#=$YDq zGo``>&3yE$<%jvTHl0;1&g1$kaP&lSojI4RYCu`@nX@)5LoLn zw0_6Lh}Gs?w3Rr?%r@!dNDj`Ze<5Nmp=m;UUoZ4nD5!Avp zx_&gjfg^7fuTwZqO?t1$L-Ms%oK-MnoN^Q2BE)1oK_j2B)y~m_@&PM`m3ADjM|$LACGy2q1k6K~Zjg?nN)@oz8C;_X?yxvh-Iw zvmoCHCPfOpUR)FFEJ|2)uo6>vhJH&axF_6z*va8v;^Z)Y2Fxx?`C?l&Wr z*>Q9iX(IRna5;tpf2r2ShXkT*iBQ#-Usd+P6QGv_ek5&RgcQKu-d8Mo?u?t<%s*A% zn9xA1sT?8Q9kC0R6F~&Vu^0I@mntqPE6|QLTW~wD>m0if0$|0wvKWF6xStX%x9#tV zVC-$*X5tXAUA>1tm)d_zE=ls3p;-c)I;E{9vr<`u?7=fW9ds2gC8z*TF4o#Gbbxxu z>kA&pt_i6Twl2xmdh1~VZFst2jnWHQ-sO&7lNy)+CaQ?0O`8Ve7sEGhQ8x?vby?wf ze5vq*^UJ7$ch)O!EKplO{Pc*A@82l6+}>9fVk3K~aQO^2*CNW9Dnh#6IxYTvRo|+5 zWcDsrS@$J{c9$I!19n?n?j<2Cq=n_mcFwsnq%=cEZiq~ffE=2~&A^!_5T=-CU1F`9 zqr$O!N%R&RX~I%(tCzN%G~YDVcJ|m3m7gp#eUu}>MC3-wY@N& z{7aZ4Qu*)XS%5pmtGeVAytsj1I$h}psx)CU%`pDsWnc_dxF~B_n-#xr_Pn3x0|WvP zByf!D)<1n36$>bzQBCPxVJ(r~cOu3(U6J{jX3~K%BSP)F5bbtS8xwDX#nbg1a}yZ% zvhNrP!eB+pDpptAYbNcj#o&v{Dx!}1oG2)0+^)Ei{sh7t6;UG^Br>CTG~A4txwi;O zcF5+nFWNrZh(kcSA7#6c?ATG}yV;&N-mGy#Q) z(m%5F+^9c8MbZ-8LX$;WDU<}kU#Fgh1Qs7cL%_R*9l}O_b#7on81{N}WMm|dWCu@f zYli7DwIb+I4e|uek`W#u6q!y!9RQckxJnm52ufap^pVU#m$}5#KTxL;^aNRdsnE+1 z87Bgr(OFckL3QwMBb#KMvV8ONpHprC!KYhCK6b7U7CU>t>wKiBceMAS@wO{96*=Of z4I`srt0-#$Y#e%r-wf$~zdH9Mgjf%J3zC}$IiEH7hy$6(}D-!9*q>Pw9 zJWwWGC;^T8iN=-X!9a7RufkypUmE_a8EDAPIKYj zN9X@}{`I&OU%otVZ=0~X{piBT1=bBmSNWzM^;lQc8SPN{{Eo?!5BnN)g zZR2Eq{9|nR^tj_lcoai6%t1|%e_>nK`?2p32ccuJfAs*o=Yj?|31rl|=gfkq5-jS^ zD-jAgK|wcPd6Pa5S()Hr9qDw$O&TN1ZCD;A^QNGn@DM$c4}JT>;Fam3*>!SY+llfe_A^ z6B2U!)v)uHE!@yhGtutWtB!M5rEN$zX=`hXLii9oP|?*S;O^P;O=pupBUZyA=8|3V zs*4V19w!ldcK68S60mn9*?;)p!8ZnZ)!h*F>M2eX<1NyikV?)E9aws=OUG=tfsa#uFKZOX63D|F@Cqy@R=Aui(<3`eTi$@r)@}aNGs~^ zYT_10PDA01;{E&g2}@D9@BK8lqe*~15##H+1igKILS$LJDq_@^&KMdRI@2zTm71+a zs1Hjw%JOP!Ya6+zrlwNYAD;1=N`OCR39+#5)R>ZoFQsF~wN0n`Wk0g!sv~ec8?YY% zP#vQ*L1`pZD6K-Ce%CoW8=K;v=4@Wjs56ruScDF9XfY!;kpBI- zTCVcx^hXyy_BY?G3n+wWAn0S?Zj^8}|GKddB*k>B^i|VsApF+a+6r-o{p2@1IC{ed zRAi@IxNza^Aadb*0h`qpmDj+4qzVLrR~dPETLxwRC5kutp<+PImpB_6TfaLw_n25L zuD!XJJ84Txs&pfnZp+)h8#i5rtv6|lY$bxlBM^vnYjL3pPE`Fv>G$UP-`a2(SJ| z28=!o=g#Vqu~RI^eA6XML~w9o;DhwKBa=1!YW222QxVnI*XQBuo0*Wbc(2xxXzA=m zD9RU8`U@6os>A4Bkp1pX_@^UlCi@L~hkQTs0qK9y?Lqc9Bfm#q5E;Ue{RVZse_uvA v7k|&q$S(PN-;B(}-)CxMCjO6xqTBAu+Us=%hiqf%Le?v7S6uz}`+xoqv?3FrGfU$5slp2u;#&Zn1^&+njOrXrC@J1$<3y+R_<;yBmPIm5P0?s{!zqEPSftHrKz36 zH5(I>`87MMJC=5LZW$f8Yhq)2%hKW`4?m9p*MXaMc2;7%y#L?#c`R*i@E-AbBTph7 zAYGI_qv{wj-sy5jeSWQAhL&c_V4Bh!rs`7r50`g7=AwRh?eR6vhP`y5wmJ(G%E$Q9 zo>CvEt%x~TyKUuRp$t<b{#?9OH5aic$~}rdoA40->(7PnCR)T&{O>=jY-D`@`)d;EuqK7&Swwzs9T3^ourmOCF7%?KYz}xyNorx*Jw80#8@z;cBSc)aoL=^C99OH z$QXatmJizLNnKM#iC5p5O0ttqZ)cTQ%JGm+G02x1<0r#?-ZU-s+wW4l_)7choxQJ4 znO8c?l5U>THkJI(GZd7>Bqebkz4Y3(c0xnXUQIDdO7aOkS%~+yZ{J!oEDgq6KOMR| z-b%N!FyT{KS(%WK;Dx`IijPUrng9Cg`_=r{IeaVjc1v=7?0Ns+ZJ%$r{%we=b#}$& z4_w>5d-o^%vF6tF+ZyBD`O*th-E2WYLDsVa6$#17ekYPM`>I!Hi0j;)XfH``(cjmZ z?ci_G`AzQESM$&7yGY@2FOOX+U6}Y~ToufX=k^o1JFXcR5^~<&-u}z&7M}JDOExDb zr}}r7qJB5LyJR==^T=4hA$FtY4_Y&2((C-nkz(`Gzs$_cjDEhosG_SIQFxv7V|Cj- zVqr)m=86wmpN)oVBZoWIr;BLI-bu|TvM6uS{eWNSv-DWeVPIrDucD%|x;EwEKRY{1 zzW=>K2+vGVitCZbv}~*fYoi*mm!hP6CAdkXA54BMqPvb9IWkk{v3?TEa(Adtnu3Of zSS=CjKG`pK+63Ca+@jaecQUb?>=6BCH?m98`H$CFayAb+4GYsl@*Up6+>v5bjh0hg zxihm>yk)mja`&X}Ho z%ska24e$Cp9lCuHG_AQV4&z<9;tS(#^ezkIPqB7#CMJVn=arO{zF2gM{c|taZ(Z9O zq53$5kn*}Ze<`=W#UXir;(mAKx-=VH`FurPeUDCth2&hj$C8Na()5PQ#QUVAKHQss z^GBWY#J<}O*Vbp*4*y1c{+akCOun6IXN!S{+ZVGY&N1G^LOi_D^6cPDpAT=T!N%Vf z5vSRK^X?Wc$$G|(2`bjV%ri=qggY5R^zLfWD?3}{I?sE%Oyvr@&%ZZ_v|qtv8MURE z%ydq<3zxklJ3ZGBGbyt!Oip_KiIV6`D+?t-8v1R;SIIcEGp(+< zZme{tI7H3#mz8~gL~Scbr<)_MpwMp{wW6E5@@Ks5B)+m0RB7Pkf7ZT=H$O+ESts30t>f-5^BvBU4taBtnqTi|#a7pA4poQI(@IRA ze)xK2;N_*#hqO|y<@9I5yIkjLmhhB}b&`v^EE0~X7n^^#q!_ra{Ob10p2`!KT4}30 zRl$6Eft;3=W#6eg2@X*i-R|P}DkAnNDf}IgtDlU|e?ZbVrx>u|C%j&~c!6ALb&3+V z?kf%zcd(#|SJaS`llx-Xjl#hE79n)Xva93m?VOGEl~1NM;hNcZ%@OZqe*49FmO>|f zW%&0NJt_NLA8U*fP_rE4h!=g-<1Jv{VxQC3Y&O=9g&!>2oK zX~%hZ@}hedV{bMksr?yi;eEV)?=Im^yQ|Nb_}SajZ?_!2tyk`ns8v}q6|T@!@$y*z z$BZuT9s5od$1A-u!i{_~sS5Vrt^K-=C?SW=`#nRcC@l{-^veEud+S%rZdS{jnbNQp zcl@aJ(sb`R@%7yrx^xEXvmwTRe%D(MM>?E(WqX2Hy3aT2{06H+qULL}*fg-E#;6VvWVFocU~BGs-@P@N7{Ts;X*i^^*grt-cX522kD+E(u4E0+d`Xv&IWEF zCN-5WZ!vdDs8^L#5NC>f`Gg9k*o^q^40|a!J2yvUFF)cf^Y7^UlVKDj9(&X~sT-^N z=w_Ds{e`txUEb(B_C5*~w$#6JY}s^Pc())0O5Z1&!Ai&RPi1`*8Qm7M^VmohR6qZ{ zCryim^OtKv`HjypFfa%%ex%QnT2lOpm~j4cv)R}>AmROcAK`A-lk3w@ zq>Fuc^O&Y`=9FVoRP^;(-)p4!A)U+KUVPa%nLXu)&hmP(FIiB!si{dtPjCO=;Gi`g zyA|2FG5#_ngi*M|>g+RCNimDu`DVqw=u(uIZ^ya0ef4vlO(ZM#Dg<*?ID5_|B_(+i zE6#tTHsWY@YinDCm_6qyiw>rJ!WPdEDsu1DKN{h>)^jz&Wi9#Z^F#*Jn)dc-;GT#w z_&>!sXTDj-mwDy2l9rYhmsZ;0U@om)XaO@1*;Wr6RSf-c$EdONijK}c;(-`;@0LUT zCc^suW{PmT8v0|(#qU${m{aopnkl}P5S`5I_gkv>cV{^JgvR`*{l3xZ-Xebc(MHW2 zN9$O9*K6nv{3exwp(k%BSBITER{Csj!_Bhw<6`!s4ARRLm-+(Evx<%_tgS4T)wwTx zCVotLc+LX6n(3ceovXVcS-O{4 zHl3KT( zYnk`%6Mb)e5`)M#MbRympq2$)AyiWAT@wUNpO4 zNvRh+J)y|NUKwXxs7GAuhBy4{GJ{&3#xdH4E4hSHwPZn~GG*X)QK z9pkS>?s6Vgj$rCuDitUSMYeAgGOWAT($YU#kSv5%Uc*og{{vZ}A#?BjJ4U~hG)Oj>Gq0adIF z;bD7%8O*Jt zKDE1lZf>sMPkgexSC*{?W$H!d<#yy*U)YV;70%l)RN|iip`y<)p1C8BYBp2Ew$5jP z4q@uTEKnC)7pr=SSQ2A#>N4=&YD-kWvEHUC`6(%GhE|p6N%t67M63?D1BsX3keUk% z6)=%!5x>hd7C?$_dyh{HJ9(oyyY9=ah8Ni@Q%{0<^up)2p{d9pYcBE#mG*Ea8ZW?l z)co<`FM#Gu5{_1PIx_jkQ~>HvV)^TwJ&&HW?8?cUs}=7bsCcR6FY}m&O^PM zC|7|o6{)Wb-+!UuU|-h*=9xD7fh4Spb_f?^@zYqh@;C_z3GrY1?&-MH`{Xn0;EO*5 z;>EfMWZnCF^^)Xnf2qGWYg^VXqsn(U_WP=+s|UZF7qk1l6D9nEL(~&i=i|pdlTO>ncY4ugExc__pjg7Jm zk*0e63y;zs?Ml0T@vBPP+42jaH2 zWx0D)`=`t_XX)R_O1ABD%I~a|jvRK9jB2r09@ee8eb94fK}!oGB_*Yal)-0HC5&R4 zIS&RHcJ7Q`FeX#_{rsX=e5jP07&6H#CWifyzCntj}5qnpT)5GuI zWd;TZ4{~$wxb#}05D$@hcS3tRv*5O&p&_b4=k--lOg;Wr-zjtaahBPJ50$C>j4UZ? zYEtVo*)|H;GyUh!Tgv8qYnHNWcz$5dux|q}Tq?%bYz+$HwN5En?WS zhaFERY|&9*;IZ}yzjjtf=T%nC(vqX=#@ZslV6X!{gMfLv;P0`qkY&L9VLDb;9(is& z>IJ9R*vU=*JoUhCR#v~_V%fNMU|$O7Kfm9^c>iZP-ZeI=Zbvj`-<|l5tEQ&%n%JhMwvJHx_PVE?L z{`hjm9)vQhCLwRNXGs9WGwsl*Qc2%2%5Ju z0C}AGsGV+TW=3`B&>^(He&oO7+|Z8KQf}VVj66M7iQgS(LId@iA8VmbJtE7B zvFSlr*j`(SgZ7Ks|9Sz+tjjAaWzL-=7dUxx=FiC0IC5cJjP~x`y8z|+-_5-^goPP# zqh>mZ*{P{JktFI07Ft8Kkv?8t+p_cs|T3RZos-i}T4c`0y+FDRtJkXyfEFd7GtXx~Rwt=eWzp{@1cbw^a)Zt{=k$E5a!hYbu>3bjlrVI>R z-@acg(8);s#EBEDsGZX@Gxvj=H z0W|vJwm8Ez3kyG$*mKwVOMOjBt6vFEy;^5GK%|_^=6jULy(^P%+)f3e;N3QfJKqpbxy{|KP!<>!zmcM~-ae;NWmvo;|`U;dqb8IILrN zMTJVz*ONDD3+n6XRu-q8ynOlcig|!#5i*J&nB6|)%(jDO8Mhja<~YwMRS%y~|KNon z^41J6T3uajJVg>Ye*D6hwn57J>$pgu%d}+>ry8Hfx~pO+-a&F;d;Yv}iTCc- ze2;wH;XVwcr@>qFOim{Mxx2H3TQije;H0`V55B~4x`!-TFZ(eDQr&NM7n56TS)O1) zVnG|Fe*LPRNyERqyqsuGng+i#GgPxLeSoJ5&oDh4-3>1#$Ze*HV?=l|qoR_DlMf30m7?~3&w~dKdPYW`;^7aSIN`G>ghA|Fcb;2)o}0^%gm*YP z$0_r6)uEXUu-_OZu2d$!%v)AM+z^0jLRaY5C~bVP^n z;zI!ZnV(llymCbKqxNp13N$9t=j7(jG+dG<#+*#|H8JF*H7XdUsx94ai;>??&>TK; z>FnEW~)zxJAm}WoK=FOV}I5~B|DPEWI0B3Uj#tk3U8jt0bl`7Y+ zwl=M|^4nCRP%e$Is5ZH#<{MpKI#cAN~le9U9W%uqrp+#@EN{^ZTSZUYMon$(J-@I}ip&{gUR_CaU;EoT-u9V| zLVhkxz=TR(UY?=y2<^Uo`?_|!muUKiVuLv>Z<6?kh^Y)hZp`RkuWxFS3*pgo{AHBu zbe;&Yn2Imy>AeF3o|seE+1WP%?of3f;N{{f#uN}{DMp9Q>rTUR_LlfC3K(OFPh1g7 z+p%9v)wC?EqeFKK1%;1heZECk&Qow^70>8gg_Tt-8AUD9_7sj$_9tK)x7z?{=1}FZJD51eC^WkXMXr_Y4fY{kgDD$jlQ2 ziSa;rKy}JRW#v+UR8?&Xl@#zxeW-gVmO-~SW#dEoqCD2=QU&hjx-70|{x#KFBJZO* zC?pi*z`pHMic_SB^(KsLil0CylmKsqQuro5h>JTybQho-%*mGryInj<8#Dafvl5@qRG)^1@*zu=$P72|(u zMh2tc4Pb4e%mB#n=N~i;d1w`lK(9k5GSQu$|GGbJL)Ulo$Qc??) z`)A+z&6+}#HVBPeQIiIB4K8Q1BSpSpJR)lyJOTPV>`k7G>`@#)L ze=rQ7d0c55ZY(L;IyYQ*!&@)UHLJRtS8Zl``d(aITy-e=+BSU(tk{*;KS+i|O%2?K zI-&U4>+jN1Gzx1DBPB_DE0OjG4R{k(z0sL^Q7cekl5~YfiOrpu@D1TLpwc8Z_lkR@ zw8v|Q1#2a(wZ+YOYI4|t;>KlJHB1vk7>Ds2?XWp4t4APHjTC+UlF_lT{>H?sR`&M0 zGm|!i07kgo0Cj6cNS0Meg`3lzU5JyyDM z;Eb?7_oZG6)r8Au;SXP`yfLHnWq5FKtDBo!KoS}8(HJeKOHo3u zfsg=FWmhdp!7hyQ+}|0*fAZwn)2B&u(aL{w)jp!KolN0EIki80?AUuj=`!o;mp8Z! z@>nn^T)nl9%J{vxIartn6$v#??bal3fP5SizmaEkXityfXbSP*t`Epb^!Sgr9fn!G zrq{0BC+48@=P6KRhJ3p}-=M9ztbiYTo)Qia+?=fEgFCMhinVZd7DL;X3+oN~r(7?Y zvI+|cm7w;@B|TOG^?uFN^ytZR)oS<7o;^E*l@o|+`T6sKzrX*@`JL=vvATy29Jt4! zj^2VAYjyYTp3J1QH4NXtP=dCrV59;fBe@Obh+=T?``%M`nDRE(U9gSkJL7f+6c-mC z5D<95aTk@6vt|t#jOd+{lark0Awj{xd%(5RpcBR~q5f0q(y4?%r{SaZtE{UlLpp3p z_ELhn+0)Z=;AClC-K7X45-6O_fN3Fni-d1#HPuE*`xE#g69Ux9l*{tl0t`UegMnp; zZ$(!HpMJT=J8!?Xwl)D@Utd2WA)y<$d?`}w5n%LmsSx1N^X_els+AHXC%`k#x{V{o zrOyJET~$;9bYH&wC(y;2Ns7d}+PsO5CIK1_`Rgp0O-n3~`fpx_3 z`DyzcJ6qd_Al{CrW7+%qj1o%1g%}pMW5fMK!t&M|*?pj;l4-R(Dwr);PdFXWdimdDw;DW8mUI|s;9Yc*v^wl)> z5u8|QLf^w>A)+wL%X{BbBk;kXf}!C7 z%kwQ{o5|55T$fD!E-5N9#LW!>@>-2Ha-fu?c*=N%VzimY=o;Uu{!zOZiWhw*`zbLo zv2EM8Uw_?Wh|sv8q_jJe*bsbV;8k7SX8_&ttr!6)b$$P0^tpdaEeG5;F{!evq9TCm zPSDFfb#)wI(Ubce4f^z2re;CNz|fEp+Qx$xmCKj!p|@8)yQWorx=B+#a?3qX)Ra2g z4sL(hcR8<^C-bNhf;5dV-YGhPmu=l}w} zptO{nhKA+`NHd2vPgmO|v8}+tgpGk+?NAhyf`Y4qNW6%;aWo#aXn3>pB&q;*@1l$h| zWhyQ!J9O|M8HQ5uN^%gyfRC;j8r}mycmsZxSi5k+Tboew?L*d@dPHb0UcBhIy2MX} zOmOgHFcSwb>2KY-^+$dEvZL}1LqigNR#QvMO(NrSYHIXY67wYT-*I+;5^&~uM8v9e z%aQFncBp{J2k#P%R+pfYksN+Pz3WMx9b!s9$8pB`m4dvyl*MOYm^*jwTn3rh+TQ+C zh)U){7W#9kptUbL7x@n6!!mNCNXZ>A1yDiL8}`K?wPpEoS=-FaOukNf=cVa`sA)od zi(Nl|?!r2r*VNPu<9By=XA-q}8*Pu|k{#+JC#wF;4BeNO|I6v;4etQvT3dU|?i4grN_8*bHh8WGv~Tma)QF)-y=8-yRRo$e_Nm2^1;UbM<} zf0=b_mhG`UJh};rVKIFoGXU3 zAG5XX;{?Vs>r96!R-isBzP{<}Cu>)_zv%Y5f$csQYb^#D?MJ$t5VR)S}tLheB|X0ENR zz1a}IgN21f(CmlTQ7?c0GDPJJY%czhA=2A_R#sK5)D<7aHK*t1&Vo2m)jzMSOhXWm zz-~R2K_?U=t)$|h%b{Vs0m7Z0oxL))as0if=N4i*KpqqqJ)zw=`9lk!|LD=9Y{$6G zT2l{dXIS{6Qr&Lc;9CBwm+u~#VXTY-Bh^g&PSI*w2PoL&|()oI)5Y(YJ9>?c$TgFGQv+tB6Wgrjo800-e z3%lPhGSo8m`*$>Ezuz5MCv$Rg)^DWM%>Krhf!ip65er0Bzkk{5sqXv@kqW=WM2-(1 zJ`foiry=|ltBQVTy)dq&o9n!L@7}#s8F46B;^N{WqM~o0DFYQgj*N^frKM87c(D*= zeZy9AqDb~3Tk<=%(8luG+R6TTL2#<}A+=)|;V^;~l+9)Q`D2%*ZwVlag7gLz5eS}P zfaPiv^Z@@KKQ4Pdder+fP651UoNh`AB*6Bs<~|_)jCu<0C#Zi6KOMA7#>+O3mPiW}*mm0m5tzznaV&w zVBp)daKOXeZm$?@hN|~=g?DsxY^jQR{knGf?_V2O3WlqztGBrLBN;MrIa??f56l&` z;4CZE>4sV;o1(yl+wK4%Q87Q>_VVPZQ+viGEq;CFW@KV2hp_!L&zInCKTcuQ1%4gp z;u-*)%Ea&6ppx2H=F778VhgIwyYnJXaB(r*s%ndS`_>Bh{K}HUTQrsqP|sO_mF3lQ z0~PdLUq_oip7^Ow?LWA(m6YK)V`LxlR~l?gX!i!2$EwPozi-VEM@60g9B;^jU1_7N~54%1;j&gG<&%_9t4B-1c$J z1vzD78A1e2hGiW%-uHvy>`@5`$CC~6-6K>v)!JON-pFjNZD@Fz?KBtvO?b)&4%PDI zrKN;F5o!twK4W0&98h!4m@S|%ta>~jJUGD5!Qr7lC85$qA6WAXf(t@RUkT}n;( z^}d?agAbpa%HL2Q*+LDbX8?Woz^K%51!!x+H)>gw!7v^9bu{2YCZq=|YinzR>hqiL z<*)uICM!TLnyl~O9`}|oh@jX1fI=Rk5H^9UFb_i1C9E8kUlIyXdA2{*12cvj| zkB?76cNH6Je0;p_&6^27e_eh}PC9nvh&5(j`TbJ~W+VU?!IqCY!iC+#_+`rG8F|){ zl9CSiF+_l9gUnxHpscP9HW(ur`t@gmFci4NlBqN#fe~En!(ms}1^;WU>N?NFC6Kv%oM= ziK(b-Ma2T?S-}CVK61*<0!|>sc_3X%{VIxC*A`&lr&nHbO1dsRU$*7Lh3rF4T*ZUW zk*W}ea-Sh^)6`|ftLwN?08P3_jZz$!z4=!SUnYwLsAk%4U#*5{>0}hQNODeB&%DuI2IAy z)&yJBcDD)K%8}s@NrbkfQrq3p*_j1ImgHh9>bJ6}ADEGm(bIhblre&Y*M^MLbz{yhZM@z!)_w#QGYonMtPEM>K zei9CM10aUZI=Q&KKg{L>jV3-Ez4M^FB%sdV#}bG=f!f3nt`xuZKXdI}4F34_xl+uu zAF7A{{uy})o51W>f)vd%qdyB^3o9uZWL-kNz`PkV==bz#A(YpE;NYX$%IvS9-l8}e z!mdd$`iKd+nvK~(g=fq{R8S`5z$GMPI4rD4MsSE;lkYVChcw%B!6%ZhCiauV4hOb%AWNGdc$y^>bh(L=VZcLC5ZV0 z<#Zsi4I%w<-g=pE9#xs&b;&Be6&HoGTBr2^iNH_5^)W0@;5593f#fE@B-#V}&19l> zJVf~S!M+ePu%ZiA4n~9I;Eqwk&e8homvP-|$r!dNS5AzlkZff^)LVo4D4av2#A3S% zod}AE-;BN5V=uhAO}=)4Xy0K`|sbMfXGnx52l2)pxEQR zi=ueaFadFpx{UMhP`tIj9+Jd&vep6D$Fn9fUzy$*F-hZ#+r^;DU{FFY-2+XAquFjt! zdA)q+g}5tW{HPybxQ#5X9>;i=!w*K$IT!NNex<96>FYRVzG=|;X%GS0BWm>LcIScf3;vW$m{ZF4h!OVRK zw$bRHW7#t^pw6f7fhukHTU1a`fHPSDt_;<{xeV}tklx5nXe2YNF;Bh&&AC3as`Yy+ zsJ#3FG1h)It=To7#|T!p0&_%I-#K6ABUVSk&zwJhKF<2BD}+^JKeb`WAH2QU$$_Dv z$6MF-!jKqN=i=ma1~k(1joig`4>PEB>{o8aaGR}{?)wNT+0siHz zD2qY20rn%e?0`d8E`j_eOj#H+O-dmlCeDj7Aq8V7|3|?SWL9`5LQhZc=;#=@oCCfG zV}j!^QP(AKMgjv#moA{)5^GW?y+J7D@3UEEgE+XjRNGFUHt~G&Bo>VqC|KQr!ypo} z9Sorf+1oJ;Q=o^+7#YQUQ&^6{TuMAWrk@9cI4r^jf7XG&(PSjeJXcY`SwMBJ3oD>{ z;6I}R1dFAM5{?NKwH@N4EvMSCWA~R}gd^xl8Vtm*qn)G{SC@$6pI_H!^)RJy+I7g+-Kk+8gQ!K?ZgB?b`>rLV9EM>T|Js9@4hbtJ9ks4hSGyAb_7q)%GlQmgr2@ z69;<-+H&^XGp2*(S)N&0qG$z9{hmv&Uz8Ds2Lgm=(j7XNz;(mSj1$Ythrt_8vBVF0 zd!TMUeEE_dbgf*?2?a<5_;xC!ta`t6TN|4npKo0Hpp&8e@u5)D2ukeD&Tm2(CAl>H zK$qH$Hc}$_=();5uA7(;iVAqU-S#9KuuP_PuXi9k>+7yT4B|JfW`fOIyOE3y9al5m zY`3nS-Ys@*68sUKz=dvt79EKkeOjdb&=x7tb}AcA^p|ab#Me+ za6DFoF7WheuP?L|Y;M-JCRZKJ1nTZAD+}iFnHbFy4zs;S)txQPaap86-F(o( zj$fT}!;X3jT--qc4i-#xD+O^)nj8V#Oa3 zw$OFZ|Duj>9wz80NI)J}BQHa=|AYfmVVi}eGwsLrU}w26>?aI{=qh1G9?OG_aBgco z7b`9mAhnj1$a%^K9t)C(0LXpvDEw4|n_n%7X`-v|g{IC~qt#{2@+8XrFC~~BhPQ4M z6ciuyvV%G9LXdr+G)Z*P2r0L4VdYDgXc3wx7*CjcfB^BkWkohUHD5a$4W^u!?yruc zF%6o%iZlL$3=0*nr@SB6kcp|d(w$MMJ02wOHr$$SEDRB1a!r(77d=A2iPp^u& zHfB88gx|k#rSA-70(*I>gKvjiNn{{~<%%+I`+^zNheK9JHjJ_|?yfFb({U1#h9Kh( z(oy{FRoYIdzMSM-pC`n`#bZIo=2(9aUiP$u!jqYm1wWA<{6>S{%ld&0sw%JXR3 z08X;tWLC)U_jdyavCpvDvLVzCYu6&U4I#b741jG9j(%_Jb`j(y%nnD*lw-sQFS&OW zfQ8ffVVF^|xC9VTyOr%7F6|+;zSK_}^mSxviud>E_kj%#9-dOfwm%vnViJy+7(l|9 zciT$UdMA+(AS07+p2t#C{;tZEJt$SK`&1zow-*krla1b#orA-ZM~}8zM(jKx{0Y?YSt~0(%Lv@Iyn69Bx0O>Uc5<&8<$|F`5VSSz zO-31DIsye(avqNQi<3A5tkvs6M1Li^|LBbS_3MY@6~ovaUxP*<&PbU>=8Qaq2Ln2_ z-1JxiNLIj&0_@e+nxa1Z1))4{WwYl_6%!MaUI@C1p8#@pWirk(4_YKE zK)Zb8=cgQ2H#{(qU>AMc-Cb%*k|$V>+OzntbT&#uN4CSI9UeOxvfK3{+yuoAzARJ@lC;{nR z8!Dx$ju8Bp%E{ou%u}aM-R#bjyy_w)B?Y5+UUeu+UOzAoq5oZdm2|hibO-#z4{!C% z4MP;@86EWo;}k>a2hiOVm6Qn80%|DXaE8AJ5XAA%Z#tmMCkP;L)&_x12QMzeq9#Oe zkwBO5x|~OoSHXF@(6BIoC0cmBf%8fs-A+$-iXT3FxCdMXVP9iEbZAifhyX6TnS6Tz z0MZ*+P4H8m<37J7uK z@bTlv@NS=jR!CT?k^Wik{ZfpuC;J};PI+oYDu{LWx!6Jc67|FuD#^#jZDS?0S0aE#vea+f=s!Wo-PEV>Saw$ z2npMWcoq{N&FmGKCpUH-cy%ki1 zhV31K74E8w0fYiSD3^4>3D|`&2*Qe`WBLr{ze;r>nr+*jw}}?PZHTnFdXeW7AwHr= z5kQk5`v1<46+yoO(!e6#%gd9ZqN0*|eF;{aUK}gUwC*P-+A+lbtXbdv;=n3jP6L*z z<#7{36&T(boJ$R}#t_1E(sX-6!FgEX_D(M>n2Jdge8bI`oRs(N?*(BilQdFztb~&K zM@K6e%B)#W+8G|Jb;0V3F!f`b_$!2N#8gSiAX=2RFMPQSjp`oLT zhNr>a+f8-thdc8eZh}zf2xm7rIXQUZRY&eApav087;t3Oy6TBZO74eCm~cWULZ@%z ziX)CT3{ADXBUA-q_Y<#dC4Tq#@zcm9D2Uk0vJUHMa4E#;fPth2teS;|1*X_@FslYIX z#wj2xbk{6(0mS4f2}w!ozkhBO`n>~Y<6b;$iH5BA&F&0PK|PUO?=@(N2(7O_gP7h$ zPj9`k?goQ8Ii`#9@^V89aY(WVFJ2z>&Q34f{OWXc-Rm zhZjBp zX6DL$8rs_42hTq40T;zAn)&Ma>?8t4Gu4pH63jRm;jxsF>kbAWdpgqIf&)})FL;p) zBks0XZPgc-SU+rzh>~*S1inbi$an(57IRY7GpCgWZs6G;5bagW*a^Hr^BM1Xgwa4KQq=Zw#!*P4L4!X2{u@R#dU|@v z7|T0QE3+`r$Jty5Hwvm@2$hkuW!M>Ja?bY3jh~Hmv6n$sZw)*EP`i9c|gf?>@`uLR8xl*TiuO&Xe6J6j?|B8}s%r z0k>B^e*BmPFn(s?jH)WbyV%%68j>KE`f$ATdnfvm=`S>c4g|B~Vic^3h&Iu#9DLC3 z>ud>|s}`wA7Vx2u@~9mJW{sZ!?eVbEW*xRF8#jFrm05&>gJIKVn2MHm7-MolL{)2R zC>~wIc^}xm+KA6^n(4w}22JsuYAsmpN%#>vK#gPpqOD(g4YK8UuHL^|2{jc}pJdkt z9KV@(f?3vKhCO?1Ac75o$|%?i<-lH%1t|!>0Du0}mBhe(puQY1BV{crV3B}IC2D{C zcrMxvv+zJ|(J-KaE*^H^uLnU760!}u~1~Y(Y=;TY%idy8Iz%dCbg1t_fHc zL(Ak57uPwGe(L6r)27Mj@@_NsNIK*8QVhCDZ)<5IA|moa-(mdf0DYDPR}kmChnlu_ zWhADGxj%mb$C&a!9SGzL2N4d{WSK`)iuSAXEe4zwBfY(afpw*&j{#XD-AH#PY4H*A|YUdUvbWnJltGnrT zJ@rKKJ>W3YCzoXlSZ0lL7thBu7hvzk#z_N*4AtDYd9xgnUF9>Nr(UqsHR%4Y6fRy2 zz=7doPpBy=d*Rm;#lfPmPbdn8UA&M?fvdjR`3aceGd@i3R-=k&?nYm8E{=%B~EPsy)d#@?O0{Pttg&yq`x}+F)d2?FG(% zm#bk!rpy3yHHnX@76s!`#jTa*c@nO@6D^>6xXMp~8P`u1gM%as;(C?6q$qCl7hX+) zQ!zXm$p9LOb~;-5I*sO#`4v~*p*f851eM>P*EL039p#yS)kxUZ7ICYh2zWtMEX9?# z2w!~begDWv#g{1@!~r*a_VM;>NoAFl@~O;$xva$w`>(PGSfM#xz4#Ga>dUbAXnY2) z`>U+IliZJC!8u#_wJ_8<*1fAd)Or(8wmQ9L51XU0ugtf+tV*qgQWfPvbqo$!U~VvD91tUV}GiyZo{$vL(Z)gsQf^ z{jV`AGl`4Fo|a@$AG0+BUR<6-ht8UaN~L2rYLUz%pUp8umHTc{T9cp}oFgkh`gDL+ z+OpSC8-&une?(QhKaSYdK404^* zD>F8bG&c5B$xx~@t`(7IiN^*923jFTSB%OUX#Fu}%nZFFD+s>c52?;N9 z3Z8}PC=D1DEWo63?j7$N9xjv6Ov4BwKL`$C5HQ?n4z>_Hh@9@NTZun^Egk`H)khTb zkc}L((?i!;zyrk-e?&{INvG^=@F8vh+oRSnInjbd8h>c5D%E z+OUGcsd~$g7Sc$K(5;`I%h{^Cr!H#2E?cGg@bzm}hvC}&DmEA6t~{!361<4x19L0; zn3xhKZ3c%XCu_f$BO#w>PoU?_ef@>TMfNr64m9-$c+4#Iu+CS-LL?q4!;6`Tu`SLv z&wVX?Zg$qF)}^O_EY8-3MQ7Ln5|u3}E+a#D%G1K+;)M&x=dw_T`R%20?p^7=Kd6LH4_l}JFld5Abp9ndDI_>pK+m7TQeXZgvpFej|F{@1XKj7ub$&kx<{c#U5D+gGFmEWXUAhW)jF35v;6xf$jf>` zZQ?-Pwt7COKp_14d~ajG#Oyd=_N%Pyi7+-t80U|I-s_og>wROusZm4kkC0R`Rz3!v zje*;Q^J7s*2MaiOxT9FW&HKR_mH5Ri#t8(fHC_qSk>f-UAMhDqh^-YTEjmOnBGcls z!@e~Y6@`$JwaErVv%Hd%M7w%D53S057-BGdAhh9A814 zX1Xl$pw%B(9G+LeaRR~%&%c)c8rYOzYD8La3i5eaSjE2Ku`wTP>JFIXdv()9aM%~) zo+FMBL+B$xm_0L_pmXkADV_u41BS0+bOhos>ZA7b)YN-OpsVA6oYu&qE|LBF_u~aK zthm5g^i+nVv8#}si_xKQjC)I0>x&n=p6wH+VJYK?WF+B@4PH2C5w8i}I6~584{$7O zs!uzzz)M?!?-8gQBW6T6XS05B*AdoDWI106NNEt<=gpy2fIupl{%b(56&0Q6vHQ0x9Z6>TbNmtQdX244IgH<79 zQdFR=6%By&L?l2_H}*C_Td1r%CPk=hNK40l;`rI%;3FWwN3$JyZu`(uO#eAjAv0_i zei(D3XmerVnF4vwdf2k#GdbWChjL+p$w6FODdL_PtXKdjN$cZZ7ROC+Bxql{SW_ zFts4)OF)be)AghFV0&&?u+=$bbs%tv1bc_Q zpc?+5pDXsgsEFUJ@p!zWUq2t-w*i5ZBVx`LUXjyh&X8TbgQ%p#nJo;xCnD-F-9aAH z%(OZ!-Zk*z-We|tHcmMstQQ|F2IMVil<0}{~ zkgPaU?OphgqUsstwr!XHE(w5i9$LPJl&!~G$l`1g9^e5mFAX{)aV`0rX0H?E2Yer8 zn5niV`8`khg>TdYkK%yYTq%T{!tQQ1jBo6!3-eXg)y2@qdjHPIHfil>__)!ABU5G8DDn z*WOJy{klCiA~~8tM*zbIuYAwR!O(rqkL4-I514L439dyb0C&F4*R+g_*0zS1j-#6bu9W2||kniDv*FK$l zvoL4^XCEe6(5ni8uA}krSV9yf98@s_*&Z8G4bkT@*W%WVp-OYsqq99e z=9_(ElauReuEU>|qtP9h`Ns_vh4 zdvsJ{`2fgBf^71JWq}*IRQwCdmr_E|?fyB~W~qzAo_KlFho2p@FxwI;-w&XWLYvfx zUu!t$hs>t?@c2^GM;%5&-h{XO__EXuSoR_P;0-qFBVU9+<(d{I|#rUrmpyV80js$FD9G<#|1dEne{`y~qk(`43&CZ%B z7Z)Zw_Yq=N=eyf~+g47=g2q@YlQKA`p@WT%W&nHa>8A6w!r+J(=u-(|VTj7cQKZmG!(Lx>QS>o0B7(m0WDpSNv3Q@so7Oix&@& zJ^R7q5i}T~*GC{YU%h(va;H;ZaByEomMw8!ACw&MaqS8-qHDY(iyp0KS6)GiuB)pA zj>%GCPoQl2jp*lRXJ=Q|=1Lnzre1zYLE2n^6@%r|fXnR{JRkRg9G_m^LCAkj|H|Vu zRXsX5%|N_z!Y0G~`gKpZXXi>WVKVdT=RD7Llf!X;|69SLs7t^ZoSoP7S$A`)-c#k= z&CN!4i6~6p>~Gi4;UzzPD6Bcc!32j4?Ziv9sU;DJ=)p(jBR-%g(F@CejR+n+`gr8% zljnAJc3^ape%6K|i#5O8q`Nwf&s7Uv#PJs6Q3(T7d%USdF;TfZN`Q~=Gz$Bi*(KS} zI3vJM+Y0yI6_GlkQ0&}Uu#Xu1SR|bpU`?bNeo=xGXSd>>;AGt#jW#EB71a%cqI-Lk z4hLLF#o;_S(AB;~AXH4mk_`}xsN2Uh_hZ^J`gW#LAoO7!D9SMMt;|eJJvcecx&Ox( z(;8;HbmW4`M3BS(q3OEgv2NSGh6XKVhGdUqZ=%S|9u=kJGBQe(q=*!S%O2UXi4;*t zq;iQwcF8D|P$^VG^?uKu`+fg-KlkUkyLI_p=kGX=FMnaDkJivFEk@;NXavFpd;;-W0~8-G{ORK$zok(Q9a z0<}5Z6=SYPx0G$ufaG=`MP=3V989dOWhFcG{q3Bbh$$Xer+uXtE535atx`%53Fpng z(!TeD&-iLW$>QEfXc2r)6xL8$exo6dD9Bga%nFbD5n3|(dWi;~lLdf-X4YPmgBs52 zS8gn(w#OvRfw}nRlndq{!hTznKyNVn^g;>1dc*`UKtq#154*RN?c(T@nsOf^k_Y3O zz{3cr_u4PNS9nm}J%ej`hd1;#KQl5kl(Kt7$0TN6567R3(YfVx^-DA1P=9zMBTMkh zK=l*mH`S+|^YycOiXg?PEnX{jS^|)8^M#9r`f)?(rKNa$uD{2XNj?lwG7~chuoPk; zhBV>|7|@ilbUzEF$S3G2V(`Aihl{2%GSG zL3F&DH^CIaS@DeXJ`V1?aNeL(US5xZg!ztk|K28f=-xVL(f0d3(D*aY-!W$euB+4r!K&_xO=cmLUw10mZKB8&K1pogP{*D=V9SR-Sw6 zM&Hary(v6B9}a4_2_9529ESY^x3ky%osx-d@6gX*DK0L4tPGpe9RM6dRp=>XHriRD zdE5il*mSiu$aKPn9p8Dh9DFJU3Wk(Xh^o#l{fo&=(OIGDdu}Q1(>|56lk`fF3yIziERw*eg`H zctZCEK@Zmev`0|^t~ZPi7QXARY-4{@OIMBVHY3>P9A2g33qF2v;MvX%bK-hJFh~xB z4R`L|)xvl56~P)rO9YCuwHiSaX%V&WWb?!(RD`?DUi6@**ID3r^nyd(^jIF$j$ zC(VAGoV3R)x@PTKvtMtI($)6Gsc#xtI+WmReP7EOvUJ0~5Y#O}O?e^=_>lEK-+qS( zUSC7DfQ004Z9P3C8RKmP%16QD^h4HVZCi&C4CdiPzij4263)l8VbFMcrmntzs2&TG zRjR6w#5BXmWUX}%E;K~dX+_@yhC_bup(^xg+oh$=Cj3Z*3x+a}0Z71novZg-q611g zpe~eR^l{lEfO=ZEsXPYID~{P{8*)GvGG^=e89f6mWuXHn0N*_GtHaCSbzgrTjAgj5 z6~EOnj&m?8hv1`ynZBq`r-$2;^7-q$Ago)4#eZw6tB;|3WEhXp#tT_=V!oeHlu+&; z3$q3BLG(+q`4tt+1ZA}GE(S_@)O*~oZY?+6qyB!ID+X7dC{{^;pn*8e>;5AAkC;RE z7Yz(&aWx0d$s8;@7PbXWSf=k)n;aSP`F0qEM%DO@BjC!^lg2I@lRh`-BmNk-$h-yd%C@R>Pu_-g)dBL zi%7kNTPG>k7g-_^-M?g!_~XAY$Mk8&3r8D`TcX?#bT@*cQe7;QzwTzSZb}p}3mPc0 z9^CMV4si79&JVlIJw7I7WEl4c76<(OW8+==XZY_Q;a5hAN9+9N$v^J9>JAPSG9i5_ z<1e%29(BJ~VT?-f3Ef6>|q2E_f%Lo25Bc= z_MM_

dpCr>IG*BdnA0iT=munpH2q$`UGD62YjKT#snbgq#s0cF5URzLcs zj>n!j0`H~$@=zFE&-dR=zFm3nlPqeSZMbKasm^vrd|#YnOv+;ZYxq7NUp{%P#A?O5 zcdBTxOy%@gTIrmwgzdFL*V=YT>+~d~he*8exe`{@M93W?m;jTq{pbv#cJkH%mYav< z9#EA96;fcBCdXhG5-*g)Fo`{AL-}ZR3xO(L*!Nu4%D=rE-g<>U)UXZi#A-bLfbtAe zAmg>gY|L)m*u2NBY{I^*=l;E@U6|Y@{M8}u^NO$+G)bM6`a*gU<^|)d{p!Vu*OhMJ z2OG~BneKY&y~<1$DIB?FzYxap)j7?AM2~ zI9CP%GLsLj0gqcdteCkIVLvZib$Y9xR+tt3@AtpP1yz$j>wlD$IzB`DmvyV!8tzah$Sx+Ea5{~SW!<-6-RB@_>V}Pr;HkR8k-4=0M-S_TG zk2OMcM3brG`o@t@7lvxHe?#jKEP=8^{Z7oTV-Xe->9?$BH)G~Y-O=&4(RSv`-LQDB zDaf2I)ZeJ_sjQr3ChPJJzZ!QOLF-gU53TN})Qq4S8Lsz`ye&+v)8B9PS|3uwt9AIR zmUBjrF>Rq3?Y{6~?SLUx5a-ob-zVcI`2zsBm`Fx!1L3a5-Z z*J_^pl^}LVGsSKx?`$X-diTe%V}dnNafdVcry5>@|a%cd80gkb&pJKpCWy}5Gm zpFj7!+Nm%1s>X;_{B~@{VgaRbvc0xrw0m^TJ^A)zQH%U!H!Wpo(LKtRHVdz3-eM-> ztvGc{Vl*iY6}KlT(v0(Y{&-{QxRJEw%|@nNa28Rt$R;jl*vN53HJR#V3C5m*>+YEI zopHZCD|-+&*%8X&XW3L6e4XI1zs$+T(L82PaicMwr{gBGoiaCcQYMdZ9m6KKU`~}z$eB!v z9BYMVEm<37%bn<7>AuAEiA4%s4W85q-?fA$CQ9xB%q%>MGoNEby2sZKC|u-Y1F z?wr@M3C`SX2x;aYyRwnnPkF)jkmfs%haKL6DJy5V+i>@>_RM}?TsMMwu|{S9OP&}A@QB!j|&X=o|CcOGwNp^g~CfMsPiLPz_w_GLFTR~Y%3W3_PH-aXX|BJQ!$&&sSUOP6gLxiZvBq*wtKSP&Y!)qr@G+ic)e+SL*JeHeRPnH)5jj53^hHp|c`OFF@)QIoK1T@?O^F~6KGJ|X{6mP>6 za;4ib1?~V?a~fOgFlu`V-xasCV!YyKplr_GPpq%T?3DW#Afd!6{_k-#747F{DN7&k zr2G0|sn3t(UB*vBJ3L9gL^$}F;DVO%?-W}8(kSt#SQIVq9U->}S}`e$fZNGsyz$C`zb8YWsm=MtKdG{j;_lQND#PA0%%AtA+#;PS7Ov` z+vR+xGUeqh#@s0`Uz*pT=b<HvTKc+7pr;V#Y-gRG<#|kn z6--C;4mPo9#axF+D=W)T;q|6n#gfG%<0<}&Yf;dLdA)1R`o1Z1Dmqc+K(9A^rHM=5 z^MciXbV4Rq?@#*Fy3c=CD?t-ywY${>k&scDL0(cy99V-6-qwSpXtbQ3u+&@YD(pdV zgz~{-h(A~Hv#eh0KgInjJ@mnRbjnXzhUM{>Pl^~=eNLDC-&${qT`d` zBH4F;VD32t=i1eK$)&!&04usD7--)ZoWBaU*I?o%S)|v#qP^_5Vz&EdrwKrA5tzh1 z{;-G=imn>6SoVX#Iz4wWfhuGQ!i>uw5vZ{yQy4b%QS?q953+1>zV9+Nl{-Xwt8NZ) z7=nh%N#>~tES1>@E<42V`C)8oHsvTxz3$5Z7HT~PZ@jcv7it);cQu_E+k_c&@yP)O zVAlgyJ5CmW`?`_R@`T~7beyWZmSKY+6 zvy4UCuoi|Xlm7OQ?PMdbJ**Y4M$awtf2i~0kYF>mG}<%ooHc#_gwzyw9jaZs`4xg1o|geg=65vWIRmFCQ|R_?D}V6Ous2!tcc ziw`*up_?8#?>Qb_1P8>~`W-@>(f3;g0VKVa8E8;L1mM~SQRn3O?PRbzn^K378P5)g zsrvuBZ)cLpl=zv`Y6LmcTa zuN{14l(KO}<{Q+zAmg}*OjsRj!nmx(IfT!~E#(_m|b#y)LhYhlRBFlzMQEL2BJ z8w=FT)#2AGgu zd?RKuz=%P}kHM;_EwN`XIR6hk*iJPa;uNe>F)oUL2X4Y_WiXDxAPm#O+g7C(S}{*; zNjW-Gf+e0ekkF#I{SC@WD!bVc%>4r)*U}n_Dj4Q>=iVr5C-g8^!>|wE|AF7>8r{Wo z!RPhUe{{yLQ}f@odxrl&?rMH>Ogm^Xt$ig&)bcL;Oum#i|Io33;B1RIL!k%RA?TAQ7!B)_AaN5Kz~^9AzwB8kfQ{Tqp#JLyQa|7`uXUg(4KS(uBH*Fe zS!6T1In#0uE`r@XCDw9`+it7G?CwMJ)SJmL!}}Q%v|p3XXY3q!x2PV|Qg;+`Un4l2 zXSNeZab{Gyp9yh}l^pd?^2jpmZUlJkw1uYi2&|5D4nSf$@E#6a`V9m8H#yVsclFXk zhVzvxIk+hE-vLbuQ7F5r>uh8xzSPy#iqIe?a1;g|Y#=}@P&`zMUT!EqE_V`gffliL ztgB)jo4RT)#s-(l?%fUN0J4Ms{5xPSIC(g9JHaGwEM~h@_&&o1D_at{fM}34rt~|I z5{3;|^xuAsU`0Zl0Zon1^WA-Z8G-!eCL|q~FGA0Ai?_lUpxUKFLSc1w7 z>+r4L0LHRn51Ni?=gi^8gU|vaOTsD^bYlv^#=!T~8MiCH$voAxBWoWM`Glw?7Wv~D zd~oOnUqjAZR)wrUp&y_2B-lOuc** zF#p4v&hRE}2I!3KZ?d~&M(@I?$=fOi9u8_S<9%J5_953hY|D2qNR@Ll)R4mh%)?Og&BQk6h~oGD)io5` z!?9>;>;_Dh8bDYe<6DuEcf&jT!~Sj9!Z#(I+uZwh;itC1 ze6j6^Ml8@qx<;P|zQpeDn^&k_E_{v72fVjm9KXn`=1TqowK zNJW*5>f;RNpp9ox+BQ;s+}0?exDx1*TqSj`CL3Q;5*P2tam<`@94;ko3GDLE;KwFd zamYQ7)=$?cpO9N!!;4WbeUauHUVnS2z~?>jX-N-2=V6(FD{JXx>wCt2 zatLF?cmbYq6Ev>4Jv5nw$M3kxq&?w1&=+?0^8Xoqi)_E`6X{SZtu2_qUt_VWmvAF$ zea?YRT4Kc()(Gk_4ZB(vsweQG9XKv9#`+W*=l<*m+=@BkLO#R5<>QcnEo>yo?8NbqpCewu*N@D zojG*_a;R%3ne7CD7nh7MtXstS0az2nihq~vGo9Nyf6q1`8cI5wBaP#}X5V8&9kf%8 z`kuq$Wo$HQ)Waz?Od~c0l&khw4#4Yu1`kPqz>R<-u;V7?`~ZKjR^0~R5UU;wse52n zsDJKX?8~%wqtwDVqGsGM@p+z|X=@`~><0}puvx{LZEoe@u z8-`h^ois_~4e-O5`8W8?VRTDa0>HPf>}4-N2HlJ-qrl5MT1(;yKw z4pouF*`D4;!Y@eXu@2zKtxx5HdnQB!Y0lV4{g{Eg0h2wMPRO;knOt#MVlhFc)>8cn zk&tVbnC&QB4X{>6-i zzdf?-jGt>QDh;&I>*vDy_@Nb`)BxtOU^&v+ydI|EAcM)xQ04oaRd%a zYEMaberx7=^|$<<9T!%5s#cso7^H@8Aq?Zw^%i`iE~9eI zGX-*Cd@le5GqdN==Y^#MUu59c>snZwDQ<-UyP-`u8bR={5h!?8FNoEj4YRh`KvIR% z-UXc47~wjdKm}fG9WaTmBR{&pz|0eP@Vv@!Y>=hQj@5T${-$yjE!D%(F#O;xhd97T4i2|N6lp zHf-uQt8~V>GE>fLWJ=ObI4A5UM>rk2o}yCz+m^?4yL=03Ux!e7kpsc_EYx-l!PW^yB}sADG) zK@s`Xfz4P>{eIr<1ghknm$f+@?){w8d6bz`+qO-oCrE=-rTI+UeKw)bcJ)WCpLwL` zJ--x4ZJVaP)8EomjWiMC{-sAj9MQDEBImWtScRDZ%>0&N-CyH2^8}rfB6_94j@~6v ze!rAka3w-%eWjMTZ@r!9N_4MwDw6m78RvQHu`PV}m1*7*tu-O#otooooq@>aF}r{+ zp3gNb)RPBxVVDK79_;m1Xh&Y^1P$2(`3_5#o^LjMuf8nkxsbQ?n7G0@txTMj`RERW zT&ulJhyHcZCkjvL86NdFaHM2x3fHisgAWRV&m{(6Q%$E6AnD^e1ToY+d~fmcN)Kn$ zn3qKqaO5jTo9Rw8fB&c)BnYqe#-hKpZqWhOkWJdVZU*kAOup6%F z%R5>@*fqIKw!KEb2+$i@z8d4avf8!uc!{-@I8QwuHlff1%~mjyR1j3y;FJda#orqs z6qts+FF_MWP?|>PjZyY`4u}XT(f;ZruC%c>3d)@2g^cfT%6c?yIH=h;*^Qo}Y_KK; zEYR&E_~}LU)n`96%bXU7(n`BE`3e_4I!MdnM%48|bH(;a!j^IXo|^6o zM)nOw5m}JtV$>bL%?DqxP9j+9nzGZ6$Mk86K;@TYsf9rC!st$zSRzS>8YG zYdqi5cEy?6y*m|g^e};B!jeprDClb*<)-w< zl;R{UugM&jEq3#)G!3jNGLel}mP-&E-851-AaI2(eh`(M|<<(`SOz8>$;~; zKk$=cijGx%kbF7__$^E=c{yYvyN~Z42nU>oytc$r(Y^%A`tIqR;+c%TN?+(a3hxv@ zhYmRMOyso%_j@hO&v4t4Va!7a4~h6->CIB{4^cRN08Tn0H|(@%!ON#ykThvJ$xzlC zOP0<|?*~;miBbgRkKS*U$bVJRx(?ri^DD03@!O1HmN=Dcl7SON7Z;4TQCf%|g|c^$ zvF2*E18{L>gQpJcZ>@Daj+IOdi}cP%Eu`yH06ekiXu?vmXIrFZ=zrD+BAse%T%S|# z6N8c!>RkTP@N`D6SB1DA{ix@sq>`+s7cu;c51@Q(NTd_v>yDt@MTdoBAJqiDQp%l& zoE|Rk102K)#!WH2ZvU0}X83;CP)nwE7I$I=VQ3g$hX(X=9**&Q7`be6{4CD2pOVy}GX4+5YP&-KJ~M z@qWeWevRmV*BFF5rTnJ(q%~i#F7<3e+on!5X7D_x)|&K5z#|M(-4Ewvq1y!qKKTO- zk0Lv0d%igG0Z6CUKS(cc8G_zjN^I~Ty60kj?0k;nKOx^J{Sn!_U$xG{0Cc} zh8$qso&8VV!Z40L92t|U!w3Ahyo(lshKNybyh@bmid1Fi*uBJs;?Mvd$!Gz*+(I*K zWZc^hbu#9}9EcyX4MRrGX`zNriZ})tnSJ6s&_QZ%$Zt#-HV--l)LtvcII+aDVeY>z z;12H@Flx>ymaty>9ka=S1EOCdr$iB6%lOmzNV9(F!?#N{F*~jE8LOF9RJl$};mDjK zm^w2q@?q4iT!&?>pdaNY_wE1kfDu$JdaGtg0lcz{Nv|b)eif_&o2g1Xi{&22(e@C0 z#K!M9R_kh#mI^O4kKW!3p3)T5MdnU(m5;I|e z#Ay8L(;s_SU%j+L!^Y`ulg!Rzn251v{>`OLSj(SyZmlvy8ScyE!m_22^;N}CRo36K zk^jtx0poq}KG=R^^#zue`ayN>dZiL`#X-}faI76^HUQ3ZwplA2_Mst;x*LF9It-jk z|KdiNbQ)9=8VM%0QrKbZ7%l7bjX`_lVSYjm=6GfoImY6|G+5QMI_3m^67-IYTLNHk z;(32b?lrv##_shu?cGSx_cyOJQ!6=>_ z2VBs~W3nGBE4GAk+pa12^hJuod>)3?hFA&F=X4pQtJ#&?NTC-rUhDom2FxBPC=+O% zCCykNen1{pwO9F>Ro}wlbir)%m$z|;zJeSYl_#XTr=MkK9zxN;@RO7lvVrgyfA0*p z&sXdyxhD(D0EYJllJtzPpRC|HKjMrTumm&jgu~PHVM(ul0P{QL2*VVrT%dRxGI9^} znCwEuAPy;pg%5^b4Sk3dY+M(dzXd4b&TI#7_hMs<&XK4OGdA^gKS%8|Z|@OE zl+k^earD2&Sjt#QCzpPJLU8eC2Dj}DcR+e@1#sez_o%par=-6KF2SfD0zj*OhYX4# zL^K6iVUe33vnHwgVb>3!FN7Pl*6f`C-BJIoCtPB}zN~k%z`<_D*$Z68{cSDj_K z-6r>*1}vPy+7b>rCm%j`abk05F+xMC&px>S-pAuC)S3^FFJQqZKXpAQAS~5bT|Ngn z$13IT#Ws@@lp5M zVZ7>n)0Q^eZ`J7HD8^rbAwC`h8$27}HFTzn4Rb=1jgk2dja9g`l|HFHiRzFHbLtl^ zPpf1lS>M|boebRWXlZ}4$xkH>77AQ04P~!5c=WJeV?O1%v)!gzeNsTf>OXT9dmVGO zm`M@FVKCs71nrX+KZezmLxMSsFYK>*+vw&Tnnao`mBzrW7&SIz6faYR)j8{TWD0_x zzuG`zYe%yM-ff!_W&LZhST?TM!&_S%23}F>xG7s?%)z8#*AC=8vA-B8(6Ncmq}3_p zn!RHqi46`Jrn>J#X7%%J!F&cDqD*!IQLye}U-e8E>@!qev5cZESDGvH8M{u3XM0H= z0F1zks7(wpxT}Ngd~wD5Pkm7I{*38JXQ6gwK)Moq2^3H?YhXSMY}H&aTg@V_^}*Lk z^|khu6puwB+IZy3y75o=Sj9eA&;F_Cd0}Sq#!eWV`O;os9U<}Wz~o8f~~{U8z8=i+R1x-2!z)A6dE1o$$rA})l6B-dX7 zH;mis=jB$k*jK>A#KQ2*UBTiEf%>0CJozayd_k9aD)FuE_-ACj@qeKBnND!N05fSJ zOQ8N82!|P?FQ&Ttc+g(UvynHlGMLcSI;?B+4T&F;HV24$?I-Aqbm#^O$3 z#jRM6RJ0QcDg$)9;x9`re{cXACV&o{tOr!2)082Ghak0J4P!LInI8%Qu#FXg&}RMX z2p}2A@a}iXTYZIlOHyC}T7>(xk_hM*4+O(@z%Xk#kJ1oP*Hf3yP8q`E$|UE_X{zz( z6p&~!8gK0>Y{CmmZj(`!?L1|Q&-)>qJu^zv;Fs@4=(}y~0agT_2OcQ15mGAVITfIH zgpO`|vf5L6t9*McvXBZIsJ!SS3V(Wu6myvEA{nyC27*Unn7JQ3AIE4J zc|r5cDm{jjL_Sb$#EyzFc{;H?z{w_mx9z&&#wL{&dFrr zZYS}>$9t8$Sd6@E`f<7@Y3Fk5z+RWG1N)$brF5J!;R(6T1VE~)$OP*Z9!~RdyemD3 ziB6&l{z2oR6p3qsbsSDCS`Wf$Azwdxcn5%kk)IJsfKbEQIe4J6{O`|YT;Jf=h6vO< z?COKc8P=x?IMn$!ql0eljp(IL>CERxuu~%Z^htH1|1lWk|K%2&de>Zjl1|gv6Q)?8 zAs~VOFCzeY0KBia#T2MI;0dav0r(Xs%MUx@S^1@IqL|ELbo5SIODJ%Bjv-gn5>A7S z9oZi7BFneejnr;qrh-|q1MWQ?huo5isLPIgLrcmCOWLn7Wn%)avxOV~m>ASGYJXa} zx?Oi;)uEEwVf$Jgzu*3R59df^sR9{u{muOl$wRy0^8;Mqx56L1C|X_=-dBGczCVMs zL`t~Gt*pFbRw;7skbvZ5d72rnH@-WCLOuAKh<`+Um_bnPF`L!{n*S0ymf-BK|4LR= zJ7a+n4u5C$7V;-WxnSzDBASM7`@e}A1U>6dMzGEftH+^EQfU|NJ=eK#sQje`%GF|X z--V=v?`wTPQT7=f6x^0B**kgWDV9Kg2>!#UCv{osrA_d4C(&VvO*0~j894cUXZPNT z=@depa0r8iTo8h9fO-qDwZQxiu|#b&-+ddP_WwSY0c2U_g39eSRNm@@A1z)n+#-O3 z)aN-&4m`<6=xH~a4^`~@5KhC{=aA@i@GPskq{MFMZIZf8lUJ?u{e2le^du{aF7Cjp zrP7R*9J98MA-2jGrwgIa5hEsU9r}j>Gj;?=LWv4ko&nJ;A#wK^pVe=V@%V zHSHw0YK(Al@A9vnz1YlJg@p1c#{=-4Qx8bbYr&$JS&c41@plV3tB2*k+_8=UXqThc zO^GSgmeFR0M_>=sTCj~~K3tWzW#sSglm^5S;@z=0CFy-=KL-5$frtfh4|!LtOy?QR zjgltJ0>(UHw@8M38*)TPcDiiHDBS6O585Ye-01AXQiSkdqUirHR?2M5pA zpFD1-fN?;yN} zbSR-5x1lK9C*R5Z!o~3}<{@NEXJ9|gvlMCScOBQmed#Vjk+zIp4(aJSuuj*86SlIt zGc4|rybB}pE=<+K?G}uHtmu}LWBFW`XRsbpWD!N(8%K&yJZPEqMY(4>0HIqgiw~3eEEv86u>! zhM8pIjIQK_obUhjZB=tb5iu(8Z4&F!@MO#;6PXktT}lcpDx9=n&?t?uz(h}B1I_n$ zjiK$dk6E$TSs;tvZ%oerYs?Rg`i2Kcid+eLZDlbgJQnrL~@B*YF3*T9ZXZ^ z&By~kfFePXzXOwejmK>C#j?8Jsr~7kw66tz_m0N&Ek$u&tE3jNk~^&aQ(C__QmzN9 z4|rS)Yx>tcz{(2YkWtx_+W*)eS9`n&SS{F!a zJ?2}D+CO2~pZIaEsga90ogrC1J4;W&VdDlKFhT=J^>P8&(r~<{(aM0&TIBzGXZVV8 zJX%3lPC$40wEw-+MDR{oFC=BH*Jq29>tEs3O6?}ijX#d{LZlS#`!QJIJCH^^Kgue( zVfq$|T|6#xiY^z_=0OuZ5QVrO@sQ@4px}3cbZA5ZSG9xFc{Qvko5_0ux_Hr-$a6v z;4_WcnE!wSiv2M1hIzwdIu2(@m;fcLS0RFbeciGA1s;mBCsVpv*(h;&%>bZwx6hca1PglLtJ@Ft z(5C9Tx&Hotn?u`(9GR>GcSD$Ifvn|sPcMG-OdbRaq`xsGnNg@EXk(%8)FJ&wl;EKh z9)*g0FpLX$?r;f`bGPXqaIFUpr#c{^@HCdGBiDaOBnVR=;DhvGE56AXvuk2l!Ztnj z=_DMQ@_zyEkO^X@%aM=W$?)ie7M<);j; zo79(&@J+4Hc|92A+Hv5(f#n@L4(vanv{xvTcfaP2M-@l-{r2glXgt$8TyuZ@U~+!b zb$}BD56F^V*!}Iu*RUrk$BiFE_p{AaMDf2KlgNr`pDL`6 zf9*0Vy)xVI!{yJqN9kL|mwpohGY&Hr8r~FmWIP$33-`Cq8NF>UiPqt#RnMi|i^)c2 zp>T2QP7NGYx_GYM7@p7cdole)-b2m(ZKuL&MP5No{aj1J60pGPQe2)C6A6Vcy0beE zXGGp2A$YpHVyEThUN(zj+9$BsF0J1-Px<^tp#sJlcLZ~BC^~JYI8l7Mo(;<_dmR+O zR&;!Se@?G{11tUwCr>4&ad{LbuJBaxqagC3af)lo^`y~mKDuDKv2y6VMn% zC&}!@^i8Ambru>yP(+=~ApHby$^nBKnd^H&wuxbgCanl?8WI;E)BQ-zHaRAH@C3bD z>3bX&!4ea)smq!c27dJ+!Gar zym`oV!|fFqKX|JTH`6X#y(JTGKXnX##jUisCY0`UU4!@NM@$Y)lztt|>wzT-mYYP3Bs2zrp0xrkN6mk^k)0>`O1^1WdQMMmzqq$KUURAxt>V*%}Hl zcbtujBYnCB2R_>x*N;VCd@m^}$Z>V9dfnLghDUAe7;;vhG(XZV z%(P-r_xQou#$)iPt~+9oR2y=Qy6htm@hrKOC~Sbu4zJ;w3<=j;>rMe_$Hj`IAMoOs zzCLd|hnpC-qE-9jGIcv|D%#%BzuTK&F2sAEnDzb`8I^3#ebaF30fUEOYFSF$e*Lg? z)+2Yl#Oy(lG=_Nme6^GGqUZ`ZQ@F6Bw0mV&AsRSe8ue>SUCUnLK%Upq8r=0I}|n^D@z&>0%AYM z_nSg6`Xm7x?x%WX^VD8ZN%GSb4hSBU{dsEX#Yv$V_>`&rX3-~a0@}(%&17&dk z)al`spm9kszt2X(Zk58+>z+zsp6w9(*%d4pQZIXiyKrfQIwfXdAW$+(SnZ( z7lAL^XC0Kkp)9tsZCO>>nam?6U243M?XDsBtGVjw&xx@u*!=8+r=GxpbO?pO06V~X z{-MTXJGdGV8zBibicgi+aN3e@ek_GvBjrFb$;ky~ayf=e70r3|GnPJeq6rd@vsc;h zXje!+2e1Ky*%^EIM$AI~W;cZUYJcB1xhyY$bJ=K>DU1PW6qZ`|cKTo8gTy#^O$zbC z*>2*O*;<3Cp28%5So}*b{@Sp8B*RZiLeQ&hkEAKGSeE;ym;mBr%Ib!$tiR;(%PgT7+?$5qxzqPukD&BTW%;-X`OS;L^08gWPHg{qL@x+3^%6_{g7V2jD%yC zqgwP^X~1i5U${oO61H`&wC(;{>;`Y8vXA@cVfrXQ+Q%y_kqYu@6S zaD!eL*7a0(5$*kbDvV9SblrJO`h1&#Jf^}-t#hsZ2$uFm4$cr+==y3Tdra+Yr6i92 zVl7So@&-i1@tWPW`oD8+Bhfi)toXJvf}Sk)#hG6u?%|umN}Hf4Pg;pFSNQ3e!{YI? zq9{Scpz6h~d6IH~dd~;Z-Tavx8Txs;SI2$qyh9btxsG8S9M6@M$-NerWh>|OSxsm%G>Bc*`&c*zurdk~$}Xx)zw zJ?&nX+^D7;;F6a!_V=x42-S}C+|W5_nFRKU*&t=z$tu+^$Vx-up0^S+41@=g=dGkA zns-+~5HAcxsn{TTuY+?Pb&uJ`{-j_2?KR1^tvmT_kFvYW1Db8y-!X0i^2U3%9Tohq(?(1eN<5=rXy5ze7 z3^{5QQ_7cn7Pk#z?y&kX{Pyf9mWLD$i`_G__v6a$R&No&FS;U!o#4ACPll`M-o09g zBk9KiTF3?}hG2~s=jJ(EnWy6W>B;QF7gc*WzckbNrKPqu1xAQ?HgTzB4{GVYQhP?7&ELI4Xxbd0RtlbH? z9*ctxYg(mAu7;_aOtvfS9Cy7kT@6PqKA=^NP$}VjmtE471+SS4hj8;mcx?vESVr^O zC1HI39L#R7M5Cmf{}hZFfVRNl03nNxPaQBT1m>4d!RX(@uyx@e9G2(p~@i0+10LwYKKoEmJKp2;%XJ;01brLE8NqA zjI^bnBn9%f-g?GFe(G(TD^ObwS~;3+F7g4^J(ZL9j&({U?d230jz4@^?$<&qUb@CI zMT|sWevBi#S_iQQ-&{fN#}Ec0%`L=iOQH!{oU`XuI>f>=HH~943cLTc2Gty2Uol-Rd-I@cUPXh0mLw;$hAW7hRbwe3|q+hq=Ud4BtsxTbfl z-kugtxz^3w6lJvVN>-dzx4f>w&Jn)gt$GJ`?8oy=nBRqqx1iClFh|#dYHXQi!pbVd zJpOuFuOXFi+lOIE7yyK3SydmtqeBPNXbjQNwYe{}o~LP~78{>=(qpn}yb0aHnp>b4 zddy^p?4|pwN6mhlHnWI`OAfcK3Rb?9s;=5a(;YWy2*+A22~ekrcas6Fmc>gDijd(W zBruk>#s3T!jFq978>ICTM-%?UVdI8jOl080f}@JTa=~0LYDZi*>!k zf^@^Cw`Wm$zfNPGlYU-v%%joV0$H0C7~r$ztYhDF8CN%ZLVuT`bbE8gd>J~Fv1T>k z2$*l|;DOV84}zY5**szn%O?Nchj-^=5r^zx)ReWW|JS+^?q*l)P$bG z$8y0I9q)rlLe(%?%6zSVKc=s8Qw*~v_Ng%p%pSrL{f=xLt!cNZ4=Voj?g73n6Jz=V zA5I%wtBBEMY09`Ahj_49@@@Oc{HI{%!sIn)&WOf|A7( zcJViP(P*xG_}jyv+NP)DIuV}%&d74GlnRr56AvWWPsj9iF+$kSf!H$QbZ%N_M{Qe5 zdS?f`+O3ETGUt9ZjvFvwF}FzAl?QF%rg;Pkd?wc9W!X=dt&4>~TtKkm-DN-5>~Y6# zo$)-U4yO&`obBwFUHJUykmJgMFnQ?|&$U89GZZO=~2rj~t?dz1C-WZNp?sNrbUT!|LmPIGZgOYs!BoncAKaNaHVYD;MUV_Y0nz zOZBS{u*~gGy=RAZAn{6xB6%6LbT)(>v+LNaFh?|c`#1|)rOW(i~&&rpq%uS9xwNUEe54jj^f!iQodym8cOEia8! zJ8=m8(zyv`uXCOo!)(>C#dIK7W<8{&w|4Vdw4}?hd){JSFxS)i`ucp(8^k5&&_r0P z85H8F0(j%UDM+`kG##-H=y}qhI2!eASyA(W;^*Y zp=x%poLOS?+4U%KAv9_&AB`1-q4rPr3FIHE@@M=RM<)JmyKw;tL7>T*oC&lT)or-x z;-~6c91ws#S5#nU+n(S0KF2n8BY@YnQ4YC!fl2Tj(M6I zl)h_SNNXHt+<4@09Wotlg}CFG=7{K?rxr}!y$>QShahtZ2=e%CXbVG#Ma*1pJD_32 zNCS%44xuoeB%y)dXAGUQ6r7cOB8y;_j8w}>NJ)EAIuKzhyc~c@Qe}$!OA=QHo-MP<{;1tbBv_A*jEw##`~(Vr2SV7lXOb>A{uLycWc~ z4t86Ydc-B%I>;&S?~6n@(2#XB*l=T5X3G#wH{{syh>XCadZYAS=AqRSL;(uyc9ZJ2 z>IxQxB^UR|!HFXSevHyT;YGPcX7ywGsLNdbKDJ31W!jB>^8wKqm3%N)224h-LK-wE zX+p#JEW2l|t*cp_bT($Tx2%6eiV1E(A|uHmy0Nl<2PMXY?1Fb*^#qZI0?WB|rISmY z4<+2B6PP*f;*9gCvDo|QHawwlKlXu}Tk(KlmH*RPfg-+WnD|EgVJv-+Qz6h|F`LPt z<|VJ~LY-JOOipA#PvxSPj6aGUs{!!xKD?>$ljSYGtIS*{!g`^!)c5^nBa^JPCQK59 z$5J`^o5mR}^!tS|%<=|!s;pLZ?aIsax`)stPNW?rWKiKNul$i07o{xSUN4>V)7#+S zQI75zpMY}xcEPJP?)Y!rJ-cQ7%-&S~f}$P=6TP3I?V3LPxBANVk75AN*m5c4=x2&h zHyE}z%x~?Y6qnGHeM54tLVT{`Ac{3+i?`t5ocIpyL)73DX?vlZhw1T&3G4t@Vgm0s`Vg4dczX3BULRlj=dhes;H>q1hzO12yzpA85;$siGw%SoY-`Tyy+f$Y zqmNPV#nKgXpVc$;4QKq*>IUBtd;1q&NU-v;!~3;{+$%TYoqyZ2gAmqok+CxnNS-!` zpg?%bq39K>E5bM3y2VV_G{}P&6ENumArcxF;P56L$B(wF@Yruf{Nb zy!X=bp+r^1*I{sYIS&|C#`{)kQ%78^PefivPQ>-TaX$cs_*S{OWE zwhk`@$zCc^ujbUQ?ZL)+IdNBTISc>cky9qnX2l3c!no*8-Su}Ko}eD=r)Rw)C8r78 z?+1;emWwRBGUk5dWf(?vnA!|nG%Q8fvK#PRG1+qA>lB}GZ-Ns9pWkgS^wrx^s(9Qk zm!f+v@$Iu0LGF=0X_$$c;uIebjuw&$gXRYUI53m@XhUNKaH!HgtaSfexlEArrqgXk zMCxj}tAIzX#pDaS*7*WT{sV;6;zSBKQQqg=)+Q2$A^!{n?_4!3GUSs2-zL%TF<(IA|ll>UJ=+QW%(tSA5ze1hx7W2 zWJx;+Z)rwhIy{ni=z&4db1)Nk(XDR0DGo0R7V6In!US;jF-CIi*7yr%4$tl6BpS_U z?o{no{DFZZIuLQsEkAabp6+d2|#Rpa%ydlmGT2U?I6BO8D&Uji9 zt!7|xT>z$H`1fq=#!6rP-k)C4AstktfLqgFb7dkhW`+ssvBG>@uLG3^84Y&jKD0qT zY@Xtvr|9!zxB+IgBI!?O7|hDKT0U{Jpl6hRx+pyo{Oz^ZXSl73=c>eEUh&xm*s{sH z&aso1!Z_GmBALlzKb*Vi*>(h#5)3Dq_G2Y^_WE**n}H-5B(P@O07Z{O)w2}Gwu#hz zo5$vK1n5EcXEgR}DH?!_2Kyoj+WGu(!xAGNO1x{)Y-JDUG8_(NFt+2wS~S8a2kLsO;RNNX0ub^r*spYE%|tT% zck|4`pBE_k;^%A!6wf>YPBuh2@ApWd`FCg5y5;B_m_&`%cA+C&&(j4ZyHZ{5VmYP* z`76pZ1-~8^Af4nWudUVBV-%Q*NTtJVwud)NAIi!7vJ*v~;PCu}HN{CXN-TDoTd~DF zWc;6b);Z%T!GP{s1uEz3Uq~i>n-qe^;he|P!Ng$tN&{QN^VUv8(eT@QNCmTflN7@U7m^=h#8#uC{1j(LITJCmSjOxX zV^szA&2{K2s(u2?mOVdZTxaDMxLV{(p$ya(lZwp#>QVBF{?e6B;&hVGoO7mv@pzn%Cc9*7K59X3y?`)_-+xg@lnO9^4%8#HUm1AV@{&4fS z;bs44Xw0J4?WtS89F2%6{2w7a$M$l^FQ$KYlKV|;qn6R0eY`#s*dGo#OE$@~-WRUD z@Kuw>8IX-59AL%5AiEf_EtB{C;u_S*th-q3RYq+~*L!D{8PeT0{>aWiVma(1vvCik ze5F0^t`GSMR)Ibn3rv=uscN_AA_qZE!D=MpAwKd_?MwqL)QE*`G_Jn!-xKq*gt<%9 zCC`Ud=Q6XwU0Om{&Ag^IVi3Svjx44t(luXSe{-((3$!%=gndyf<_f3$G}mtIEEm5{ z{wD>Myz?gOxp|-Y7hcgy6ZMfM_!J#+dTSe{!BFI*{K=n5B&olB2E=KE+?Ic%k>3U| z+Sen3z{%k``xpi+QD6ZfZ^?)eLyER;6SKa)8o~a4l^Gs#i@o0xdv_4L%@-QpUHh9P zbm_ok%x8{~4{LxTf%+Jj$>G15u)@q~E`XctHl?LsE%(FNW0$N3J&&bU3U99>7<0`B zvOkO{xAT?BJ?P}~$Qp8a&|aCXgP8srM$~T?y30zwEEZwC+Q;N)=rb<3!F&&n9REqv zHw25f&$mQl(f)MZ{XjWTQ>u-E3;dh3t{U=B(+?DVC2G(dX54wA|5!lUURU(UMSm%Yb1IW_kgOb~z1Gy}3i0lH4T zISm?g5VmD0S~JNy^ms5~ov?uARJ#b=tj85TU^XL>+Ddq)hs9ox7w3W}eybO=_KpI$ zl8UI)hRuEk#nZ72E=3M-6++cVQNDUjYV_Clkaf$0ck^xTeUKo>sI)R1$p!+8Wv*kf zVVR`&Z5&`US`d$^aCmT#aPq5wn|D;*PJ%)Z>l@P_>wk)@%f@aK+oym2Cx(%@0BIZ2>Rp!{ z_UetTF3%((3R;BliIrYLFB4*6BK45z{@bTkL~8}+9S8K~M@4CUp} z@MEd1Ua2jR#y%6U3p;J1YYwD>vyAFZ4m-VGV~r-3o(z|vvq*IhcoinxioBcVH(?ME zbhf%TW)8sK#|Heub1A8g2My1&08^nQ_JCZ2S`ZpI?#2ALTrqfYH+c}_Sst2m+E~O)B9pDEBED@6!>!fkFHA5^5C%+7uKnw;!>v+VQ_UYcbB7Y=CdqB#J~} z)$$~4>kBfq48v*~Vo!*&^lP&ez&y)p;ubszr;&?$1N z`jjYqEfhLRDA6KVAj^nvbMb;iO0nSOmPjbD1W1H1(XjNCL-0U`qsR)tmd|_Bva!-N z9nU`xe(#oHFDPKEp0w;>c+RC5G$-%RKpWEj; z^{i?Q!0-m?ActL#f+Xj^1zZ^Bi-z#-S>0<}&2lzq4|e*5Zq7c;T#O9-eha2kzuz0S zSv~k|d|q>1swPd#_pu&Q_AXZGr**N+x#kz2(9ZllYjYv;N)5#HAF1lV(Wnw?x}`Rhl%1 z!G!U8GqzC^`DSif!cTPTe7GOcOW_YAeW_c2$AkRD9e~se_K)w8<&3iVy2pccie?@> znBMfylI|E#ce2T9KpI%D$MPPI)F65Jbq}kV&nxwk0$5pW%O|q@*xntO*-33ss{wat zDZm@=bv-SUdl@n;AEaOj*;ap)(7#+yi9veX(l?5R`ZQWKEf(!DOusQ=AyTZR1CEOU z)CqKS9!&22Acc-%utC$i%M_m_5eS3gV^F)*+V*kf=%aXOUj^|y4^;tcaob|2qFF$K z&jjs*jjGHh8>oS98_LA4JHTZgs3O@QK$tUPx$Y>%&-UekL5|^m+2UhnaP zoiEr;D}3qZN>)CnE98qR27eoQ2o3bgRl^4X~n;k z6`0SxGkFExOE&qN6Id-B-3z}*Ghcd$WeanQ$;p%A;4TwOMv0@;)U$bB>v?mJ**1<9 z78Z);t~mNYW}u#`br|VI4R`l%ImWa*>gAcPTjznalaTcMiy$g9D^PUlt`ZVsacfCb zMPX;yKJ~hTi}6htxN``xi~pkod8TGW#nq9&el*7d6F{W_1Z|BcKJP`kE;aD`eRg7M zg=@ypgje6sn7Ir~PXxu*ZfX9KNKrB;pMTu8Ets~ZHwzoQwibjQ{`&S~!4=^UpgP$h zKKjA16r^5e=yp>A>)|DJ*;KPI2A~G8+dh(sU($#5*Sd;(2ucEp_BPGe&O|oQUy}W< zNevF#g^Yi{J$L-h9bTc`zt-kE-kDuwnq}=J6Y1?GW;yu=#GX(x{y5?%$P|eU*g^78 z5nDxxF}#eRB>cQVi6y1f(e?nt4GXV<1;DZksMvd-QIw4=PJgBOju+kXKjG5X)>eH| zy}_GNc%PhmU=Nna9)8Ab38U7FFVS#7jDyl*ds=WKl1uS7$Z^?DrRK@MeZEQCb@St) zb_nbQ{!*CXUn?mJXTl*KRh1o+W3V4T67R{J_^kE-#e@q86UbION>HE8J=C-?@#rE z1MwGckV8NHZiZ3aL1-SrHC;L+?@@^WFA$d5-XA9)Fxj+NWIB-Nbbj{Jz49R>4G&V0 z$3VWI^g_chr1_&&{TZf2F-S!~aX(yF)Z3%TD;KO; ze2X|doLMX2htzkGI0O6z#>JUZsQwL6!tAN%w12flO_^nJ1~Ml;MUH3SyvI&i+yM9e zeO|NW99ic@b|s+U*no}epfokCBg;Zy`o9^Y#MOXYd$D*Wl-lv9i3IjNI>#jCY99rn zHYgvxELQ=F?+8bJ!KLWWEGFPhn=bh+81TxuI%`k6vN7WyuT(>z*QN5JdF=}GL#=Q) z^n?d5xUa+lz(U9k2ZBwyg`K&C;PPsO~(%pG1Ezg5hyNwo{=pZlvf^h`mlWW|(}>4o8$-pQMM zq0CYc@ECA?BmLUKws=oP-0k#@%43NI+4sm3;Oa%=axfLMtX*hMx6!IJ3>=5o&-ULt z^Fmnb&i9Dp5S37mCl}D!3V?g)k#u>AcDVFQAelZnBaEdh{lucO3g`&(=GzVL0$Zrd zZj?h!R(F3dc4zr>VH7v^o0SA7&Zp900$S)7RqnxlHs6JMCx0};eCYFxhc!}{nFCcp zv9yBG23Flyfy>z|AfycWCKvkA%_K_!Q{oyts>k!hO~ww#Vjreg!=(hgExUy1;UZp&!Mc= z7HJYe{9#5?D@e=r1(zt$J>IM9gs*YG5lR^{x3tNCdw)W-tC>3}zxZ)0g$d8|!wcsb z7*B?yHnN@Kx(kAA3AuM_p&D;sY3j-t{+H%PpE< zeTxOx%gd(PQvG7KH^ywYR>!K5#t`6d&hFFZdVWwI3jYSyjc~kyH|4|*O>tn) zuPU$uVX~97TeVJodx6`+M_u;Usd2O)B^%)X{t&n{nD9X|eXTAKyu!H+;a;oZs4q;- zKn!5WXUSimgH}G$(L{k0Z^ELM_Sb!a{z$~P)B6q(#HY0Wvv&|38=a@OHD4|-@f#AIxwo_)C#-;Sfv~RfK0!c6p)d)A%nI^vlk2I6pHE*|bWNm`k_mPLT#6h2GQ1D|7*LBq70|jEBS{%-L zQ1=W_PIXNV%HXDxV$21L)9NT#J#GLee}3d9Ee?JkOO1 z4NW2l$M+~3 zxF;wBR{yhepD1PNIy7;I2oyBFh|+>w1X5(568|}xXVICN534hbw9$|NEINc5h4!ZS z&rQ>1Mw^RT#0dUIEuU-9u|ymqA68eBVo14y;M;`P_+etO?gSIze8{~QawF`V2pe7o z@s5q4qEyOoX zmcZ?qL-iJ_e{OF?K=KqM4bUv&6a;~~FA_h>Cl2`y`=6~(9K06U4U&@v@EM$G0YZmy z#jor75P1s$wx`mI4=775-GZ*8+b~pi0?Ykg+qfP%z|v2FdLWwHWtQw(yc08v&lhMN zG41l=Y~B?NP~_|D1{CI$ttCpO1m8KR`%%;FZ#2| zNK3CZ1yuo0EU$BRCJbsPAl4lrv!Ke=%wDN zoUjn0ih^SNw2eS`H<1X44BC;oN3`z89D8i5K`iv(5aj0SlG_^#0q#YXBfxeE_^6hk zE~Rk}1eBe-yZesFz^_O;XO&erSH)}ywPT>5$AnS_l#>w~_*TN1Hv1YQ0LQJfiUinQMKWf>E;DNI@@Z*l`4CNp)MD0d{RTP$UeqCe$_24Dn)^sqy?DlB#t$UET8%c4 z(APvl3@hp~U9YmHL{itZ0KwWq;ad%IdR@?-ZTwBDzzfO5TSqVz3Qf_jyta$Bf16_} zR+-qROY`6n3F^%|sLMjfYaY@9Ocn93)_w7EmpR_{704g>=hf+Z zUkTJ@bgHTl$zVt@Fr9MrgJC3spA~#bd0@mx_f!BA2f8&pk+X1v>}Kv z`&;JqiULiIu|aa-S`SqBw&m1fNZVBGJml6W^R7f)2w=6Pwso5%f^MV$H2aP;NUvK| zrgy?>3?YOS;Yp}>#vo#L%ihtk3hWBeEpdJch)5m+)c51y4>FTPgD%Xb5KmWPm!VbG z7Z&v|H6~jG*k*ndm|(-@pd~r9fggYjbcmf^yJQ!-MyVJOfcTV?)0g*?R+j#zb356tpmHtEbvl1>Ad|Tr3`Dnej!!@hB_|RXlZY zHm;kl6YB?eCvNC>{X3}cD!T&&6bP{;t-;Q)Ixv7&?L);&UbP`4-Ur8x#rDfidc@(P zJZg=Ya7aQA>C(jkbi252@*Y&#t3ZSEmMYN+oiij;>z`GB?iBdopl4NjphgEkg_Mwa zTMDtW!Se{T*BE}kBr`bzygax|g1Q9+d1i9v>7T6m_t=j@Qq?X;UB9Qy4e$HM7m7!IyeB!8l7;XbsR+*^iZ8u`{g0xjJc~8> zs^GjHq}R1qMNJq)XsP55*Ev8dIV)Ss8p~oI43GV4x}f&Otq(5cdVx-z^|4>v7_#;T?L&&MT#cA zf*-5;ASK01i9EnjU^G1QEy~JOPf-0a z$_3?Ev_SaIpl?SKq!$8q$v!^Z{-Mxa_q_$?sIdcU(dm+X^aK^dclntKN~Dq_()=0a z0Du4E379DgzQO_S#RVMN`^34usP8b|76pPZP8|*}S&T>8y>g3eYb@h)eGQ+Xk2VMN zoEh6L(*!&|AvHxEx9J@4{MNz)Z`zRRFB7yo%f_k$nCZ_N*ZW)McJllrLL0*$F*yUl zL0XlWKdUrwpHR}P5%!F$dwur!)`;HL{j7E{Do&8w3}le;bZ_B4P$6b*8yxxsndUMo$_KPio zmx^5$h7jt2L^f}nn|RM4?M^&WUWVEP6xLld#jZ<}#JM1^qll+x0Emy}FYOeF;x0T^ z1tVc~cNap_-MJn6JytGkMoTSsa0+~0Y=*r=vg9ZWNbFa$*45QTMTSCwXAiTddhv6!R}P9b_^mG{fm&l#bN)m0 z^AlD(@%(ifnn=!Pr_OBRtb0uBMoC=L*~BYd>p(g}c*t-|@5Q)26V5awct9o5q6q5TfvYAkX;<^l~8 zke1t_{kH{Cu#^PK0fn>-oVomo50P*$%=gvGrf+hf?<=?a6?Ub88by2tn@Q9%ybkDe zjal04AVetjV;0Drh=ymzi*cN!!NPBPzCoAx0ROvDBEm!<6}VsFrN77r9%aO>25|a0 zL}v!XktJsJhp_>8Oeq+Oyk@=Yk7u!N=+*dquqrXPI%DaD*C!4o*&Tcfa6d{2ESDpo ze7KioSy*QTJmt9&K`)oAb{)^v5zB5?YT3Q}JP*zN+y?^N>sbOPt+Ct!I&3md<;u$I zzlCJIO}|PI37(RzrSxhw zWvRnJ=GSls=sW<_?)f;@tl{cBYBm(Zsely&#ur+9jn;k_pv_t2Qab_lPzZ9Qq^)|b zRaC-5fwC}vUY->CNq>&Q4qON@Rp1C zfU^wYfQ9;{Wot?TzG(}QTb;!YGJFxEKS*Tyc2GYA?F=XhQDk8{<0XZ#kYv{lOKUgn zLp#zipaaa=^ePwdu!xOjL|g8Nm9pPrz9}?pT!vq|c_YAY%p4O>VN*rzzRxNcKyJ)M z&BWsn`_rbGFaGGAWdjvGFVq7a5=CF6Tpt9rXL{>MOKWOgpVkr)Xc8=dC^=mk?StG5 zC3d%~H-MUJ{jFz7MId|_Rx#z=C?M7zAxUJh)1f|-o;5os7OEt3#|P!Hho|)RRd$}o zy7w?+1e*45G-Zrze7N{1_U#ST%2loJg@E?CgasvA#h&T~uYNm-4I(A=o9%C$K`E{q zkX)FIZ=4@SkQ%t$2R_xtfFA&KVs3C5%g$-G(N)e%%U6<&`Xezq2m9W5RI}gil&Rch zdVLH#r&%TNS@lGqi^(WW*;6+o`0=v!M)`M|uY!Io_S~4fOt!la;NxUgnZ?FS%;&a& z7_7eJd>+&TO1IXMs!>@amare2e_PK&@XB3xer3(Z7l;k+k(4F91G|ot)cT=`Ve|FauEF?I0QAz+>t+ zUdBDp_=4ZEFT|b>F(V?J>pNM zABnf-3PM6?%Hpq9T_1pe7yxjZr8)Sd+d&Pl&nCQG2y)y~V0C#9Z|Yz4r!aYP4l+&m zqW=C*_bwq{I#Ro!eVEwtN6e6(V4}f(g7kFY? zv63%0MXEgqI=5N!%q#rMIhQ3l3~VN|5^6iBGZK(>n|K>gKl&#VbrjBNj$*SNY-V*m ze{bV{V@86nv4arTC_}Guqq}F9E?p9mlssx$^}MzoRa8Gm&Eg?z4?On(qKAnIwV}i| zAcoxnSTRuClB%JfKsQ_!(7iEco>suqw-CKj5f>y~sJ1{uON*<;6M;^|4DMik2>Mm_ z*CK>X6YBTKh8Rs_?u+Z3HwyH9e6pl_G+K~dG_KAlnCx`dF-$V- z{7FtxDN5{EHN5FFz$KBp?y>)Q9nWdOT-gv#1K3mM$G81J=z4ndW6Pq8_C4r>+zwI( zh-__roms0q-*(vG>%V(49H+Zj0vS{5)rs&Kqt^o zpzs8skujC%zLKExmwl6tRv6R!C?QPecdBcC@Z32?r-Rr$avmZMSUrOlI8z%VeQe``Bb4k-i-yb`~qPpJ--bZ7{@~q0&J&Itt$o z_Fr#H)uvB(ZA~5;li7ADUW^yCB)aDmj=%F8irHR`VU})y^H|(Fldhd70BylS?*`>{ z%{;4Kn$nq>9d*ICmKLOFdId7clA}SHs^tDVv7HCx*>Y zaiYx6(*E3)Y48zu{Ezg4IWe)y#W_P-39RvrjveOW(AXR=#92-ZDCe|YVA$5xE-*9v zpcSo|@wN1|%9AO$;L`+Gd5xSJ=Z~N5)iw?F*~&kWR%E4^T#L0cw-_mSS!3g@`b_SDD4sy-pawg{12r4Q*^bP0pe1;V)9R zZh-#kVI&)$94G-U8uuq?ON8u3p&&4ne{af!JOZ=^D$sQu1U8}GeO%jFkW>fI-HQ>m zN+oAp8fq7_glmD=!UzOci_Q%=kx&u-%v?2<*}BnqO=^VtwO-b}_c}{6 zUEO@M%j8@;bN9)Vh7$cusHt=|S$%wheZS@ITZzb-GSDdyTEZGvVU?z>jJUex9Y=&& z7D~-IM-1frJp$5i3RFgjl)s)NLsy*x;KH_kwfxmoy(`xY7RL(2sHm$WM5b4Y1uceL zADf*ld_`d|MW$ca2dL*zPP&IBUffyD=5?Q&$@Lo?oTL?BTofLQNpBiOXRG7WTi54P zA0n-~1~br2KZH^vI&hwwdwrAy$}62aYwsRG_g;n~%+sDi3LysddP$O98eD_zTh7g^ z3=r#Mc=AuZDmKlfnB_#C!u7c|$hg>jz8=HsR1@!cWu(kNFnfMnanzxVDzfjsq(jE~ zG6l-oAEpKW8ve*;9u1*QQ#!5i?FCVbj{PWYM{(@M2UEZ*6@xAQkQd)4I{nO0cX!|< z8|Z573MHm*ucaHp_ME5Mwrb!_h&r(E2%j%xU_s}W;kPj5ES$#b?xb+TsNb!vR}Q5G zT3@fguw>$%0`;zZ(H6k2;t22GO$8sEQwK%vhME3Vs&5Cj4u6pX} z=^eExBNGA=E4qh%p@jnljsz-Px|9O?vGWlCutHwg`J}5YhdvcPbsLk*A+rWEUv-6^yzYh5%cg zKe__;oeF~Jz%SMQ@#cKq;DRLlnUJt>cHPRpCl_G}G6olZdV&Yc>kS-xa`B5B&GobF z-?#3z$#~vu^~wt#QZaI=$jD1zICwm;L1z~hXZKmi@v-7^e|1^DZ9!pJ%;{T!zJu4& z85v}xd2am3Z90VYR*URwH~nRaGAFUxZVUSbS1NQ79XbeIrwr!m@gL1xD02dZlkA^3Oc z_Lf7WlQH6-+CpV0>>lm1Fk1Qb$-cbREy($zAg!T}iCMPmb!Z27VxGHNQhHFhHCRTj zCwiLO=cuP##e&m@(_-yP-yujBUo`+T<|UxFaao7S%3kI7ebevkecgYMR_fPt-^cR{ zZoj?8Kl*lig-?k1uz1QH-7Nk{owS>9V=#i^Tk7$W!*eYiKFY67oBr5NTk3geS>Y(U zv-ibk<3EgmJB@evJrWp(xf3SBuv8)^bm=qRw_f(QnzZ^kTyZeS#DQ_Z^>M^*9}4|b zy9=8ElK)({BKpKDgzG74L;?;+IoN+B;`F_Xt;5~xvp;u3FDK2_J^P$Cd+lXU&U16o za91}ja1|_0XT^mqQT3zub&+TPN7Z}B_1yOFp>p3iX{$MZOA#a=~) z84jCmSbzSM&wvO7?H{LK*WdVXY;vl_dZ)hZc8a>{W6^B>HfBxGW&w`GaMLV3q+ZH6 zI;^2@Rms(`z!Bbc=;3iqYxXxwx3O22eNJZ>z#o&GAN(}1$8Y*DZbG$M>rMWh(%8@|Z zPA*-aeUbiZW7O5Xy)}&XK1z$gJazsR5pIW;o9f<+mvJzcRR`D~OF-b%PVHzl{ZZCpG`&_&B^4kv0<{8sl7CYTj-|R>~1hH*Qsi%hr zC+`xyWP=lH)@rUjk%kf^wY_y0q56w%h=Z7m<<*BL!1J;$kMgy0%e%BtzN@d*RBctJ zdN%*j+A|cr^;`(4BzfX}ZpOcP%0r89A$0VuY836y4#qY5edZ9m4V}KI0msvXR7BG5 zxmy>e+5wlOo!FF|b}8lhV~OhsSj_QP_H}Pj3Mv<^3jk`+oWyxj5>=wx*>ziJn+4Wh zb6568$@N4b&5lZEXQAYn%32s42iB%tFHpGNOR$HJF9U5UL0@wxtb*G_YBptj_hx5_ z`Nkz)_sE#)EB!UiBEVi>Kr;p(2m?>U%|d$IgnQ@GC;~ek%Ns1?>a>Q1MbvCTs~nu- znNE8gIFH%`w?==SFO`}fuO{*+k+|hlNtBurQ%8P`XNu^meMEzBVVpIkpu3N(zd{)| zwJ`j|BHX8B&|7BX)IMDvcNc5(=hfYMlHONa&M1&J=KqSst9dGTSA+7@i-c6b9%f=x zF8c0_5KjB6lLL*!tN`I5&}H-!^Q%RO<>Q=O;*K_7e+BAj&6+jEC6Bpcy-abF*}iVn zb*@FfnE3A4_fY#5SIbGBy5V?Sacq-Ud_0uOZYS|}!b+&$u4Njf?fSPIT1I+4XZyaP zHvms0kF2En$)mr%bRul;U~(z%Q;Y7ct!S`P$%C}z-U9xBJ&Sf6WONjc>x|aU(>~%o zA$Lylhyez~EAq1;C?b7>JRL~n0Mt+y@`O~#+|nYs-C9H|^tKjrNc}2%J8Sj-DC-vC zqQ(zeqC1!1Wf+HtO)$W(M8A@opZ*}Y^{(0%vX7)eH+Sp|<%EB45Zi&6(qW`Hj|z8C z@S4&K|FGqTkk*tid2hWg5v{_nEoE6;9CFL~?x-^J(E7QlNvrLYFe%lkB;Q929jcro zvIPzbkAyG34SfCPe^|iJu)k*oy(O06t<_IpEOkE>qpqjo${Ni1qE^^Sz8>KaW4t~& zQ;uDqXNJxcgcB&D<{&f)#tn1S)pH3LZm-s#e{NEOi--%U)Vme#vVHtl3pQPRNA~OP zGIq+%T9=>K)yeg^B7XyYLiyt>(H=@_bDb3QU580{iq)U*JC%M>Ud3m}H{r+l#Du%* z$!UZwTfTg`J%lMuX(MP;LbuwqJN3tdkN4Wr!Hz!{KBlYdK{@9w@e9IBJdoj$sn^a! zjY)qPK86Sf&WpUYr4rB+5^qS0F4NG=be6)#CF@b#?d4!Btc(*9iF$I6_pgX6H~I?W z4-IyHZ78Pr3Px|%GTWsSVIbHiwqA|a-q*-S#HK)7ZId<^JNrEnq557B-5&GHSqy{6 zJI(DBx^=qN$~u+@jW;RNV+`FEXWPZh7NCfV?;9bcR`LCfT%xiR$MeIO**1_5of!%O zAS34-v-8|#F*EeiTH%2v(=nlDohd#1+4RA=pJzfNYc~~N9Ey7Wnf}Uz@XG2)*EZ<3 zSf;;V{cLY&z+b>jA9E(mFQ-74L^;jDGsNO!?u0G4NHysNh-K5S*m&Cy0i=z)V#E04 zJfH@Z#h%D7?5qMicp;K!wtYW)KG{R=Xx$VLypO(*cxawn{)><2?O#=8J|odh_?T+m zeYu=H>b7Y9_zITNdbNxKZ=TGB!9vSiH-e&TQ#;ytcCdZP6Pwfm+wLr%#_|Vv-6C4?fl;_6xj>#-3+)hWh43`wz zrY+98FItXINQ)KwM3~TNNbKH-6Y9y~^OMa&UPpeth%p4xm{?<1@ikkHpipEEDZ8R^ z#qJ5E%UqI~t2EFfTWxsT-p=n!evbYIZxE%w%lFm#_r@z9 z&Ym6}cr%X@s1t50-V^=x8SkVP26%=Y6>2+)zK!6db}#!8tR5-}<)!w$KwVXTE#c(e z%@5z!X$}7#zgTeuiVbeo7US81~Pqy0HUfHjlCY&a>sop9m2=>{O2cNt!R>sURs`Pc&zi3%~GfdItv|uf@!wq%<34 zr^Z_$njbkcdpRKD>BQ?>$sQK}qQirp(ej}7<@ZEa$Ftvt5^r{m(=C}Osd=B@?Na_) zls!?x_M}T++Sm`zE#fjP0SEc3j}Rog>7t8oK3SURI%wJnJpD1SpY-gX3D!i^D3(9+*b#(Fpm#6)-8_k8aU+Ch)-D+Ne5{$*r*0@SMKoY^L62#DLcGKf@fmr<ZRqNa>?F1)4e=o zCr&G-@C}TA3#>o_yl3)90~kI zy6Eav+jvCz)`3A%JLLWnNxV;#5;6-T-lZsXGK-SQ7&PhsN65O>WD&7eX}{i7c0iv6 z6H%vkf|9yP{5K@I$FP$=AO($z1JdgpUKkqw0q&w@&cWT(B%lQ1md(MlE!_Z_6WHw* z@X|4W>V+&=Gk2J(;_G^9)~PT^1xoKw+heQHv5Ll`Ry3;@yXkQL@c(K`dZ~MVa*EYJ zN8gS2A0o#17{@F@dDot5B;3g#^d8!O&>gVT9^;T;Xr~B7@ByPLY$gG~Ki_&di#;|iVXMSAVB9n?91au-`p3Hwk|CV^p%x;;X=r&U7pG|YaBPA10x)HyO+?}7htmTV;bqpK7Z@zB7 zcugCtc^}x()Xlm}Mju4#buLVekr}X?jo17?VAQnVZAjx4xQiClpd(0vl0;%Ga@7kD zUV^k$P(n_EN8lEk#AiIsbA)G)awVq+39(ejr3W1C4vEu6h9jNJycOh&e~#oGwEQJ_ zv&HQ~=l;@xjd>@WR|CkiAqg2fK(}=2dOWFU`1F0|meQ2E%(&izA z9s9;>BT!cDU=i=2Wd}JB8PQj7H(_KmneY0v+>e~p5C}DDG%oVVynTnqQ)@GJ{?c#i zT%ByI{Y!Tz=&>ix_bK0Oe^<*K1%x4Bj}22tvc3vwVi2@)NwD5w=&WH97DrmGKVggq zbWI%{#eY=>ZvhP?IWUuRt;(U_aDINCsDjwJxmj0OBon0%Jv`Cp0{b)zI5DMe`O5}C zgc$0Nz!$RaZjgrNGpMIW5>$l@>XNeT$D4+sMXE~{6iQg3U?G}r&mufH+j)UG={-RC%)Vfi>Xc=lbx2_tZL zqcOJ`IzDxh5o=Jl{*f$&B2rwdQ4YzWS(+gFH(sZn&_NIPj0H4`V}Bjl?rrzFcZWq{ z51A9{=^a^=8N6y`b$~ASgTjq2X(q{nE~O@#FcO_{1d74W83O;O`-MQ#M<(Dw11l7p zLba4@6!30V-NU zbW4Du$(Rm|b-0PTj$mygZ`kto=uN)!|9~*x(6@z=rgaTvlOmPr!BTkQRWzK7$7^nO zKJJS3{IOB9eWU(NY*D}cSya_AUl_>xs-&N1!2(zHt}<-j7hn6ANWQS)k!?8C3J|z` zjr!hRpFf#K*XlvTsI9s??MMfWktn?Zk!1;^G8KnN?nhio#SJ@tN>~XUNb<~`hiPVh zm#VPe0wVNyXkuAT@4rot>+^14%=^>Wig^OjGRMPv%QsNGAoK9~Jyv(;~}p4BSK+ zmxa8wEA?QV7(iM)sCu^Zb$D#&-Ptn<{kOne@*lFN1WOw%uPXl)8A<5+1S|hjwu#W1 zA9s5#hE%4{m0PZ(j_4dvs}^k<-AM8BcUzjXQPehcR;t9uA^ndY zs>L0ra}j7B!+I`x8Ls9LzGSjz*7RgArgGaTai>)>ew17a_aPhq?BEo&GLj@y?~oO< zyef8y#Azy|x+{v&D%wDKBSmu=4U^V2L81C8XJMDNZQx$kRYYc*7PF6{{SxrL>aI*y zq)TzK_0U5ZU#f~FJ8b*>dc2p}BT6ERlyPn9)#7_FdGNQl64*dA#bFTfe6s3X3? zu@+Hp(PI5N;@(y>KLx`)FG!N(Ptcz_3;RsEc8gA2SfiyMTlNmCWpYe0-(3@H^=?%S zjl5~R(C2iP{(|F|+flqd`-?O4=WGi}0T^|f%a%H8U}l=Wo%kAj#6`y0-+%*U%+5oI z6!FOyU-?`#ZlXvo==T@ekxeWn7vDC(~k0Pl&G`?)e*@|;4>z&j=I$=0ui zK_5pitHpz#+RxDO!(BEv^J{kH$`R*8SOsP#@@NI!j-qOY)rl5ghEUngExsK2`i$c0z^oqnmtx8&B+fJ5{< zf+^eE1Zuka$TU6N+O6Imou37|<8Ve6aXxtXuzu3G@(j9wm=l{As8qS=bjk`ao`ZXa zxXf(ztU;^Qt;n)Hq$1mooj8!u{BMJ0#>!U(n$cm6jHDs}I?0i!b=Sw`ii5k3T4PdeCUWL9Zg`(@KN^#2|Km+!`w6{^z2X`lAnLHA}3b^Cb=N3*{`rgR)Mw zJWF0?6>XLQ7{_|gej~TjJ4@{2bB9w$-mWF(+{c__$+epvjaVob-xE>B&nP092p>4G z&hl27_O{l(qpeUN5UJtAm?f0)JI*DA4noc6rVc&eIDV3nGrY#~7q8^4tzvMDW9aDY zK2zpmf!|AOIjyyY;@wMp5`OxEs_C~}oV0vsQ&7`;U#m_n5i*wwPh)Loz({ zi_op<-ht5XU)PM!TwEe2nY8u8uDlOs!{y-*THoPtg$67se5=2AOGbOm3z?fCeh=^w z)Mz*&pY|xa5x)YTfJ&!MVZG16ghsE6)j;4P zwcKl&_mAIKaoI*p6Uz}$mQ5cH{&R*X#VxK}gO}C0<4hfoO;mK1USxEK_4JP?tk+=I? zCo!P;0ouU(-XaS_0g1W7%AG;OE=CVymr}-0Mo<0ne^m2ldoh!Kvb%026E%=Kz(Y%6 zLMIZ^W&eipckykb;it-+J&*5PKl9+Nk;?rH-W-)RE!A+!~4@9Y%Z2a{N+70lH*bAWUoqs@CecA;h_xDVyBhs>AXg4EZ zG)zfx=h?klP*$jXu<^BQo<%n!Ey(BU>O6Q;H@(b}pJGj!7d$!O2XQ}dEh{Bh{P4QU z{YA&&Wad5eSM6!<>{i_Akd7zu{Y*ckk>rrtgN2H8W`!-cuKIXYa}-9e zXs6oU-5>5Dsnl8wP5kUi+hcS&~^YNLHzsWL)jy zk#~o@c!|0%Z0WW$J4(_uE(y>9Z<$`|OuZ9uhm1dML?2Dmu0P0l^{=yqXdlTqDS+V{ zbZIG}`sp$&;t@nN{-2)hE=5iLwxFPZ->x!1B$j`SqI5%~0{`qxTS`-To#QMo|E1v? zAIs}3C2lbztuHNhI=}EE<>$Y=Fy5oS&ku3yxCqp1PI;tkt@`TaqEI~Oe^TwFmhNfw z?VDb4;s;a^CgXu$iTPYDT|KUCzoc!nl9Z+NQ4QGNisgTd2jw5G8r=)zj7Pwb5?6NG z_SlSvph~cgby>O%fUS4y@)n7}|K-DDRrE+N7*Alb7<+;6;hPQag_PMs2(tP0hGLpTgd^7uUnoIAOS;m)=l)vN{ z_%AunSP&3ee@D6-njS9hdgB0bwJgW^rmDUh>1FgZ*Ja|8-4tW)lE^VlOILy`JF>wC)7b!qags+ezF9E+9TaAM_U{2toi zt8D$^@0MPfW9?eHpG4hk>%U!0#;`;9F6Qx)_lF(svz5QzpfD&I{=pZmkKK|&EK>aE z?TsF6@7!J3dmyBwvDE#e{9nLUQ>KpfIoC)Y^0ofuA9nuUKjrit7h~M+yjx5<)nLqh zalF6}L+l)$!yMgtPI_l}zqGNVvIv0Bb3$Z}AXSz2xlw}hf2Q@fcxW5HK47eopvI}T z5^(6bfO&~@x`RKw?Vni&?MSwHwMpNu`&*__Z(rt&dwzor%H-5=vq7nlqA-(ySM*oP zY{aG4Q!aJF-P@a+dLs7W5r~*ZS2PjUQK(dQ`h2M`!)u^gce+oV<#jPIp9|KPs_HvL zQI~UUsR&bDI1k4Qq83dfwdhWyTKkfve6lw#-5dJSVQP7>c{y*mqR|2U?yj`zaYR z-Um_#`j60a_n>X|-XFDsFES!<-N=8(14MQCAB=>4POv*te;ngIowLPzjk)W&%FplH z{1!4rCue8F%a{3foegAnb!`lGT}re6zG@TpWb3<}?FsXx_e$NiB;QmokK{OwJ<^j{ z#PW)gvzfSRW+JLumjyPKJ0=>}K&&D_c;POD7?{8lM{g+iw65q=eD$JhG!1ee@%_|8 zZw)4}*n^qNfGFuP4<_&K?oMD6^v?c0gM;RF_o*l3_fWR)+UJ7r^;dXDJ-44x+s+{? zGrrkQo`Fw6s<_~iO3Bo)^$9YP$Q|>)3w#>PAO%TAA=Hq0(=b+vfof888x9J)(z;Qi zwyNqJnKK{;ghc8}EcrG}IWc@($#5C#thQEX%&fazg5$oKWIJ=u!fLrlB}p5G%*cx$ zh4aH=kymf26-~Hso^BXsp?d6Lt?jp8do$1!6LeeDMD5G6g2K%LzKR$x+DHVpL`6ng z>e`(Qg;8{4!i|s3?oEGPjO*w31V1&48>1Nbyqym3;{4m};e1W{|2@DV51FCFgeH>{ zD;qDktj_}CHS85zkNY_aYtEWC*?thdKmRsSu)A-6_V97TtTy8XDHJz#*-3X<1?;bqtm^MvPTev%=r$&T~m^88fQH9XR_GQSg9 zIu_*BH=n{~v>EJq(sz6Kcb(rO&+3zOpX8kb?0Whs8)ggK>h9s;VbA_?#DSCV&SUBI(#pB+ zs;9Q4j}6_|N2GmPNXI|nN6lEM*ReWI6MfYL`tTA=kR`&$@}fHz6DqW zECHbmF^(^oiCBLZ$lI7Xx6-*IE_wUKg z4|boHP)+CRX2t8ILN{Vkp*m7!3-%>~l5*4v>fMOE3?k5*(T^3uhCg1fPn^{#e%bDY zrS3eHp0J0JnUTE)3$vN1kZt?F@W<4QMan`WWYCp=vSV_ETMh9wJo?MtK*;5 z21Ops@q%yTVUk|(aLas;LOe{jjl-==bbE+ay-i=xA`&Hn`z6_9{*xsBYB~x}0VsC9HW{L%K2EK*ez)4KhI(#MM@R=6}wyt_B zweet+(N>HSGhDXrCS%ETL=CLwUe(~#*PX-!KrHt=^G(3*AE2ISM0}%Z08RmU&13hm z1XMbc6N2f-^}4yD{n4R}zfT=;b|g77rjAPTM$_)kJ{U^Ye9z{1rX`rAdF#B}Ty0g= zF6=Idb2NAkO9dwXSw#uIpblh>Pj`BkIztpM{`1LkGJkAgcVvGCGRkxzlgv8et+8dU zgDGB+2@Uc~#zNOx70uIzI}D8qZtHCkL%G0{eejYcGed`U_+fXTO}0ts_)fE$^Dd=q z?|JiPcg5n{lx0J-LTY>`uNsh>+Jp_)e}s}YSz2T z-3nqioMufWt00HOYn?SS;e*VYy5=pm=g$k4%(p%M&M7G~tJsn=*ng9fV~cuprKq5-t!ar@m zlF>`o_XXbvpikb1`KnwCj-}Add(!W&7{DO*NV2! ze_bU>RV^zSO>z$H_-_SeY{TI%9q)L|fxXO#1Jyy({T!>G6(F--R}b2kQD(R)CBlT% z5+i>q-DO_G>ZKF|(yU~T)got!kWS_S`h69|&Y5uYM04#WtQ@=Cy;}J3>1VsrLbRw5 zbG4K29t(}DN$bEd1UdBM+cwS(%-gR$)CbUTMw#I<$$O$-;{e1syiC;CK?~hGy^m3@ z&5;~Ya)rQSOBchi-jv{X=^*50#v=Hv0wPAx(h1Oow8VDC(y96teHe}CuHqJw$z2rR;KR+R=U*&NfLnegcr=zQcr@x7je6x-B zTJ_}Y2_*>rQ#K#BxRheRgP1LdL9#YK2aV5;^bskru0A zKgn`4p@Ej>W-f9TJ7J#o5U2as0wU%tzdv547NaB$l(Ytd$U$u z6U`1W*SIF+e2IuCZ{ntq5=1FZ*tMCSYDLXPtfc8yD`2;ew^$W1ldGG`)66+$TF=jG zFFvAs4`CMh0Xpxbts;!nk>^>ARudRcLM#L27E&D^#Njl!|9X4zar!xq^rNhHoPUl} z45-WVQO3x&MG)ToO2n^&g5(jljM)M(lSl(l>vV@gpPfoSRNQAS z?8Elvb?mr}3#ppp4KD;~H|eo;D7QP4$rd&ptE0KoAB5VX+qY9yw*|I0masukP+!H6 zsgLjRF6~svN^kBf9Lx3utW6*sgs^yXCYncH!)z`GI^{_2zsARVk>vy?2+(< z2?mPi@AyxwlVcP>@_7;p_L`?|Xf?>Y%Zau$9wPux4x3Ce537oN7sS&< z!*;UqT*HM`BZQS&m@btqA-29m=^zRv>W=%u%E4o46C*s2n;R2($~Uf;f z7bnsil@Z;#jPOYY;4jsS3SZUa%nsLGX^-!2li+qC`<+N6$v`39TLS)mnYRkWDZX}r zu7R}&HqXZJwu$@9-~PD3i+74H=Ru<-hu_{Mg(PGkIV$crzt7Q{n6`#&4EKXl(fGJ@ zydV|Og^~AbxzLO~LNQFA;c7<-(n-9Vtp7Ax*f+0cP$;%pk|SxFI#!8phaT#hF?T|e zb)P7z%4?tLa5-zNyD+-|WXu3=uFZC{=rTZ5Ty;RTg7-D)PhzeXwELdix=O1Qk3jwW zCr2EadI|8t3NjA~TWCV35}Ouc<3%@ZBvx)0)6E)fN{05Z<{nO8GdDRtUQFbR! zOSsy8dpH(xwXIvf9)zR=-Fbm{y&;gN(+6DGIilN+T3(QI+!yo@ncyQM0^};9n?Ii_ zl#mB`woAF`&z7asWhGzL$$D0&Sh5E3+ZB_a$XjBPj8p~)FN8_?_zLY**B(-aBM6EN z+Kh#@DTiP&HW9PH|7S%)Som$*JUl(=^eS;jd~@QV0q8CIWlh9KsWsb<_%~gInKsni zMD&h&s$_bk6Vp})NCu$uqZklMhO0_3e2dAjwB?A(3d;5_%0utXRK=v+Rd;XDd$$Zn z9GYhf90z|474q^O# z5*xk87TrKxBszdb(bc#_y0hu_>4l75$j_-_@KLJAso~fa#QvGVx8Gvu;$P~@VMz(f7%%@cr(XGu)sS7vxP6IV4?uwOXL*7THjN7;0&j zCN`=cM!U*h>8ytfEfMGA@hgB~>K|659HR(nYWpk>m5Of#T`a!(Dhnm+{FpAAkn4wI zobj2UlifJykj+{a^)obSi?x5qB1$g|zP8zWyAo;#WyLN{HCZBc9i9ea$Ah5YQZYqj zd893BPT!8%k$5`1Q(c3Lg=3w>0hrzf)y}|I>GZHsbc~(fC`W^ii5#Q??NYe$lzrW% z`m_OaCtWwc-=OvCgSByzb3G=n4ZCY1&b)jBp`QZL$Q~I0p3jFpNs`q_iK#R-pk#Gp_IBszW;?Y%vb@jg z9e(i--YHeuSFZVqKy&L1dw$q0_s2*${=z*QKgL2?=^dW*f1}RHNb!2NVYV-%7jjtMN&8c*3?H=o$ zDpWe5Qq#3K^3**Iml%@5e<-iup#?j-KXa1GkekX+Qx$SaKP^QYjfY>*ND z$7kao{9F{}GQ#C#cPW=$tM7jM6go!gra&=Ep)mc_&_+kVR+++_;ppSm6eDjqlx_UQ z^MRz=kKe7>7tkJs+!;ER&WUAdLYz1nQW!qo55-MuZVtf(T zQap?AZw0RsbN;PId(*x3+ke_?n>ymPtOFPL|JF@Mz?m_}SI4E6qKY{!e#i#Zo;w~b z#=`3f5QFw$=TDYG7YFi*v{TIm?ga?6j7p_Y-ZM#9b;!N2U&^;xe4jp}*P!X^*{R|B zheG*18NhQ6GqWGyi|bE>nw8hPG|2)NXi7`#g49WD*K%{q2RLcm??k@F-5dl?issnK zpX_ofy7F58W*;(h6t&J^c1hC9;-#jM%&olil8CRw@v-H}aml}Tyim_yiM6|22oJC0 z_0UsQeG`3Q^n%e{Y)R_0{86fdsrY|3Pz+L1oH8s%q7KG;(H`BBmwcm(P zb5i=nG8&i2jW7(3H|AfD*GjX6EN?b`uqEq4V(#dJK~ro#c~1Y`^p~>n7?mkMDf2yf z11U)FnItSV^)FJAKIkGsK5x^r4^&cjw^BcJIWS=Fj47>X)o{ft?RPFw;@qw7D%l8o%%*7GpOtp5Y;M9YdMbzW ziZdkEHabkTgk6t`$7ML{>|2W6m-|;YnH>MS9KWXHTsY*jh zNtvw_ZCd?&#Shlan*;2#^HA3Om+$H0vjG#A6-m4ml-2CypxxIKY=7d-o70sM+*keo zKX|JxW#8PuApU-*B20-$guFYCtuNjr}=1 zT0ov`-4XnWnAm#UBXGq1co37^zQZ|ZO(x{e4(N`}K|P*&v-4y@+W5FFiCya(JugAc zHPLtDTiEG~^(snA)y!fomoK_w{P(|XK%#Que}!8=9!C~``>ono9iL%Ru9hbn_OMSa z;c6LjzI;JL4#gc;yc9=8y6(S?cm%nulqQC0vTYv*gLA~6(8e@VfB5wsE^>k`cn#L% zG#T%VhZ#1f*F13MROcy+=BX8Y*_T|OXz%;Geplix+w)`8_zz9pe7THP)H**EhPm0V zNs~CweGSQm>jC#uwATL%be-wKxoQjR;dMn^edQ6;JMoY}@6HrgkX|#+_N;-G=`j>kj@e-+l z>ngFN{-(ZeKZ9hopw7iSRQEHmo~LDe1$B>U&eeXo=09oO%l&|3;HQ#HteHB384INh zpxVP;Gr;0ROuWCt6g*OS++)pGgkWQFncce;;HnYDqn*+U%+`1IR8vnT+4IY11Z-I!XHh_NT5pcJJ=T70K05 zLJVfeT>H!lVVn8-MsPN?p#NJ+?HeYUlJNQYl(6)_e2NOJU^Dfn-T6EFSStKT{(3|!@@!BI(z7cfubX#cs>w6Rv%-`Fvx@8T zJZ^y6fI{sJ!0_*A>y{tk?vY4%~8 zYhbAKtX*-*VxSvmq{8ek374Lb_M3wKN=l+bsz^ohlj>SpF{0*8#z3px`g?nOn{scZ z;HDZQiAtQ6D;INS`eJ?k{4^q5Uk{QBO3&@jwX#xXUa9FoPtm2O_**w{Q$|%MGP@-% zYfZX*JKeH90e(h8VR?AB&)H;p|CSLrT~ZC8I|TEwq0gNc-xzn7Q&E~8tJWFrlc_45 z8VjFTO4<&DAp8FdLDR0%=L+{#)NVc9-MI&ZyssFWTqXy1s=Ry)#$$E+wT) zI4k2jgvQ>hRJN}0I$|}H}keVrQkc51SHd>$O-v= zqL6Xz(!lO&6d2ch;p5s^q7D#aAsUHqU1es z`WoVE`)P3w(MuwUu~8wNv!=tIrOlL#Hk1+cz1g@gSYU$DazZ)=3lCU3maV1YB zSSCg{C%s(@gs*ar-ey)-V?d7A+TNh~bZ(!rP1<6Np25ckbNTA$9#|9V)A6Wv;RI z`WRFjF(Dy^bw?Nvt{x5O#i_hv4s#Fz0fAL^N_f<+exPE-H^;!&5K)b~jx9L!) z@t#l=Gbe0y)pW2=amxHzw#ewna9PQJ&3aayzCn%YGJo9G`QiN8v!oP@a~Nz=M+s|F zc*{j5*ktzzue8(0D`N$o5UV#x=pTS+g6-SQ>kJ*((XJ3dg<1d)4AEKY5DEV~YF&S> zp2>uo$=L31Ln5m0c^5ka@2du_i9WhJx_LM(pnQ9diX>F3l6N@iaZ!K;g756}T;G)HtX#E1W2pa-b$H0;4O5|twpdZ6@VGz+C z9vT#3#}`OgzJ{GIqnT&?AciM3;R;lfd&>s4*(xR`CIW(jb)m;SZGU$hC0PQIw;Ekq zQKpT&D$xE~(iU00Ulya4788T9HGJTw?^Zn@pKh11{&{b7Y%C1~TgaWC0G+FFG|uD{ zYb=cn{$SGfE-mnEB)Y`*R|86+)wTYFYM?$jUkGI@t&N4 zA~qj3Y4(6-k?fvG%%4%jt?r^y#5z|URQYkO6r}vEJes(;LBzPK@b}S`_;+R#J?yd3 zWAw^+r2K+Fp3TElvHF?hp>4g-O2cY6RXuM{4)52=eJ^`N!>8rFJ!QXKjD@1DDq<_p zwbVUp>Yvv7ci+a1%nVN&h|hIv%LZ-U0%ak2^IrA+wWz+%l&;}8v?D6ZV-1G^=Pq1N z{*HLshe()v{J^c-*#L8vcv$NS`VSQ>y5X9JW5|Vmby4~S`Pj)J42;X8LPF%whI|9x z6`5vQAHZ9mVcBk@r;U_nLS>@TB-uTD{`(meF4=IAeI67Pk3viQ=i+1^czw{07s<*j zz_zd-G)oO`(P1u?#Y%FDTZMEj=KuK6I6S&6{xCCRp8j^6P#(Ykh|cRsUOY$LjP`FkZx62tE4d1kP>|A_j4_hp9C9T_58r~D3rh|qkqz> zJ$MsU^2J%?@ecV|F3ru&fVBVKKnE5&kPm7rf+U&yky6)YOI{~W5_WoH(M-B|voI=@ zGUqjQ@Iq%op;Tsj2LCw$@3npmaqqPePl4Vk8`Jv}fHrObCjnz};pMM8t~W5!iR4z< zl<%4YF`9dikCI^W&NVNeJPE<0&Lo);qh_sK$K)&Xn24?>hHv98h>zIwQD=iB{3bOwlkO?bZlEDq=f47!+ zw${p#9*`<#4X*!Yl~}pe^LUqi^)~!3RIy}=SDufsiovDG7X$y~RByp!-#byd_LOHv*!DbupQm*7L5(GaKEhW& zu9JqI-(vzyhNglS_j!El{pDQuE>)?_MBDU(7q88>Gu5s?@xk}$(@mRPP-Ez zqW{(8JN}b=xZLP<*~$dQq~XBM&p*JW*A6!2PfYHCfAMffwTOI_XF z{W$O*6WGBDWQm| zLECTM`0j(HD=eHg9im(&Uj{lcb4K4t>yxmae$qaoEt=pTY;^SB0TekAYqx#;@}&kt zYUU;tq%%ovgH@)|m@gSdQ||9VLa&-lGJmD4d;*KNjYcnR))nk)D>jnxPxIpI`fND& zT*3XHA&UFhZaGvCuXN7#zhCYx<|es~gn^TTm$vT@-s3t=6P|T2TDa%}hH~XLIyXpt zfBNj1q1Ki|S5KW9TP`73m93EnL+6NzFJI0)=05TbcbA{GmIxx7{E90k_13p2vyRvZ zcK=iN(xYfMbqV2gkpkUIpuGhCLeC^_%{fil?PJJ(B z?=tOE?)5!hu})?;Jw1Hs`t>Wo?4B_f-8zWB&^!hTg9^ zF>2kh>ie*3hL{KM3sl#%X}bZ1Uj5c^yWvKOcukg_@?V+bu$a_3Ap)3cEnOo1=sIs8IYbyDVXH=nEa6#%h5N@rdw&z=(=))K&h$4n zHYzGB?;n$(J;g!=)OCtcX8%=Y1^UI8GZx;ubq&0g)%RoYQff|;vF$mRW^USczX4lJ z;S6bXx0ajMVmZd4{N${YbQt1(>iXielG5RLCMO}Xy-svU&f}l7i|XekDd#xd7uHN8 zX?#yXKk^OT+`ZVlA!zGTTHe8NY(IQWlPLj{BF`%?oAxT4TKgG)54VraVoE&KebKGR z37f*MT%`WF$>V(2SroNe9{mHYIhyb}Ne1+y8DWQEbqlRw)WDa?)iacRnP&X^o( zjm1x#N25k!iK3$7&y>)c?@`p1UV2yD-1Oqkh|;7g=QY>G1KU~ zA6iM8$$Ki!HbtUo3M&;uKse%0!*%qn0f&vedS3u;ZFpDrWb5%WjD@6EbekJdAe~Uy z9~FC3k#7LrM9dlvgk`PQZ?VV#TONw}v=h((J{S9EZ3DAWrnnYI&?l3ZU+YlzS+>gz zwioE5V0f3?29#(Vs(JRhSHRrxt=dO(BOijTMp*;|?qlzomM7aE58Ita){yn=wE>1GN8-!}4->rRERjAH+|fUQ%%KioU`MF~-?f{a3}l*v_gdMx5PVtox*Whnw;7qV0;+@Mbj?))#Y4lw!VV=GUT@ELZ31U`r8U7* z?74bKLOl-s|Gv8wo2EpFPDle3EPbI@9YZ&07qP3>~{=cM-6fw(3JyDzBLp z-ARh-DrbAmb!jYbBCVl$SD5EAdWNn@a~v@!vdHy$j$UA3z)ZXT3rcG93ZGZ6VmIy8 z_*dA0obDjX>ca%er=HO=A)%??LKQWK-aa;w780r)4a8+-Rlt9k`-O6U|I>A3ekH3G zGpkeD@etX)hPV(jAb>M82=DwkGY{?jR@{{(2KyoZalogqCB9nQpPDi|sY|-; z_K%cOOv$e0ly%F+l%|NZ=f5{y4d}{N#_l}6=Q*%eSS&jtV z-V!soc9Dmx?9-=%@l$=ZN<^7yS592_j4EFTh*`ew%|Es>VcDve>#2knzyxcN?c??G zvU4*wTsl8aiM$P}v23{L8>^xI{^@o%Wc7r!)C#1V32ab~IwltGD72>y-vUoAxvQ~# zJtb;t?Hd>v_vOo%q~WdX^nQ8-(clL`o?$s8Y|$dVUoRKqg}XVHSv~%DM&8nW?Dc$8 z!TX1k9sPS%e zgMZXS{@8eY#>=)*ozNxoiLtAust{ce#t2Z3N}P)S-X)27%*Cg5M zphhUXbv}6?C?KH6vW#B+-@+dbpAuhj{>?fgPX7jha0mxvP_!6ECq{b~ik$c)W682MjiMju=B$KnitYKxO*#NUe>GqVf6<9O67NFmKDo6U@=-*1N%ru_yx7W|jeRe-9k9s@!5I~fo9l|l>|Nn^k z4tT8F_WduBRcKHtp_C$0l4Q2D&@e+r%N|+DPNkl9LLzQS_9`nYN>3hCWN#W|?~(mK zu3PW#@AJN&r=F+o`#Y}dyw3ADkK;H8#DhwTi-C=DA~8n|d9i-^xpIIZ)_QOXb;VqS zF*q`P%aDG!PWD`*!O(|ZRrUDK8Bs;J(A~yVUC)>WHi_>TQj$(M$4P}2#wnZpIGf{K zpWRYVI=_95nQLoO-@N&d{f-9@3Moeb_XlaT47`WYs=fRjkVy?V8vZoeKqeki=R|Lc z?e)b=tKNCIrQ5a|^6zyl2j-EC4qO}(a{IlDZk_+?jK&4h&*R8&s{j}WAZRu<86+Cz z8*bV(&(ZmupH)#|iMz9oaaVM78}`KU>nvR4ORPNhf^&Jfu!gh1+4rBq|9)n;-wq)U zue_vZn}jJiGyngInTk`r0qG8gZ0@#rR(M#G@F*tdMg5A3Ot6hxdA3*9&7& zv|b$xcr148D9_b-F4YZuas!MTth|F6D_+)j4wLXD?qYWoqvW!lm0M3r7p~@ zI+^b|YsEDmd>Qq9`HSlWKSj-@j|(lwgqu+qD8{2Qj2>Uxc?FdX0sk>Hlz=)|ZDQx3 zPN7bf)gx&Wh{CFl$AO89o4o= zk#+*$vc!Nj(?#^R13%TqX&uKUNhb`{y*`k0WkBL*(vOhRi!*~$A3l6YNnHD&ycenq zb3HGRZ>@|p{4#8s`2w&0)H-%7j!(w=k}lUu$`dAhs`FPAoO^X~01p(ui35{0Y7EWp zx_2F2pBW1Plb-@XOShIwJ6!!g6ao*+)p0Q;4|4u2bAa<#II=QxxIYcM=0$%|r_-jTdsEp)GzOpD9QIGtp}u>6uW>o{*ABt*jP?lho|3Xs%BVI`!7 zz@RYZ_I%xy;VW{}v@5-JFG6gxk75vLI+`G*Bee{a;9lL{KPI9jG-bCtMXuD_UAHk} zM(Bn&N)7R*Vz2B+dnvbbe^c$JU;-8WXtx((GsXo|to5)uu%F zo@+m|UTO)aL#bZHJkzrEa8+{fEgJ8tJWS@6O6sSfVd@$OEZxKdA=%{2L?jZo)dZ0I zke$JU%tSizaHS#E9^-cj&yUYB=b#I9`ftbg0gmcVn+R+MGqC)0oH*^jes!Yze>Yf! zgSi4EGPo=r(93p=MTB@s_}@6Gy4Ub~Z<>GcJImoW0T9}=Jg}w@9D={lX)1_Bup66I z6a{V+v@a2&dhfSRkR)@*haZa=@;Kx9z3DT@DdiY6$5ne~rze!0ye1=nw{W#G8HIyG20JeUDX-1h6}_gMIo@wqztS&sL&_^Lj*bHis|ag zyT}vSR%E`a?gUq1RAgi)u+wTBa%o74$*dxRfFxTtL}0a$tW}-)*@*%6-ZmB7)xG*P z)B{q7^)MJ`ZodtkfH#PYCk@zY=KJU83N9zsU;cBC#?QjBly(o04OREmbO+U&%134F zqLbAIQ!y2foT*Xg$&@+Pz77#UE>U9$zH1iG%w)mzOSQ-L-DK3AJ9m7-w);I-ADLD; zc0955?l~_=l>VLf|E+eA@&}yfA2U2iO%W{3cZ09~$7P!cp^e{eu`qb35FB1{PNUkc+aunTGJVW@m_bQ)swNFGEO(01s;42(ZloNK1@3I zOr4AlyZ^VVih=5$=krVi`(tXnZ|!^jqfZU&|3P2Wy>M!wr#~A0o3K7mE?DU*5h&cX zNBp?kJ^#o^;YwFwpHfVy2{Y-#!P4;h{H;FAug|0o(;0^?;Kmi|g{L^h5DG?CbAQTb z{uTRkA7+y_z!XmQva5aY==QJenGZ|DZJHtf5$gN*j&ieQJ_NHV32V396XQd3@2LGa^UmwdqYIk&>(?)`ws1BRSh6cfd0O%8>C=7~7Pz@`2br;b zFuP0dBCkQlhq)8GU8{VgBcar=@Sd7vh}y@TMPucZnrn z3{4;>AKoNsUA=lWYTpc6Hu63>h)rAM$fFv@qe5pIEaOCR{fthy)x4~zs3>vMZ{Hv$ zb{veYa`4PgI58n>R7#bm)@}4Ea=mxLkdG}2j>F_J?a@haS7f~=_I@sZ`XNuwSV5Zf zl;`~AM!Ipb@R_-L{jXiJn*P!Rx9Mlvga%5Swb;8^PEKxrj%+3R!RPdh&^f{(a6N1Q zO5q)ezuVgnMaso!U1Pk9KfiQ(J)*Rko)?yq)mdAT1HtaoDs)6Rb;1GK?u_IK5aulA z=Vmj?)^hpC1~}~N+3lN-SrOo&k$&>`I+RdGkoBgf<)73_)YBqs*hIl#-dbRfT|o-( zKUhT|CfVu@fS+~485xZ+7aq;$qw4A;BMP9=k|8)b2*Q}?fcT-C0J^)#3PN+a3U$M9 z3*P^?_c-x)EFT=o78m%z3Be14F&dA&a&iYB$R)3}fmwLw)YZa9hCNHlipj6N z->!d&X_iggq$tEaaxHgM)(;C=89Y@}5n9_LVU+GiM~PiUZ|)bq#@n z(49JHBZbS}-L`zwxv!|($C@0DQD`&f}ZJvU)zaLZNn$Qe1J+kuUz%xsGIRMsGyZ0DguFW+3oFj<_igrd$f zGTRke13*4@L~_pa?fD|kFEF<3oFptNXsEt8LhI<}NH|5{we2fgyM$I2Oh#+tX&mxOnLk&!l%u=3Buo<=}J zF<7!859%{*X@s~`wBAh>ErQHl^Y!SOM44Ri3S_1Bazx$IVwcK6n4kbKb(BKju0*KmPWBuz?pnCbC@#J@XinfNHs`* zAJ&4e7l$3*Sj!n$KY&Z@^Y*I2Z6ADDkoeAfPr6f&HbJU$Gx6^}6hriX-{GbPs@dZ{ zfAo}Dj49=&pDJ?>j%J!_w4{-F;hs14NTE}C@O01J{nx?8=5ARj=?3HH{WK1hMT^Tz zAa^{9#Apga(xp9+-q(CDyoIot9^Mg;lY-DhafTQiI&{eQCk|f(sFxULphkSw9Wj}0 z3%U_8(qMzXBy<@BqDrs%X`@OfpUW5qDhf#i?rcOKuyzfU36W3(AA?l-8Hf%qv1G}A z2WI6vf+O7sZ*r*x7vUCRGNN(A`?o;rWt!}+69Nkw=doZH`JVSsq>)^iTmil>uE}OX zmOdPz2gYCQ7GCcGx|FAw6po^I#rFVh{A`f9cDapPDZo>k%;;^GlpV19@sW*`c$nf_ zjiYns!Byx=MhU^_^K`Nq>Z9tI;>m`&v+r7`z<<5uVuh-G7Z#D7wRkuh9i0FvCiF|o z%4$J@TjcAUNTwh9qY@=4&JGxzw~hkDjlVL`V$qn9h!p;%zyHd@A&IAA#@@a zuH9w!$Ux!;!mHr;AlqUdZ4hGp0|TSbvWX)Lx;81aA=5Tl;%xR7Y3cObOrUAK#+GI> zDtoD0+!SZr!h!R({qEy37NP8fi+z%dy?;*UAt6$h9nzB%=uBVtzbsfZ4Yk^VSFb)z zND2!JcM{Xzwg>md23n0sgWd^`B7Y21pgRd3fWx6N{C6*kgckP^wOLs8(^}iQx(K!d zGfowvT0+Mt5_!u>^!raD+WH3v$ALTzP~r#_I#sy-H1|n+05+u+1FMhd=>-!GXQg_y zpX1D*%NRv{7`uSYq6Mim6F(K`*}ZE9YzKYR4ZHYdtQ&R#byWkWQ5y;iEr`&;r8rLd zdZY;e8m#5q%p`&Ozpo>nrsObaSdR~3=bcBdn$(@DMJQ>>p{N1+r4!~-$KV6wfGOjh zk_#Xj6hfrK*><5pOBx9e=GV~Js9P}?Rn`_#DbKL-d%*qTD16{k`4^P})6ugBw%lpb z)bp^gB6927HKS>k;37(}oF$cRegV}oo)V@n!_zI^0OCYO^l69@YpT*;UrKC> z)oSEwRJ_7Q(k_adQ}N-e@9Sy6snnMjkPXb81}^Ed8aG5YKxQhJq!=_~PandaR}yAh z5zWUFvYH~Xc`yUngd4$7RL|m%DqW|!KesB)zXF~8vv@N*=2LF!U-3ksJs%Y_+)Qru+ zGJ-Iv_ToW_k6gTXv3}>n3oWxU8#f*}o9+0TE+0GcL&8(j3`f2qZJ-J&k=s(dwtqMz zpCR}?mKi*BJvCtQH-j3Bd~$!Y-bc-3!?Uj(YRA-JTCq?ciPeZ=~IS@27iJ_ck~_Hby?~``pDzGKJ>8O+j*0dc`i&x^_O- zuF1IPR;_B>Hn#WNGmz;jTd_HS#PC;6b&^iHNJdY<217Jh`!?^vd4CG8MU||c8@nbD zRMDl>KGZzWdjjdu82Fpy_wCsafpM5aFMsSv%7kYC(&BEMTWHkZNgUx@Bkz(zP7VCY z2E{8#7sfz-k3o+mql|w$*g4PZYbtVq71#1#X)^IRU~&?YYN9hqf%!!;$|4L|hzHfM zAW)*;8G}o|d?AhPnHoqCoKO-pyg~l0e6Nj0|W7;al^ z$Bx&%A*pTnWi9U3ieqn7RFnngb0QUg4F08U>GL76w@+l3uBAnfmIPc6Bb3BUh3AI6 zq(N!YM|iMkm0KB&#Kk97kS-bU&s$B`8oC@C#!WxRC%?1M%>f)5(LX@25wTv&Myx67 zU~TGpJg1@TS84IY;s+( zj!qz>1Rnug?FLg#ioX&QTUh%(1!GmjVyj1;AMb0_iAs7(;t6KN9m9}v9kd?4VUjIs zj`xp#1Bbnq1g#KelRDw{XrL_Z59@I}dh{sJu^dO(n9?Z>KFl2CJOONZlr#Y5W~U*> z0l#VaRdG*&OfnCm9I53PtcxsQvO5LXUYx%bxHB<2&xTcqX8rzxN*h>pT*K)QMNnrV zSt44YQiokubtm!dPYE^_16<#;DCp+B153?6?G!V$moRHqi4SC+o2Wona;(2uZdC2& zJ|tsRIah3va8EpMfE-Es{HG-sO-&o$*`N{{`z%#v289tRR!5;?*a{Sg=!vj5G;z&H z?bgn%`36cPl$e261&~e!?{$i6)!V<{2b*8JLmH2`WCf`ssgK)}i{52f^=-CVK|8Vc z&4Gqg715c=bLGQc`oS9@LitCX^y>q23_VH6+Mt@0KZ*lkK66lwqw#`=Y%dBH)d$N4_a?(mcO(JGx z83Y5dU}ze8GsodBbPO2M-N6TVy1kHh-`)?jz6K6H{s9565TV78JrETca>EigOT08* z{R26tV9C(4s^ZqfahA+LbG|E&jM)4Z_!1i&rIgbg_N+VRxL32AZEkkU*l-JWmEe+X zirnR{m^@fW_87&w1yKg-^Vbp(S`D`xtHNKoJYopllmSwkT3CXeY0>{@g^qePn-IN-#9x-Ae*Vd$)bWo{gBIH{K@g35}tx3lkST6 zAE@1lXnN;n!VBK&wRGCrO$==VyvI0H8h3{_{$65X;P)gMEcrX(5oZ}Q9+sN-<)v1L zlP_cq{+ESOuaD}r8w{mCG)ge+kj6vSco>)PVOY;aPfGwhI-Z`MH?FMoRC(WlZju7# z4=!r~O1$tG+ShTi$Uv&eEqa$<>GSV5wsAWr2ki8t#g=9)q}DUH1G!k+%eqZ(o?g%b zugk6Z%HrzID@Qqe!2yJy0)v&Iim|t&?O{{DCO_Ftp58WC)}rP@q=e`fkLi~}NqOng zr5jh6@Kx)Z{^dF-YqU-27(3vSORs+(_Aa)1E_RT4I&wC|DzqX|P>#y^(~VEQcLq1N zz%A_U7%A?SmCyXQw4IG-FzOWjn<>kPE~aB!-2Un72_nT5x$pdRatib^%i45xFO?{iJL!|1#rcOemG;qQhPb4ixio)98b1+AzLGj{N5`xJ4 zMqbgf<&PDDiT9s#ucwoRuX@zjFscbI$VDk`DN)0j2@yg`S-xUL+0{I-u8`n}-r}#f zMcz*O*sTrldKynw{+s5I*mesu+oSWmrvF{vc+rO109E# z@ESlcyq?I=wq;MAzS;bBb>}GymUTZ>?fxtNavy7=;C<_r7su$s0w~ZgU8y>2K>xqw zNG}9;)Eg7d)&_D55SY)l$hZv&KDHru_CG-tYWa-O_-L*ZHC_kX z#35Pfvc|1#Z-wt(TMtxaNLY`PI{e;L4A0}^Q*z(E)4x zw}UGgj6d?ECgrO%d)@EY<2HjH%;;FHQ4bksG^U4i8|R;$DED(bQZUtJLtk7e76UgQ zJiuAs0Pr5y59bmJlaS-A4pw{CFQKDFU_}fUza2^`G>IL$zMZds8M%6O^tmsCj(Q+ux3yo9 z!=?Xz_a^0wJiB=fU}<>~4==9;9Mz!fEsm`PLA@H}VT~7UI6DdSW}oFVO>0EvoQP!w zh1~Oo(&E-l1Wb}eY%R0uqt-DC@tj~~Xj4iG`1J_lKRxT>@8u0L+D97Jj;{Pi-NuTE z(&XkmtSLXTk#`doYYx5lSzz;m$@^lTLjqmbfQ$5&Rj1(}RK^DC-rE#7G((JSj-y>K z%f3C9h8#RLGV<5G*CK^^*Y+2fa_nB|j?|x2>*)H`V6U|NQNwrqeuI_?v$+p}nu*a&-S`<8Ubq(n<>|gs`kKr0ZrHThiH`&}}Fz&}Qr5N5WPw+6@GIsE9G+0F& zqf(Gss?-kRqVU5l@b(Te3U4#=`o)p3pj&zxtgl_DRge0C4TbuHkbm=q+A8N|Pu8}+ zx#6?P91WX>e6M-gBHFquQ}QVIPC|F3>ILSkT_AV1=juDYoL+{R=|gP)cp7E=bt7RF z{AK~ZVJMdcIp|j+v|7^6hq94Eh5VfRr_i3m7*{fHI`H-9%eemehxsB>Y-i3K*fJgA zv+XFweCD9`Ap=jdcpoh>?R>LDcBexr71^5lD_@2C#AunPpG$vxH-eG=s-$ph%UH!)f3Mcazm_zbO8M>6WI0GVkj=YvZa6H%i>jW4HmuX%ek zl2MWhuQ8VLO8IQKeb2(mwb+-y?7GCE_Vq8Xh5P%Vzp|H`zR^Gj+H(j*l~FQ&b(jXM zj8G6X=U^Op8X6sit{~(6@1xgWv7p8MB*`MWOdS2I7^(2xso56ECNl%CA1(Xg9NdF` zgw-2HJAP48Av0%sov;f^pn4rgNG@7%ZXc6(^Uk%@=Kme>$E|jrVXW((y@Y42ycA9t zGeG}CQE^3Mm_yufI`ZEw+qVxy8rxmIJan{ZGJZ;bOzDJ{^h$$hb$%kC0r@`l2bdn= z&acxLQ+|lx%YPVxUjY8g;d4G&JKu?9b zy_?DVRL@n8uBnQMLmcU5-}XaLnCxziupWS?JfDS*uSFTpf3iypPXceeR2G&9j5a82 zBSk&B5Y#&Q+f?~(kyP<{XrGPMnA?Qq@a@Xt?=Q`TKTD)~Bk&q1DuMT-UU<pC)B_$OAl~FOKl+*$ZwL2ZqhNcI~pkmAR))fd5MDIpF;2^Qw zui!+u;afzh!+tp*47}VJM6NjLrA zmD+E_P-pY=Zw`m=pu7i#s3k|}U^tc>SgAWJH1Ncm%`@WCkOro}}JjiTZ_=~fg=?T|6^4ZuF z7wV6Yb6oJ#>nGUYkPAr~jcrW$`Rw9Os@JdCuae-o)SU3*%Xw{%4if}=;T;a*qC%1> zt10jk$7!8Ojqrq+E2ZR%oNPH6;XXCEOQa04bw za*yBbzP;grpbxhM2?JEYG2cn{g7uX=-t{}#$rVxD8mbb%?KnuW_05-#FZ|Hq4w;)- zVm9Qm`5E4szx4ZN&iwyUF5r&1^Vd0#l-`q&p)VU_p@);{%9;Du)cIFN7~U@e6KuDg)Lz|xoJR)ELeqmkue&t{ZzJjab(ek= zZRBUeZMg#c%1kNbsnKzh2+J(!08r!e_vV)<`(k(;N;`A5tVTy>cl$e1a zQE>(wbiG#Fx2wAO%ynw;(F3*7fp2*+a~xF6*}BgHX&;$J211`K1VF#*PkI+}eq3mQ+i>TGbeR$0c<>U@v$^{o3C zs5bpb0nX)zd}0yOi|W&fJ;#R9^NLjOj{~Qi=syX8d7l(@nv)PUO>(QSe zl`lb(02e(D!`gqm>R>fj>(4`j4I6JSy(dxVh3!LLQ5-pF*X`5X?{HO@JYVmdKDs$0 z3$~9qeY6kOoJhzS_>W%|Uwv?`^Yq5ea1OE@?feFwKn)o9++AGj;LhB|5)tM`R z=nV?|2q1^$wW!@^W_A3YGiXxkZ&J-sNmLm~a`9X~O%H3@>_1GrJH)6EMY3i8{xIFA zB+mt!tk#3D2MjKDCm3a*@tWksa}DFo5?~E<7N=S@`fP&Hm1lZd@V?x!-mR{N*D*ar zFIoK*`Rp5qPoHEkhGGhcug;1^idntRvjtNQJDfijBzK20hKRBM5tQOs} zrJR84Kzl6FaEXhNG!oh#2yUYu@YYZQr2)*2$;~zJHDMas!~@?9)3NJ2HcW;uy#j*E zJdgJZlBWzxz0+a&Vj?r&k`+ULTVl+o80sWHpDnWAPQnkCSVqu;dB1tw@WRWh`KQ3L zT5u4jk`wV}Lm!v0RCZg{aeqIf7ab9?pLCQ+mlrIzZp=;1G?1t@AHYq=Y`7gK@a|u2 zs*dL*6=Vrez~@tQ>#_F+8haFSz3@#b-1N1BUqvukZoxmiwOFZ*9g)$|G|j#Y3##T) zYO&;!K4=v|$UBYPjOexVz$e?G&*Or$m^i~#!`Xv~1g3z!UtH~5)|PCtIu1M}rb`^S z{vF$rL|1)7EK0uk{LOUV&m(POc&ag3#z|Wj?*2IQYhJV6lNB2yZuFp8#EkZ&P2p{ z&d1GjyvnxXB8#E`2&6xU@wEJ5cK%Vm@| zZRpAl-3P{^)C#hNyaRl65&t-;k^kXkfho`FG2pk-GV0(n9OK>OL!my2lk0zb0Q>@3 zac=#y${A^CngpmIB)?aYkwmCPatiXQz=}H5JMlOYz^gfEM+B@T8Vc*Cx2GzKzqiB% zc*b+ciEQ3XdKlz}kcWJj=D>PPwD4eVqZkV`ab@9);jPbh)On~+B<>>V{tvdn%R_il3|pb8Jcc> zk*I}9gPSz7z!3oz*8kbFHGWs+Le+sdYNIaJHZ%-_aaB0j!6jL1qTL-vd1n%*$_Vg^ zQKt!@d&vnqV20nNH61dulk2zpXmvNKSKfMiVWLrF$88Hdcq-Z+V?QVZU76yBz%kh#?g+Buo%9c{?Dk_>lO ze$s0SNCr^46~1QJ{95Q@i+Kg_wvK~U9iF}BTwR}Yz|*G)unEJaMDqri3d-jfP!U*w zc|$@81_-c#S!wb6^0_cAEgj}RA1z5Yn8-*0!sV+BY$OV<;Q||B#3L?BhsiEWKvfrc zPMhWf!S$j)h6n#x;i`4F++Iir)M$+4W~gx9H(Mj76M&H_%WTx^AP4dc7m$gYfY=DH zf=}wwJ=p){cM>)|ScmERjJrl92V?vEh{y)Gby>yLFxLlhBSSUG+2z9+!uyiYajE!TDn}hPB?6R}2lBmMLJS3@{SxgPaPK=Uk zLRNX-tYlurm0Y6o($|dwmtPT34{We>^UBR=8mObh+>^+d^5xPKlhq=#&l~y^jnuqy zLl67adTKR7l^p?5!9lq9Y{UQ{Wx*eDjCMD>4m@YjqAopKOL>PM8vZVLYV(fUmh91u z-Ik<1Q)QvD`tO#)?`|tQ($mN#cp9(B?C>d!ZjL~2lemRw;I-uW+HHEq-cvIw zQa%#uq5z5-X#&G=jhF%YVay-oq&Rft4xzQq*1DEZ^ipye?UA&!IL_};B4`WkbeY+G`(R35C0C4=B`u4eQCo2t^&X7S#5hM|sRDW{Qt)TguJ zb#fagmOOqW7%ewg&b*KvY(0S^$U#oIkF9t0!bv)~-MRMUhAah=FvM^&7+39u@DsJR zKOnSMSX*?`CPWGJc2tpomwaq;=1Ds>&80JY*Kv}h0UU=)RCWF!@^)q6Gsd=YQHLcX zes6t(3ux@q2E>TSO;|o)h!F8OVdntttAhR|^lHa5;+uKH z>i|ln$JF|-%XrQ&7Dez-zs_EO{6teYd1=I>LYw}Mth?l2P$_;zR#e@5;fVUbsegCz zIgV0NTitd-&MZK%Hpm;Dx+*r&E4@o=Uc_u!_5RVFBJ(M3Q@j#RXK^h2yL*&Bf~>&=*6&%#NY|OmtlC1n!t}G z;fyJT7hVxdL7pzlq&si>Xt}muJ2^SH7VSQt6li00(jmW+8y$xrwsW6U)Rx=Lw+(zW!EA{eKA#-__R2f9*Lp zbV11hgM}{hWEt~{gK+Y5W4fg2fUl|nrEA)v5!{j(khX4JRY8bXa-K#U!`DUX*;+As zH!~RYYY=v)Xx$g1jSrZfFd$c<2fEE-)Y^Rp^NnhTBY5=qsZ#%z=DS?YVW0IIDB1Er z53bH2(H)!JBWEu@e;qkgU00hWac-$$6xl=U3rDaTTInS$!5>W{}`R= z&<3j^eO=b~++qJ;&HAM0+WLAm+J5LOYj7||1@e%*Ts>y;BsWLX}!*=G@omu6!PC}bqF#C4_ttlYz5{r24<7hYZO`LE0iym6XWE%xB0`Ya-^ zAgqqY-IsqH%rcND{mM)!TYs|g5@c;}ZzpE~XrOT6%RdVao#}m_U*OA za|#R#Lal*X@xiFS_n(66RVR-lEjfYN6jtfhsC+5|bPU%F%O>chAG67vNIxyMr~sxi zQ&5{4SvR6m8!Hh@)^(P^B}g$AD05rQPoJ|`t-**=Mysp9 z;dRf@UjrsOs9MKCAg<0(fH9ru_U)OY?uZ~N*8-Rq*#&oh*eUX%K#PLhT8~K2QVleI&l;{zG0ReGdDUe?OmT(ALQlAu zM(c1>eeOo&ioH|bc148{*NFUCm^h+Iqh)BAL{cK89-8pKA&D0hl!iP!9ph(?oJIvO zH+V~lUJ9a{mjqn}^9TSRix;5NlD2Mj2CRH7Kq%TbYrV5nhkA>MQ}X$9+Ne8JdfE7{ zQOGeuYchxe0NQx)E?$p5$ISvRzb2@;bW(dMqg#CV6^kt{*xE$33iXKQq#pQ;>g-HF zX3t_dWV&?VZ)|vh@f*Wz$ueH*{Dv{*FGT;Scue`>XRXE~ zf74Kt%kP<25yq1=Utzm_7fB~-jl2@Cj&zvAAq!{%>}2v`RND=?SjU%;!+r#YNJ3K_)jO<0d+rfgnPCvaZj*yhM=g*u53+7_GB^E)+moExiSE3ba zD!Xn5Gcmo5F6%JVk^IAl3_1g{hJ)=aJ=gXQ_^eIs&YG1Hy4Dv#-X^!$Ur{R&|J3N) zLQ9oJOyBbU{J1O9_igkd>MG)U$SYwGgL}K>@`>8-yNUnCdm@qpD=fJW=H~OO0iMt{M$(J9)+Z2ySF|IS7OGxzS*F0T^_$d+kEw)_PfR&7h&aUp z1*&exDP7&p)DpWG#)66yTHbgC$Cb1g=w5V#*!8@0bIPTB#C%KZoi==&(Yp*=xkN%# z)UQZmwnIDQ3-8G-e=uQ3@AbKx+DQhnq;8?Rs1SDHVxJQ;V2ibWXkCshYlR6`;!kG&-9(M1bDsvzz^LSi+#u}pSx$?rKFlW6ZQpMwa<~T_Yyj@IE>j{_A9K?C}5e+xalllyY;|ED8D)9VK7NK#_ zNaJH-Vj41tBR{dv$qMyxg5@e)r6>@*<@dO z^h8E1->#9B5CL0P#qsUc1dRY_4R3%R5ciRh&Ev8bMe=V}be}=RD zcd$gO04UQPS#xunEb~Fb>c;4^C&XCw)@A3{Wl&h7GTrMk7!EeLBRs-EnAr;2Jwh79 z(pq4dqrWc(2H&r=yp-FgX3B2s{lGmFAFkSQ^kqe@94_ZH1M3}ZfX(V4BwvxhX<$be zRs+0f$Lw#V`EQ82`xWu*f50MZuk(_#gdr+qhvz2MTKg1PNuPgomK(MZX=_Xxk2H~84T z+rM)@YZLC@+sikLN@=`61?kft2zNfLdgbZb9Gny$;~}tSSnoc#50&PwZ6ibxKx$^3 zeCD`kuJMF@ci z*3H;JM52R0(SymQ<-iEzp#jmeZz=bD_aXI>{ou)eIwW)>w(H18OIy}ryQqn7-FoWK zp__zE3)OhKd87K5#`Id*-(#m}bJzWYd0S~BH)@fF2%z9jXvjeHCXzub2Vy^>rLEnO zo`)u`5bXe2u2A%KfkvN@0hb*kGA3D>8!=QU5GNwh@rW=xp{8)n8*i|TI*?6X0*9>k-}eKQu_5u&2==0Gho z!@_aJWAk`tis*}%@(u40W(@s&EZ*mbMx5e&(v{3AIFc>LZ_&W1nNrX~qo4wZFNtR6 zb2_d+1J)di(>T29tn*EkX6L70_vUB>new}0XMoV+m2QnYA|{7G-E=#CIPR@R$^nC# zcMTYu=SZAt@}U>`u#nEc1u{hUz7pP7cO zIoV1ksu(URz{o@5)t$zWNBOZVRm?#5Yxm-Cz) zl(2F8PjX4U)ouj8>R64#kS&toK!#V_dB|up?HM2?AHyDLQk;ik_9zR*Q0r8Wu%H3@ zsr6H^9n-Sgc3H6zq;|XOg7`LG_qkd0MEKt`Go6rWF)Pb+n&d*LJ%yeXM$tZTtG^wjmmg>!gU0rdPmaGxrzy4d|gi@5v0k1@_chj$H2a{!Zu(k@Xv{Y2D z3QaCrpNokA{=Q~Wj~|DI_N5btQg|asyiE&X~?7eh8V01a@aDq!? zm{_vxWBScX{`V{ic+!IJR)c$BQ;76b^9p`XDK8;;Ac>AN4@~_@hZE@WvK+waXW__7 zC)$haU+StuFN4%zq_5V6Oeyd|9>&`sH&Y{&Qj7uE#-FqI1-s!b4ZMETn7a^HugZVV zI>8%{huXf1H+K5p{F=M-u9=?(LQPh?PSfVgr4MW`4^&&bE!gB2Ufq<{_HEmil*$vg zEvVu@TDk!-cfx4HTNfo>jKUYaxNrR3W?AC`s`l;H??7CoMeUF~rQ77e)kBECtlgV9yp|+UON7(J8 zw^I5k;VY6J;{SkFV6EQ}F^s_&iJR#WW(gtaT*2!i9+Bi`-}A@Q?q_lyyfHo+Ch@0Q zyy5M|Td#ih*JT`%G2Efq!(O;HW(kkci{nT2U;wY%L1x7gTAN`b4K*p6G&k@}eu@1T z{OnmQkPCg!uh^ckX}fX*;%7aQ;-r8UBwJ%Y>zp}rMlA|s7!pCCV|{^OMH|<{V?AJ> zls`9?9Ps^Iq2wsefF3aTIg0^J-)0kvrL1NjF-WbUoc|%W8}!L{j_-2amwYb?87(^U zvJBOXT8n7rh@=8pKQTOT<9>lmp5~!AGkDxfw?L@aME$a}$*ftYMn?_qL> zFcPk-1~78r{jzP22ZoHW`ND~Jr0(k)ER)JlXJ6|TCgp3qI{ZLyZ$H~D&h_P?FI6nA zTy|-RK6%HNy@05qp(V`AfDOz6at8+#AD)z2a)8j78(Q$x>-VS38{-5IeAsou**T-@ zJkqw(l9Du7Yz3>bA?qvhIwMK#i|=QXgBn;!u9dtkfM;-rMb8tiuEY%umCQruH}_@qSZj|JXtk~C3q=C;6?mc+(Pm*hI)ZGg4QaMsS7Cg zf#N+0FN2_O9XV3qG}g%FhqE2hrC6|0QFT8?5+R(~n1~qzF(9^MnoUfG*%v~$A|Z`< z5rbX7@5}5zB4Opoaf9U{Jo#^!a69Vw(@t9BzmN+JdtLQN0rrSWq%y zbf^bczgko>*Ms$Uk^F)X0q_T1`W(P3B`Va)HKxyB0LjG&z8ExOflz2cQS)wgTtBP% zn$pa+AGGB9%76>+Ga{|!?vBmdOkFQ2DP7b}0~wh3{e!tqZlu>a$FnKND89x$IiOYi zTZVW@oPy0j|G8$j#w`j%6RRv0yI8xMvQqKqYRiu8VJskmGDMEt3?=xQ3$cCjZNv?Z zp^4~fO$;-Rd<~(|1pF?0uthQ2q0IBhCF3pXTPVXB*@r^|w5|TB7 zDb%iWA6Y@UJ?;l*e?^j{WTOXvz#h9fBDl!l--q4@cmDc0{!UVl-&C2$`@Gi<9(2$j zeiRgqkX>Me#0MF0jRGGU*|xB{rP05Ge0tkaG3^AR_x9ma0{x887+US33cr^_fRzX) z!32>OwKDF4+RAlq^0zc*($E-kHysZ&gNYIOH)>_Gcrn57Xe(1h@>PWxN@D5cHeme~?lrGqZ>MUu$jH7rcFFb7G--I)j5`MD`P; zYD6AZov2?sFd6Y#kj7i&zc1GvLcKR-#kG0Y+S^bJ!~=yzN<>Bxfd(?-+SEEXE<-#J zV;tbak`?vP9P0(uX-7KaBm(sHU?8FCJmd(B%PE)x;I^L^7#m8AV_-S@(fg`|>6ETR zI510!f9`a;E#`fE);Mky4Te^iJt}G-zFB{FT-b`dJAjsb(WWwr_FW|Ixsy5gU(|c+&er`2QrPS+}|0_W+uJ65WaZ4Z`t6VXjkWswNtKL$7mjYPkPL{UrzJ{ zD#;7i=V_)Ty@_;i{%xhO!zs#htmhQpl_K$moZr9LlWgCEw7^am?rfz^q;Mb*t^W=ovEVxq>uBxc@oKV8}<_+6}$52bz zVgDOQJYC26Llv;M406SYTXs;|6`B#+zP+EO02vCuIkuXr?)T`2(j_76!cC1 z^SnA%a%TGj<`osFO9wxhMAQ3*8~$@-Hg>2@{@x-8$Peetb8t@bJ>V3xwyF+`JQ<*6 zcY5=8J2SNTreLX{dQ&Q%m>Q6pir~wN(}bTo?DDzq<|NX+ybSQuiSAjNb3QB%Ik78n zBe)TX9xuA@j}>+pH)B}v-AF2;dqjGUt&*0!V!U4|=5UzDH&fbZnx@BG$4GX2twJhsx6RM{9vKF_R#I{r zt&Y{EBN|$+w(xu5dz`LjMEe&>CxDmD_fnBeWW4?hDO^)1yA1({nPz3jne+$G(Q z7Q*lJK2!iF!5L7yZ>sWkk<$x1C~Alng#GC1?cIt-Yco2($VTfZaeiE(Vf5|0-$uj6 z70Z|Ja+@-8@+`Aa%H#fM-MCpT#BwUXMJsP=sZa3vG_3ux`t^6pFQN)X&GS1Q+2JRc zmH4#(zVDCHYO{e|6U`0JWwP_n{ ztw~_K+3OAok6d3m_9lLfD4qD|hSSEC!;*P=pgdH~Wl~36Wj%#7x?lr} z%k_m#4XYP?vSZFdTG5rN5JU|g;8OUNIg9Lnw?dN4?hrC4^EA9La>uVixyHCY88tle z62rz@Tmm*0p6P1HlHf4u|LDFz04=#IRrR6U+epprd9p>Ov>Z>l(}j!2mYT^M9p5Xi zm-+2a(W3b)g1iSK7zc3_T(NG+t+$*;tttZSt!#Kir389l@ax?6J+#x=+X8zVWZ^0;2asVt?G<gnF{bX(=OuB;*pVQQC(8i zWD!CXy7o%1t0Tro(xZ-uX(vlbcl69p9znk5s$^O?73?yRc#W&mRPFbV`HACBJ>SFz zhawE{B&%`6CHHCHl9+%SCfXEDmTpAFfo9_IvNh(I_%T!uB!6U3^_SPotd~oqC^hXS zfRMl!^$ZaC^vqM{MJG4HEuaFb*j*+cnCh)EO1KAq6+h8Bb?OBic1mp~1j^Z}5X-z8 zERom+-si$>F3B@P8w>Uwki10g*Mw&S$!4omBiC~-f8_^fq@1SQTX-lbw~JXAk;OG` zC0Yb-L)yJ3o(B9~XTo`pI_1Q*E;oL1fy+L=Z~L29CMRkx=-mzngh%TGzJnR#E@P0<4%B-zp}? zv4t|g+d{{_)vz%&HI>-(Ym7*3BxVQj_^cHTg>BQbF!u^C-DVxFQ(e&(A8@Aa`?8~@ z8HzulwQ}7`MjY>|pZpwPH%mCH)L)$`ma9YwZ<0MDW9V`98wFbV`VgI=m(P$8G_@(lf1LOEyPBe(X*kwL z-4p5cea=L_9Qa&hC9r7yGga~3Cs59}p3k&y>`2YCFce$|(5EZC55wZweyXb1;s8pv zCU!gkAwKMZdf?nDByp=eL8p z1?z+)nAU_;#?7NvHo&V$?|2H7A}}c7&$1v^W=-r=meUM-=(T7S_xI|!b^GLH|FkE| zbX6Y;8S9StGGzsUiK0QrNE9jA+X9Mvju2YFg0d;x`RK7@!;K>49$_@kso1h{0^c*- z*H{6@=Hq6=S;OUMB|ygJ{izH2du;|fX2fTL!@_eY0Y#-}yh!aqRrhx_bKK>7INpsJ z7Hj&cK#nllWW|uwW#B#;uq@u+BHfP3dlm2*z>!E42yX-*!$%X*M2uB;O9WtyA-XSH z&(A7I3MnWkbY6W1g{U(D2rO{~G#BoE+8z07lCzg(co2Lc!O86$iwkxVk7}gGPRJYM z!^6Xe&G%KDFtTg5$t36|fGnVkN6Et@mYD>GL8Wie^!7D&8~Q{M$WF~Bhufz>kckHo zqvXqLt)kR=E7Hx~Fb=X3mS-%rE*9ejxE9O4UsLc(k?dXXfaUxhwzrcTF6+iSKX=zi zwk(~RYSfaoXcaDuBaX-6yCo-;2{|%Fp}d*izw~}{^#2j{9q?4X|ND_wwK@gCfOqs{A>mOb&1bbnJ~EpN*!BZ8 z9Yli7PFt)wB76YlFGkK_G;SvUUU7-&EDN3bn~KbhaH+4S63|O2s+O2oMF9bos{Ys9 z9Mz%xT=y5nRUQsAnDrUpByAsAXzE}Q8h`7h&kGjIDfd?+HLljTWL2+yLsZL2fnb&d z=gVDF`9)=vcTtF@SRMKnE4M+hK07@ldP>zE%NWu3`9M1FT`rW^5 z5!!h`>)zZkC&dM+Yk_ci!Xn2dpeeP}Ir)gmr(@poLZxjhE(mSlz>-;g@AvJpNCbxO zrYkUa*ihyzAG|tQ@u;s#PWKg6V^(1CC}}l9)-Msi@ ztsNork_|lMHe(Dm)b9y+l>~jjy@eunWR@9ukG^xdr`raRz-a#22*h%+|Gla!RPU+$`(tSrcga@3fx$Q#t<8XB8L;w=!^uS54QX?G!VI**PQ%-E zTIF<-mMCOAOrjTQGF1N^P2au8Kj^#;L(>U$UiPP%ncga)6HZSE#HMF_(Wae%A|s}b zAx%28%(r4n?>)WKvrKO;H=-}330gr3je&8$q$xZS?HilRO}F)7U{-LX_zz}!`u=I^ z#uCM-oMJipM(CGg*5Dp2+44|j=%biX$^TvU3Y*2h<6Nt2Y4yZoL|Hq7TRh}wc7&|D zdhuezj_81JEE&bIy|JGvXg5S>K@3`1{$VK%X^w~W{&YMNB{ z%-eg_&w<(S+UJYIEzNS;Mf1nEo7vtwQ-HP{~m)X{x78Zk=ST>*;w)*i-Y*3DGU z+_v}!ry-@_OiKRI$ck0&W*qQd-}!mr!lL@m%EkFC*iZR7zG6t{Ab;khzJxfC&OQ7aK@I*` z^#h2r%+C$0rthj3$({(>96lu%{_rkkdHM2X-%AT1{W27|7!$L>9DPo-0)HW~@_I{z zyU{>Jdo9zQM{c_ka1{Y$M7Bt=tQw$}PyEqYDcL5V_v^?R#BokX_AxXqKaEM@_?D>dSiX3Kv1(oc^+kzd|dn)0)0C`Vjk@ zB3y+)rv+@3>kbxmwR?KA8E0|qJ{p&7Ivyy0fsC3*^kw=@i?A$6C!Fw4L_z;2Mi#~3 z=Z`nAva$x%1+Ky&qNQ^!gpIdH+0$v%g zdg+Onw{Z$-r?}Xqx2MlCBx7eX@b>Ng$Qk9bJ7P*s1(jTPXa%o+eq($;abc04(E(%z z$7u%+F@oFji#``Z3U;L`Ba&7_>xBj6fF`%R=@5m?Tgf$gthU0qU*{>wp3_orag|+_ z-zUS3RcyEN^uP+zl2;P$^T8RPMs``X4_vY935tZe{0K?%)Za3MG_>5S(nWm}_XUx` zk?9Kw=r9pmiQ+)zQ|rb)24o2K5q{Z!*ZTN2rb3n zb_QwiOO-8~f!{F(e~Iv0NI*pN!-&WdLXJoTk(_Q9AnXM{)D5*+mT{+Op_a~}GkL1d zI!gH!0bUJ$_im$tq9i2$jR7*MNZcT6N22XhsBuiY4}Im(`GcbRXstY?WeD)+&y9O( zN=gqvi?gilzO7?Ghv&b_$R3`XSwp@`FIk!X62 zxGGFuUULmLXJvZkT{we#4M$hRd2OK5UPn|L! z`G#IF3fvM4MD`01md};IeK}_ke#qAaLJ|p{Sp0RY{vivCD55xp`T*!lrbNyg7JK-H5qV5I{P7P;nzi@Z;>V&}P8Lqdj?b#o{eajfT>I1#dWsVm*@}G<^ zrlunD)8V%=8OSgb)D`ng9Wc-iz>&|d+s~@~Ym~s3g#hJ1#;>8bR{`W*hnPmn)!#?g zSJZbv{ArZqdILK3Sq2MDi8Mu`xnI?&@ePez(PMAml8+wIo!dlFH~FZ?ni1%}Ai(%Z zwEBqjIGRyU0#L$^Idx=#)W&5KJ%!%w)7rJEQMm^eo?@uhGit?e#ym%}SSPBm(#l6s z$2l|4YtJjPp{XX1JV&ZJm?`11Z}`;iUdz&M8}92iW-o)u2J`L6s_8hSBAUZ83e&0T>=_V3jI zK#}=;=i)D+f&RW$p1?H-Ee>dY6t2hKCU%9lLjYR^VbK!1WspD^sL4QWo|d=xd30Ci zscWYxc__63ER&X)ceKJ7b!Y~U!hIi*tBTXb{(hwlo46)4IAOqfY?pTh&jY>JlU#e1)RDeH(ZQ4c8|y^uO~&vBW<*z~$V>pR56I;v}+ z5KZWV)-!<;ic6NX?jC$&FtNm7O)ZWtMZ9BE7Hy zir3zJjDrdgHSq#L<#)mi%GqAOdR;s;j}t9ka$D%Qow@wxXuRIKNvQaSb6rV0$y2O4 z<{z=-$Mx>YqH;&a^iZ#l$jsGR7v=y4jr4zT60)z^>5E zVgG4*#qI6#m2c>5cY>p#@e%=yr+hMJoN;WyA#j9%t^9#ArK)SrP7Qai>h}d;Ub;In zJ}r@B&6>M{JJ&8DI0EE6VT$aH>`z}wT+#Nuw0Z_k;hDddqWO8Tp<3;aRuSI|JY26W zQ-}o4GDZL~roB0t@3?gL!acxw5MjRPyk%VCgdI6E*YoR!@9K)6*@2{__4m$M9$w2~ zsB`Gv@#6wtv=(q?J*w9-U=rAFrSo&E#R}__R)WS_!VgNOmGi}_w%$LlzyI<3gKm6_ zC3|kY=i_79%O#Rt(Z_y=Dm#DXtc|UWi$ZaZx9o+A(Bj9z<^JJgX(q+HUqIfm3kRUG zWQuVi4rZVpSLC3!=B~mDaa&(f9`+{ssaZ|KR-O$U%jvnqsd2Tb$@EX4~9;b2W}1 z&Td6XD-MP8bLer*0(5=$=03h&DNOn$RE)in5%tei6?C=?yEjI1J~%ks{L-V4{bkGS zm1awg?y5*}1!wn&s3>=b$czkaGUTSv06}*ICnu*q4~B{mq^{7=u{NMn%Fre@NL)VU zC{K5{gl393NK8yDEGkNcj6K@zJg@}BwcnmYp{jvV6GI(&g-lC%WUGhkRb&UgB1_1k!P;Z&lCW*%GM{yQz8LVB-NC!L1f1Z<;pL&pOyGA4f#-bIn<;AR;#n zdiA-0Z4@OeczHG`vyGdDs(dA(ZNu)Kfk%j|c~S*kgxP`NfmAI_WS3GwfYTzI(c zS#bfG1dN^RL=c@|9`Q9x0i9b)rU2OYpg6c$b{6DKUmlS_So33{udZumTcf`JGN`64 z!*Ozg(_Vi%CS0J%<+oUwf&Hm8*6AO9(P6Pc4a4J~cAca&ye?nXOyr3M7l#l~TQWK@ z^S%V4@`1hOE3s(^?Ac&8RUU;1eCtshTsqhmB>!+gDo{!7s!NJ?9`p`0#%>}kNcOZX z>y~0FPt@f-m4pd|1jIK$=S|4q5rG!tC6>pJAFpq}w9Ts9db8kS$`ZrP7~T=~)%2d;`;d^s@c)$nY<;x1nf==fz>W6RV~mz%Jaw-1hHn$M zc80cqO*t%SW$xLrKz@kf(Fxx^5v-S2%uk9N{1|YY>B~2akqBfgf~tK3a0TYuVnpFN zCT3=n^EkjEhmfitk3^tT_xZ-7c8&n!uYal3TTm3Z+thSdj%zOanWLp;yQR;z5Bqd< zNQ++=7hG~XO6ybHS5vShoC-sx~GO`7&oTHxPP$xYFxlNUrk5k$-kvtq`Kbn+b_K{3oJ4XSck5JTdKibWJnp6&DNxmx&-*I5{ zF@d_lbhZYF0LpO8nj0fYvYTd5r4@4Xdx*SkYi}&ShwLduZmT;6fv>_bE_LDU&&hd6 zzRQ>XfT17bryk$>JvLYO1SeM#VT?pOB$Co3l`H_Kl`la5w#jZId+bai4cLu;q zRXZ!_K_Lt^6kPU{-zQ(eujc_4;HxH-P+-tv2)ia zyL9bWGl8LkvPQK|9<}m5dAy%=+}K9ib8Vhsk4w^DTSp?Kt%brgACMwZpYDX5mlMLqHOE;3N%ZhYh8uVq-@gP@kyjyJYxOzFCWOX zl@(XD@dmu;ALr`ZS&^nN$Nzi4>%*+stf6YCO*U^fgGw|zN_2Iml>i~A0RmlO@bD#2rx!!g02o}^*7D~|jY%g39l za5_-1BUJ-{jg%j8?EXvpcMY;;HSmxb`v&O6~pI^`*Sq6 z?*9qME~TVVZFoh8F^18aZr9sBBG~98ig0u*3Q0nxVqO5?p@C*zVAKdjW>ycpNuP6p zY{+aP?Q|MIyAKbmIpkh~SD6G|qPPF?TjUl5YUu8e1}zpK-mW?FSa^G*uh(#7qQf-v z=9b|~+f18N+1631GtN$*x+AWIY&Owp{rfmjJ3`mmy4K)#8~|rukruej;HR*Mhl2@%q?IRh2KCgTkWxAtp;KYUzp? z&zRTqA;&pm%KhiR?HC*ursOhN7D%vbuOOsr4;H_geIxu^bmrVl-{oJ@2}XOoCVtpv z1fwdlyIG1rd;kGlnYbln2mBa9-BN-Gw5U&h%J`Cm2q>mSk*g$?)@;2g@pJ_{3yj`4 zExhir!w+Da+Qz2L=gg7{!UCg>bbh`r+hSbbW_o-PO|a7?DqWy?KsCv%?3_>iYmBP# za{sLqGb=Kb7}%xrNLxZiu1cvKXgI_pDZuRzsZ-xPIUWxlyC#M$A=mGd*^HQEXdF}5 zJwgbw$4u*Cx$_+5UXALQ=)_C{$m-@$ALddFDuqw~IAXO86ZNM7nTq_XkarsuuFbdO zv9lGhvs=cS*%_d-G8mW-!S2#Wi3z}5mgj@(fS02GN!0jaCHndmD5BlzFsq|afFsi_ z%+0TAfv8}S+{_FPHw2Q8m!g=x(`_i)W#$-awCEnvT8bOgi1OtqQXTP=h#X z*C6O4u*`LBod3i`N{_VA`A?OD8jVsH?`J63+htof*cpXo*!Dh~)bH3O=nzs6e4vW9 z|MP2$%mGfhnbbU?;*#T&V|}}$C7jLL@NK5qv_3K;8Jfc~dlC*HB3vb;E%Wzd8Ih6v zm@Bkn$D;`{IHZj8tQSydykpfEbKLPU&*LK4bgUimnk9K$?o6PVf+9FF^*vXNZAuO0*DVf57zN}$!RX)>%MgVI5L}zCY;t;!OzH2z?*H9>t6iZ+v zF+Tu12w4zjD?9W+4gqKG7qhOCbYI%gHB3v%lTFmiVa7q*X`)*dxq|;NYA#!w8?6y1 z1oAjx76(ehTl_6=k!e6s$4Ks&nsL5h`FUYtA=FfESa}@x6~4)A3*DrqE2?}85$V~F zH@ngU8Gy-t5&SLM#b52BQVlaMwvFh=Y;3H>Y|OV8Wo&WI)FE^v)-C?8!^5}Z3d7>!P9c{=G(U+kNePJI88`kx zVMBV-hMP3oG}G-9kgsfuu8JUfV1N~piQ?A^_v8_2GN8dOTUe+&Ii*7&e+gk!0!FQR zBLJKMvf;UBkJj(jan6wDDf`dkm(1}FEobZOp+u)xwT|N%C+4iDmZD#Kl1y49>FPcd+C^Pv9f=SI;jIG4&nd#z8!&}E~(q{dJ zq53G5{QII~wV{Z1mLhqqLIeFSn^(U`Tec^)1nDES*z;}?6+D;{9=4F2?k4WQ;!r>U zx&aM7i9;4Iz%p_lVLHzq#z{$mu0-;{mtXaT7S4HbNcsgGAs^(`WqA+_L>eYqF(b!mQ;2h zd|w?xS^hK>rVC|Wx75#hGHo;}eP=!a*josBqrry@bjgx#H6!XMXU<-D2Z^9=7|3Fc zaa;6IrIio~R&ERR_bMs2@dJ*TR3+yo0_R@*4NE?nG41&4M%lBJ@%lcQ$@M-uw(*BO zWD3e1vP<44Iwn*Ft*?nrNvR!nAXQuJt3{W}PDM6Nps8)P-T}8Fq|JqpFiqPbAkYtG zI3!92Jm+!5(0?%&apN(f9^T56+Mm6|d;->B@e0)$MiXEB zDqz78L|_3&ZO?(sMG_0R?gha;6P_C3_>;leclQUGIb$=m?cTB=%UzW6bCE0wVAc(= zKpC#4S>nb9{ZVNG9$1*K&luw|Pbpi?o!J;&rXoY9ED>f78NLa`QBkcUanEGf4q=3W z{vk411BB9K-`wn#3CE1b&Qa^hjwIrF=nIO}sad`2nRQ$^+-Q*DH(KnI*IIJr(yX$? zg&Q~JR>>5ekx(wXSk++InV#Tq;NihvR=cgUXbd4gqNAcJiOY1oWc@xRMH=Sl!`E)W zc;hZklQ`z9>Gg%$f&?y1hWypHs>%-BF%Ptf*<+CVhp=E{^Fk`MUftiomW2a&e|_Tf zw|E8@u9X}zae>FY3*`dO5Y*#mhC>yIEVd1(v){W%cven6(_eIR3{&$+!IRWMk>2|J zj$S~~WDSEx_$Pcnt)whI3G=wWTp~MVLTZ(Q?Cf(!`=5O4_WWO3o_&dSGH1u``6@-e z0|ttdZs5~xYQx~R0;X-Q8KZl1SIVDFAd^12vv&|Kn~nvz#P)u?YZQi8HdHUqZ=0Ds>r;TU8RIY+B0GZXIsIa5) z;_nXA_P@20vkQtG9M!)o=zObpD5$XSeQ+*Z`i+}V>lyV8VS#g9N*5eQMxN&h3;bo1 z>VN!_5f4|ttFaE~(8k1j^@bqEtQ#6ZR2nLmNSJ7Ulg_7EoK3bP5bs^Ru?o}8?AWq# zBSWJy0K+9fR_hn&UefKp20Pti=lZ@~BkulzLrBtW_mW3yDLj<8CiQIQ58=mebz2DwsiXop>FkOlG-% zl!}!)!XWIhVdcD#t>I2H=5RAW8W^O6z=R1`R$b_L z0R0_I$VCWcYXYtwbtkJxpeMvGkvn@SV;e<877uOeT(}hTIbTC{CY4OYP(k8LKID0B zSY%}RLJqChm|ngw=)@7CenZ%YBtU}ofJ1cB95Ta1oLu(}5xg^h6p0erf}8s^Tboa; zpP8slSE@~|3wXfWHWi#1(dTG=zjyrWm0`cocGKv)CoV>)3v$~2_>|I9>v!75uZOWr^=%LC4UdQzDR!9^>AXQ0O(fvFx&H4ElEqxdbevHWj~Oz13C=)BJ1L$)!wWHQ zGzyDdq)ujK24oPqGr$`RyN!C!BJ?BngHVRC>w|~@3tieFTKfYcBh+D45H~!`-L|e1 zONPkmRV6oC?h%+7xxIZ4!T|`XZT>L8KyAI&n_SDJ^%e$vawu>v(q+1pm-s^UNR5(B z^y(kM%SdDlun}iZTnzdFz6sHQ(xo*Wq^h4V>pCpRy2M3el;@#arWO5usmoXov1p=9 z!^i4vYT&i{+1b@-q$1{RM~iD)om&14Qa>W*AIKIm1C>5R38*wvc%ezsG=h#=MO9Tq zZ0t$Y9%*Mv*J@#s(Bw? ze^fZ_D3$c*)R~&Y>oH!zVdy z+RueYO7CsIk;hY|RG=Wjp>@41paiS;eRQ=xsrygZ1KLn)FgKc%X+EHN^5hf#q81R# z+#t3yn$Rk}hH5D89=Qy@Ag8=za&X|P0$5@)2y}aUET{%yq&yP8Nu5BnpsG=&Gj?vj6A8pH_8?P(1lDe*|?1#tY zH!v;x3lgw#cSs=#)80{)Jgt4>96!Cb)|QOulEgj`!ud9OdL_a-kb_<`FXQ(88UD z=?_$xrw>x=EIr|m0F5UDBZ~Z`)JTYS;6TpCpvK#`vr02``+*}MPrNbI;*_B$@#VhgT7T#yj{3BL615{^ql$8b|l+$L0_%aI*ySvsP3&eUD|6L_S& zzKv)>=`OP9&^&pNo_O?J(i0Ni9_=VfKZ*z|nKEGA){6{tbte!+9(w$MVQGnnvQxBFNhrO(WvF(fB+YUzI%ehF5~ryA zWtnirG2h%&u;?dfOHJ9bwCSB`{B^Y8v!G9@ey08Pt!gH*jg?kx78gT4fDbh|b$-_R z1sKQg1~xspk0F|S4{eIATKdXtUb|{Xdp9y80-*~Id}V@GD`^C94pjrsb`2xojqDC% z4G>xFTYLKKSu*XLZvFrf3E^e};M6Bx%ABI=zdm7Zs)wXg+p#Hw8M1UgSIWp69n5O8 zIr6`R?mkBO5w$7uqA^~zE_qkorYp!9*<%35>fm-x7aEXFg3L}_Q9;2QX?lQfG+Lyc zC_EMP7-H!RWJlNyOQ7MAfTAklR-OW4pZyNZf+Pze+o%(sx&@PH}pFHQA%{E)Cfe>wPZVU7}b z8wQ1M;sG7$f^=0;HvK}O3dXIw?jBJgL-qS4N?~uvCCW&`z9Ko)q9hH+1-KSuz56=* zF%MpFt{>SUlQ9BMiuUWxin1#Y@{iHaBzDYf(f3m;JRIxZz`Rd>W_MmbR87J`j7B8K z3ux^Zh$DkfY<-Km#vkCE%2CdZCenN;gmvE>Te?A7^is7g=+f>^Y_5Lbez;4u`>u_4 z&Cx@?#&0lWnT@%R!w4*LWk(T}8NR&;>7)JGYIFPUIic|y9u`)D5rAjZ)Pm8=AteCR z5?uWiSrDg*O5v#Lf2}m6Brlio$XDbg#$F`p9am=R`4#>1YS=|fhZuA@|1G(t@L*;Q zf%yWOEPSc14ix##M<}axqlQ8ezJ?3Ku zk2lDu6CJ8yZ0}rdes8F!5r!Xm(6zOiN~f%?hi>*{VKeNN=13)_GXxf8AZ%%J%beo*L*%<*jJiGW-FQsT~T4fLjYyNWI(Zr?g+-(`8 z=Yt8VOu~<< zIqM)fL6^<86EZu`;TU1Xt6KcwW+TGGzyIhAX~Psynf^IbQ`0pzZ>k08GMkugFH~0s z?8|GM|5I2+UXeek$eh-8gm4ZY|1AfvvI(~F#!sp~EIc73@P?zN0Zv$w@!a?Ow8r`o z(cw4KM+ES8^&{Q60S$>~E64+<*! zq|*9{vXo}aTBXwaHqgB@_@O#O0j`jCJLZLtAcMDrsk%=$zJ29a^SE!7SG^v+^Ot)J=vtjl0RE9{CdE>mxQ7oH6WR&#z|(l1`WY_S zcUVc{dd~=^r)eo^lLPsHPKEi3;Te?H*2wj2WC-PSDoV>l?*}z1r93=J9g$7T9(V40 zUww_ya+QE2pn}yQ$N+F))>4)^tAz(jeJ~r>1teR&*?T1mpp~ldrr664tbMo z$nxpkgnh(flb6c3;g^q`_Go!e=tvf}4j4mr1rqX>iJ|yOPcgt3V_EJNz4(((P|cNQ!|9|63ue5^b4W*wv}e%PnPQ#bXP~7*jnC_aP4-+ zr99w_-H_$5vrdgdG9Cg!+nm;-{+)&H<*FTtND|z}*|OBLv8nks)E6aWU#5@ExL-h` zPo4?7dL=%!iSN?cN67|oUQ{SF-~W5WQEBt0A_*>k(f*7n#!OJc_DbmCmZi7U+M_8Y z&Oxb^Q$1t!`7ob$>jr(3I70v62O8B&g*Qc4t3sWNyj=V5pWcoCUtNsLmQBscKpJxJ zk$U4Q70H|Gz`E@fx|}h>zoSr`+TqM-`6MtGxWv-^Q)dq|rL|`k2eH`JkS$NUn~?QB zZE#SA{+Tc(`{}m)D&)U#<+n00R@+m(ac0h;-YQQ@?l^v9@sba`-}0`(HPq)kc)~Pq zF!P1CM6oU2m$ko0)0ZBE3+R7h@TFI}u#acz)7tgp7Wg{k;#=s;oTd@fn3I!%qAzM^ zb2mNvX4M;kO1OCWB@XLO#RXZ*9-E{vNIL809`%Kz;VWC;H}a|E#JcOT;03Y(9N2hKGkQW1UzAd<4N#TUl8phT^(< znvO79jxuJESgJ|DqT|x7XQpUUk%fgAcveho-^+4(Nfn<%n^|o9?dyZQZ{*Lnu@yc; zsNX0t6o2(M3>)F^L|C(4OrrQ8Tb48VhE_x_z8y{z)R4eG5)nbLAfV-)`n(j*mE0{}t;= zE2F>1r|{d9(K4G7_8CLt;3+?sdz-?Js-1fCi*Ub_xyi}n>SP+-ZQ%*GkS+e#K2{TG7>nJ6O{XK zAVMqq_xn=w&o!61X%jE|&IObw&+M+EJDV~m`mBYsKUm{81az&uK|H@7d z{E@F}K3a6Xx`{F~RG|E07^(}1v&eVC&F9dUlaC=siyB9xQbie;jMwX*Yg8Uq{_i1L z9b1L>Cc-E#8aPsuCWxDTey?ye{1l>_)B@`lW2*W;D4Smi}h}NyS`;Hc{tP3%dNVXdS5?oaY8r>D@$B08)gRHO^ZEeB zPujQn_m#$_YA%T4lq_Zf9sW5#tU5nZ?CY(A~(eV%Uu$E#oL=~fcr(> z*>_Kgeh+cN2T=7}o;6-PHSvlCU;ghSpC++o4KQXoFCmxYxom%!x}7Xf*~a+*59gD) z=}(p4+<01KC_ej3%h1=%EuVBG&3fgx;DQW#(#%b-e!4G{OPhK-nEJTtSovbgQ)c`; zX^2dGgAd?m%WAiHthiDun}gl~)7qpvm?F5EzD;RN$`o`s066}+t2h5D{P4_eLUc|RFjT5pxt=`cQf{D z^O*g(Aike(EfShHZ{FPLpzk%lxh2Ub;~Fn6xJi?Z+`vd(Wns|8Pql545T&^88TvX% z?m5XAQ?nU++jH|4@kQH~A9A*?68g;2Xo?@h>2Pyn#xKyuy%y5AI5`bt4gEEh;8( z3yus;2GTyRbW9N63U9WolIZisX`}0NX>I!UU7!)4tw9;B z)cVxK1+p0ijU334q4E2(P<840rW+}4l^9o#f0&~dnUY_GyKbtNLRloMN?u#Q zY4G_+o4e&&seK8@A1Sk~n6P&%Qd~%$q!yxp!Ksa&sRNZ{egGew*gow@8kA(gcs_6Bz!kxwDcrP zPnDbd%wA3ZIQjLX>qENdKk~hG;6288b}|k^Zs8>Qh3H^E4Z;`E>N^_5I6NFem+{>+ z77Z^}nA1A!WwZ|hFTa}=P*dVQupb|YJ-P-P^uTvkF4}SNPF$biu_ul7afWpK**?7` z;zu)Oa-R1`3mkgvR28hv(}q<#LjOi7JT4$!A8>MUiI60K#+?&TvhT+d*PL1mL^_%o z5AvK5(bD%lK#vvRL>QX5uTbK3Z?S^Qa&qR@w@TD}q)$wEoh9VE+38b5V)Le2UMkW2 z2tF>25S|AIuOg-tl)d7@l8pEgcporDgT$5~K4Tip+}Hc?;HKJmBaiF7^{QdQjegIgeQ!u{heD+ z%Jv6&zA1TL%!G#t5QCB4VX8_0bIj9kQx2bB8-8&K`Tp2=s{lXu(HX}>;|>e9wc6)M zfkw;ewtd}F{1=X}A9d?(Gd%G+DEp7UT1a_%&wI@|$&%S_rekbbu{nF4qg}tkO zR5JWSR^BxoTKVlr!w=ouo6NfO9i+5y0Rsvr>N3}Rj!ejr6E)gnWvNb^S(%VM;W&Ed zJ4&Jl_n#8I&CoO{%49PTBxVzA5N<*+pRaUDmI z=u`QEDiABTn20Z>xQ&vID*Vkv4V9LuD)JTEQ!;l~K7MBF@;Xy9-o5W>0^joPVf#|s z!otHLRc?|Zf%Oz>2v zasx~eU33hA{Rz4A1vLS%b*!<+;ZX32rf~c)KhX@;eHVWtyGT}i@{O{j$5Z>77uRx8 zQ4g+{_?28%^75b`TeVSFnl0vQyppl~9^=4xk?#=z;;Y>fwH}Syr(>=2QDVvZI_fO= zcVee?U{zw$>GIm=K^Z`bMBUT<-m%D$XGHF0<`z%RD2c1!vAuAY?%JA-9*RKmd z#^ z09u77CaROlxogoC8dlsBBO^JiI96G@qJIq|Mz9+4Iz2|1L6?7KzMSFWzZkaJ&@_xe z^18-7va(H^Lm0E>gUH3t@d#d>d~@cokarZlxvlu#P zf^IZF-en>$Ok6%SFJUWalL##EQ{(0 zZvFfX*#JhprWwdbi*m~KFUr42Nc5bXnzOSfpODH^tXCA4<;d*`&f|)@P~CNpq{# zd+{&Ky#fF`T&9x-XVe65(f#cHF2TDPootw8i8DJr?yhFNRH8X)+Oc z6NCPC?fOCXWKs61*2+RBe;u#ma~~`oPJT?^IAT)XfOFb=v4lf-bpo-RvW zuX}`$z%Oep%9FdEybn6^bUE>b|1GZclTQCHOm6G{WjF`+ruXW%njZ|Ts;~camqbdT zPmpy|`(~}SQ)UimRD`rx`cpAAYY~bpXJnu~#`wwSZ%=#)GbO2b+s6~ZVP#xy%ZkL~x-q04O=0D5w-lM7uj+;9y{ujFn;sa^Z20`Z}1h4O|*2E#ZLbaCy zV3_Qhz^rQ#fW5QY-}noP9S0sV=<@!r-u9zEc}!|^ykG92H}yHVC|Z2I1DRYweW4#9 zGc#&*C=18Ra)l{_u8&qL7BWkIb55pLx$!>?Ddlwu(0hcJfu_7|KFU7LB*a8J<6nAX z?JgyJ8(yA^Ij*E#dUtyxrcDr6&mQLO+vro1HqkwSoVp` zz5};t*OGWfDob$bP*F;lo8Js&`Q`p9DkKhTn|%M7sZR-edQHnchrI8VUAAU-bJcl+ zo1JRw#ITE~wuid6JCj7WCQz1XZa4nj`(}>lR1K3sw{^_W<40xS-c!ocK$b_fPyroS zpm)J|c?}X!2($z{(Mb6|dJV?t_~G)fn}0X_IK^n$bIeYGK^G}VM+;YpMeEqh%MsHj~9@yNpSB-c=h z4)yPGV(!DgaZK3h0u%eVRVC^o$jH$b0(3?{S@@<-XK9kbyo0o7RLuV->+(ftr47VA z6AV7`bjln5Xo+|!YhlYmI;aGA=nH64RG?#!fLR|qi&rDQYu2FVt2Q!B+$q=3#avEp zcZvD>B$nLO!i{LfeK;lUF+T$W0iMytvgEB?t8q56{(H+raXjE)Y5+Lc8Hi{y9h2Y; zVSM9d)zFbG+#hdoIgXcZPeX|n;p!hV3BkQRe{0lO*Hc}M>&q8j!j{FhjhRNkEaYW* zB$tc!7tmP)z21|qDci|=4*-|39$nilm*YCK2CVfBN-Vtgv!ZVeVnf-_9~-#7t$$(_9P;yvd&b>{)zDp&g|#5`T+ zzhSk=Qpf)8dwRwI{-2wIam{CS7Ye_mKyg2?X6+lhY6AOO9~@cTS6w|)qzB;Vbu&j? zqv45|hT-#^}{X|Umlu9~jrr@zz0*AeiMQTIEra;-dd$yUJxsDaie&&pmo zdV_0O%S+~_`<+Q&Am=izMXC#9e;T4r3o-(bgY`w zTAp^C6TJ2<)|xhpe|EfezBxleO{o@{#tD^d1L#{m7a)q`1Tss$6wUMt5Wf9-bBKiz zlUv1dUhqBm`&l0;)`}c{e(m}FP@30QvA%WehFE_x|L~98-5b^`to*$hrNVvMEaJY> z=_Om$MSo1zG)I2?M85!vZ_RpGwLLUb!GB{&V2uZki{nhB^BuA1ayCPD; z#{R&=znNZNuHxC?MLR%teDVI2TMqOMzmhGBRsaB#Dr$9QKs{l+1Gobrq{mFWy`hg9 zgKp{pdF0fqm}oQV>VeqkamFV?k6sXY6Us9_C0&=-PQT3n;TkHf>WCa=_O56l{i~=j z%f6IHdD$;dK6N9Lm74g_bmbYalLhR;6Oz17|AyhvT!=EE+!JAOU**olqh#$ChA2}dWiqJ6qu=D$cW*{)SA5a(LW zBb->1c|-4LxL3n(Z>qIGqBxam+l&}>Y?I+-*S-;%qdE2;D_qZyzQ0t!V_sKwEq~y+ zj(Ar^Mcr|?_3r)ihk&X3_^SqE)VqG`k>)gBZ#R{7?;8EZHLUsPe6y&(jNuN zkqo4mM|<>a?bJw-g<_ZAFLyJm9^Qx~zh#uQ_XZp;RVFUwR}H$pEdRgcv=rW_JwbSk zWo$Ejl}-`YkguR36kfYwXJRaaij3b zBgkvtV%c7|ts1Np*S`ZarhNgHhZ>Nqpv=bf%|-RQhUw+UQCx?@gb$>0=wTWASE=|(T#|41~gfAD<(@2AF+r|*4#Jy zt%|vc$)}IL{xLTlt{m(T+3~MIIk-nUD4JcfWKX3 z+eS8ETcE5twQNhW;}|`-$ya-B5vQ0;o?4Ure>)hO%DHIU{%67OKjP4iRF*qR&jOeI z+ffE_=Oiv(U-alWGpROnOpr_AGvAf5;#G0=MJ|M}`_92guM1oB|2@G&2P|;p`a{9> ze%KE*>*<;Rxbt^NtcgYn(1>Two(%<=4Kf*;K%WxbHv6&O52%fqsji}$m_iruUiUC1 zorHOd7Dw|mIjpgGe&1%zkl3a4eaqA0kyr*|Rq+)fT4}v43BtA($FXCxl(3oFo{INfX**?OoyPJ#TYIsQs(9ukgDoj@*Z@}T{o-!~9CJl46 zbHzkO-vdAfd>@2#$tVFd$4~(a2Y+#Iotn^AIv>fpU70Wkw`Fcw`GAbVA{aUVT(m)u zJ19|adHaV{2lpbQE(-#D1KaF*=_g*7=~%!mTYBzLd_18GvT7_S@fHcXlLUj2y1GK5 z1{X+TX*f1E`a!_O#rdg=p}T_9+1!pbxanW#L@|&_Ysr;tGayxvspGt0Zg< zfTCu|AZ)^vfg)Jlz4h%L=wq5-I$;e&U*6{8teNWTI=DgrpWZhcAc1$js&n+jA}0EB zCl^M!mF7yk{ZR03^6!*(MBQb3UuHG7tPocm1ibcbhx2$@ynlh@{{P#pN5CYgBuGR; zjIjsh0(1WMLI7~g)4H(t$Lgib1kH|daj{=xaW~y>y;Vv<>Iw%Jm#9aX6lI z?Vr)nxze3XraFS`eX!_-h$0kc$ILg>eE{Q6&`0Y{NJxm8>O$(2LC^*P!Ryf#FU_g7 zB#3ESYte>wk}flYE-upN{++ij@>|ob0#~!Wlk>-ke#Col-XrCklT4zo;WeDniX^(V z6(HSQqP-8A$7?bh3*SGv@n)l)p3aWU@~@nxE`I&MatkUUe)Nrx z{U?I0*LIm1VQenRIq>$ut&A{cl`)SMS0Zocox_+IGDVyW1R@F=M05nKEfX}2w>hZ? zO@I^JXFP7J0H_7VHvti=48&YOaNx570(ZcZ+(Q5Y)||FdqA^7-V+Z*|RM>YokKbj+ z;+i!f$e$?uE^ne|5eMJWmciap%Q^du9!24r^VwjXW8;jpo)$g8jWzL|TCkOc;PT1H zHWa*!2iv|8=o6rdOLIK+)(zUpx=ug2)>Pf>a%xTA%v7G_w8$9m6aWnX6tRPEt5Qlh zFNAXSrhAMnPu>ahYgKqPHoa<;BsEGSE+ci97F zJp$kn{enS&JbmumHX!`Je?LkL6sDh-$n>QJlOqS);E+9V>+@@3u_`JnYbSmuX9I5| z<}y2Nrpiba)}_`3-HhiVc?Ea>*UVnrgr!X2-EMCBEnU?r<1xwOJnw3DddCYBpN(@U zE92Glbm{K2>SU|Gj!}@Atl@s?csA zS9V-($^+%=>N>&Hq6$=cF4(^NElqy~I zf?@r-)vG!DX&eWQn0MPVF6(++w`PU^wAR4(tt`79pIveAOW-o5BYXlkV_cnB1vV<# zmUf1xxa`w^9^NIt#pZHnns#xShteyx4o8_U!(n}6X~hme_Pv;0FCH;Bk~w=;7K#~X z#-sr5YQ;F1$6!ES-j_$-Yz3P7Av{A|m$Qf5sD>6u2aFrKUdMnJBMEZjcZ)iBfNoh% z+MN{JNaiNd4|WvwVN;-LY`(>_4bX|9G#_ z?eHDtA(6jsJXHD7SdGU7kUkJSHyKS-LCjZW|9W5A?YE+VJr3Q#r*?_nNLYHy0(XS$sEncCxz_NPG{FU$*T6 zldBqJ<*5np_1xI)D^W4HQQ@=<$UF>Aa$fQ3)vE{Y>0pR_Ws|61PC$kR;J&RHON9?< z$>E)~R1T1pDj7Imp)gaX@Rdl!U9Tfr3Q!Doe5J_bxli>lL(@xS*DL=voZZe#@px@Q zT3deWZoNIJ(+IPeYn&fCAg@s?QZj22Mc_Boy8D%{Y?X!zC5c&%6QBxTTVhw|`Ab>1 zK#9BN%^}<1%R!AFaxzl?CZ1P*B`pRxBqs#x9z&mhSz-rt!I4UYCnPC6GEr`AP`+MBf@W{wlBS@qqgU_b+D)?DF zNT36d-%RaE1nXFk@R_7NSoneh*3@t(HM3>?_H%Y^6GLzAwoj-TBeitDQ~FGw_s_Hz z=Le&z)~`s2nniuAn9>fZ{lM0Ks&M@pS${z6ma!U~cD`(nJLto32cC4aydKb+FSfWQHOHsvwXF6KhVzcytXQ%l6I0o z;KZLt8cEyz4169Y$Z2O&mO7^|Q)?+^+RL9*<Dl>%-Iy>WLC5dP56qNYx)CeJpdwuEa;Q(k|Ao{8Xq`gri`$v z%x-F`;pn?lkvf_38U1&6e}U8J{mCGRx=6oKDljmP1^=RScfAdsXMol3i+)C-SpT-=c%t` zn($YBE46jv`gI}oZhAE!fq*9Hzk(3wT7dz5OgJf4Ef2QjLXU-W;)7YxhYv!atgRr! z;|yT%2KsZ@F)wy1Gf!uxLdSekUc5JHz@ct(3=yVbT8CWUgI0H$T|8iH9(I-yQ`@?_ z1pv{glw$CG2J$-!BsOiXXlT$*V36F@0tK0e`mwoep2u6D@9=21Q|GaZNgM3{pz)~5 zXc%sE=z3n1jptj92?mbecRns{Rc2{Q?tyWw5f+% zm8Ap+&L0mWror&-UEZ|km;M~;&c$Ey<2DO*U=Xhxm_6oYx42f+eQe{on!j=2RiERQ zfE(>E#v8^mIQs0XQuP5YbmN|-{RLlbKy_|d6+yD?7kGRw#9i))DX)}J+$ZIS9U*v- z=ixjY3`Ofp7N34Uw}TtnVZkf!XqN`V@S#(xShDr;I&m|NuYUmqRj!A^gqWO>$kw%w z27=g~wn9HJrYLcAbkrB%;gC#Q>iCDL-%HsW{xCNUGUy`a%+mFdrTk0wK?~6>W8_<7 znb!q*|(vZTj&^L_gQ$N&Db#pMK6&xMkYS@S(J0Y>dfDRf6;iSN?NK zSjcpUucckD+TGn<5^9jGC~vyKJ_-dBx%q*mqL@~dH%0`y3hCbzpv-@JkP!N<(%``pS{<9ulIVd z_gY^}T$vS3Rlg7XQ3Z?~_-4I=Pd|W#k2AjLCQB1UD}i30gp&j!%fYUw4DH)eKUaMK z))BeG;s}d>#W|&xH!i=K^YPtJVzg_kK>g_EM+Qji{OUaZoXr4XY#v-E)OR)Qpqa%Ewr&};UD3ldLDfT!O*bMQkRM{B z6CKADVA^W0)pqvU*+7#D{Ga2v?HfKKinq`T#FjX2LzFcTpUt{XW&80SEt!9m5G_bO zF*tRvF%>qNfvv)RR7;oQk;hKPoyCo8O9Bw2_q9_$v0OKyGXYD5j!!t-DuFc6Wh%A6Q?AKpWsb< z*&naotb`jq{aD}$x6Tyo(YyBJ@{7<;%mT^3AeC3H1(kx?56{rrdC*0ynRS?8)NqX6!7Y z;Q?>JdPss`pmp=(Eq~b2l}r$`T!1JZ0Hb-A`;LynZkn`$;I*(gtnAGK<6~Om`|#2Ge|Szz5yCzEdZp zUIP~TD_Vd>RH!5milA15PkFaal=Gw(i^6FQUM%)x{lOu&%y3m0yqQ;VcRHqx({Z!pVtl= z;VWQfaQDzV%Um#ih##4UI`}=ebtr^j45ebXVz3=W!N1AySepLSNx4}7OlrZM&?Mvh zn9#@auScXyzW4!&j5G4GN2c6Q3M0Cj-0_%mh%9r=8s&W3gX+6>?%;UZDwRC)$I#!k zFoy0GK4%8RoBx_d$nlq3X`20sgTIeHw$1e17ZOz_Tx+6k+dIcT({Lmgc)~oPSCJdE zHZGT%$LJ(yRpJKgI&jvL2lijztleiKdJjQ+kvd+oqmn1jNG#4PxAe^X`sVBV^|IiU z`^t%}L_jVwDT}W@s3D#k2O33OxJE{9Z+pNCVPI{4ecXlD9;V1%p+Sp3c+xgl}}hWj z{fH|auv)vr?=#gu$8)xZhKD~E)L9pfy&PsM7&XGnz3 zPRJ{cqV8jW4SMqT<_7%@e`_S*CI)2bL35i~6nz8ocxI3$*wtU4DF<5?qi@f71;LO- z3=Yf(m^t#JwDTvnPEgAYVi7*^m^R5PvvPi9Xb7fj$d`c!--+?YUa^Q8=#1>Y#IdZx z5b&GI5?2*T8!{H7+8h~oteh&-E(FI+cKmBo!Y7CFvc`1%csPnKUt^axFRa{#WEBNu z>6{d($e!B*fQeV)v!j}`4LebTz_r$lT&5-J6Fs{){IRts%!@XQ;fa5UW4_| z?+Ej?w^!0E#y$a2IlvT9p64hIn|)o@MppLMQ8}tf3qoIxuh_kb`NdAZM|m@K-d(9v z=yYCw&y{-})dH2ZJLdI)JhjV}t}M_jyr=tqEy~+2pEQ6Rf4!!(ZiRcv<(Tf3)Dn5A9Py0DDYixNW6gX3&+vK-nP#6_S<20aNnqP z_rPnBgWCwF02yAMOFSdE>o^ETO18S*s-XZ=7$he2ceUJ55DX-`(`OnzR^MK+85&_a zBk866JZFVeQ!tnB`!&`aMNSp?N;>nGMe4>f3&sez6&`iVwGcvo6Lf5zx3-4;C9plZ z_&Lg`m|C>tHY!RP z;j4P8h#IE4IJv~$RG6{ZKQfl$6>9D74nt=~CM4DZGjD%?D=rEi9MiPVd=A-P@tFO< zkpfWalVDc;YN$bZ>p1VVMkMju@k)GE6+)X@fP5G0tcZPt=-XLbZsTV=j}A8}efDNS z#JHCy=eRmZ;YlTWp?}Vi&Q(98Y|N_WC68>~L)Xq*#XQ^zQKorigvCH+E74*QwxJ*N zsYn0)4~JU+viCZK9+n1|SVpnm4hXKRK(_7xB?PBCJ-rZ7{kd}9H@&Mxr|6K30k=6QHuglN>i@E0r?^keSMJat`n!Q)UnyWq(MgK5=VR|6`L zOm2z3UA%nwn8dH|+9!&@wf4FowFbZ+ID!gpHfo^?=a+>XRKbQ*Wed6f-_)Y% zZ;QPfE8dmR5M~HgSQyuYOL@BO=8!7-aVaTc{k8MTa!5CGh`RUS!868JbSs{RY0a>WUk zCdq3}ByG?>pZT1<@t?u?rDWa09LoV${;-*iy5|M<#jm1_eto5pZh8&|Tt zy);dlEhc`l?xcTaX`P;wc~t)CELqZ&@qgzd;q9H#oMPoOif`GP2cL#~%bq*dLGm05 zhEH;x;E8k1>p2{#!{0h|1l1eBOZs&+P4Yk@UK9bnuD%~l%HA~v#l`J3MVwmVXthe& z>kPh*KXqb*R+mBX-rEo()4=Oh9A*~${a)wL_YX}4lsR%-i<6R0_CQmy367I|xn28U z>~hZ^M{k~-(p|lN$2XMqYl_yaF3bO-u|3$G$=UCpdDNU?JP_p}TJO^oTVWW2xna ztxSeKf*L~X$ozUm`*G;(weVOd?By%8YD%~<1yY`3j0i%1Y1l&Qc5cb>)DT z)CX@6niP~Dd@ISKUd~*qG7daS6;j>09*)RPZGzI7q8HsU@-k52O;*nFhAZ@<|C|s- zb45&Ua_x_;P<*Jsas3pWCYhJFdB9K5-O9$TF~ShabQqMe%{9Fv-)+_h8sgl z^O5T;#Kx_ZqzTfDAJepC2x?SCZ+C;(DEP2}3a01=Fmn;tI|0^q+FKu(02Kn8(S+*q zm78hq-J^-tU^U>GtdoBRerEjlipd5=0XZ9+IaZa|e3TIi6=6WFeCh%&c>o-iW7Z9#-h3md6pd(-z9iwO1Mu4U&1wAacxG*&SAi zfsR;JxQ>ftU*)wedgEW`itIo#`{~g=72e``!U))XJ;4qfV50X}sS|j-Oy1oRFsDnN z_89?kj^gF+K}d7zgwQH*xVg(C06C;xnY zcQk~?k><=D?Gthg)f?__I`XJEA3HVUUpb!kH0n#-e1x$nbFc z>}U-sp6z44BW(5zxFRaSYW0>~6i%yQerZ@cGYCi29ao^j`#vej^?{}am?d^WgX-N} zn53j<2h#*wU1gDDOX&NxTn9`4xSoHu5(BC#8={8eTVMksK29^LbP6JV8AlM4hMWlS z+qwTTwuF@;MXOfoP${w0@cy6oH*b*LCs?V9fiuB7JJovdax}@xXeO<&(jpv_kXPzxk-AWX%kWcpD zYc}$Q%JhK(OR%?)(m%^aACP_dJctUSlaur=Zm83H+^hMWd zxpxZ>KO8s(W%OV!f&q1`{e|9?OP{qTGN%?|Z}LL3A0tf8)W%eFM2@qgqt*VMkrJ-< z?a@>7T3Mzy+FLIJ3pC>(oC$uu>4qPyWXqr&d{%M;Y(g|0SN@@44{yGU`% zk010v>UT11kAzon$d*iaRyWw_wd+S?<9@KEa%fMV22S86M=m2cdYr|Gz`qk5p@WB) z2J52q9amtA`58%Rv|}#D6kXqs_-UiB$7o*h>hc}pEp|IPa5na>(G9bUUAMv+i}&}i zZS;O^jX%#02zXciT!_#c++!2%7rPVDB^8`gLSkXF*C}eA*Q$ZQ#IX`-+=9-7hT{kn zCr-Og|HAz42bH!nmYI&D6Y|YcrobN&NNI(I;?|_K`8*i8AX<#M!EhKQ6Q?o>Nghta ze)LGCZxnjYXGR5rrKha6c4u6M<*FVxSnoy~?LGjrYm*Ds;Fk2e_%2=dpV6z};@S_; zC8YrR+GRqAQ#FuS1a)74$Q$-vfkUL4(FxPm)mxg~AvKPtU> z8V;IGxrTXsp{b006#z&Out_m3%>z?L*5csoa{UTYL z)%3Uv_)g~&PBsYHi=95gOL7qcXu=9(s4*h-~n?pGh5Qx z+|*(Fyhf8Uuh(x1p#`}m8m(irg$Q-ND`$F7lj-qAkrO|XQnHQb^g@<~4Z6;VTHu*M zZuG1r(wWzp)P3?2Orp1oH_15VI+5OxPh>!Tz?@NTrj)rr_Yj2Dy@0z7GE$iAge_UMF*wm4!vX*;=uq!1O7XK~e7@c*S35m<+sfU}w*2 z5i2Rjnx%(%rx(EJsAdiYRdJ~3Ct62IdwZSIEy#)+)PX(Q1$zi8v*00U;a00929}=R z*4L^>lB97tws`?a%7ONccS!tYBxBY5#G#0Bv(VeZC=5s&nSrJJ&Sb#!Of>WDjEG1* zq)3mf)7a7V85HgjAo>G8giso6BLx=3ulaH-I(!M2Vud1(J{9Avm6-XiMDhkg#|X-A z5hXB*b}!5y?1!;$=eHL9s9;q(*=<|kC_dTJDbfLS!~g`&D+{#Qd7?!>X{W#@?HmpX zP%MM$%@lZ3f4Dce3hEm@M{Fw34wG&Y+LvIkU1SU`*+^B&%Kk85ss0bGTxOTmAZ6Mxjxdmos1pb_LX73gz~X zsVYk{!lEr4_>8$~r+@{uo!c(&KE+&Qw*nSy{e``2){wS0_jj5p;A&bkngmPB;yk$c zj8+$?Iz3Y{62b1}x4KO(TNzQCx^)AqW7P0A{?=dbC?Q%h;}$a325@$$9&_DQ9^&&6 zmhl6I5mlJr1$vqd1Bm;9f;C+Xz{x$w+`-i&-R3|62El(M`@5mg9oMP{4!KJ2`T{pr z%JwTimu!`(y?x>ZK!cO1`F~!EK`DNJklkt5-jyCET)rB3#H4q;uoyxue_r2%yy{yZw=tHXVHY`MCbSn3jSwvGlarspmH@d;)Tm;Nu=L{UrA9A1^XkJ z#&5BUHXsv1(F$|GShH&ZooPW5Y6X-5KUk)CP}jVR95LH7{T{1Y&Ky%h!e_u@TI}b) z`}=`Dd@`Cwk^-~cDa{fO*Hy6X3WS26cK{f+p2KxPUl-vn?J*1Rz_bG=l}fm52malE z-E`8q#ii7TE(lBrb4R4Gzk5HfBs;ww#I?($)B?~d0FKk!&8oh}JG15rW<;XGvKq?; zL+=A}Mh_wJH->_S-QSEShM8H1BSp>;cXTq)lFN67{W0qR)dqFMJcClnwq0WYBR&Rm zqAop2U@IHy92W3HeQM}f5dR%YO$<0lyA>g@CJ;}D=FUo78{5Ui{{$wHnb<#tnU@t% z0WOw%I5Egh{;-DJUFkkS-V_7US-3zBj+TYI?exl?d=?g;Rfi z&ci=_7gFJwj&%%$W^n#RAav`W?;H&!#gl;S++i?djUVLTN1$p0xjb#(;8%lX1A9g( z)h~T%*fMqiT)=U@Yd?7Je48zT5qD26(MbwnnZvcZvu*dCoGLU*reC!+66P&8$xdUKJ^AIAy|8eET#hQMLv{W)W1 zVA}!bbHHX}-ev%#Oiv-)y#G=9?g7?mtpDU#e>Wlp$&vrYdM_Y%$V{fdpXXM$Gbo$v zzVXJF^{&?RmO%mkreiPYHTZC1U1mfbeZ2w0%p6&&bXIyobmVH6mAV-VamBxUxBM2! z-bNLFpsvkA0t|eErGplTti`qK3KOkY1%eod|%J%XgB!2xmvZFK{$o?#uhHLoaT2y%{(K?E7L7&A0}h&7{sih-v(kszi4 z+o~j+r;LEik3?~9!aW7X5D}Cs_bXArB0j&eVe@>zWwtJrp#JQBPs0E5hZIjo+P}g0 z8x|p8G1<73vYwHwgXxO{Fow#nc)sIg;|zjg6RdKje2m!=^Vff^GJ+S=A7Q}@Z9E~_ zjLY+zldSCLP!RFGR@DaqgqJC)bwoj1-QJ4cDs=#(XRD1I)6!=R%-M~skpjJOhVxh5O)%CeRl>45rsFoX@ge#vvL6?e#! z58rGHw%nM%18l(0Y}ePLitrtXI-wlO=|ae|9TzH~G|FcI6Za@3wh~Z?R6YJzd#Y) zg}>*xz;K6ggHIy?T+BhmS}i{CAz(#EfE`oAsV$d6)-x8dU zQ4^by{)(JBE!k`f`2`EH`^k0`42@biMxSGJ3muE%kfBQ7lt_er99)HDZ(HbfHpUc1 zz#Z@A<>^rL0U*{ec_0Ywycnnt01Q<69wjXe%+w*QkV@7oK3`B+2-Of=7e5F^yvsP> z!08{3?1oS;b7UO_T55mng~>bK&^-nv)2znpjx0N5WbgCPB2vqA&&z&Su~z^vI0E1h z5$_ZFN-mCi&%^nDzPyi`*y%H0sQ6_y&1W3HT;r4!D}#mG!tY`nE|!|02LSUPg7VHU=>m!!@eG4-c6jI zeZH2|Bu0$5Kk^lS+U*eT=-(dW4p9N1UV~!lM{H*{Rjt4N=|?FdE+4n_9nyXKSMsgV zN^ku8^P;HmAU%2=2HRWdwZ&#GkXRo9JA9p$7}{gp{^utJKewA(bcbJT@Tt6wVVq)$ z``wy7qi3U*u3dXA#9K1+c0#r)Fh`qmk%5iq)6zZSr?6$7JRJ=h`M`5$1&S|~P-0#1tw*VTj??COsO|50R2c?ehZZKh%q^ zDY}7%WZ)>r(v@qk&TwHSN1iVJCzy^eVGUP5#PBCrSoNcnKwKX2I=AG0zM_coW~jo` z`MBs1U?<|ezCml~9mj|3*dDadi*$~2OT?TLg}p?4l0CkvD0Sz{#dnOG!l1j5d}@M8 zBwPopO4q7)1?%K+D%1wBZ_k1W^lh^c#YII>eBL2`+CJ+qhWh=b z2QX0HHGQy1uK^tD8$^&y=!haSvYr4J7uZ}TFQ6?39oBZVLaA_z@dE=xgY{TP6eF^d zb6TZz@NWR(`wh(Qn5qyh5iFTYu>lJ03oDJ*cR6eBT8c~rTbaj~w%2;z>qlam(ZRjt=vcmw@-WlL?&&$}t(3~)o7?;NMDY`O9mW?3xQ3}ae zTLh$NV3?lUN6X3FtahIY_^nuYspHtJX4m67C~UrnRP-fzS%^LpvmFAj!H8eQJOFA) z$W-!x{V2E6r3i@HGND&HP*;yPm2HE?|40gppG#qo{cNLXyb_9kP!VJBR1OVYN3}PO zEw}AJuv`W+@^W{Sz1;N`hH#$819-}m;lGEVY>kC#(Bq%r(%IQVp(aX8fR4lihp_TE z55&;}8l+`436M(CXWY$mo{8(VzcUDCvSo1YSs~>6fwptm3yeFjbOUc(Du4Nxe&O!g zWP;djlqWFFn467DK{0N}!Cf5xd=}6Xjco*%8~Zf<7uQRE2d zrC?87<=3&V;+g`}?=af+moQ|}*|`!No@a1fik+SwbI<)LHl7xToZ9Z-B0ca$=0)R< zY1PJEtRj}aP%SOPhX>Oq08PDpq211!McXV%hFF%MaV;p9azp%P&FEpsNF-q6j@!FmA=7 zT+o2-1-0EuTpHASD*>y$|M0=6Q3KlLp}ZictXvnDhE+PClwpHmV7DZ|S9}UWFs}LZ zgG}Yg#dj)Bhgd7~^X>V_toq{pzDN5VqE>W@e)HM1r%GQ&re=_QvKfi4D7~icBQ*Ij zgsMHAmHU0z-ko3R%0ZMs2SgrjiaLGe`PC{a@>uC|H4vX5%0e6P4Ons;k6N5=W=@!?tBPcluItFUv}RKEw`Wg01)8Xh#{% zOx@~8(=l}gwwS^k!=0tkI7N_Agh<}L&K4nx;&&iAgDAi;6ebIaftjZ)wk#ClEHDLo<+-f{qE>W!HVjsVz(gYh6PNOChRv-X@_2jfs^`6 zS0!*h^LZOn8StMuX2_ZnUb4ztTRKmU^=?V>YZ@XIS4x3>{b(E)JL^4wG|aU^dYL5x;~uNO^M3y`IPj7t zGDun~OQQWqO+E#`Bt2@?Ym|_v&4g}^um03PJ;QieVak%3NX@)j1e1CW{f*^TBQR*D z&#+pV`17u_=7q(M)EEB<5p23l;O4OdNp=MkFE~J%tinA&Aiit~1&ol1Y!j*bI%tTy za7G|}yF4WV;7txRzaW{JVaWg33x>m-1+?jz*6i)N7G@L2SmgghvmvJ4OMr#^voC&R z$Um?i2`Vn|Wjok({`~oVj*Tgf0nqOT;Xak?FnkU|MMB%x!hEgV4eRd7!nyoh>lH9S zG51)i)_;mi6V9X+UGTj)9-k}z-bVKmBrWZKMFA`^?PJR@r?TxSgCFG1za$ig;U4$% zI6~eUFea_u3o37BIlOzuCv9XEnd;$DwwR|zW@U9DR_y}>Zv*hakt1oD{0-a%Vi)CYZQtbw{Y)98dm6f zs1pG(8)N0v?tPx1wNqSrH}!G!K+ApREo8h_2a`Y#9T@xSJO(>5>RXBJ?_f^Tbvqc{ zR0+kfL-h2xzTO3OBRdE=<*@4*!7$w)Cbry?tf(LYU;F^ZFmpiTkL_x+{+ik$7)x!} zcE_h2CVb^=uo8%DY7j1-3P!APt8KI0C_D!E1x$Fsphf6xK;B$PBB6~_9CjM-F*+oj zo5N6-tfkR-=a<$Z^)2{y#1@shrLd0FU2(6(PiRH}qCC2Voc;<-=_z7c+zuftJ3BvL z0TmQxEKQYwfQ;p>ke%`vf>(V8^cxL<>3gcuIjjXO{2%T)pYY=n0eu@* z0I0=W*lzR599=&^A=8!KKVo`EQz#TB8~KSA)&IMbbsy<&`ErMTJjtsm{WZsayd*VQ zT;61x%qtG0mslb73CCQSQOb^Fb2LT#^IYeRFF*k(i#s6Cv9YD)z>-A-1{$U=escK4&|66+%tLESGGPg|^*duI-1NjfDiQ53{&I-@-^&;K~3yw5fQ zRQ=y~TyH~NFN2t++-8_=zR4<~2&_@sx7=*GJBM2h(|EsbY(YY`s?L{J4V}sY=qwlB zwH%lhX0F%YZBh%sx@ zN_mN4;W?vu*F~s{RzrR+cNA*q zR<7!Q;u^F2@VGon(%Ik4eVie*GHBoWHuxe_-v5pJ ziRhCnvoCAkZ2@izAzBS+JMZ`wd)z7=7yQ+a?QHuAeoj~{2aQ5UarGECuNbv|x*N!T z0M$p$r5&^Guxg?1qdbxqNNvY6zwQBmT~3=V{bxMW(8}i1XhH3}v1|^UsH3W^X2Cd> z0UFWx{JTlNenLsZ7&;F7oA=t5C2^GCgfJW`!IXCfWT&W$F_Mu}==46CLyO{HnL@F& zI~V%4VvaDuzFBJT{0`fY5ld}Hl7cTFmk!>H9MN_i?J!th2m##n1r}*b3}fZn@S%az z`F&5?trPfRps=oFMaFGFFrhg>5L#uRF~XW5fNJ|PLUYX&GVp2l^uouTM2lY3#q`_e zswLz#vSR2j^Qrz8)k6FN|ELe8j7`mZYdnv8bEv!ck*v+=AxfV=ivCFvJZt-B6gD6F z?{#$+tvQb#o`kmCy*Ss!bTsZ-qYh#~Z5NgO(IjM0!~4i<6F09psT#h!h&18glJ$Q9 zICB36X|5-i$8kM1nzzhT<2JH384Qp9rE?lSwCPwKJ*Bl!5-+r1c^hxRlUvAt)3LfX zwpGf~YWJFanMfK=d!e+B@58C5&P7LYL%?Gg*wJ>a?iX4b32s^@Cu<2iI+Jht&ZX$=A&}%Q_V%(wCxNh)GZw5{$_&T$M1Q-h+w~ z#X(Il2pu-SYlLnio&+{UhlUt;k3KimeuvGzbiA`n${7fKs;T~q-*=^Xy*(??UuGls z*ZE6ajfHz??oMagW{C3uS6%oHq3h2OKLe%EN9(u6Npoy$Y)X2)a>Ex2qhc_{Xq6ch zc#zLpbr40pQ($9&G6l<&CUJXy951=cDsqGYRjdSduAxr_BQU==o9Fe z*}+QWgRbEw4Y;~j>k}gi-7(n+z$)gYHM%b4L{a0*foQk~tNnp8vWGe&l^x7fvih;A z&9{9Ox_7ZD(_YL)<0iGh)dR?&vI+BQOLyomozL}1;j8&QiSAh_R#{(5?m}G!`+uVP z*Q{(A*_Y^{1UH-~~{q|{Jb2WG_fqQ|W;(n!j# zM!2;MSEs~&1z$Qr{SW22%b~BEJ^qdTRh+~4!9+A+%T<(KI*hNeb2;Bbxf+2;0(L9> zZ$(+j&duA*``K&<_NI=m^#?lH=T>)Daf!gx5%EpGP9&tGD2jNzm4D!G2SV&|$|2~q zni`beIOhdZAS!{gR27-k9?zDBY{qWrolgbu3q3A?rdXHw5c%mlN{IfRlNS5Rl>KWX zO8`9nDfPTlt?+VdYB{YXe`Dn*=<8iIMeUoZ$QG(X$eA{!=LCNDGHhA)NUU5^dmCm% zaC|u-2FC3JARO_f9CsMK!*`KHpP{tZWxxWfdT?4g1??y2Azf+=|4c=G8oe2+U%Cp` z$U2NcQo_hz-8qvYP7gZ}oC4vyb>4|Cxi4FwaV7Q>;}{jfrrU~-p^pFLCv2DmoB#0% za5>nAbv6S~M1AT|dyc20v-88P6ISNyfs2ZJU1mi3fK^=l!c?*s3PAoiAVfU)fX$y4`(pIl!c4@KGQi4nSXNO4gV}rDFXd|OU4%p@2-^Hl;-)*SUO7tIhL}Cv zfEgD5ww0I(IEisTM@HH$Fao>tbsI`JYmw*pLJV0x1G=kZC+`+={s^HjdlZ(R?tcd_ z#l2Tm+kevjM=4Iiz;pE2X#k9i?R8!Uu!8XWn{%0l@Z_z~!FUSBE8q^)#Zk}-XcpWz zE3KeI59KrVW>~A?%%*!jJBJ~xbWN#++j1i?p$olfyto~uD@gs!eufjTx3N2r3AXm9 z=)fQfE|$c{jE2x-%#NEnZZ6tvjFHNr)^`w>FAafeJH@)(y_)T-@$mD;0u-#m&)mK0 z@z;nW024-c255*cTQko9)mgobsCrGvWG}FMo9BI`rmp86j_%P_j20Y7uQS3j)e3;f z;~Z_^xZr{=YSDF9QtePVb?-C~++f4o#t+q9cbsWX<=1)g;q(LuN#+^(45l4{0<<=QW8H#tt@U`EcWnnbn zQ!TkA!sC!MJ`UtST34O@srzcr5c+PJb0Gd(d8d?F>61fAbrb4mK;pn73|T$Gn}nQx(k zV`H%rN4@^pM&%$-3?x451r$z-gxln)U}woo1uEO=xX`Qr3vc(|6{lfmOcjksv{k*K zqaZlcfD0L-i$&s~r*gI~(=~@`_5a)B#=jCiJoVqU>p+<^u=lt{k948W*VizES$g?L zkRhP602os*>+I}|x42RYWwD=Iz#QryIxEm<{M?4SYEUPYN=7x)S6gH0Upku%%4Ns< zryR!^1qj80o8ymURH4~xCDNYvDpxYru)Js~{`B}jJtQz3i)0$g>&D+?VlpW5t~c-k zEd6ImNl6L`1QUb$AqEXpN+%K}+<``IE>C9ipr%$Qwca(K5bpRl}=<86I~ zG~>_>*X;kj?ma1mo3C3s_c>JUv>;`?4CCW0JV2@K2X){|AeVG0Hw)-yc`%#p0*dAC zuRp0|W`=G*v)p)^!6*{*%Cr`8rcHLC?JlO+=BICz~TzkgICC2e2Q=r zoFM2ql;Dku&~2eY5yJ`~eoEMjYTpy`o+rOJhDSFD(Mr2TKocOGRgEDfP&)&fyUAN1 zddw2BZ#wALGmNw&9iw~(qg){j@8P(9w$InW>@}s+dSf+e<19$WN0PVpFo3TTW)B&H90W@d z%E0b1r>&0W0z8t9XW8TIs-8x{xG#@|GPBD^I^pU986WHZ83?f|CU_5ee2Lh)v-~C? zL(`Ep)1C=qHYkEB!zcw>G1vgDC{BhOSR)_c_G=gNE40031F( z$$fRkZ|qm-Mo_Uk?Mpt%(bDz%Y2%*PCl1!U@~pq|{q)h>OvXFR?)}SnEQ!cm`TQX| zd0eLaI&b(1jb~ds+iu1TlKeK}{E zs_#SRLuw-rDiqeWcUw40T{#M$J?zy}tiCYPL(+e7^|fbERw(T4}reQReaIyPd!=`!7<_mHQPjv`|AM+ce#HsR96XQIV? zUMsylzS=YQmS|75k^V~!IdT??<3mvT59qwqr3Z`K0;oh8N|Dy&{*~J5=~H^AXh=@L zAIEWAfJ|Fo0MCil*eEI#_9g2uk~k-}HYi8v;}SS}Ko~`>8-m5$ZZxT;_W8pzEE8!- zc*RHhW7ab_B~Wg|=AGJ{W{W%U;edE)!f=qnv!6qpb9$!SeWp?`?>WlZKboc+m_`~M z$)5-U)7QjnGWl8eGD8K9=m-r(=ng<{XNiet&?)=ViSI7=Y0OnaV~ zTmh^iu<(dL^!;E=HTi4Y_vb-@bw*(%unV;gbK&dYlm??jVHGfX$v4g*iBW@F#nPZe zhZPul#Ai)n+f6OVe9BwtuSC>JzuoFL8)+7swR)qeUBLVMYLNQe-1YY&q9P=TifLo% z6ClR(eBZplnC9{b=J=Q@<`7)$ZEHE^p-3rp6iKk;^gh^vvWBdM{^okRPOwMvW!^)5L;o0Il`(4VOUhyx#!>Y@1eQ2cmqqPcC!(O_<4KjicON1{ zaHc}DI_FWBwZTH9iLRL=E*~R)gK9c`>y^=sKR)ah&KKYx&=L&zi{pJflM?;Iihgn7 z&t+W1hIpcjv;<=3wNOG|)#r9^b^C^2K%Jg1{v}asic)jjj~+r!dNe!=4mqHl+<1!M z5Lay@1~H92P1J|!o_n@zg|8zvtMM_3dMsB(OtpoI4xDr5jRJf0%ka)dVS01!BM%NZ zIWAD3Vb@3%V>^W0EHZq<+5e2cdNb3nUv(oefQ!!_-}&cnOk2+SRoYZ!ram<~?VC4P zds47%I<$g-+^kAz$=*X;b=LoTz!Zo4dAe<0^KUi!pRry}NnLuyV}q$X=z94cI|m7c zb)!DOg!Ah+Wj)^%nrsyP2?`1P!^K(wrR=^&eJ9J6V+zRNAjy5jQgbqd9JShMvoW&a z)zW;UsK3Nw>Qb7gSJC)q_s&&wgk)prDlE>T)wcrf)~hQ58_O*%n8xUPpW{BiT))<; zMTc4g<{y58p+_Y@<1kT}Z0UB?yY5%tU+I(PNbeK9b`$bgHd-|A*fMiNqJ2vrCk$DeqU`$Z*d#{5Y$^(A*z$St!iK{XBkh@wNKS1)VrqR}h znVh}}CLgN>I*>W4gRbH@af2^b9^Dvt50pA(n8O+xLG&? zyT22QoSv#tBch|&2~*S~ZE`dxf#6aV1y-|FnXJTIyh(CuUq)Rl9_^4i^n0Rs?Ac-@ z%|xJ$=TxS)E)(jzsdb9;K)z?j(#{VfCb|d91=e}e3dT%IKOfe+U&l7}rZ6>53T%TB zQCMs6Z}!7`-9K&jN-sR5tBhI|w+RY@t0ETI2sX&W+(9j&!3|dkSwWfl_YbLcl7QL}Pk9&`b55Iy z(B~|@>@sSx1?gO!vs-@I4i8p*e|$t)=eUqsyi-#iYORY0+=O&CFxfmW5-j zEA0L4Q~g#P#q^}bIxo@emMXHH!llq^S3?%Y2JS{8b%E;KHjk(6mU6}LhVQ*UypfOvJygv z4uzMsJiEWckwvX^@gTSaUP;<2`za!$8pxBJ(B&@bzV4pwH0bMc8fhV-|7yUIVAsa1oCAm)+w#33 z_q&EEV%Ml>$1C4ymfP!oVkZ(f2~Ma))y+?ggQ*0+43>o3YuaLI$z$8F1qS)`7|=w8 zedTreXV<4k^?N!l0LBArikpM;Wt^P%0vK6{m^Fu|Ydmj~#=5=b<@b{{kairuW4IGK z?jU%jMkUuHiLX-o@J;uzxz^%5?t+#a{P$1b;{G%*y;TnHW$l58@#4`h7B#expLhIF zqni9GhP4_7;$!pf%3MqLKEQ)tJteIUKB3F~$H7mT1moMBGF^YX*%*W^Q0@xjac#FE zv6_=5KedW}*Lk{2%>Sxcd@R(5s4W=(Wzn8zlysMe7Fhfo0Xd6#W4h-GA8 zmM@c0z8OChJVeuZR-$NhOxvBGU>}Qi;;@m<_L{r@&p^IA_etQfB5JBd4B-xNU?nEu z)h4b_6*_lH45lVcT^=u3ZuXXvIR7+iZH_L!C0sP14UYuP3qPOBbAVn@`yIi>=GQsw z7>u8*q&EFls%y$H@Q9x*`V#h19wJush}px%o}|hWR1| zDX8Yz-aM<=Yv1$PMVaCVi_&9TmOC1kA7*nA`sCM{;Fxg7;Sc-3y5yeo9?Xj_PlteV zFa0`qmZz#c@mp66?BIUNV>9y=-?K4(gMU!^3+lq+G}UP>4I_Toum5y=eWFGN&eu5V zdNWCWaL;9Tz!Ix{R(OWU+ZMYE=dSKi`DpPFOgeTY&CrrF%crUPU`h*o5|J;v6M#~_ zab~j17Vt}^>;tE8(BP)+Mb?D`muI_BRPzM)>K=qPwE#%sknC;@fS`{JYIVW)B1`UK zVjPyqIb~+@H|0YJ&azisz7#Zq>fNuK zj=xRpJNPXc4(2ux3S<-!T$Cv(1NmjgSpUNiLz;oRu$w5Go-NL2$$cJ9#&sK!Tvikr zHTB*oc8v)gPDv)@4fjO=*f@jZ)~n5D>&}LVMSI*eJLx6-)M%m~FPx=29gv&bi_Sj@ zY^(E}QeV~Bm~`$h4)T!7)+rW~L^}KQ2#EjNM6Z>Gy)P(95b?kPA0t~!eVRh#_*z_zNgJ0_L_cL_sk|i z@tL#ysfpb^TWN^h1~Q$ZA0C(_YE^p4nyLz)(1@CGtR${C41nYB{6~_f<6Vp*- zCww-0NhKYQ!>bcxtQi}RyUgz4dMR(!+8D3kA;@dq(_Fw ztzwD^KQd4pn=e%6a!@c*_yp4}PI2Ln34o4Cg(5b~-d zNia>ka-cmWs!3^ zC>jP3;uHR5#1(Ga6TmiDlaB9%&rC0La@UVP*8A7M5Z)FJZ1vual`{)}oqLf-N8Df2 zU<-&hE%su)TW}{s7P$-$~uj{i{v`U(SDaO!MvdproI&Q)r0d)D6-Ntc9i0_8mJE3Q+{O{M{9aPlOjN?f(**sJYh@_a|JL{2aYM`AKpyw|+u=iXs zK@5J0_wQ?wpAUl|wR)zXhqMwqm7Fxt<-7%nloE5C<+p{-yN>l9g)J%!w~YCc+~#CD z1NSi}we*~;wPCmmfC4^b zHk9ZbS|{}N*E%lDKU@4u-FK(z-X~n_v5+ra4cJP7F)AGK{81@wNMf_KHvKLC=bzQ> zB*VslajeEcB0^jGf>+z0tQ zSOmel`~-lIO%##l;yJxW2M2m@H_QA53V?+9@F6jw8fu-R7j*^44Gx3?< zm4K$=PmPR))jJ*6Ldo6J%lSWlwri!AUcx%gj$4EaFeL`3y?QYu4N)+^WE!{_uZs`lVM=e8Wgb{Cj?PsH8iEpNhoe#G=bg8-YJYwT^&M=pNH+j9=9u zeMXbc8-M?>`Vxq{PDhV@NCdHoD4XYgV5MTDuIqXgeF=Bl^w}^FEn20e@16Ce_u&Xw zY;xzc_WW5bO&Vq89AEk4yLPSplJ~84l%8=6p>32ilRG?s&kTL(_v(LGclMPmU*^Sd(d*iRK<;0~FI8mDkIvSrs!VqrSSgtf%QG-g(xs48z# zBr@-HI>ke34N3r(k3>Nv0PF3bD z+~oqqxCogUA>eDl0%*1?{s?%Dx^~;5#V)mKe>BEIXwQp8K*Cq_~1UtX@p@*Inc_bNS#e*4oExMdkuXykbItN-XsyDXFh7+@iY4W!c* z?UZQ8=G2hK(uS5?;gPNHS;7tA6R-{a&knQIxP4O+R^EpZWc+)6^>Sv1WYX}PifI-cqT--OQvw1dm`Q2P zaij;`XXs?Iy~(-#i0R@q`gnzs6_LM!F^K9Aa?4Hz6MRY zdEVaY2-UZ&fRiGI-DAl&uEiO^Eez2E_(LYg#CJj}Zp>^@%DM-Y!Nitgw(DPxVC)wQ zW36u#5V4`!?7ELjcx`6R5UVdQ<|#omcuR^I&0uV(07qtT~jNWLX| zl_cDJWz_*aLd$i%rp0gT{$gHas~RyJ7WI6pxlg|uMLD?9cP4^>*%A9=pE=%Kb(_ct zmG`-S7!z%Uu1PWyy?dcnqS`n;rz^ZhXudtme%$hp5RWBa?#A$TP9dnL?>2W04|WoY zxAZnP%{FJJ_0gp@I>5+M?YD5nV|`GoqCVpcDX0d^|5RGGK35IohQg~ioktVJi};f) zKT%*D#+3Xqf%j)>PKB;1b1$ty@o~BXX%cex&?btS;GF8j=ajv(s*t0Aqb1Byfr+#T z)zp4EWe8bMtjHgaU^W{u2XoWm5@?V_D%!iQo=^ULh_f}1=LH$Yr|9U=&vfF|JzycTApaXzT5$2F7!BuuOP zRNcx)gdR>bFS^|JE}VVcJ3qWzFvx#+HUC-#aS#5- z6mGoOu!*?E?Y+Z=$)ZF{(S=7~1fQ^j=9y%8t@O@rRUPhK8O+=sbMNT82mdxKK7C-qGnUmK7*55E#vcDS~~eGp3_E^wVyb25wYBzp&_6g;n)-sEtK*+_!(geSv*!D+sDxKfOHOJyr=SBA24KiN~MmZ z$i&0Ww{Y|mHW&9t`7;lBcPgf@Ujui9`|N0N{!r>*B0=Q)Xuvk|z=apSMh8HBgO$vP zy6S7VWap>PxmfUcA(tIFF`_(*$WTGd1%i~Thj}!Dy>%iLE#!~WIr+#3?Q%;~`MSOM z#nn;|z$*V~xB=FN>(rl~7{q0h( zv17i!JMRvkyLT@N!$nsmDb-^FZ@<4>3weTz)r%y3yoH;b^9dsbCu%` zRf7vks!T^=7;V8th=yvKV78!Bzy%t@MY5-%jSm_-Elg8zA8&V$bm|_n?MQ%tAr01N zv5%st{HoD#IMM3Y>4FnX!J~4b(pjWMVI~sy^fC4q;SexJry)Zp*OUpo=!tLzVLP>U zDdhOV3g3)FL3{yB%Y^HZ@K2lqaF#@4g`bXlyZaDwcY$cwU)b$sR>vw+H9;&-kwT}g zz5r*mbDwdh7ECFnT=m`y+Kw>)HYoc^Ud(#&T)%~>BxzF15p0YfZ1In*N@H78dBj(o z2Nfjl*xavExY#`G_Z9i*xgUI%K_l7hn|Dw_ z3f}YqukqTY?FN5-2`WFB$2is1_~$v%?sn72BX6L>sp(8QS2dH*vQrWpYW;;9Jts`R z_@(s^YV<8$I4%r@6xB9#7pRE&$nrU)0aHsEC&!k8NDOBm6>s^D;;_O3wB;)MPS&LL zRB7$5MB@AWk5^H&fo=1!GKV}5pu`V*TDzQs6cas(>(n0woXnaB$B|;d-80@AO2XC)-oi4sn;x?1bso~U{o|U25LyLn=59Z6}ZPMQ| zB1mvFdgd+?#~pr@SmFRU2YIr^Ca9LzfdQ@|;Fuj?4-rdBEg#&)o)M=mmnPOR|uy{s^T*sff6&xF(94OPRHi5u0`R9FxSW8MiV&-b`3FCKK6~cK^z?7{SFR-3ooj$` z!!%F0xx9c>8b9-H9;J$Hv?=ubzDq-g)ma0q4F6+yEZ0rn`)P2VYP*O`mewZRTR>Ki zs8xm49_Jb-U`+S z&JKF=dJ@AHlc<;0aXeh9Z2X^X9wSifg@4L5l&$@UnVh63LI6-pu98?Hb59{t*K-hV#i;K?TFsvwm_(wVTsFqU{A|1c^p!5`9b9ZEzLCBz<0_s%Q(c z&cCaq<>8!Uv89VcC_)q(v%y}X1#o7IlFsEPvKFo$nl&hxFR2CNrKNbfZl&h==iY@l zeFJ1UDiU}LT&D@>bW;qR=;s|p$O$*!ch@a8J|QS{&JKZrFS^1jU(AL;RGMG|B*HdH|V9X zb`DbbToghaY17Y8Fn4V?&WYJ6*=ak*S>cEnl;0Np{5QiGZFt%@ zV2m``Fat5P$fDDd@6MnjhaI~L`1nkP#c}Ys{Kyn!{*5JwA2!}1JDj-L?lMm|-dPCo zweyRW;`!p#!oO=yd$u7r(Sk6gsM~}Z=^U;T8N?M+emnTH(mne;xV|b+EtHTCxIkLu z{mM$%n(w_$ji*@N#9Kz;%`Yypg}ei6W7So=J)I1$){Ywr4q@w#^B+sMr8;HMAGN`)h>Uzs>oXB ze2c7L#zu;d=wWQ?0%*YLL;D|4ki{tU=DfJRB@X3p-ys2Drl0JvWe|!iKf%iI*)vtM zE6I56zlS2|lSlw0A9{>owEd;dBZ?G4cBELGlvNvkedHM2NkUc@Y~qQ1>%C29%isbe zV$wxJyX?+se>BhxG`N5Tb-$N403FuqJGqi@iYa>9(hyQ5CN}}x@s&v>p6+DEZ3)>S z@*_p=2etllu$~6cAf#l-ZnIZs-{OUnkLZ#4R3iEsNDbMbT37gDx+|=FTBxdkz}g68 z`^Mn6GmxV72croBT_S;LkwX~qFo(!YM?l3Hs7*3aZGZc8iFDLeX8`FxdL0m-D0&J# z9_sTy-?fiB(|LsVJ8}ivqpQma-`->!;yxw%GhpbG#FNOPJ-AT#KtKz6iJ!+`ucHDP zXQYEg(-7r(K;sy`FYvK>O99D9Cjr}q4LK&^V~6fWA!kN7eUdSgtyClMBr?SSO(K? zH+L*)-@$v&qe5}%)6!_b1Xb*6Y=*KCN+eA4GJl4AIv9PX*RW^Kv`|O2nrOW!r0~Je zl?G8O-A_<#TC6zHQ7C~CjzSsDNtV3?x=-keK@sIQ1fP^hiMthW2tGb%ou1`0ugt^- zx(`v*fg6$=!Ny>tA#MFf`NMA09Bif}-&15c;{#ugM-dX}%Xv>>zcWgn-U2&x0W^js z<%`#K+bnY6IS@4ECz|QQIEEW-_sE`3(h8J9kYD-F?gJ0GYsU*R*6z!PwtNzIb^8__ zFq;fesQ+1Kz(Q9MF;B!oZBhIChMvVi_|qnjvn~!yn+9Z1=JyG*kG^CC38rSmmt%FD zOtY^}OFPHn-+{jWBVNTzK+0^_aAUf+&N0?N z517D1&+YM2dGe9<{e6f9WJD$eyiQTl84OR+5$*n4#12=ifQ{#IfDn>Xaz9}*YJ4mZ z*xKYjYV>LW{bCzQ@sRYjb2wO!8$PN87aEG|-CZELFpx|YWI&a@B3g3PbEGwhHf^!{ zV72$zj|PA3!`k*1CR*PHCB+GYFTZ)Q+HjDv=VR|7NCSG;JE)WWk4yUqn?>ArBRc0x z1Mwoq=QDQs&#Ckjb@fUEpU>J5ef1dFtbh7oH4tUZjx^2R;Iy4IfaPRjBe#S+MQv=O+8ll3w1LDdv| zrGh6xC{33H6Od*=aIyX76@=r&OzAUpz}7trnpP)KgY>TM?v7FB11^sOWFSFuaDUp8 z+{&C!HcC4G$+|IaK0zx@(}TlK!IHAUW$^DQ!Z3@$kD0ggW)*W)cPrHoH)rK8*FHG% zH?k>7!ty+r8j;v$Q|Ogc7bcP)qBI#peIs72KdA9OK~K<^@Y1g zsSD@Drp{mFT19PQ2q&6Sn}*BXAom#tt%9E8?T_tIX3(S|58C5?{7(X2y^PXEL?=;n%4#mcFYel9PKN6AaE;qb z-gAJU^gaIGCo}||yar1~q-*d}mTc#=9}3-50*{G46W;)x2iCbePs{<|yx{}k#8vDO zlj<a6%si0sd z0{V%usAuvLFX$EVH<0lf8$Anjycib&buNUe8iZYpxYWrAR5|Lqv`;CD=<@-eL{1kg z3hzb^uGMSW>28IuI;1pPLX{>PFq`ojQ~yt@cwt?CO%zL`!JrO*~ws2 z%P#eAL&c#xH+A*F0yNJ*DCxCTFNyByt~5*irjV0RRjh)xPb)Y@Rh=9eP%m1@Ig0Y0 zfNUYkN+nok?i^Wsi6xz+fuk6WT_F_fsYx&OY8(y({3DbD3Ns?5G@~}ASMu0=joaAr0s`e@En2Gw| zMhQG^N{6sG$y1O0w$`i*&O7azhc<8IEanuyGJ-1PVeeT3$BK4Da>9?FQ~?gc2((8P zh=QhSZ&ugc!ScBk2(*eC4NOZFpjvaY>2c>>5l6$VqSzT@%kGYtF8HX=!aW;ap6ns1 zOVsvH(9@>89;fWd>PrVKz@9x^egy~=*C^=Ruq^{!!>qMaqlF-~WZJq?K5s6vW|B8g zB`ngjlU!TADLnr~@M>_kRgHwmYN^dqnZ+=-ezX}WmK*k}c(W&att_$?IcGT9>>+yv znxNjNng@`T6~!-ucPm+(!a@w-I&0G5*lrlbCc0qpETf!-Axl7Gy{J2Sr@eN|o2qno zX?JU;QXe5!tD99MeXG2+o)QYE2r>lHgRdi8a``n*o6$WaDm!K8*|9iq?oy_+#%)Np29eKIPX z0~(h8rp6imr0^5!JecOJ(e!b^GrF&spjcW$es0f=e5DeT*KY(cLXRFh;M{NLW^7-S zENUDTS&x~0r@7m`UYY5^QhOgiAde|qYjQH_|HuK}fM(4tsX&7)k}SB9L9GWl__6Ts zXa0T2>vl?!4i(v2R?KvFuaceXS&P-&=^fm5nQwM+$(oOHraK&}Y3u*-77=ZnEjA#g z-0vb4Ni$A%QR3>3FD!(Jc&k?iWNqp)X@{ZWk()8(l>fp@d;nKFlnX`ARMbp#nb-5F zx`J=RFd<(GjD`~dv!CECHv@7ymoElV;06o4%+doZW`+kVf`4IkEbZI5dJYqwqn0ya zFai+$uCLVZS)R7$zjRE+)vq^zl|Z%1bp^NIQb5Ey)1vX9 z;_iEB(z|K!%=}i1BsTo_@7|%dGFU5qiODagp+Q!^VWB_ZMK#~c0?WeM@sk9bU2e} zN%18OKCGl1W&~J3psPE-I{Ri&&RI}a_~akXE_;Z+VZW+n>g?;&NM>;GxS7K7_p>Ra zCDH3Fg)9H8Ed??qLz+`=0DavPlM0n^a9}m&6h+}*{&-yptERCqNO7b{ zD?ukMP4nckE_0b2Dh$62!nQ?&NFJ+>{j%OsbWF8+`xl`=rD~>EJ{nMRfEs2)tYsk3 zU84m!RdX5+9`TuBj&5CU&X>^1?Yt{oadysXUPh2<$q#nOWSsTHVHvoKV}Xlu_H(t< zvc!!-P-rZGcytgA6?X3Luu?_so zWTl8uH*qAo;BLI>dku}O{DQfu|F2TzreEydPY{`_xTxCu99^!@t^U`l)BPZ&zUehy zEU9_o2@3L)uFr=nr)=|{)BZz4(0Q?99{b2xhqb6N*W#8?a|K+Z@-{v~@A*EOXlU2><6>Y&+~^9ae`7mlVHfOzoJ~#r z-!f#iz+*(oQp!0~QJ|`S(VP_PjC(R`#0TF56hBHp!cRxWkNeYC_;v7_o;x@Yaojh} zz%rRdVsl+TGvCIT>pic-B5zvGg*h}>z1~-TIe*MKmp|GrO!DCOF9+X=i;5n6!Tyid zEt>uV=Poeck^WV>`qJ?bM}Y2;+m6MPZUv|Q{Z>0~Fk@4CTU*Xcjiy8FhS=+`dm|16 z-#mWo*s-9A+8+Hvk)}42-@>{HsVmUcdwc!;$E(*?LiB5F`JN_!E?f>4!I(?mfru|Q^bEAYyE`p#OFJ{FGSsb!_ynTp&K) zk38Stz7FDvVMXK-Ez}69-@z4YK84Z}3&~d1o!O*Wu)soiQ|XJ-^&Z9gv^n>8@mY+s zo6gi%>Ff%PSZTe6s}q-Gu`K^f)ub4c@911XM;*Da-jK}&>INb|W8RAE5*BN z`W~FiFe29kN$j!2<}X0)^61Nv7NzSkwd{1qR0L*2rPkkj*>deduq5wn7!y+kEz!S` zn&f{cLYVDv->mNDhiK6s4}z&Hty(vAs5C^DO@|3<-DrFSlA@(#MKY5TqCaIBP4_) z`W{i5oZ=W?Eoc4x8ctq#1h&n{jRo;P2Ph^+T!I`O;q5bP^zzQ%C6qbvhMFV1${6&R2S z&Ym@H^X{g2|l_0;DL+BUUS`GABb+Hd?bE{~% z03)44{_&lkB{P;cmh`)8mDhkqW>W2%J}L{{czfmNnaZP>5wiAAeHpQ>9sL=%z|{Ur zvO6O&U;Qf$k=XLzjp*P^h>(aZO_AgSI`=M~J7pr@#0=m9y+zZ3sFK8DF9qtTqSF%tl z=_!|BRaV~G=xD3Iqqh(?l@Hp?9BHCkS^{<0gN}g zj>IPPWQ|AFZ-Jk}c)Hv1qO5ECVBeKXLG_FIe9tI4Zy`$>wj0rMn(>?p+yB`i^iBRdepu#o^c0VgmNPX)yicA*4rR4rJSBpU`zX}%1 z4PFDU3>+AS3$|&bbJbt;$Q1Tq(w<8LtlM7{WbC8#nJbZEb9-^TXeC)=a20)O_a&QY=?Fg5Ag^cRF-&w`#q~yqB=@=U7cRFuKeE75e>}yosHl)G628egNr(@_ z{OK{HRuY?UQA2o6TC4KouDb!XzzH}s;qS>{!8y|1?nLt5OoK!Iqse@oRC*O8eUxm# zHqn@YDNVb?Le=UMgjRD(I-ORA17V#zU#I~t%%_x`F--6Aw>)2Y9D_D+`!VL+B`gW* z4)1HXKW~_O7JDR~=jrel6%QVq9=j4UbboqjpI$6*bT!gQ^ePZ17-kb+A}W>+pV4VG z0b5GSCSmHkb6@rl#(NB+w`)>USeMJn+tqRSJJ7DM?-$VdaKUe$d9B9^E=0<~^~&Y^ z!(Y2YqVcfi5KnV^!G{hKzD0X7tddo#lT=^&{zLljm-*58Uil2lgbeu^*Z+PyNf&uk ztd@4hJsrG@rXH46{|LBt$vFN19>KESUFz@hW|sW;iT;!x?9Y#}Ec@#%1^iR|+UP)} z6*l98&HZLwrv|ST7Wx0wF_=s|tsvM7s+E$wySSFuA0DhWW8p4fwl_CEZG zOuMr7#coMsi~8;m2&iK=IWSSpZ)gJ#d9fN&A^QnGr&P85ubyi{QWJg-KQr-;H9ccN z--8%w5uwWTI_LJ;bW)S>7-lN$lM-h#j8EFi&wY$k5iG2)T4r!Thx){g;=_lPrQ#vj zu8_lD9iMi_@X=(jvcy+ISCT&EVtN2b8#iR&omwBx)A#UF56*T|v`%}XExVHSouAVG zcM2sd+=eNLBz{E+W)jJJecY(i{}k2&p3CIAx#k^8Y%?FpKa&+^B=->gF{scDUtN2A zF%Q4}+5^_6g#FxuY4%9=#g~^Tafz$rxC|y; zzyL(;7~1q>i9V6;i5|O09`hQ4eAOPq_7j8|^R9fG0PB)kGOCUdG#aEQv93DeyAvei zI`8R(Wq_;gLN@%&Klq_ZO`SX9(__ObGlK~tMv3|N$}2tX#|7x}?kDAzJJdZc^Q%Q~ zkfy*1Xd!7q#-!oT0{s38@1VKSVJL8vv0q`vjPJByCILAFMi`tC%Q*28M}5SYZlC)X~|&kDanBrBMPC(y&iRXuc4S zEA3uRej^DV8zv|Pzx6x@7OXNLwHJMTWDBhfbq_lx7(qmMq^uG8G-*F=8JF+Am3n`}!sg^r5 zn*KZYas;TA%}7OHr?8D%`3MCZ`oNk_I=6PVw?7AhGx)hJb*TBC&N#a)w&t9m&HxZ= zK{b@E$5Med!=hEGK+EdUV%l-AH~0m5q96tDls8PfcEcUFXXslRm1Ux?{O7oiP|fP6 zjbnmAHXjb6$1i!ScqGj_e^vOrQ`!G=k)AK;2fj;jiM2piHBfDwJe| zKxGzT=f&drib;Bxk94m3`Z`hYC{azMO{bV$?X9Qx-~tae;n(%!(3)bcpRravw)veT z*(ipEts?5=ex8ChS)Zitt2Bn~5!u1r^_k+=y^0`o8}2{H!@esvI<301{_$_h5XZkE ze&(Sh746`wrE-h{0~MpzC12HbtqkCfs$D3quvOsrn|}vOE!Kp_&E8pqD7gjIOp1zp zyKrJ8RY5E^k{p)&kQhqU$wnm`W!kj*SG=W&wsG2gUOqzs9bSmaJA|2xzD(2H+F_*2 zU1dcl@%Nr-GTV0xHPy3Vv13@LBY!*##OD6!;IRbre>%R_(0(ud$8E%NYRCT;RN3qg zA)5YWacnK-Bi;O~x1r;|@)_X>!e$>;%H4@lLIC&;It2w+I)Vf->L8c~+pc+eba#F! z!7$>-G*K4${NDRwR(aRKV&U%+|379pgtF*f=YCA`Qq?&XUTu zB4#>ompqRZp0O@YUm9gb3h|u9w(5o5q}8$tH@nF0Q`2f;@`Ht$=sbwH5FO;i8pq*# zrMG0Q*)fNvp2hG0MrLqev*7rRc#d~MkXCsZxBu|C4%M8_xHSf2ejeeij$4EOl3ICo zKchNs)?58g6O4IE47j##_`X8?yU!#hpa#RaNLi1r2YGS zuZLbW{XI`3K5y_`$cVjbm2~)+q_U+m{%fVa?Mg~`oxQ^4!_IbH@3Mx{NXhd#u=~$0 zCv1!2JIqBsgQ=m0$Dj(&UDI>DXuAT#&!3jzz6+x;@k^xh01_0-oL#RZz76T{a;Py% zeXITZ)I~OS)hjHN>M8m`^9`k@B@64fp)hOgwh!%b#f_Ws0rYAwh+8e$ok>m`Qsr6?!1Roi-51>C6){#r4D}gUcoI_ zfuz6TqAqUB@%Q^^3t%EEQyFdkS)19tKeJyakYI#`Z_N#E(-a^nXj_Xn#dQFC_2-y@ zBSGFQuG=R<%80vMK}EqUlma9Cet`U`lCp;m8Hmc(_FJ9{nvC$-VjgHa0K@CTqD4=0 zFIr&qBADQ(!86CvgHDOTU&Y?tgQ0juG+AX_UCfNmxUFo0+w-Dk>g-ScKi@LUoPqS` z)5DfK1rb;8VOc7!-&#Kf;(qy>o-HMlg4bT`lnwEO%ccH(aJta#&iCb7LpKJ&E$IgC zX2}q;NfQiSb64!fqmlw-O>NU2scqf}(YBXM2fYagacF6?x4!igu0p^`z2KMhs(<7O zL#S-N<8o8gNRp+|wzO+Dx-mri`>~X@dp74gRd5Ol{Ff7!UfUtz&=Nh?Mgl;o32B}v z*`tU0*2CXA<-MH~Tu^?gs7THS?Gmh6(QOjjT1KlhFOxcXk_Y)K@94G=bh=L;J;DAH z;50$*il~6||NGT=*6jevt0aB9ZC8$1C)x`e!X+4eO3jDAwlJ7eW-?6%lE)JRc24vX zw?rey>F9_!q7+MO#0L!C*9OZ<_$T@@pzY+8XB*u6EU}%k0LzM2+SJ;YN_mrUH%9<( zv6s76Exi>iU3um^*as+K+&7$b?s-%Bmct#QUR^(zY}I;MLXt<8|GGDb*nfKjJAZpG zK{Z|>u7Fbr+v;HSy=M!l!b&zxEQ^#Jc<3|;`iY*bsA+f-PkCM$d-N16y#k8_Szl!n z^vQK9xI`4@FDgtLj$>ah)ly)GuIy_q_z>OJgWNT9xEdXyyeGF22g2Be#DMU9CUQd5 zm{wm*CBX1FRtXT0(1oK}PoC&`A^k={q;`4^1Gcksi)L`VM!+ku3#(tT$bOrat z;t;mFn?ieK?np43VEE!B&2)9%9)Sx9NU`e8^2GRjD2qBJ0_Uf5L+=#KRQpJo)gHi> zVrcg%ZoF#DfG?@1l_`Km#PHjM5CyLsb@-CIPF%3EJNTBQL&TlXVlHc4oKK^@=#f@8 z?>2I%e0H|beg>k?F%H{z)9z7vXlM6XVe|NC{rtg0(P*LonC!U5w}6T@+Hl&jk)e zxF-xbuRpS)z_}d|MAB#6oiA*~)3~SHz9#fIhiZXp!aBGNS^kAW1Xn6A0VDTZ?jHSj z0Z}q|2!Zkr@(D(Yu_NPH*FUd;0l@?3V=VJbKV4kD4UuDs8ma8-0jUb?u96;&P$N+m zHPAt2W{DYXz+4HYCR!O9`oY;wiq?hcaeR?y5CIYe{6tX^PCO_ngQAG6Z>_9>^mr%Q zPgh1(zy*xD-i70xsRJiLeqI1*4LAG`wH6J@U-lUqDT~JqO&IYR@nF>K7MNPQve_T5 z@=|H!Nzo>a<_%?I1d@*`hLOgPF8h3AiXsHQ17`H}(^8=2AIRz9u;f^CNkAId9qfNn zC}~I5*R0>dq-ow#$%H=T%BhE>MefoFbbN{X$dy;0@Sm5V``C3Mle21!prVZ_-93U~ z^2l2O<)sF+tjJo^$XdlUaB+pJXamw31-2&L?+BYTlj3x>)P)4q({sC3uz;(NHl< z>d9P_L+bR$iWARAS{Mk{bnWGUa_?w9{m2$|{zI35cLkMIB z6*5*b!}q)|H0J%I~_qBmh&huC4NpkEfmWP(Mv&;lb{?(j|qc54C#Y^Wlb-^ zY~;`xg%42{4Kj4`{t1Q8-;KYE!pcAVvMz{bNSDs|Dnr*PS@)?sIm=W1DnSl&^yB(_ zu+N9U`aXzd+E3stw8z5A4SW8cU-M*aNpx?U-{KIq@9Vsq`8?yl*ilqBqItUVQEGey zy=0K(^RsX(4B05GR1&C(!-t#aHP3I!#I_2CI84fErs!7Fue5*4a~F{M9?DV~@VARU@)~^q*rB_Bg&9w`CF7$4Y^IXS zwVymWpJCKZjiwhsllW2%`|0D*Hc;yj6_xDjHIfZk+{u)X^i7A?thK1ip6}g=WAu$m zgrOAo_Z)f^7qB*oD(DFspST%!Hro$-I%Iz6ByxLLY0L#{OaZsddx}Igv(YrPNzGk5 zhsD6&_b{zXAfRUc*7I}~HcI}X4}36^YcMYL_dA#ynBm3}?1V;;p(gA2=pAUGNQY+e z7<6S_%XE-lC1Y`$% zBQ@oM*OHgY?0HLmd8Ez!B>!WFH|*fR`Nru8=7OtxFpCbhT_q)mC%@KH@1B0am#%(* zxPeW?!ZoxAd>Ae2>4~NSc^5>r8lp>CBxh&m`rsmPCb{W0OrN-j9R0OCr;&rNnpvf!kZQ* z!=mF)UYzX)3wf`L#AX?QN2btVQt8#9+hSN)IKZ*nY{~nQkT(iRHPOPWt-iq$q=6dw4;~F&6QhMOrO77!Ki6PPU-8;fw1`m5+^iVP5G;W9)WZ0vgCLkO z`MT@q*wOg;+(gg#YyDBv=AGh$Z#H?(a}1|Tu-+{I)C26bdwOZD?;M)B*O)u=$Dci|q_FBhz&Cmy%!HOiSv zsT#-{^l*dmMFKsGA*&^5YTR?n=SRcfSiZ~04kQ&*x)pBb7P^TuN{q^e6+Quab7Da)Bv4&=@Xr|Cv_G_YUr|eM`{8GgUo-svLs}EWn7(2lVZ<4kEYsMvn~nv1`Al1 z!Q^Uc)D>Q*JI7Kz@Z{JH<$)VmbH~586cTL(ZBOgc7o5NBN)rXcRD!a)cqb6#dzz^e zF{dirq#`&niX>KJQTMno1KO$cEDvfj0+hU2>j7?yzJ&lia1xl;N~X17SBGBu zfT6LyDjEPeF($Y@G7@O)0rMb)>0vUN>MAdS?JiDWdHw6trd6+Ky!}jDh~Dzm z@BXu|fQdtdN}YK?`0HLXnT+1gp$zG(4sU0X->o~lojdzU$?Fj)_L+`oHq5RXI^7m$ z!F=!w$9IHgvIYmx06#Pt5k`@QqLIPx-@h+`c{ax~yUe8GRMIaSCW!Qg1|Kt#N@9R>~#x-fdUz<+st*;G%!?z(;X^2G)or88LOZVHlFUc=ifIPOv9 zDY$Sa$fDuy{40j7Gb^BQl!^3X{6PJ(ObcL|saB2)ci)h)1)L;f5Ad^sTSTPj5-D?j zlVkP)!5+H@U0!qxFKgdUHsis2Ft8E8N8I3^zn?Enu0@Q|Kb0-kiZG0Z*c-j~$PoFl zLm;Jeao&h_eg`wM$M^Ntz*JwP@O&`cad6t$*&gp#4g(6a3^O~>nWGtx`Ymy;>d-yE zQbdB|Gq=71K1zE+vGDpm;q{?5=nQ)?FRK1|i92u4DTd9q@`0Smgg}$6a8F@sd_H6E z?sjjuf4tQRG>v9_#`Xq{KE15QOK`!WtISy|ZcUg80&Zj6%E@#Dj?>$kI_A|* zKSp=U$H~e`?5{gep_M&EVbX{1jvaf#-fm6z?idPg%@rG#2RSTM%%e$S)nEhAq`Eb* zV#gBgnqxaW?AQ9=4w6Fu`6qrIsU9%x5ua!w3so=<)B2ijnJ`$y`{1s)SkvS(-|#27 z0T@y3jt1UA*XL{f+~}+wU@A!HM9M!YFMvla7x5nHkIpO!_7w8V`?r<0fNz}|F+eCq z9X9olYJ{ddswK##{C8#rqe+p~A=^J2$2!{$GrI=@^b=g6f%sJ;7#3<;j?Upfkqffe z9al(f#fMG8^u6w6v*F5{Ghh-6u0fOUqlu2w`e?%T3xO51J^0wC&6(Vj*Ld&mQD!uB zc)G>jA8T&0D`XeCp4_^X=6n)5u8L`%^zv8IOGZP|#`tT1S_xF;WIU%Wai}!EeL<K7c0A#HnRp19!+Z@>x9mFbunRp=LYmlRYw)VV6&j1eF?1 zc-1a_cl>p)bN|oR_@J2iat4M~nEaMCC@wBO;2pa4#9{0f!(|5wQP0YhwE5;_O=^R5 zm3epWNv~)TeIh6l#WjbO4cmI8@5g6X9$mgQQ<%RI#ipIw3;79F7nl`QURQU&(^PY7;3T6I#oj%`&3aMp3>Ptn*1_8HTe8M?bL8_?TpOuW zgMbbwdIZ|wZpUpHo7P_l9b`1T-JL&7C{Y{!es|B2XAj!i3kvaw%={oed}7SjPt(bk zD{$~_1tnh}!KO;J=ix84lbQ~uQ{dGGoq7#;2H&wHFh5DSm$OjGG6*f_rz#;dEYySlI zc(=2x(39HFLR&wtT!k1ol0H*fGlpqrCm808Ed`Z0X4hwsXw{aXrAvDc#m6i(O@EK! zu80#9p@Ggd0Hl}F&}{7KRox&{afy-Ov4U0&dqas4w$$5hC(^f_8lz;0uY~kNuT#Cr z=5x-SQT0J5(fCpj{vSE=6uLJk~&3Z%M$xx97_z4sVf^7+&Lc3g-F z%id?#0`{Kt;Z50?6L8xnHk$oBh~)+GF2d3!BV*W zwV!v!LD066QzM7(jUK%r)K(_?DjD{sS#mk;RJW|HbE@hTFLs7Uu2EvrnI*5*#sBa_ z3E$=6aAI%l!4BnYSa4ukf-r&GzH?S{CB@IuVh15PG#bvdun@4q0C%FTj701G3!XwN zN}aQ#wV}O{K3F5W6io7jBG>CFj$8?w<8Ov8)v9E3f#V>YJYsh0NlfXAi_1}At3l_T zU4)Pj$7mhwAWECuKjifyLGKW`{`Y)T{+X=BHc$AHe2$q!%UBEzYdbDW{C6uI}^)JnHmra zkaXQ{=iP0P^gaUV_3OK0|1_g^?eNYD1Ug`F)@p|bKS+6Q8nsqOI;6aOG)26e27g;t zGzMpz-F;+vo&<|>f2m){{Jl!OAkCfby;?F^>h>5D!K*`jJgtcMV+&Ltjb3u=xv|)DUeF%vQFPF z{(~S&^*dI(z7$?~}#R`X|}1 z@yWr&*!E@$;6ZMn6u^Ux-G$MBfhN^3MC5wTn~E;yYm-yfXwG*R%sK`rWZh%?fNkxz zUfA38BVbgV=D+s0wnpp*+eHD?DzY#iFzX!?^UD=*%7~eRm%V3!J?=4}!7`$8gmqhr z?Jla>YbUs{lA9hh_v6|Dcu=lB-dQOUm>xlpJ;O!aoIy8mcuzYKtVb>H* zeC<~LyN(7qE!R{91#HWu})qd={bvM470 z4l*oZS6uDom?pebWdv;!#Y6zb(LF>pckhP*?;CD9@{+<3Mt25Dnjvg%xmA+^O|0th z@P|OaVTh4oyy4wKE+97KUB}i0sf5@1K8G5&r!b-L*rQf<7RFFkWrg~!*OoZ9Z#h)o zJ+(U|N2Am1NOiu}ye_ULa%Xfe)?JraOB0;Z8I?Qm)U~zCseC$lyuaQf?(K};llad9 z$C9&)G)KK~OuscW8FvVn~}mm(yg1;f_#~grM<=Z44GTDv-N3dhMwKMn1 z%lXYaB-$>h=oYFJIyoX4st@RUo-DsXSNQ}ZBV!|v zNPhH`^95vI89KY(UCfB0lUIsQ8|cgK{93a68Pihn*|rUrdy{D-Q}C>_CI0He#o83j zJf~1ehyH)&UtNi@;-S8J%}b$#Z0uqPe^}L#)nRJG>zHw83jcR{9m0{hJn#$wqZEXh zs(_k^d3W(}E@wqviP*yrg16S<xB(=^%5 zU#Ruf7Skyo!WU+FL3lEic|6`@me)@wQwqeaYyftu&Wx zs{hJ0nRds4qoFRfjx***JvO&SMHpBV;>LcyBWOIjD`=hMpB2xqW?1@|e98a_WB#{n z&r8272F_3Yb}7$zq-{TVGIZCODr#DSODJOxrv8ZdNI}i-#yEET7Wl_aV5hW>&#;)Wg2kzUL?k?sAgOg(*S}&u=j9Z+{z?zMlyqCBY6+ zpCxm;6?r6COT6Ue>B5BXy#-g@LX85p7WJdfP+=AixUXV@f9kI-4uRQz-%pH?1e)sM{e1xF@PenaZ$ILe^0)2;{T~$x?V@_<7Jh2F7D3LoL1r`LsSb@Umt>;y4v=f@zmp99)p?} z=*L~>ePJRl*L?JMLfkEkZ=glh*d0bt+5dDNxfo)jjSzF>mgoD-g5`KLi7tI`k=E?j zSyPw~nAf)m%P0YS)i%FAE`)F{a1!vR4ZCpQN9uPHYkM1{`C3gf+i%ThnBRNXZ@0da zKtdR=%LFsC@aw%x`U^i=(~?RTN6mKE=DJrquNR(I~fvTkgi_bZ~NC<(lh)dOA*LjY&*s6u8sdY8tPmyy?Qi0b!rBv6~vV40D)*&PG??y zHQ8=?0?@g*pThp7v;#S>3$<*1GLDbGWjnF654#@y(0}H5-5?Yii7?i%#*;H(qDIP$ z>t6Ga_;Rhq!_A_h2;Yc6HYi^q+_)$NFNS${Y1;*=Bz?H+cxtt~y;>d<9YPI!q(P@C z8o-VS+^NkgTp!NNKP?uA*D1f{xT{V9kP}rYJ3CQ8O=QAcJ}xGyvfeRmZJ zB!x2T`}zCq8i1|@WJf1pWg)mX&vdYi2zRzmVH%l6>Nu0srsJ7TmkH5vIr3XDY)%)p z^^>?Sphz*ppI6~tM342xj|X>qy7oc&UDNj$oiPWY0=aeQFO2tpsQ1E5{v}>KKfe?) zT;(UrHv+Tdr^cu+nD17^rAmW6{rh6D#X~{Bc829_8hLyPg*zKc83xMuyJF>S$olNk zkA&I{9yXmS*tQ-6JEXst?m5RFQjQz#u6Q|A0&c(+5BQP37ZRT-4WLph4E9*)#Y|WB zQL9$qO(g_!-nh;bmebpp0AT=_$H;EPUw7b>+&x#|e>11EkP$!&-JH(UL@$?Qkt&F2 zr{4T%(evIe$g!khZ6z02PGN(2!=m579TRH-9x1{W%lX=!v%Yl|z=1E+XVAoVd=72Z zm;8mkr|v+yq}?7q{TQfzJ(QB{X}N!l1Z=E}I}NYL<~Avn;NLK)QLlW&x$hsc4yQt( zCp>Dp4M9uQ5I6S!G4&nrRJZT{w-hZ&ix5R;4>lfB*A(J+IgE)bsg#?)$p0@xI1=U3h4HX7}%!7=G$(wR0CJ zr{N#vq#tEJav{`o*waW*8rkBYwS&C{nV!&H49IGCIkDt!p}(|LF1x+Sw79 z7@J8|NiR%o%6D~$^qlJ(eZ#-_ekdDfMzC7BnqzN-33b_@lPyhOE)a;@b`{F2@IOt4 z9T$J4kJKT|EM45%}A5OsLxtC8@u7N*LUY_J@)GMYybN@bW{)GFc1g#vgvf z;&t;y_HZSIH?`idR;5*;2L&~f^|pyb+MaaY!tz`@ z7&4JQ-V@evb8k@|T*^JkA z+`D}H~A-v%~x>y$Xu8GM@VemGc% zDSceA-u`BU_$nMZj=jBRB3(`S=)0k5{l$Jw=|dxUhGf4IMFwI8fFa*e^v$0gMr1`CYV z@j^bu6vI)s#Q}Zl)I2bdEY8TB?9Io)1QGe!bFBxB*h*-#F?3g)3NV+Bz5JorM1HLA!)n}( z|FZ*MNNb@vW>Je%WBJ58joZ+n6E^v0^U)`XYlCGTHGZQ5o~o^^Ws)*C^t6rv7X+k4 zPz7CumWKu@Sh0-&%`E4k;UZM zi|F$%1KQM<2b-BZa1K*pfK!ya@zxe5$i_C;r9V{>= z(&yi<*xZSB{=9;-n9ptS;PA9|mbKq>;dH@+%1KSHNzG3l^HX+3REHYb?z?LaK$OsW z_K%`GH~;K6MPc6QSL`0Ua6;%W>|uHJfZ zNPo4LgH0qt-y3(jTdbk52iQ#&(3R< z)9c`eb)QjCAifVn8+&%e1i~Pa_TAZwfWp+g(6?O3QNTDb6|Koc}nT$Ix_%Z~hYV%)PqO-T0Mf*aAHo=+0*?Ns3+5X%!>|8&F&E*HKM!7Csa zLnR(dQ_o5GUaLsFBF+TnXpSX%g*fOk`_|W+RFo-&=RgwC&S$n}dqZ z?Y?(*4eFXoQqwSqo4+^GK{?6MxivAXgByobUpHIw|EFE(?uvu=a??3Aj%G$2IO4cZ zFF)I2oT={R3qD|&IF6_@h-4P>rm5VZO#LYi1?29q*r|W$nDPggZzsTjf#v_m5Y6#= z9uaev<}&S+m&wP#O4_AWy!a1 zXK^0LZoEpe6y|9k{cx21*q@g;zpGmx@ZAo8kd3duvilEujptMv4w3(Ouz9fsa#g#~ z+C}R<+ejZ9UTXpfc@W>b^2=eYj;&2&p>q7-lxHLyEd0K2on6N}Oa=|J3o0XDUin=e z#Y2TGW%vD!%HA=HgC-mOiSVC4J*HruEmbISfSD%U-dj1`u_D;*&5H|Z;V);vB) z+gp3ceEI&3ejlD|Y(3$3@QjegKEoRq_tb{IKlkEA>Um$+XB+fRS3I}5aS<__9=^6} z`%2?8TbS9k#^bMRH-if8#9W7=^ojI{gjY( z{TPOkPSmf^wn+?wI9ozk$FesL0IEtOIwoQvK`qU)coZT7Ci#%&_XjoY@jZrFZ1)OL zZixU%;tFg^>-lwwxS>(x6Q`)ccSjE)ONIt~n6k?pN!Tn$p>U1D;5ml>SgUdC&u8dM ze;dc4)UVndW5J(Km7t)y&4-aQ?slPjUG~3Gc;msRtVsDx5IeH*UyVZQpW*{KuK#04 z^JryvKeS?52G+_|ykLdG08S9&LGq*Flzd^Fp4E$X#qw;SKi}fgKA^{m$Hl3a-K2z&rVnC$`RzJ#ouLqq|F37(9({cWJQ0z;1nv(Tz07^-&Svf*y`vU zrAQ8^#7hC*aYCTUfM9k=gh@FM>&QU%!oSrzZ$C~U&Mef>7l>hx&h3tr4<3!ZvLmjw zY%_G`%%k&4dPM!NdEIS_`$^mCaj_fv zvTHSp03V<-9Eph?g(R22Jxt#vM$S4#U`-hq7BsVsHB<^Q=!G|1;L*f3Rd@&&X|M`MLz8L z>^{)Fj6Btczi+U9#R_sQ;|Ope(PCfHE2iwJ8#|!1FF{dC@7&golH+_xip?s3jl7JE z9})A;-Oki@)E1y(BM35lsx{Web~L-=Wa&#=f7Z zkC}M)R@ixG{M|3pxEnA@3m6J+A`J<9RCKeE!$FCu9(ReB;qv-s&Xc1X^Yr{q`iW6ZIV&=51~O;W?*8L21c|? z%Y;r|v2KTvjvF9hDZ>?U`^81iu#s8D5ZUbPaK*OPf1J_9R0@K;X28!o!0P?we>O&Qz%zjr*K&30~mepMFRIQNN zxd?7({mxS>7G|MYkJ@J7|4=>wT_7BwM>xZft$nof{b5e=xSmYIj`sJM1JI;WCU+-pF+qsZ^8_tP ztQ+dSTQH}19K)onzI5WO)4nY$inI+o0Ipm7-y(mpk%MEQCuqdq?O~qJp};hDTW1hL zyn$^Y7P)Vj$xABl`t!kp-5{NzlDi=bGFSKe3tJU5(y0;v-GF-slB>-dp>weX(rZv4 zTtl(@foaotBb5<-`!QRFPwWq1B^~jB)^XkE8x!!UeK;!t`fAm`ekxZKt~}G;KjvmL ziObspY1{VTkio3vN(Cf+31Np&$B zxETnGWRUVVHz}eb_{{}TxO-_*eP<_cGU#zaQ=WkNO8;Zb1LlaY^B%|r_vJ14?Ai~H z72BsLVbw&o-n;6H<;5OM%mjxJesN*F<~W88cph0m30)F=yuX(EU#vVNLZ3YYeYS6l z&%~t;EP0!)4xoJhU(cvZ-TK4MXZ84-@M&%yEO2ah`Tus>BJ4POhsA(c?S9#_#{R+T z))&+vwPU*{aNa&5Np8%od6GcODN*qT!b8C1gia?!(9w0HO1>!`8%H|$jZdeJU^X_T zBw*6YP#3LM#;SMJuOJ%olc0|UTr!i_g_%IQ`)|CmV@F(qKdYO|_;k|D7C=bjw!4Z^ zg@YA6YZ&;$x7^z})93EQLmXoHP4sA|rT+pYfVl4M$#Jr3aeAo&U8lleh|AGTrY3^9 zNoj}Moy(weFfPUXT}epPCKgi06OhBt;rD~y@sP9`8gT&X-C?ZCwnm0ZeZLwCw#Oeb zA!EjeZsj1`k9cR#%93<>;G>;~C!h&l{7?h-$H?pBVO=bskCrx7#?q;zsdyj$#GrDm zcCT=r(`MK#3&oMcDih`~kGZWIz(?45@twAPsd&I%Gh~fre(7VIB>d`y6nWq}Z=yj{ z`N9>fERyM=rJ?t`gu_#l`Uf8iN3^Ps`p|8!L*IyN=PrW_B-Q_8cPN^1}SfDyv zl;(n!>NOX0r}XiIT-7%|c@KWHk7D4CPViD=V7%Wam|}*_)Zj9U4a%7pAKt*w>~qE} zOXqKIl)`Y;rQG`N4~p>{ZdXrbY08I1cQ90A$Qpzd1>y=DY;nY@W^H1bBuWlgiA0yI z+r9X}afNP(7cP<3YS`#YX}Ch_eseg(FX@ifsZ5=*R;+V75ehgzTz2NP!V3~ft~yZ*i`T~ClUm}R zv31c+Y9IWB{t{CKoQ~gqTFGmqJ&G-Iho;?!v*smom>p9{-@tkuh-#k z8R!5_fo%+Il};e3BtDd>!eF%cKsQ@F-D8|#lCS{clK?$aQl9SU6kMi(yIvXC4juET zP-W^=w{j=!^{Mj0JtkO>+6ZUkT~)A<_+4u+rL9CMJPGHdv@*UeMp>=}rSU2QlNW9r z1orSXd|PK#Jq+}ihpg=%+?EI}o-4GRxyqbk4DM0MjWFJC(qJLDbYRAlR9+*&E%sZ= zm>&`1qx1tp|Fm?g;W5RKH`vsUf~k$jEw}oBd5(o*2xIM+wsk5#jj6M3uPb;BczhV~ znQYfvN8`1Yqo!45C-#m%*UihseEq$}aW41`56Le8f6d@*v*s^u;60RPd>5*Yy>f*e zU5VC)&prety6`B1fj(scve~Z6WH5gVo&bu(D80|)4 zmmemksfp-InPOvb>H;tcZyk!18C;H^|MnqpyrdDcWaCb-5`R?k&gs&cd>#^9>0`N< zz%E?Zw7(#vvAC3`Uu;Z&oUA`nS8o_? zO2m(x?i^VqQn9WFcQd_rfv=nsx0gbQq#NA!roZG!z=bVHQ9Kn}Q%`J7Qwqjod|kfC z`?*j=r^d2l-F70}aEkQl+md7*@sL3OlxaiRa$9Vq82o10yC5RqIaMLRM>Dkvu;hcm zjvqVV&JsF>n^z7-%JGo)GN>l@7P^iTP+xMR4gju3M-KYr$TT<2FMA(Kz^Al=I3?L< zZVag`1qi0S5i2e7)A*jH-D935m+>t`dC%)p<_-DXYQy!8Tqn+!;p)0(6s*wHuw%#D<%K2y1SJ|$vxIe6?#V~&=v_NauF^mh>^cIp!Ew@>#SoSQ{?Z! zC{@px3@mQo2f2O-G~2e}$PWg}_{qvs_hhC#+S3I7!w!b8qSH`35SmNp1afis|Id1h z4j%EqfPhlXv0th+gBEzp_%5n)rW|!%&?~DzaCpSpXC*ecVthgt6yuws5S0+Do8p2%=aNXM z+jlgD!#(_^4G-in&4{<}DfC*Le(iDVXl?=sCu!SL8M83g_%)45%D+Gs8zlO)8ySM% zdGTgeXNyy44HF_u?W>uCBNSUUKwCy;zop{Cf7MGRKiO@nTYntjIxSJ?HnY(Tx!{?Q^%Wj_^HmZg(`SqBGoMWT#s`Pn4tp}z0Anl z+k1@{_oxqb%V;nEz%RQ9fOQv?r3odN8SJ5+^a8Y8XvRV-7@o=txL;b=$sS_TE<+Ip zW_*N(v$jede@_)WfUW?Ir4opTA4`mFW8iqUwT^hJrIvy;L(s#(c-rPKuIbZ0AWY1n zCq<>C2>-k(L|ESApECVirjsY;zWvT-S<-W2@6XsDXvYlz8A9WqRn1Bgy#+|4h2Y*( z=a^GoK_iF3pb@_&uWX7UALXAj@=#rbnYe8l+2l2Rs*uI46*#=?Z~Gayut0#OPa z!ON?Z3EDTRRg729G{Y9!{tjfzF;o-sD$;;7-IDNhKtR|1RmBR@g_95vTuj3|e#Hek z;N{g;FEm3>7dM^Y2FdGJ zz=ibGAPwUWd#>hz#v+5pGJf?4qra~;lKPwJPUHKr1dQcMM|&E|ESBXk%KNv+DObPC zQ^tg;CL~A?wA@!1v6jMyP&W)7Y2$)!J`Yx}+c4W)C0RV5YogGqKH4$dJQ_WG)Nc2b za{h>7(dhVjIS^WC_<{*{$TO(A(5z?JsCYv4V|k$Y>`< zS>*eE2|J*xD_=9*KssJ?(G66cUMf>I!yq$o%#{r<&6MyibR!CX*)pemAug8~IN!_~ z;7-F35_>tFE(1TA$=A+;ysW{%`h$7I#C}c2&{+6R)8=N^H($Wn_)S18ET6iCpq8dK z2p};H3|@Y`q@>UOmc#7`{){noPCY>>&p;-?^L_GF01UY~wkvgd2>FLtB0Wt?oY(1d z-pkNSug0B`3E**ZY+^;LCu@=A2=EuUXXjXM3SzmArVy5m0OL{}g;>sHVxd$f{UKxw zUfm@o0^tSfsvqhk`h+q}C&*%ru3r078b?KW>L$ds7i{+KRo^kser=KPs`!bBxD`B^ zC%}V-bG@rEzRJY-3KP(!2nJu_&84gfyr=OS_rtf1zioyjHsEwRN%t8WQasIt{gV(g zQG^sNBD{ZJ?hjsk&0=sJif2n+?L3}lhCSkwR&Y_Ui4supt8xuJmf}q|CPf)2{a1FLWh@cgvP*lKQJWr2L-}_cA?JK8wrHm6GTeEh z*RdiN){BRb&X1P_qQZN|fc~UaMD9X78+nR~KWkuerH_hBY(-V&UJ{~4Iw8@xcxc^gUu0yOdxca^&2$117p=wH84*s)DoKS zbHi3xRK-kRA)hptxOG9)OGdi~JiH@+Kn zhiS@)bdtMuuQNY@KB6xGSTNY}<@mdcxz##wojmg`W+)KixnQ3tI7@?sgbPi|5~tJb z1SHX=cu>PeR*b7Qd9SbaOb-wd!)Dx!snZnB7>dQv;EL10P)1t4nd;c9e|e=f_CV1! zH#{pR^JU`UbuU4tqCvNe|@b(mrUjoPko9 zXW$`d`+H@DLthCYbXWp@55F0C;?m8oC^M7kT_bbLs^(hMg-1O2E##(s18v-yW zWm5rF^!yoHP@iIy%nNP2poEH{jBVB^X^W949%q2V)Xhm2RqwzWU~(8Fb&ThFOD=x& zjLFGWg$KlLGzwXY41(PmQAh?o{Y`GjS163v*^ z1b90@&Q;E{-)}_rZ^nS8dVXh^%HtZhMzyYB5nW1eDKm+KHcE28 zoE#q#6KZDZ95(25?)xhXYeotpIdMl)Z7s_N?1!>F&p?W`=bH&|2)6)Q_~Et5ZhZVk zP@7d{W*k%+DoWiQn%Mf*EYF)h!!r_4G*w5JuGVjvn9@N80=W=J`aVPX>4x8$qTPR& zr4u(GW{CLj_st{IuFjs0#hMGua9P8>CImfJ6|Wpp8q z$`vy`7}2$N*z%-wlca%TBVA{x6UB7*;R?a%+wn%&Dh#e^9N-tuE3SF}hGc-!e*L*4Z+{PU3fPofm=_v~}#`|}HM z@SyNUeK^x{7D&K0h8Q#471aTI3;x)ju32qTO=(=CHA00Y#A^@pU( zxpwkERgtC?vWh_CoxQR%Zb?5EuIrECfzZy0zc91Ce2H7tlC-Dzf4WR7 z%D2ypgM_gyBZEP$PjaAOwN7F#99xl95nx{rutdJ?`i z2{_4`9nvVU4On>ftTgC|g?sugiZ(SCI8G>B@vH{+|J({CWlBrN?o7CZo3R)gKP@-f z;&bLo!)JO~=CWk`ct~Cei-DUBUS*0~;ZLEOC&@+AVFj|u1AIplKxF$E^5Ybh=UKth z8T)b>F%C*C^E?Yl5(kSq4}tgl1%jeRjKP^rJEfbJtuMzal?ol^(xlQ~Ye{P&U-8TJ9B`$`Nu3KL&1>OVhgJs~)!cexq6|V+$ z8}X1R*t6(71g4CE^N>?(L00>w=?b6UOxiGHU6Ha)p~mJFB-WYj5IjAKt!j=LW!A0#mqy5o z`{3C!qc^`d87ZfnPjbeG#H!=KoKhf(Kgbmk-x-w~I0gwIrxT&+SnJ{WS-1EGjS#CAckQr{ z^-QGpp9UM|vM#caE;QCd8)Ts`FrP)q*>>pD9#^&X_~X@AK>qLMP_E(41q5b7NISwQ zs3@)jW-@(8gF>g_7%Y>k6P+nay|=7UCx=xK)HWQZRq-hh@FTL|s{ma&3PLpG!(lVv zTPVSp^Gv2rT#^&Yqjtq#b3^X#qgPo`=u60EVh$f-Xt6)_XP6Ac!Ij&Mkz;6taa2)U z%K_8|{;LR2EudsIvC|KNo+mh8SO*bv;rEbo?`-+P5I$d(vK&vW4(jl%8!<^B*KM1R z73agt`^y7CQ2SZ{<#*V$Fv-D1n`3}U31<|<5Xaai?k1~$F4Q~c3K}9$rDYj1ux<%N zf9*e3JmDrt?i;4|{OF0Y+s;HMFPOud^@y3g;vaW>JpbsWAG8XKEiZM&eIns!sP+T3#bfI1B=~8!IfAa9`DSAg-q`iA6F>dSMd%eC z9tc-NZ_T2=FWAT>pYfBR)e9v)cYegSH{c*vz!6SSMJBDtR+T_ms4gRZe4w4Ml-{pd zI`=|4n2Hq-=@Vpu2~aBK@B`u(4tSaMZmqJpRjixObK`SS#pjZ+x-oAa_Hq2QDzmK{ zOpdYTB7zCFnddVnxmN-ApCj;Dgt5GrN=93MDn!CgfZ~j`(0Xwg@l-P-RTzA_Z5?W5 zAj6wKw6E1gB<_bJh?^dPbznJINFQJjSCYd52mm=h)uW%ywbmnREJ3PUkX+k89iR|* zU=`vy2(6p(lu(8QfgHRz{Nlyo*MO2vN!_I-u0AO_&-2+HZ5POON7)4e{~j)hy{WAN z{J+G(RV1cPpvkrGU}gGngntu^&ud!ZJZ1Ioh;Z5eeF#h3ei)U$j9hV7;V>e#U-vE_ zJ>Qr&fF-~?ntO@g#U#pP6IZe5Uw|abaykT~agUtP7^iHO&cN8zmJ8nC6z$@A{ogqa zN6$4*?OZ^i+6&CKW!IMD^OVvS8mT{O2--0GqB}SqvAb8H5i7^$*zNCMK7jT-yZ5eY zf1dD>iL|PJ%w`bCD$PJ@C2>82{a8tncj6Eh2q&}%v!4Ewxg90o=T>Pq&h{;|jJ7Qu z?K8XSg%7%vESVJcG- z0eMKz&OOqPlT1ro-SHua4$Ma&og6bsP=|0RN37)D6UIyWOYVJIV(@Iy$H04zuoxJ{ zEXRwSX87=yeN`}}rSicc4GcC}1a-&teO5(5=5MffK%sb7jXdoerDH0_zUJx`4)ubD zcS0u~2mw`nuh)^15tawJJD5n?ti@ck> zW?G`vt#CA>b|>5m7I^&wppI|&jy2?@p(0_gzx!Lgu5>q`xz^$cdfjj)M zA8wyTobSad9zl4gb-CTjlgju_14MxpQdxJhZOONQ1) zbv=@}0Wmh=$7_Ixb0&Hh<;VMC@+RLY1zDo0WdaC^r)c(OUdQ6j0Z9~hSLC9#|B2ov zLMW;=%07E0{@>=$rBUhPHuHBAMXMx{8xsfOl0J1sIWxgwKo7LXb^(Fhh47aJmJ1e) z@Q~J@Sjn{g%`FxpGyfD$`r!f3n5<)*qpsBa#Q+-zQ6b}d>!AVg5C4+m8o2ntP>LND zACW{RlBW8sC**2^ zAg||u^S5$#{U3OEllzvbX%I^Z_CsUeYW0q2)pJO;@v1g(sLo8=8fP34Ma+qAqmO^IdL2xsd#uAu$7jIybtQ71F?6J<@1M>rb!U9TbK#c?v zwGiC_X#x}P^0FxyYs5rart7I>3*(~8m$d8U7uF~IpAsqqTfE)P&zF-l3l?XDc~B#W z0G$Bu(YLPgnRgW0-0O@44gzvF20=8|WpU2!XL$fP+xzJ)@}B zhwa4BWRBWj%;X`c$9ZFb53yv|tg@D5LFd401B>LS&LS{_SWDFXNN@lUzet;b{K2nX z@CR8TYpIsllf)LY%BY)aG{kV%xnQP_0bZ|JAox_Ffw!3d##8u{fhj__iC@Wl%0|6O zX#n&E?t|^WN8ZKnLNa7lCe&FOHV0@)R=kRLHLOf7I7(x;3BFqp1M8&?mk-gFpAvi`F{WG=A1 z&QV(-7qJPO1N_na{>f64d#fu53)HmrwS6l1)w#IV;`HeVcH|r)i6{yLrVvwbJb{|L zA>tg)(8qsN;c;gr`Qe)CkJtGNaTcUNIS6-3TZd5RlUyB{I@EWV;?ILXh->d z>ynQ05?&eVzH%s+FyRav`W!pg0Md%4$)`ruY;xs0X5n8%*!9m-y>g6xVF(&)^I|O( zC+P&>Rc*zuAe&D>XNBE4$wxkS4nP5oIY+IqC(e75%ou7&>Cn>%Q;3ou@Ep?|384Qi z>flr|HW|(4AAvU-46apeKAGu(+f{nw0fla7Q1-E|^OzwFDC$0E_SEkM8ZfY$TA&ru z(*uQGG$GAitU_<$7nc9NN?va3eK1PF8LPfrZODP09*l&YzOLG~8YA>22=_)^XfG-1 zAbt}=7>wneJqlX-Q{`P}E-(BQrE31YqdYT;xj6I=I8jk+=b@*EBZLq3GCVl3Yt2Ii z#8_O0hQ~*i)nHV#Sg2AwyV$noQR`KW;5SeZLOpaeN}tft0xfNxZ9j2pe?6E(NHeVR z8T{;27n#^l=Jklk8ZN0St==T+A+(SwKbLlwJ?(1%1zWx79eYG7B#@*Pr`3SX8e}XA z5zsT}ANSq(mERISdlwdzifNu4DhH7~(CWgEp(>D$9s~#TXP&G~vLQx3`kv zadwpET*XFau%fT(m_goS7X6@EeSF}L4^0Bd2!vwF!j7an(_NlW%Vecf6yGJ3h1pyX z^v#xFkm=)(GnI5bjfhdDun1puV%RtV#DYI_ljdPkSx`v9cI#tVx@arvys~fkPOg&p zYP!{sWDc1fiJbrwkSU%0d)LwX%L&4=`SdKbxL}DObpK6p7$;MqH_<%$MATIehh<2* z8GFo-vILC@ZLI%2)q~wY1bqnV%aARRB3gnre^g<5SB@^4>B@~kf7NOdyJ9@r*TCG= zcdb7}AkI4|43Y;pFn+gP!x!5qeCrT}0SLHWO}H7=MSe6= z^i`6s@?r%q6lcmppCnbVlCrE($6LPnA9>MR^qoh<`ROALZjSkXv?Raw$_$mfKN0{s zTU>~ZJdgd5&^Pi6GharTizbp>N*~E>mQTCAYd9gR2pb{zT~vJ0MrD9Id;}j%BhJPc zXM+$~<;_$c~Uqq`b+8iPgF!;6MS!+<9 z01TdF!EAw?PQ9=^X)QetRZzQ$Lw$nhrJpW1HX7(NAiUVbGqs^%C%n$C;uy6s3nyaJ zQmtENX!Nn_QtaBQAA$~-uwMjYG2YiP%A(Z>xVO3L-Gc0-qlljUb$NaymxXnN@qg=I z>>u2m4(%A2$@vR4RQgpMfZ(5L0TYiS0Pv;rWgdx-{Vju_6gz$6;v-P+gm3@Bv~kug z6G|KahwmScSpmtfmFK<}K`z{nNfuR>k9f|gX}a&{L4^=;>}1HHfn55ut`&ju$&SMyqXx=Jjn%56_5*jOQfo)_ zbic~h+%7-j1yw?j{k5!Dw|2s1ic6~UQ_k}u6W8{~AQA`*lY_7$57?YEnpfmI< ze@`oFlRY@M7%b|ptdn)?ECkH3D87)%pW9=y7IIunAgM?V&|bcCmk{TaWM64CcAG07 zs6B7~PcMr4P*)NQfpSs{iey9b$L2gb_V;$N>eKG($#LSB*-FGiB(Y%%Vtril4Cb8r zw?8O1`-0J&tsD%BtG=J$6T}*VpSuqQ&pqk zBQq7Bu1eJtK7C1&^6)ree1ou~dS%lJQnEDWZt$y&gz@=<<3dz0r`cz)bRM%89c;f{ zm$MRXrNS@t{vIAAp$Cxp?LveJG<}UJaAOY|j30PF|ER0mUMCw?cG0@$(82rK8;+kn z`~Ci|`#wJfehQ1)KJPy9>>iiY>!)wJ_U=hmRAqNjCV3YY>RqbuJhyVY<}~x&8Ej}sg|>6PSVj)2&^ts?wm{L=N8Y?LgIX{3XhSYi&aNL1#^PbG>hxno3#!cIpt*v$*_#~*wdwDjbQ$*k z^IQ*1kd)RQ6xo3+bs^A(kbUjGACOi}gqVTY9OLm1OxYQOLS=;7AWPXjIkfk?d936G z=kj8#{eRrPAfvgYTt*wtTB2aUso(G^9zT$~rf>S<#ryfNn8VL-cipK7wHhwH{--A(y=>z3RuXB4U_HB? zxokvbd~Kmb5QJzK0LJ@DW69Nd%R=&Le6r<&8Z%iO^a43MXDWz;KGFE~uTA_Tx@mD5 zU9p%$CBaK??F(q3h=-EEdn3jJiEIjfFOOgG_FGu99uNNE6vc$Z^2?Q5Cij{`jv~~? zIp|?j*sT&!UJ3{1E4+(5Tr>W{fpnBHb^d|`cWyz? zWNlcm-$Upv`g_DTd(1`v@;{Ak!fVf(Gyj$MoXi{bK9%$spc2ou(I!F3((Zs`V(TLH zXxsUb!Nk4>6v>OMrRKN7S4g}&h4sbNcM6j(;H;?D2I`tM(m*Mq764BE+Zjn)Q>U-eroKCo4)P9*%rv*$249D051oaOI2oDn4~m{p0{oFWBI>$Q zpHYX4N;GQEy79k^TzZ#tmWKTbI5YkY#4M`C7{+Z-U>wi>G$? zMr|gj1FzTaQn_tEZ$qScpzQhVGp_sii6zBQ{s3O|9q9-WCW6aq^5Nm2q3msLFla3Ec9FL;b z+YPD-uJi0^skD0_Y_SgNfOK5H=-PGFYMb+OqO01!Hb{@J#s>|Er!o8tRBC*1RQNxw zdQKA~W5mrw73#RA2ct)qifAE_Qy3+cE?`_>~I{L&&f=6ipP zSREFOUg-BWSx_i`ST$Lbc-L@U$JP1J>EYoDd*ot|ZA{;tWw1i>*;d=m+cgH%r1>kw`ZAJTQv)Cc_ndpD zzQ$yn$9W>aBdQphn==)F*j zYrUWP)Ej((x`y$niQ{*G$YMYIUH*eF(T#2VX69p_{83+d-}i~0&B1JG=hFVt7Fv#X z%|dm5>4(n&a&u3mdPu)wKC2BT{moy8*2dUB_H%sz%m_a&i!;x-7{&s}rm?Xwqo^dj zWs;J;B!-cbZz{i3M#rfCQP~?eP8Aq-cq$cBpXYM3K}x zqirnQ?X16WFT?*RWw`Me@U$Gvjbqfg7+4BPP!)Q@-1l$rVmFenfq*_a8>9bkXPTAs zJi)_OUq%)W+E_LX_1u2^p1Q>+0uoFT6gWmBvlMw&XrH9-P?YSN{ilhudKgis{EqY5r|n&L4ysVc!NCxpODlXMr}(L-AH6;&KTo@ zjXYn4MV^?(Cdoh-k)X0LZ_Xmg8|LGCSj|t%jCd*Vj^6jSimN}A!8+5}E6|cQ86dsZ zx-g%1&?Yy5c5v_QUmr?~MW{3NGktabk45+jgkpuCm>%B4dy|hNPa3}W^j^mXp7AB0 z%H=})qpbQ9_rP?>Ol!ayui0ih{iGC!P+YH?8|nc@x^A@u zInK(Qz`YQ*t6*y7oL!5k?bgL!i*;T;7YaR0tkgoyns2T|H@nDI9Lf3HZ}d6~S{Dj* z`40%rRooYo;N!OYX1Im9XqvrKuFKc^ai90Fdx1m#Lh=^6Yf2(}z)Y>AV&sh48_wm0 z-ML?F9oh@sj7}HnCmK7mz2ke2vstcJQ$?& zSGp7Bxp-X{YrFZBS#NJmz4dnA1u0VwMKej>x>-p>CP^jJg%a7H=zWPCS^As@i$x1e zu9?-;Ie=N-zNSDZTII?6zm=C=Cf6YN*~U7w{?n}>3pNVioCO@HgaTn%HE(Q6;Ma2DfF`-4 z&EM#@aiesMw2xMO_81wOT#hVQ~zkLc)u z=d~l#Z&ZIy*dPO!=NIbjf##fgi_2gc#}5GTpT2^@VJXIyyw9V0v{^Wi9PMvaMgXK^ zCBhTE6=lV{;@1ppbN<=kOr$}Ak8m&Kd=^+*xA8~)`oO!NaQ{94yBmjC4jyInR|d| zv_91S)B)F9Ua}ZT&jwecWn>l4nG?h^H2mERN(;B&sN)!r_3?-(IMU@I`XswIHhn(R zORg(dh0R#`qurOH#Obws2F8aLw|XRDfqj#tb3;uJ?t~3XvugFK&UcMa{0&%w zQpf~`v=PGh=C8dS=yi_|9=#s41Ciq|UOXeSNa1X?f7DPNAxQi43Ao13n-;w>V|sx) zPb-)vC)adbqsxQ`y@2UlZk zXWe|4ea#Ws)qK+_N~80l9w%k`Q?{lvIfeL<3Q2^IA$k_eA?EYJoEd%ljCe>N?*lk|Ut4^$ z_*Ll{Ue_NTUj9e-cdbgkIue!`!|!sw_`1kx-pRM#b$Ue-F|+N-r`;z)1Xx_mr*1tk z8ELlyeZb}TYeNloxfveEb{>EPI14p~neFL4>)R;1UEd737{P>@lo9}NlhL2&nr_`J zzCd>$@uD}i3PexnH~vm5qCNArkdsUK8K=FOxCU&{GZ}39YZvg4+mc>1-2#6j1n*82 ztOCF5{BXh1E(^}nZBu@rWrr5$1{2FpWoXXqx+-)ZAu_kr+#>=1`B8XlZil#*bbyp# zm+OdklY4PT^5!aU&Pblow=w=RX(sDD*HIUGy}M&1pT7FYTPRM!nqQRx=h3j}!I^Ng zKN%;PY$pya>Vgs!$4XH3`@k8U1!)fb+bXA>o%f$|(wNyLC2rQe9WJxou5}Zj{SNky zIG{ZeR^OY=?`7cDUVIBEyq_hSpY~?nv#wz1xwm-7hS6r~w!sCKnY`$vzk{;W;dKUB z{qC`_K$-rG(8hak8MJReQ!P?0zQZRrIJf8>P_VnJ!b@);WiK1jT(tv|h6=G+3JVjD z1Za~10<=XHftI{RH-(Sm0Ky{Ya{H%~&-^i>STXbDmj9FnTcZ!rFs4LI4BYYOnSKApXYnM#N{a%xPaOb7|`C$h-+aL$ErVmu|NZc zWN(0vHsb;^E+_h2^_{h?!&w@)+AH5GLM6{LF~{S@nL(U%Ex(Okhq}b+f?eZYmum7g zUS}Na5~AA_7x(m+Y#l|m(2rO{{MfH@dBZ~8b+!^f#XtK$?M}u8-0(9@JX=FoNEXE$ z$z!$-k*+)SPI+$&S$Fe~a)RZl&WX2vfbtA``)srF%y_V^V5}w-5HRUk)^#Vvg|TARu7iFNUEfREIXLX>?R4jkpHUqL7zoN{ z@<+l`Lh*bHz(!jvZ#afUV&Y^%g02-V^RyyP_JU;7GrVB$pNS~&((cPrlTUnNsYxpM%wlaKEFy5@`d3PgGpG@R zo0GRWIO)nVbbY$!rj17yl!&YykapLe{8K|^aGUZbQT!&WGd?QS*#{VhvdT(^drq7Is{#F#*=*PshM#W3ax-a5 z^YRxN6qT}VFp#G`p}o;?A4&)Epf@*^xJh};+vFx^-I8RRW)a$ai&H?3{)mH4i-R{O zwD&IA56dgx=n6%Qv&64Fs5Zqjs@X2C>ApxX4N@o$homHD>jL+^qpt445PG2YvB9K> z<7cF89=lMXsCRy@#S0gR!ta|x+JEzBF?5^V-RQOq;x38uyKA0Q%#|k2%=HChzJNBL zE5W~=VCBqJ@}Nayx_)^>4Vd}M(QpoDh zlt0rS+a-(R2U`awvD&jIRBDi*vil#(x?@hG10s=|IlVj&ln>Zk9ku=N6T)6sH7y#D zd+8)cVpsuP_Tc7Eecsn3HeVExyH|tb<$q@yzrqK!{U3+6q=bs#ZbV;lXLn*G88%Ji?3vzGY9 z?{y#ax2~mzZ1$U=o_bgWRaKt|fBW8tDvr{9wI`>xJ3JmTSR%;R^)f|MZXEhER1VDr z$9Ju2>_7Xa1)ZF4zmQvl-fJc2$;HgqI|%s8n0d%SJsG&y-o_7zyON{@Tms$G`8>ui zH1yh3>a0_XaB*Mb`sI+jH+aW=YGPsTu|9T5#;nw%Klg5k8D}Cf?UsgO9kmF->SK~! zW<{x)Q0)%CwK@+LY$ga0YeGag$$PA1_I0JFY2ND7!PhX**1Zo+bJ7a-La0M9`fuvn z)_9qFHO@bx@jLq(<|SR7A;C4_@AZx1e3);G{Oo^e0(>6E;0#$TUc_H8kUH!$v7DHA z?D^1Ckr%>xa8xsW>}Pmwo1PqqQCWxFbinrCU#o_s1a6du1TmBAz*ax5nMGvMM86p- z%#z=hJdl5|@caB{p(6Qq^AeTlg~)3_CHOs5e$n6hO?2kkl^NNIv3c;Wd<%B8a&nslB9lja`X>lEvf z!)W0`ua}VL?!qxrvXas!y9JJj?sP?7UK9DnXP?YY?RC{b+fO_wny=Mam~R^Zr{|;P z0;mlD#1~ZGQiEd6(z5k4gGTZvV!3R-j z11KVjWJN?#l8EHc1~4F?C^-otNs>rTW!oZ1Qc(ekf`a5El0!>W1SBJ&3Mt8gCQZ{1?NkRNZ5>FY z;4E|h92WDJU7?Fh$%36w0H;esyZjj}OIdhrx)gp1>)*7WpXObzH(J_el*+MHdx1^_ zVVN)CoGZe^Q@>%d8X7C$KBf7~9eVxd+93$oNQKAV8lJLU{j$x7v#tvg66aDRFzQ7^ zFspD)SUo6Z3{zZx0{%)>9-yPX)MV}OaJwYCvmCdl;UBHEc730<7A~cc zJUmb_s@cH&-MZFbmX;l&9lC{2==!U!x^3Fsb$XBHGj{>lzhfL{=KYUI6gdjcvl?>N zMK1fM(-d6ZbL_CHtos!-P{yaf6tRjO;1l6zCt9xB{_Q38-jt%xioLZ5GQfIKBq-2d zfEsGY0$<$P2^Qy;3suP>k_AKl6M5E$)=-P16W_+)5^{&XzY8lkPK`MOgqQi{cbwV4 zEzqC4s3B8PQ6oOAmn{d|28AkWra(-|d$&IE3zHpv?>fO0X&v+RFlb>Bo|}y879S5E z_R>K0Pw?oZ?(qylg2#+g9RXdNyKGVx%C#9CsyKG=BVB)vZkMxF{K4V%BxciD-({Z| z9W)p#?Dc^FYrA9sDqkz0(QwVz%?^qgTLA7K}n4DWV00_>7ORFf)}lf?d@tFznEk$Uv^ml$9!T zAx#yG4S5Vi<~J%W#c3217OU-Q8x|)F$>F(FPYb;)pjs>M^X73t%&j#3lXU+>0^i>e z$5S(JPS`y$+UV~z(PBt9L;)@=F#gRB%!L;mhnv3lxjwp`lf66Z>smwJy@of>EEGSE z$#x29i9_}PH;{_N0d|}R@Y|EaYYAvk#`kZy=Dz~*bxhziHoRyJ0>=Xl8d0!3|I+;lvM$(l5mmGPUj0Xv=e4sa969y6f$8>Wf3!$C^dpI)|`%a?$!MPa81_U z$_`AQQ5uU{=#|e`M=+PjPzuL#_HZFz-pg~Fk~;9Q(!ebosxDJ>rjBD@9pus}pNQy? z*K&jnN8eLW>~KnOy2Sc-_{FaCnV$}^H^?zmB>#OLKhs*4wPOD2Y|B$zG6HFh1k3Gy zAOdS{$MLVXCjqjls9?~eoyI}%QNvP!bTo z{j_Lb_@+okS!F!5(Y9;s6g2>U{u#;srHJ|;L7}4xB>kkb=MG_6J~tWHj%`XyY~__Z ztMSUx^MkXW4w$RUSKk?7KmD7`0y@_gGsblq)UpXLVN5c;3KOthDU9`Sf4@Z znjqeEK(44f%)9_w152gScAq_l-N;sV#3(n_+*~q2INAe{elP!*e5SdkH>hxk>VHXxv^tY@Ce0&E2dAOsnJ4FX`sG~QJ zcI4k%e9PUnw|u#mXw44hL`PfJHk`s*uQimUZS^V`qt^jQfM}x~uhwFX` zsLO%fGZ$?!)!sR(NfDUX_O7ChDqD@Hz@72Dv^ZqLMBS~)R3QCHsjyZHU`U_aFADpy zquNideyT)jAU-w(g=dbnJ}jhHc?Y*(3&KGvPP((Km+dFmVXBa!K^0AbkJ|DosM!L} zzG;kL+Y6*@#SzFpa-xS1LzF^teflcIPIgAyo1?z!F=$ET`TqDFOfB=Z$43GX8MS(|2y(>-Wz0oqG4~Srt3eI{j&0q zHjN`8F6pQ&-4^U=@--VQ*l)y%*Oqdi9y3ZJb4r70$<=oMIB?K%SY0VF<|Q=CwT60^~nh)YP6 z?{f#lbW!HRTWSsifYTbc)=sqcTaW1)51cs*_6rX2Egho#3a$h^rvEWiC^qVt$tm)Z zH!4?X%M5d^s9B5Aaff!Dn*v*e3+9iK4t^@n&;obu?E8S(TPecClxo7a;dl?&# zF+TvZAkNv$gw}r6n*rG(NH)OaW#68`lDN)5LDh69b@~uC|M_Pv{Qi{q7)}4w*%?80 z{#NfhU?#BQ3_L$`%Dz$l$0C9hMacqfEy;5y}%Kuq3a2FbPcLH5({5bT8R=viqip=>B4m zn#>3Ms1gJ2o_AxLQm-vT1+G&NlFz;I{i)Wzza{XKpPT8*)H;^iaeY@eE9H6g zc)1_v%&cM9uUr7tUAr$-)j*C7gbp$FVzeuAO()GBG5p(#0cn#A_E(b;9Hllj+Nj76 zdoU^raa9!-OPhjoNqX;4UP&*C+2>th#PXp6;ul>^oEy7ttkB8>7w$^_Iu@(|<&`RC z)MU|sun?Rpxq|2c+EkZN7K^ps(IDduo|>~jOD}05ftuBpO3oH8NCfg6KJ^=xA8IGX zQ%L=$RTy-4(S(aa&ur2`o%ZHI22~L*{QK7;F7HK(fTU>=bnmen*nzur?S@)N|+pR}`M|1^Oid0Rj zpT8Srb(A1h9JdX`Y5R%R4B>^-n3l!QtPfPaB)++*;(=7iCh+7pzR+@DQg@RtQ$z=v ziu&dtsZe9|&G7e+z%*?sVQ{#vIAxt%Hn8!(_TpI=raxE#FZJ#5Bl*%|aHiIf;bL*s zb=OvmM*}#lS2&b?tNGDZcHD5czu+UV<>&YA?z9j(gK1g*JoamIbT_pJoac^V2C!0o z9sx5QT@o<}Qz3#84lR<^AYs)-w4i}wQuE2i(=@b=k=cn2YofkgNLaNB8d z=D+Eb{~=Nl#B_s0oA<5VHDkgI{VZ&>$%E`kEj~l3wq+8!)dL$su3baPl6PmnDD1|x z&t|F=d$at9^*tia90Kb$cb9V|4HlTM8c}8;@%_UkDwQ<=NG?b0^m{ z;W38@i^4)z<$zX4{v@HnE zM5v@N!*l? z_cTYb5+o;RjJH*Qvx+1otHb0eIZRgS2bCiR_h3Rjm%_M3ZW5Y2S27;Ct`Q8mTpAMr zBCj!wfHo! zHOh2S!Rib_q{W!O+F`zOA@@2h71a~50->480S;<~eZ8>+_~@?VzXB{gS{F)hbva!V zI$|K-nzA6Kc0q=#wTr3r*g*IC$B|yULdt-(ZGd+mjwRbu3^z;_^g?pTvQ z?qFx$Nq--0N`>}CgPku><{gs36@Jz(C%|ReB=ZY&=3LILTR@e;>F33d8>)LAk{4Y{ zCASUv^rDKY@VhU_rVaH(4UG-C7#;onOiYAg7nd1XD5QPq4+YQSzp{QSBrgJ3uVaS@ z;}U4#zyj3>E~q-R*^9VIYAX)(FYjShsXOC2og6(B+mh0G^Xxax--pHNPdnGj=#qje ziNWF4VJnae;`$WUK%&Qi!H68Y%@ypJ(9))kPW9LdoFR0%sfrS5`nlca-qah;_AvV# z6bpJ}mf6!19<)(B?+u#iVsp$U&(egS%@Y!>O= zWZIXY7`9Wjdx}NI;x5h1vlykCpOYm?ejv`v+vk)txw2Y9Qx-p3-DzTb$cqaTd9}PY zM$Hk~^ihpZp59yejpY?Ph}e6Z1lUKtm1pr_E1XKRpG(<9l`G{hu`Avi4ncOcH%tc` z{?ubHHW`?*<7=YDYOZIhlqY?E;%61a@dy$G;bGmG+_UOV4IylD26|J!_r2dRmsD{Q zSD~4-Jh>*Rrb%J)nL|Yzt2GU2bc>J2A%3ChF zu2lPe9za3_{}wfg!rghV&umBL5%hY4FjTqSxzvNmHYJuTtQ1fhqaCx?77UulFUSt% zgeZB6*`#@!e?)YUHYYv0xUZcZr=hng$v)iZ>Um{3EiR7fQ#HRT9kS|b^pf=6&~yp? z4&nax&F$6Kp5Jq!+0S(Mch*|290&4F0zMpa?p$m@La`)6HZ$e*$24`CsG?1ag7s>$ z^@E6^IAHtNR6-tqF&ep552@&%DRqZ1{WllvF=?|xyasr|>YC7-2%wN8;mHfRs9phF zV~3|j4Vf?Cb6xNzBWOW()-)@!#uh$|27SmW#fw2*=0~W^PE&bD*I#|^$``|BU)fDV z;&%GqzE1`6+!dYwA)4)ihhPc0fi(4uTwi{#G&kXt3Vob7W3cmdPa}lm5Re2SL z%bH-z`9{G2z=&a%kz4sAFP#4HCrF1>*mt-cvzPrj&nawIDdhVGG@S%{f749?YfNa{ zrXfZB?G?xg6}Q;~%w>APvD7@veemp>siy09!pKyH4;S_{A?GZ_MoVc5>w zGoWjXFuKh+1yko#;x-&Vzw8z`^6ZmrI2l@2F}WN1;0RQF0ld&q_QUy2C!mc7tWaJs zMo7wYV$=ZP2{;cNQy3nbV1knh1np$osc?s1?yKGlIE<{rr8^$G>5XyuPz%?W&PI34-7 z{Uz|z=R`U*RuUv-m$|#J zuECp9C8kYp_{<)i3I4=xh&FLkR}m~(SiBEVL%;*`=p3ncSuZ9)Ng&IX3if!;+2|cX zzL{C&Lkf>y8W(`*{-eHeJ^!0h}}d!x_=Q9R~wR^ztV)Z2V$ z?WIzC_G{jWt*-%!d=Wk8u^^lKVhudyQSMFeKE_0m2CBL0Z40c8O=&T8ZYt|_P93Gg z{bJpCKR+h5>KogcCe^C3>GKH(W{X`qWe#9<*Fc@g(exV%14w)NFdOYJz+hKMkj6uq zRf=Bz6kAspM8}k=4C%BNE+9t=qOR|KJ{GofKDaY|KNzkSq=f-)?A6WVSnm@*Fsl=n zjbODHD|?8{z1fNy!;8IejZVe#({*IEMW3<>jRWz7eP>_7?2GYafinu481!LUPy2Wsk99MeH;p<;w4v?ktAh2(0AwG5#3Tt`zH`yb)8D z`#gwO*DVzYzB-vX@s`lq3s)zz{+*giOlY>K%9LNEJP3*{S_BHnL+Gc-r{y*855<-N z_Mw|=i%}|lCa%Izu`^d(bt`u2W-^T{x#Ib$>{|(cI|g5_sNwfFd9D7SJt*Tu0>N&r zhBoL=Cua7uhmpO;N(&bKR2WlfP8qqVowlOSdESG@_%7sg34>v`w{vmFroQ-@(Q?Rj zbY(>80yG?R+4vbckly5T_pU{I@uJ=Dz|O`aSJM`^VsvJ=ZXL=fUFh!0HdUVJEfgCX z8Zx6xjb@eI_(Z*FA`b!@xaS0v6g z8(v%WAP273@Q3KwWI3a2`v$&bcK7uirwPsMb-F+WFzA@nZU z*nhy_{x#24B6mn?Mv=gmdjuP)hC5kJavX>X>qPSNu#zJm?|#ow65Ga=)_PT;FzX%gF0OYF zgkri6KtoT^UZY&|0RI(TmFrE5Cj|0hVF8e;C}}~wElZ?4t`-aS={i^D@?%iuS5bp+ z>>T~mN6=qd0X0>Vocz!_u;{a~NKA!3W!|U=&P=C9t9-fLb)|>Eg<2~`L3474^`+s= z=D^35&?IzVBDX0R^`>iD>usurZchbwA#Zx1QHB(_Q@BLL5Zay9ezfVKehnHeru`N8 zfL>2~XroimEXR^czCEq)C0dFm2Qzh&+qdF+fEtZ;K*}u2q`mC~U9P$U0Tob`vMN{K zmh&Q;QDn8`Fr8AjL>W0q61uVtuw=Sk(Dz;%Ol2F-sTT^+Dj8rQL&G9D)Jy#J9my#7 zQo|A=C&`alRq_zbt0X)+I$gG7V&X1p&g<}LJAai7bQT<$KS@`iJN9Cfp#ofYBzg6P z7%H4brwn6ZWA%^FfU9~>4)5DPQABK|Iw=1SZFT;T{Ag~;YMqlUV~!iYSbIZ z^{<_Vdr;3P8{(Fg&Sd*7MpuAZF{r!rj=KpMy{3aOL=mBlGX7{VxB~H;_8Z1!m2!5o zly5q89aC!YfL>#+(BMti8aKZV{S#Rf$jk~%!_d)5vBpR^zt34ucJR2Ge~8a2k#;38 z#CtBmVR-FhtOCZ2x6{Ap#P) zw?3A+E`Xo*l{l~9prMiij$WqE+Bne*`i&_nn5XwbcPuh&gA8g__Q0p(rj`K~>%EH@77W3{%htvZ`!r;CfR;hn z9OfGXZ@(^7I@jXbU~QNiKTXnznR(&5SWMsyGxByreY~4T?^CIf+5rqY`_w?^(xM4g zfLEZIVrSL6Fhkwixz6@f!}*kgfhQ+kmD)llRdP{hsgV54vydv(Luht(R#Zab0BREJ zNvY%x?kro#bAVozLNbjkTKY^1vtkMwwQUd9-rw6oxbf(bJP7>bLA&5?mLH&LUlr4P z|Hh65mY_qU>j&KH`>(32tUm=-wjgVdx`(HxpaVCx;ZU@yd3mSYa&t(qn$L18`H`^a zp+;!cOYMXT4a-GEMVV0VxllEEDYWHP)K+jm`4tX^KsW708N=ef;IQ)5LDcN4V~LoS z44W?@R5TL5X4q-uagHxi``>}RUx=I(Pqk5GpW9rJ2v6Nm4D zp4O=GmG*+80_CsWHO2V(j3Vz{#@nM$dGVGZ%Q45LT(k7qO>^35fh`pp%~W+5%7ISJ zf77sxV{G37#>*YBBctCc;GUr-yy7422xSE8nE5pGYS?_XCeI-;t<%tkH0B_5lnx_~ z!lJ!1d*J1(9d>ISmy@J#*cOc@qF!S;1Z$A@sJ)(_!g7Mb6G6R?CuN3E?{pxrARo$O zA3x31Jc2c0=2d=Gg9IV!w7K!1wAr%Ks^%t$#*eKkrv8T6`8j{hE2Yrm)&v%P>_^X? zUd%{M5+ZHh@rb=TCEl#R9#3y6^BYn{W?9UPtn^w&UQQ*@0_rSt7d=H*r&PtFS|~ zpmONTO_#|xTC1w!B4v`WJ~`sNSo&Zn?jhq7qynT?SG?FIYy)>g53UuP@=0gFSMp2K zTPWj$W2u?Jzh0aZu<&#ENdV6BkZfcEs#jLD)dlj9Cl3(;}(zqXl z`um}Vz(diF1h2*FBB${u88mb0;r!F>#aF=2vC`6`w5ErKeqpQ-kIwe8GcU!+JL8v}o zY`G#_jXFw}IIcrYi|A3c7}@vI8i^|Yk#=QLq$s{Cuc~|**y(PXAM1nuhtKL~Z{!}= zNUVZ3f6^n;M$0W>CM|C-c?A#OD=e7&*h6PPFR87?B!eB8MK=2TW9?ah5h{;%j9CdU zrw29raEHh(KBj!~N=+#CD_6tf1a|#ktjNpT^!qCQngC6xj=1Wlpzeob?(Xi(912qf z!~w_H75z(Ag8Bs__=S)8^HTWMR%Vx82jxpvW}v2RvR%moC62a*gRd+sELiWSCnhF( zSGE$?rd&){7A7BNY+Fq>*;2tf38O3KrTW5_Xu*`awdVBLO^jt$)_Vf%s$9HFvqz*c z_2wOGBE-CVU2sH4d_8QD_N8LeDZ(FZm7iZ_1=X_T#YwnheOD)b~ z-^zPfsiP2KwE|i!H2n{@+0nl(ra;SKD>{5_OMAI+5hHfv1HO#g#Qmbr{fz4tn`a1d z%hGtRKeQ-b_uKEBH?V1Aab3$2Yofb~VQ<0cyx0vrDp3<{uV9JOr>o4u3^ZF_@7#aV z?^=S=yi^(V`=u;3`53mm)}f&8nI%LmeTNHy98#x9QD@saJ8S>gwv(=%S-l|murnq! zbjb%UroU#D+8>pllyKjg;V(wO5v|XVf(45g4#0hY0-AO%w`MnvVZD*Ln^=N6+ao-C zSM$qt--`e~8L;$jr@xW=n9KbbiL&j0{vJU=LB4dUJ72>k!8n+09L>zU2ZyP*IwVp4 zS!P%xcKOEV@rC@MOz-(rB)310f3ojrH#m>E{;8peVJZ4IC$Qd|MR`R}2s8!RIFvM7 zzHv*fIS-37ncq(#O#VKB>5njSp;N4w7PY#4Ymv@*e>M%&%$>WkOnb50G(_%|%PL6T zy0^AIdryqc(ef2WKU&Wff zzFp8UkACUm+3;E%^%RyI3O7BKte_2tTQ3vS?%?4#2~BZ}o5;`y`y}+0j@9vce`fsS zRB)uvhcn(QGr`a0Y*5f0m!ic0{R5^jS&$4@Z~gw0!EWLNb!IVJXe)rUTJ%O3sR201 zMyLCp^xKCaN71qbR zSjFSB==ofn(d2lXwp1wQ#6S=25+d}m{rq8lJAc$u7uj}d2kIHRyW?YHCLL)y5$!(E z;`U%(p4Z0kyWCu{jtqlHI3YT@(n5+b!Q<$T-c?h@iFLU4Jxd+={tI$jg&#&v3aGF70dXx9LSpb3w4}aW zI{j&6# z%eD0mLe{NwiSq&NMn*c^`4ZMYSC-znPw=oPcobG}p4%akgZfn9ZpD4enp9_P=V&go z?w|Fb<0@)MwVuA!TQd?U*L=Evi9LTZsDqbIo*NS|d?15u%n)3veDv~D-d}gRFzLMo z&0!b)qbaPHiiXN=-@|hWS(fK*6Fpqd| zX{f5V@sF6IUSvz81Bb$fzIVT%Pg}h5$*=p_JG*zEJd@LT*Y&&>al@T=LtN+Yczj`a zd9V;KFMrkFb)GP@!QpN-W-`Xmbf@J2_VnXc(x0?`T_EW3PUMzZrjUXVOfw?2{Ya=V|3hw{*t8h;T`U} zxBeWbB##UafBUYt>STt+;fC6*_JC##+sp;nb%(ycNcWeO1tfQ1JAOO;o@~?F;1c4w zgBTuwn^@v;IvoudazAGH!Qxsk^eB$#)G7B~J7fe=HoKEXWwNu&Z{Ov+Sa3&5%xArp zB)vBvLr3@BmIhc{$--1$&+vHT@5y&G4Bey>!;1YkZV%%ZSoNlkVz?vd^@5QSwKIcu zFS6KiU;5eTv8Uq0?AWN}P~NbKW?>|5s}%pim}P0TZN?Pvu%EZ#@i8tX$;p-%ms#c9 z@8ikq%O@Z23pRMincr#TBL@;n@8fc5X=!suhvvuS7gr3<-!9jy?ON7f{VrNc{>#7c z{piS(kHKHBY{6J6q>i;`l;#%q3Ua(n?X>lRTaD!k2WTr2tfdngF396H{+Z4>I~9|~ z@UsF@p}W*z@IhM|+$qS3c;5E?dxVQ;mEW7C;nZ^JwRs)J;~d48Wo^~{kDeYJ7)XA+ zURjoS^nkL2(uY8ffkfDKn!?xJ_wwzZ;@QGXXmGSe^x3rb){fgD7)O10ET^PtpT9Wk z=fvZ5eOFGR{e%Fy;CH^|Z-3$?ZB;UQfr%CGxmzi}EPnLxZ5K19&b5+I_I@#l>sdf@ zLk2yP8|r=TRuk?pp50};6T5JJBa?D-!LRI6QctXpQXY+Ds;a3qJ)OJe2b;#nCGq}r z1FxgQ%rn~spv`mN+q-n9_ODl+AgTr!T-Epjg!9x-yi_B=oxo4%U}xYWp$N9(%bw^i zb1!(6D(I2t%RRq;EH3uAxIB{CSodsH&g|qPQ!W2m27!i^kf|W1#-DJV&{Jpek4kD+ zrANa#6G8$e6U<)}1Aa==SJ+K4u+{yYlpLfVC6mmrD*1^P@E#z1Zx7|5kjA3sL0hmj zodQef^4PkJ1q9)Cixw7{K)*Du|o=f^vhm6dCM z&+P2zP`YyE%Fz6!hV^)Y+YQsJ`llW5pALL~{FVZyDBca^JGZdFHRo<)V-v_VNvo04 zQ=cB|mtX2>^gGFtT~1tg!FIyMP;K)4$a@9Z*WLLGGA>4yqS?9g6C=s#A)J{_Pbyu~ z1>f^yaYdd9!|`3*479I%)DMW-sMvf}u)VFqPPD{TOb`7{)t28yCR=xE^LciVJ$TY%x5d*wHlnrep?HkQ7QqfYA`8FCaQQgecG z?LqUXXKr3C*NZ3kn_D#~!JJNc;tsa$)YUR_V?@uv-{upX&g{GAJhM}u9<1LZ@)QQyh?dUC6LI^(J|clf>&uLH7Q)gv%LduohbEFSjl7( zcN&}mIr^oB5oo?9sGi%FJq5Ghl(;oP><1#x*o--P0xbepv08CQh>4!D`|e)HnX4Sk zaZs7t>;C!kf$!7(M~RW93ssc^9}X(l)JZqNwRt$2RJ$jVi$3S0Jk6?7)s*hK9W~i# zq%{?+J+C5r+~kWT)8nhI<8leQhlMC(5B5x_Zt$DbZviNubw;5b*Ym{FDBU4#^$_QEmr=9 z#usNrCrO&NWKwRB-SY>2{d!fS7Tw&(g{hdX52i*FT|F!wGR3oMjSOio&$ivpwm5&g z`L1T^9cKFa_nrFt$M2AHzg*^9Gh`{BT3=g9$j@Jl>$JAEPRP!75V7Gr5=lt*yS%Jp zb|}D5Y-L@H!dW*)z%6tqy5`-wbJr?{nSt57x>PK9+8(@aK?O$%15e%Gil(pF&bs)K)`;Km`jo0bWBA6#1vbWBG53)s4LoUf9~QU!<5Sw__kTW9 z9^xd8jMT~26#)n^GBNR0hQFG}+NahQ0L6&KEO6w&5#f?RL;n5XZUE|f$;!rN(xnkX zE3c>)7>^fY-n#pjNHy?$t|o-L(6IWyIp&@1p*xo{Vhq`2%~s$khkL(g}p+WMA!i^kv?5 zQ)tGRnEz(rs9l>YRH|WY^9F$AY)zR{43*8SvF1&W%A~pMxOn`7(R( zcrI|&&*P=cqn$KAk5f(mzn6A{8Ftrl?a>7v2w2>{zW9Kit4_vy;k&u{_52&E;N4nS zT8=t;lJKSEI^K{MB~xnNGofAOK0dKT)0#m4MZihcG-)tgvN+xOGPr$$PQ5#8Ie>GVr|PWF8Z*QkAm8a&w8}eqlrXnIbB9L=N$qFcmea z@_XL7?camGKMHn0OQKpV7X;F*@KX5%Z;wmX-fQDVO)}oymPyqgEL$(@itP+DbhpHl zq27EY8&I6*?H=>(TExHTxjAmA{d+hJsGX%>EOto+Pqy<}>B$D3c-{t7s)3>xZo~Qx z)hv9;FZ1Ah#Q^&29d^~y(&`1Ek1uucWu_-zQE~AKhnPV)oz&FS02Iw6MO_HkUyY#I z5nTX>g8;G@BSnp86bp@wjnM&)^sgrlE;yq7Y;9rTC+tlQa2rOm&b~j|@_V~Z&h1Ml z4ND|RQD{u1AU5&$(g@~#{rYu@kwoA9);Oz@Q3M+XvP)z%kux$f3MO*u<8yO!N7y(y zIUT;6g$?$tx%3t|IJDo?VlhBC%s-DY#INZDKIL^9vI7d_HhfY$iwEMG$?+XNGoSg1 z)cur#e_5k@rqSBl%OOGVbi_-Y(8>rrky&!e-NR$2VR=##|NfKOds4MBAt=$IXBPy4 z-ak73vxBU`u!B#&wYBYoz@*k}qouWV03a4J-VkCv@L^%M52X@8=O#@ta8zEC)K%`j^qhyiskGl;cdJPKm3-S0F)W5?-#~$pwO9+#8fy;`$1yNrv<%v#MYDa%wr- zbkRRcLmw)mF%fl90ExK6^zU85OF^{mNq|t%F%)vr&bKwd7ou}f^BU72H-~tCAoP!; zn8pDkPlvzclHxKlgiurmkk&dGyU~_+q8GJml_j&rp$G)P+th|N(^!Z>0z=oGf0a+PFd)&3vnqOH+VWcMb;db^jvkZX-brS48?hNVR#?g%6Vd2t@OC|4PV!?Mj%CU=jYRMBlzxh?@qWw)g*gD(r9Sfi<+Fy}O$Yz`TIb)+BRX z^P0ee*`7-?7B)5w9~#w*mWCpUzU;PjC5|fKr)GXr}o& zHcIh_&O=1D*L5s8>D2CnVU-X$;#eg3_#7=}lYsRA_B@anX)CY<*YW)8seA;(WHTzP zPPvIRN2ZD1tM8&kGZ{FFLkIi8?9CwRRKpHK&0`xBTB)? zTNaR9QJ?kI=ji~|{qGS$S1_{J{q@H-G731vUkDfgsV{65q?3CG{f&CAVLnS?d{ZJ< zLyum4LeJ&O;|<~Y8o;dg2L%Of%WUrIVnyN4G~GObS0{D$!neM}Y5eaM5ES}hMx~}l z$gKbLXs79qPmjo-b_!Qj?pEMP)l7dvmCYbBEr8FwRu(R3XlQ)+@S*DMrBDRXiMmYn zN|H)u2MUP6>^X)>s?ltP`nGjr^X71lDDGI3UpAkvUFPYwI&h%e&pg)ajG^m~M<|cu zLtfs6^XI`o0%0R`r!ndvXz^eaaDqe!^L;EFVC??yiL(O{-yR|5c;{=BRBo@$jVR#i zg8n~t4geB;%;m)Yz6qZyb!~t_{`=qo0sZfPf%aPec?E|1b2GU7zpp8tMWN+?KRk!F zRQ&tzfGX{wG5+s=x#)+|d;a|#Ill?({qMi+{lDq_vl;)lJO6A2_J6eVzrFbXMb3JA zG^~E`OW#&N&mmBkZQc~~(2!f)>V`_JeCaOEYqlPXQ$ct<{-I%JIz)C8l*8WeVsYJ) z1ju*(!;ul=v2KKWL(-(+?>R%B4^7gH%H^e{r5W8zH&ywUZ%o)Z@G~*ri|5W&9@^Lp zPj7A+?g1;j2rS4jz_xr9|34-Im0lD>LZ47gFekf=%arWM{4-u=20ZVVMfq?;h-+7|z)O}h- zDG<38d%hPrSr_W@h$0P;XWhv)w>&r6Y6?L+vytDh_h-iX|p`u`te<~FilG1g#^lLG+$_+5=Wb3so}ZvrBd;Mc~# zd&hV5>g#>TkxwWqE9YPt~f8k@HygYy!N_gjf@FuJb2W7`z3uOnE!Y z(0L8xF@WGww)^}Tve!>SN?nZWfPWW6DVoRO4b|VxV>wYC3`#B(H961bF;DMBB*UkMMeUqs4KAKS?RP7yLbg)G&GO0#ZprB!`JRP5QG8& z*q*2D(K0T!y-uA54lS4X8FU(c>y*IaI8tEF^9)%3)x1GlNPy}-3AtD(rR4KtX(lG{ z_WdD|KoZijf>k;Yp3&lfQUQTpS@V1EU4a~7h2xi4`T5ZDe~|#!Zn-&i^qO;QHU56c z(Jvu+kpk?zXCu#Pw!*89h5Wb=2e8Wsxg>n|0V1nCP&WOjZtz}2$LGO&WC@>H36x=c zTNk~M=LC!mkIu-*h@W*v;ZfUyAHH9$3t@!HR`nP-z{(!Kdw?gZqYYsKhkPC<-xeWZ zXNYnc5ru|JJ6VD2cOIClWUl23dE9728qhfoHTk96cyXXteXsd;hgEWIZ82n#UH788 zU=fZ~4xyL=`6JLna-Bj%h_3@6(KRE@2??d8a4r0e}7)NVJ=2gnSL+06T%AgtBs{ zTpAE$kZu3t6Ji0pTWjLg0Kg%n8D%E2{&1(m1eC8{y&7wJz|i%U{{7|)5gowUv!(-8 z{t+F}Gjpx;&jX1>zSq<7VPV}Fs^q3cISAZCXG80zLu`#`S5n7O)*SMa;%49yudtZ(=($HX5SSN=N0jTD-C(-_ZWxX&G zkF`U@Tk;uYG4a_~GDys=ylF&9u)Afa6$1~7-BGkgVkP_D;1>#|R)H%-Vcj)$_RQU` zJ%HG0cml$8;=MT*C;b&L?2MwZlzaI!*pc|e#G?qdOn2`+7xqPs~I;E-v@^)%Lj*i_w1HABUdVaD;qHOM+a5WO9 z2n_R_{);{v#C5@Zhu&X z^KCiHDb>OzUtSz<2GLa23mS+zUS-N+$XAdJA}p<-X8L*Y072M?+m_CENZR)+*0=&% zGSIBd9i*AA+djSu*~_)?a}&z+k8B9dusJevNbW)T)&l^*C2KLjeB-9)C%%g*g>Z2u zCWJk6U{zCK7BZxJ^NQNd z{QOL|gSwPv2u@XISOVoeddErvR^=u`rZ%oJ%X@8^(qQKu8a`Xey)NRuIOV171m?KL zxWp(*h%)q;%&Sa6N^{>UBt^V8RtU924Ut5^$^uauUD-+>sm5G>Hi9lc&=gH9IUG&w z#|W%XcDjN#+obvl<%?F?^H8&>5KqA9L#_yyo)$HSDT>;3f2hnbLvu>dMswPz+X8y| zRsp1i68rypc#ud-&lq?jqu}s~JSh3FtGcGl`BKz-y8ka%$idIKj!^JpyAa+5_?tW^ zqE{qM#z?6h*uF%QA`ozoP%(=Y^_?v(EjPyc0Qk%+b67+w_*SPV0mFT|mIfz{^SKRK zYH=})T(YbovNIP=8WD(<=9Q{%X=$ks8{jXsTVd7y#?6~%?@*$o;>U2RXf13@P!1^= zi4WN82rO65(Q&fElNMvkKMfmzahp@eL>O!rgc538b#!#}J;~KN>23h41G+DGs)hg) z3J2w)33?KGLJK*f@@AgSnh@?-Rsuj~ce}FQ;D;k&DTQV5f1Xj>;K|_8o9h)LvaNOE zdoD8(#!yuq>u{cGRa1x#r2^pdW^jm5x~mJ+8V|s-zZ9gKrYw#J zc;V%*2O(ajY84A8onZRiJ0E(1P)DYI6=?E<~aUnm);K&K)m9zXx^d%3ja(P{`Hn}wehz@UGAK0@)s6MFaWCh+ z;J{dL+;c-p>XKy{EZD*iB`mUXOWGT&j(48naR-duQI{J#ro!z_xrNL{&@HSetqzu| zlzXQk9s*6xZ_Yg)0ZVOes!vAu^z*Jx+gNps$3!X5MNSKVrY(N zfvK?6uI({cjr$a+TbOmL(zl9&qoKX0TmEs@2Vrh9{8STwUNmq?TuaY)EVq#J;gc09`-&1aE($b@S#;mB=%KqQfsVRQ>&srMn?x>xQQ0(V@AKX5J*ZIS^N(Wq^XXf_1`RiN!G?kRW;{ zH6_JleyknYnyw>n9>-q_JxZ-Md8uW1kXRcM^8ER84yPU1X(d>*;vrE`Tm#}@EbE3D zD=Zc^wU6ILuRff=7*r$zTwBAJZzQ+{Q~whW{G;m_EIU&dwP1g2nEP@phQYkaU^3UB z5-bFeAXA%H!C@Ye*8_5Mv67d5@|_vC244)VauDicBKPG}seF zar=T}H&%yHe4;923{zZySsPqDfNfT9wJQIf^?c~#>K^%Q^edk1wyn#MZs6rqC(pC9uu3Tv? zG-=mN`Y2C>^GyP$j7n(~GLabN*ys-n;2&}s?+^ravHzU!E`L;M4kQWF6j05p$X(#o{Ve2j;*}sHTaP{P8{@6eiO7xfFd)QzHQmH*ftbits@QDn&~UMic|uYPo~nY&ZDjr9<kl^vA z+8uHA^=W_LNfdDA_FA4x7WVvK!5&R}u3>INlhxqVj2WC&7UaC37r z!9Sp-AAlO(&pOL!G0ElubKdw!(U45&ew~{h(8b+R(}Dp z&~nYdfD_fEP{nm79HS^?u~4AsGIE{^ja)jdmNQ`}Gr zK&PTGFta0a%}He|wwF0+FotLl59(>4!+AIf>kIirC@nNgciUKs-JsU%Ikr56?cbMw zw!rRZ0Qw|PJ&3kK$KfgpI6&7&QC*Qg8A-JFpP`gR-MSG9WS^ep#}q}WVlo2BpAO_g z6%5CCSTz)b_c35?w4&R%jKuuF&0~u}p3sUC_vsE&(7{FbN1wA2^6iWoxu<|O`4&io z*l;4i3+mj6lR=9e9fF9n^gCM&=S!8CcaX%CQCRw{HUQZr*V5hc@$S~15HfAF6b8AW z9<^h%?3o(+)J3(5t^rA=OF?{7RnR?ipA1lFT?WEbL_s9$<$-umqXwBXuC*pIkkJ|F^7n zAL-0AGFb&V&|taN-I$rK0LjjiJ^5;ZD8J~PDuAlSXjCyYYK+mwa;L-KOD!d2&ETv2 znN5M&k2}q~pnc%jvGi+43aC3$iBj-cjR50P9nUlbxNHY^_IbHNs$7!+Z^qibiqWB!M`WMomRFSq){|e;TKP?BK0vV;=fFchM zhuntYYRE53xD-0K(WwO^TXeAj$;Tp+w-?XQ+YVj(+7^t>$ph7Sj8DeKK_+G2{`|a( zW4AMSKqxn;$`#Tnum5)`m15Q%X(;4u<(1ltu&@yMWs4WDUM04D->8Q}V9W5m_uqxI zy}x!%Q}dN*8DxeaAWGG$94a|bP$&?Ytw=+vLJy9hO2kf8u3*mozwF*}BxpHLxFNs~ zBJX@d(U8MM?jfw7LA!n3eBYohP{|Gf1LC?=FKRuzRH5B@xOTQsWzK$gthuxm%Y z1G}IUAkieFa_{3#w7-OtHWE&2sQLv7StSsWCU}&ThQuU(W2FzhDaIFw_y9VnyHp|` z1#9PG;06GD4VU@=r#Mp6Bs=>xs%;y__E^essBO6+A2Ls_AnBw{l}>fQDP!i4VBi2L zWGFjw?=13VQTo{j+dk=cjn9#Yt!!2&u`d}TFR%gJKSen&AQ+WEVW?w-goDub*9gl5 z^ObKX3a}y_$eB1Tq>-e0HBbViDU26=T>?|grV5m2Kq75@kT6MvVz5A90REwyH*Qp= z>EyE0^06A($;ZwhgVF`10)a-YhHA9Ev%b3y?p0G*yMKS8OY~hM zV-S*!Wxn2oi;@3G$;Y<Z48+DT_Am&2{JsKW&sVYg`5f^l=WZw$_@?(vT}nZ2mD@0r?OL7tNPxiDZ43^ zAOAo)2u|P*RU+7ykZaP~ihlUAn}9`ikl0t`6mUhT@W_cgFdv2?6)TXcu0B|I3JH}= ze|iByz9&J5{Z7Ih;%t%G4Hoa+63DpmcLP!lg5y6A3R`0=Z3;0R0zh~Lkzpo+ECI<~ zKwqd{_vnyHw6r*v$3%8ziWt}#D1V085yACP$tsy94X}ZBf&DFTC=#z*1H3}DZeK4V zB%?duF7~W4NEu`z+^dGI-_Z%S$N_-010VsPe+b-*6Uf;f=__`*9Niv*_BzI-&<@O3 zOdJ_P_TlJ7gM)+qQmDif6(cID|#L<8Xn)dU#v4$8d|B|*MZAlelu zT)93rF^!DqAIB0`kfpxq`94m*nX2gk<*|H2C}PkEtb`0g^`u;L$c>3z`f6^{nPK4X z=0fmt`2gBZ)tnZ4WCzeD+DIj22bYVbwDBHm;7@eN2p3Si`v zzMU?QeUk)6#|o*4kr|9f{@&z$206Ono$s!Mh0A$3?_xWB45%~~?U%1f33b1?wXXj^ z?Ol01)p^@K)zdU@GgDI(A`E4j7ITtBLenBmh&B{W=aeO)NR}bqr%xNl(r8*piqkZt zj6{p&G*28$6D_hOszWMUhmeWmz3$&Rj+y6u{(Ap?=lhw@j7;aZe3$#a?(4qp`ydID z)TP5>MgF!Kxd`b(ty#0?WlGfiNUC~{K_w_JnACh4gU=_3k&94wc!sLgUn=nZU59p~ z-r2}}ACXf;&DdHDy1%1xHCmMIf3358{elY_*tyXXolP(3Y&a-xg{Mr+X2}ud;YTOF} zr&Uv7n1~h~ol#aHT-4Hfi3G+`G%6^9XIC{Sc<(^)GoX{9jiFz&0=HCfU^2X!4Wcj9 z8vfX|2p^)z@4pmu)cQux}S1N|}PS<@fG!E6$oc6oe0-tycNwdrRzELwi@(bB}R$MOB!& zn?rq1Md%|FP65n-&jgm916_~+UxbjNQ-B4)3{fNY>xV5YW9GD3(x3|jP>f$C};0`uq%RxZ?M8c*$8P6gwGU*hZX-b`%$x73LS0dFyiG`O%~ zY*bGwgH&3GnfEgK`OVdt%w&IMbZwE|EPqIWpUd-EDH&vGDDA5 zqUOIA_PFXpD}YXU;15nYV7jPj%P!s*AUCOX(upPI0^oe1K+-0tR^9@<3jSGJKai=) zLgFNT#Qa5=JZr^_cnX-~>Zql;@ZaL;X#$KXl%@B&kXd zi&ua^L5#jRl;^;->>NV@^)cVfq57J_lN{qiyK8^lE-te>a7|bX+U4a9!O(8` zp7E4BpE#>~rwn3o8F!x2y|M2|DZ{LfEgE$w1HNKnbL$(&${tqHSniO5uS0K86vUp( zf)=O*l^codbJyGJ9bLc{Q?hjimv(7Bn)=CCfnPS_;4IZ=&tnB5K18N9o@0DV{Qj|B zNrI8rE?y46r*xNn9eQQUjTi&a0V*Pkk9Cy}?Xq3ETJB&Y%+@%w<{xHyWW0s=6h42}6A1+}9!ME7#)CtE z0#rc}R@I?HR_(C*2(uZZYCqeK?~mAHy<*u0ENg_B6ADHU`nmBYYnYoA`}hHysStTG zg9{YRqne)_*RSWy;lBF)3^QNg#<{3X$qFBqEdQepul*VnG1JJ5I{WE@^`nw~Li6rJ zxgHO-kXF^8^lr2`ZT%%@*_n^f+9;28nC%r=2g@^)szB0>pow{+43wL0<& zxEYuvSCEBz1_qTOF3cSfnj|zsbIXhf&JFZw+R&D>>&e$Krf+}Q;8opBfdm;;ZYb0k zCRerrsG&<+e@aSb1_wHtQex z?Shebd72wjX8nxxSX5X@B0Ad&yQiL)l1{Q0p~&QyjEuEeltsqS{6g+o{5;BjoSjyq zX1dSgt&zo5m~*PZXPbjn*VET83wZ|gT1*w}lyk4HtT@FV{~WtD2n5u6`T1GSq-&W= z>$#yBm2H9BSNUUt>aOi1E|4dVw>8z*4IuOAnCp#vJ+kc4NRTfjNp$juBHa}1ILh04 zz|MjY#IKid;LoyfZ>kKN>vDS`9K`g@{O&a%T2xKmERCm@eQa}z%aEvdcsp{E56aE5 z+6-(P9HimLO{7j@?<_yTvj_wgx&qL=ZKFT9#oj+|d554tRzY;j(V-E&o~V83F%vkC z$V8vp`d3kQMNh<`svIpX3Tdca=kPXfOc`~^DEa-2As5v}b)M$SupCI0+tKDFoRg@x>peLi9`^Z81y?j^{ z#VDNtDC(GTp6v{8C9Hk-;;!oZZr>H%WB0(`q=Ig9${awJ*NvA0XhBwMW?y$#2}O*A zIvi2=xT$jJCjZbIEWTqFXC?8;%y=`p^CuuoFIQFtD;t@#1M&4os&rEk-3t2XyP^o7 z<1BlB+3ZtA=a(Jyb1>HOyY^r(_Uo^|o+`qdRCI5Qr7KLUX?cfy;J-=G$G@XTQYjx5BF zC{SCxM-!hU#frzHSv}g4dUJp2htF@92T*a>a9m#8J)%25WYIrz3ZfTbX|cVarT~LX z_jPuj0V4IjazC^~%+QU)*F7Gl@Ul=Z@N=!Tk9WgOHXG^A{)`&$hbb!w zg>nZ`QG67cfs7iP^|9(p7YNNiJU>{QD82A>lJIoI(mcBE{cuu}@BP$hR|+L6>v0XXKq_0ZPK9sc;|KV5;gA@vdCVuNE|RpHpId9Ay~z`q;B zfY8!~S2EPa{@{S25+n64gp4;i-qr875ucAQ@EpO%4kxa&w%XfI!JF9NwMuL7{cF8% zrzz;#n(-SzWX&f@ft7mjj>NbnCLU<&l`vLZ7!)ydUxuVh27D`b$_&`(?3^G^ z>M-{xH5$DI(&B+rmDZrW#2Fx#^-mLbf$>euuAgbT@8}sr_f9H_n~(;wgob9#=$YDq zGo``>&3yE$<%jvTHl0;1&g1$kaP&lSojI4RYCu`@nX@)5LoLn zw0_6Lh}Gs?w3Rr?%r@!dNDj`Ze<5Nmp=m;UUoZ4nD5!Avp zx_&gjfg^7fuTwZqO?t1$L-Ms%oK-MnoN^Q2BE)1oK_j2B)y~m_@&PM`m3ADjM|$LACGy2q1k6K~Zjg?nN)@oz8C;_X?yxvh-Iw zvmoCHCPfOpUR)FFEJ|2)uo6>vhJH&axF_6z*va8v;^Z)Y2Fxx?`C?l&Wr z*>Q9iX(IRna5;tpf2r2ShXkT*iBQ#-Usd+P6QGv_ek5&RgcQKu-d8Mo?u?t<%s*A% zn9xA1sT?8Q9kC0R6F~&Vu^0I@mntqPE6|QLTW~wD>m0if0$|0wvKWF6xStX%x9#tV zVC-$*X5tXAUA>1tm)d_zE=ls3p;-c)I;E{9vr<`u?7=fW9ds2gC8z*TF4o#Gbbxxu z>kA&pt_i6Twl2xmdh1~VZFst2jnWHQ-sO&7lNy)+CaQ?0O`8Ve7sEGhQ8x?vby?wf ze5vq*^UJ7$ch)O!EKplO{Pc*A@82l6+}>9fVk3K~aQO^2*CNW9Dnh#6IxYTvRo|+5 zWcDsrS@$J{c9$I!19n?n?j<2Cq=n_mcFwsnq%=cEZiq~ffE=2~&A^!_5T=-CU1F`9 zqr$O!N%R&RX~I%(tCzN%G~YDVcJ|m3m7gp#eUu}>MC3-wY@N& z{7aZ4Qu*)XS%5pmtGeVAytsj1I$h}psx)CU%`pDsWnc_dxF~B_n-#xr_Pn3x0|WvP zByf!D)<1n36$>bzQBCPxVJ(r~cOu3(U6J{jX3~K%BSP)F5bbtS8xwDX#nbg1a}yZ% zvhNrP!eB+pDpptAYbNcj#o&v{Dx!}1oG2)0+^)Ei{sh7t6;UG^Br>CTG~A4txwi;O zcF5+nFWNrZh(kcSA7#6c?ATG}yV;&N-mGy#Q) z(m%5F+^9c8MbZ-8LX$;WDU<}kU#Fgh1Qs7cL%_R*9l}O_b#7on81{N}WMm|dWCu@f zYli7DwIb+I4e|uek`W#u6q!y!9RQckxJnm52ufap^pVU#m$}5#KTxL;^aNRdsnE+1 z87Bgr(OFckL3QwMBb#KMvV8ONpHprC!KYhCK6b7U7CU>t>wKiBceMAS@wO{96*=Of z4I`srt0-#$Y#e%r-wf$~zdH9Mgjf%J3zC}$IiEH7hy$6(}D-!9*q>Pw9 zJWwWGC;^T8iN=-X!9a7RufkypUmE_a8EDAPIKYj zN9X@}{`I&OU%otVZ=0~X{piBT1=bBmSNWzM^;lQc8SPN{{Eo?!5BnN)g zZR2Eq{9|nR^tj_lcoai6%t1|%e_>nK`?2p32ccuJfAs*o=Yj?|31rl|=gfkq5-jS^ zD-jAgK|wcPd6Pa5S()Hr9qDw$O&TN1ZCD;A^QNGn@DM$c4}JT>;Fam3*>!SY+llfe_A^ z6B2U!)v)uHE!@yhGtutWtB!M5rEN$zX=`hXLii9oP|?*S;O^P;O=pupBUZyA=8|3V zs*4V19w!ldcK68S60mn9*?;)p!8ZnZ)!h*F>M2eX<1NyikV?)E9aws=OUG=tfsa#uFKZOX63D|F@Cqy@R=Aui(<3`eTi$@r)@}aNGs~^ zYT_10PDA01;{E&g2}@D9@BK8lqe*~15##H+1igKILS$LJDq_@^&KMdRI@2zTm71+a zs1Hjw%JOP!Ya6+zrlwNYAD;1=N`OCR39+#5)R>ZoFQsF~wN0n`Wk0g!sv~ec8?YY% zP#vQ*L1`pZD6K-Ce%CoW8=K;v=4@Wjs56ruScDF9XfY!;kpBI- zTCVcx^hXyy_BY?G3n+wWAn0S?Zj^8}|GKddB*k>B^i|VsApF+a+6r-o{p2@1IC{ed zRAi@IxNza^Aadb*0h`qpmDj+4qzVLrR~dPETLxwRC5kutp<+PImpB_6TfaLw_n25L zuD!XJJ84Txs&pfnZp+)h8#i5rtv6|lY$bxlBM^vnYjL3pPE`Fv>G$UP-`a2(SJ| z28=!o=g#Vqu~RI^eA6XML~w9o;DhwKBa=1!YW222QxVnI*XQBuo0*Wbc(2xxXzA=m zD9RU8`U@6os>A4Bkp1pX_@^UlCi@L~hkQTs0qK9y?Lqc9Bfm#q5E;Ue{RVZse_uvA v7k|&q$S(PN-;B(}-)CxMCjO6xqTBAu+Us=%hiqf%Le?v7S6uz}`+xoqv?3FrGfU$5slp2u;#&Zn1^&+njOrXrC@J1$<3y+R_<;yBmPIm5P0?s{!zqEPSftHrKz36 zH5(I>`87MMJC=5LZW$f8Yhq)2%hKW`4?m9p*MXaMc2;7%y#L?#c`R*i@E-AbBTph7 zAYGI_qv{wj-sy5jeSWQAhL&c_V4Bh!rs`7r50`g7=AwRh?eR6vhP`y5wmJ(G%E$Q9 zo>CvEt%x~TyKUuRp$t<b{#?9OH5aic$~}rdoA40->(7PnCR)T&{O>=jY-D`@`)d;EuqK7&Swwzs9T3^ourmOCF7%?KYz}xyNorx*Jw80#8@z;cBSc)aoL=^C99OH z$QXatmJizLNnKM#iC5p5O0ttqZ)cTQ%JGm+G02x1<0r#?-ZU-s+wW4l_)7choxQJ4 znO8c?l5U>THkJI(GZd7>Bqebkz4Y3(c0xnXUQIDdO7aOkS%~+yZ{J!oEDgq6KOMR| z-b%N!FyT{KS(%WK;Dx`IijPUrng9Cg`_=r{IeaVjc1v=7?0Ns+ZJ%$r{%we=b#}$& z4_w>5d-o^%vF6tF+ZyBD`O*th-E2WYLDsVa6$#17ekYPM`>I!Hi0j;)XfH``(cjmZ z?ci_G`AzQESM$&7yGY@2FOOX+U6}Y~ToufX=k^o1JFXcR5^~<&-u}z&7M}JDOExDb zr}}r7qJB5LyJR==^T=4hA$FtY4_Y&2((C-nkz(`Gzs$_cjDEhosG_SIQFxv7V|Cj- zVqr)m=86wmpN)oVBZoWIr;BLI-bu|TvM6uS{eWNSv-DWeVPIrDucD%|x;EwEKRY{1 zzW=>K2+vGVitCZbv}~*fYoi*mm!hP6CAdkXA54BMqPvb9IWkk{v3?TEa(Adtnu3Of zSS=CjKG`pK+63Ca+@jaecQUb?>=6BCH?m98`H$CFayAb+4GYsl@*Up6+>v5bjh0hg zxihm>yk)mja`&X}Ho z%ska24e$Cp9lCuHG_AQV4&z<9;tS(#^ezkIPqB7#CMJVn=arO{zF2gM{c|taZ(Z9O zq53$5kn*}Ze<`=W#UXir;(mAKx-=VH`FurPeUDCth2&hj$C8Na()5PQ#QUVAKHQss z^GBWY#J<}O*Vbp*4*y1c{+akCOun6IXN!S{+ZVGY&N1G^LOi_D^6cPDpAT=T!N%Vf z5vSRK^X?Wc$$G|(2`bjV%ri=qggY5R^zLfWD?3}{I?sE%Oyvr@&%ZZ_v|qtv8MURE z%ydq<3zxklJ3ZGBGbyt!Oip_KiIV6`D+?t-8v1R;SIIcEGp(+< zZme{tI7H3#mz8~gL~Scbr<)_MpwMp{wW6E5@@Ks5B)+m0RB7Pkf7ZT=H$O+ESts30t>f-5^BvBU4taBtnqTi|#a7pA4poQI(@IRA ze)xK2;N_*#hqO|y<@9I5yIkjLmhhB}b&`v^EE0~X7n^^#q!_ra{Ob10p2`!KT4}30 zRl$6Eft;3=W#6eg2@X*i-R|P}DkAnNDf}IgtDlU|e?ZbVrx>u|C%j&~c!6ALb&3+V z?kf%zcd(#|SJaS`llx-Xjl#hE79n)Xva93m?VOGEl~1NM;hNcZ%@OZqe*49FmO>|f zW%&0NJt_NLA8U*fP_rE4h!=g-<1Jv{VxQC3Y&O=9g&!>2oK zX~%hZ@}hedV{bMksr?yi;eEV)?=Im^yQ|Nb_}SajZ?_!2tyk`ns8v}q6|T@!@$y*z z$BZuT9s5od$1A-u!i{_~sS5Vrt^K-=C?SW=`#nRcC@l{-^veEud+S%rZdS{jnbNQp zcl@aJ(sb`R@%7yrx^xEXvmwTRe%D(MM>?E(WqX2Hy3aT2{06H+qULL}*fg-E#;6VvWVFocU~BGs-@P@N7{Ts;X*i^^*grt-cX522kD+E(u4E0+d`Xv&IWEF zCN-5WZ!vdDs8^L#5NC>f`Gg9k*o^q^40|a!J2yvUFF)cf^Y7^UlVKDj9(&X~sT-^N z=w_Ds{e`txUEb(B_C5*~w$#6JY}s^Pc())0O5Z1&!Ai&RPi1`*8Qm7M^VmohR6qZ{ zCryim^OtKv`HjypFfa%%ex%QnT2lOpm~j4cv)R}>AmROcAK`A-lk3w@ zq>Fuc^O&Y`=9FVoRP^;(-)p4!A)U+KUVPa%nLXu)&hmP(FIiB!si{dtPjCO=;Gi`g zyA|2FG5#_ngi*M|>g+RCNimDu`DVqw=u(uIZ^ya0ef4vlO(ZM#Dg<*?ID5_|B_(+i zE6#tTHsWY@YinDCm_6qyiw>rJ!WPdEDsu1DKN{h>)^jz&Wi9#Z^F#*Jn)dc-;GT#w z_&>!sXTDj-mwDy2l9rYhmsZ;0U@om)XaO@1*;Wr6RSf-c$EdONijK}c;(-`;@0LUT zCc^suW{PmT8v0|(#qU${m{aopnkl}P5S`5I_gkv>cV{^JgvR`*{l3xZ-Xebc(MHW2 zN9$O9*K6nv{3exwp(k%BSBITER{Csj!_Bhw<6`!s4ARRLm-+(Evx<%_tgS4T)wwTx zCVotLc+LX6n(3ceovXVcS-O{4 zHl3KT( zYnk`%6Mb)e5`)M#MbRympq2$)AyiWAT@wUNpO4 zNvRh+J)y|NUKwXxs7GAuhBy4{GJ{&3#xdH4E4hSHwPZn~GG*X)QK z9pkS>?s6Vgj$rCuDitUSMYeAgGOWAT($YU#kSv5%Uc*og{{vZ}A#?BjJ4U~hG)Oj>Gq0adIF z;bD7%8O*Jt zKDE1lZf>sMPkgexSC*{?W$H!d<#yy*U)YV;70%l)RN|iip`y<)p1C8BYBp2Ew$5jP z4q@uTEKnC)7pr=SSQ2A#>N4=&YD-kWvEHUC`6(%GhE|p6N%t67M63?D1BsX3keUk% z6)=%!5x>hd7C?$_dyh{HJ9(oyyY9=ah8Ni@Q%{0<^up)2p{d9pYcBE#mG*Ea8ZW?l z)co<`FM#Gu5{_1PIx_jkQ~>HvV)^TwJ&&HW?8?cUs}=7bsCcR6FY}m&O^PM zC|7|o6{)Wb-+!UuU|-h*=9xD7fh4Spb_f?^@zYqh@;C_z3GrY1?&-MH`{Xn0;EO*5 z;>EfMWZnCF^^)Xnf2qGWYg^VXqsn(U_WP=+s|UZF7qk1l6D9nEL(~&i=i|pdlTO>ncY4ugExc__pjg7Jm zk*0e63y;zs?Ml0T@vBPP+42jaH2 zWx0D)`=`t_XX)R_O1ABD%I~a|jvRK9jB2r09@ee8eb94fK}!oGB_*Yal)-0HC5&R4 zIS&RHcJ7Q`FeX#_{rsX=e5jP07&6H#CWifyzCntj}5qnpT)5GuI zWd;TZ4{~$wxb#}05D$@hcS3tRv*5O&p&_b4=k--lOg;Wr-zjtaahBPJ50$C>j4UZ? zYEtVo*)|H;GyUh!Tgv8qYnHNWcz$5dux|q}Tq?%bYz+$HwN5En?WS zhaFERY|&9*;IZ}yzjjtf=T%nC(vqX=#@ZslV6X!{gMfLv;P0`qkY&L9VLDb;9(is& z>IJ9R*vU=*JoUhCR#v~_V%fNMU|$O7Kfm9^c>iZP-ZeI=Zbvj`-<|l5tEQ&%n%JhMwvJHx_PVE?L z{`hjm9)vQhCLwRNXGs9WGwsl*Qc2%2%5Ju z0C}AGsGV+TW=3`B&>^(He&oO7+|Z8KQf}VVj66M7iQgS(LId@iA8VmbJtE7B zvFSlr*j`(SgZ7Ks|9Sz+tjjAaWzL-=7dUxx=FiC0IC5cJjP~x`y8z|+-_5-^goPP# zqh>mZ*{P{JktFI07Ft8Kkv?8t+p_cs|T3RZos-i}T4c`0y+FDRtJkXyfEFd7GtXx~Rwt=eWzp{@1cbw^a)Zt{=k$E5a!hYbu>3bjlrVI>R z-@acg(8);s#EBEDsGZX@Gxvj=H z0W|vJwm8Ez3kyG$*mKwVOMOjBt6vFEy;^5GK%|_^=6jULy(^P%+)f3e;N3QfJKqpbxy{|KP!<>!zmcM~-ae;NWmvo;|`U;dqb8IILrN zMTJVz*ONDD3+n6XRu-q8ynOlcig|!#5i*J&nB6|)%(jDO8Mhja<~YwMRS%y~|KNon z^41J6T3uajJVg>Ye*D6hwn57J>$pgu%d}+>ry8Hfx~pO+-a&F;d;Yv}iTCc- ze2;wH;XVwcr@>qFOim{Mxx2H3TQije;H0`V55B~4x`!-TFZ(eDQr&NM7n56TS)O1) zVnG|Fe*LPRNyERqyqsuGng+i#GgPxLeSoJ5&oDh4-3>1#$Ze*HV?=l|qoR_DlMf30m7?~3&w~dKdPYW`;^7aSIN`G>ghA|Fcb;2)o}0^%gm*YP z$0_r6)uEXUu-_OZu2d$!%v)AM+z^0jLRaY5C~bVP^n z;zI!ZnV(llymCbKqxNp13N$9t=j7(jG+dG<#+*#|H8JF*H7XdUsx94ai;>??&>TK; z>FnEW~)zxJAm}WoK=FOV}I5~B|DPEWI0B3Uj#tk3U8jt0bl`7Y+ zwl=M|^4nCRP%e$Is5ZH#<{MpKI#cAN~le9U9W%uqrp+#@EN{^ZTSZUYMon$(J-@I}ip&{gUR_CaU;EoT-u9V| zLVhkxz=TR(UY?=y2<^Uo`?_|!muUKiVuLv>Z<6?kh^Y)hZp`RkuWxFS3*pgo{AHBu zbe;&Yn2Imy>AeF3o|seE+1WP%?of3f;N{{f#uN}{DMp9Q>rTUR_LlfC3K(OFPh1g7 z+p%9v)wC?EqeFKK1%;1heZECk&Qow^70>8gg_Tt-8AUD9_7sj$_9tK)x7z?{=1}FZJD51eC^WkXMXr_Y4fY{kgDD$jlQ2 ziSa;rKy}JRW#v+UR8?&Xl@#zxeW-gVmO-~SW#dEoqCD2=QU&hjx-70|{x#KFBJZO* zC?pi*z`pHMic_SB^(KsLil0CylmKsqQuro5h>JTybQho-%*mGryInj<8#Dafvl5@qRG)^1@*zu=$P72|(u zMh2tc4Pb4e%mB#n=N~i;d1w`lK(9k5GSQu$|GGbJL)Ulo$Qc??) z`)A+z&6+}#HVBPeQIiIB4K8Q1BSpSpJR)lyJOTPV>`k7G>`@#)L ze=rQ7d0c55ZY(L;IyYQ*!&@)UHLJRtS8Zl``d(aITy-e=+BSU(tk{*;KS+i|O%2?K zI-&U4>+jN1Gzx1DBPB_DE0OjG4R{k(z0sL^Q7cekl5~YfiOrpu@D1TLpwc8Z_lkR@ zw8v|Q1#2a(wZ+YOYI4|t;>KlJHB1vk7>Ds2?XWp4t4APHjTC+UlF_lT{>H?sR`&M0 zGm|!i07kgo0Cj6cNS0Meg`3lzU5JyyDM z;Eb?7_oZG6)r8Au;SXP`yfLHnWq5FKtDBo!KoS}8(HJeKOHo3u zfsg=FWmhdp!7hyQ+}|0*fAZwn)2B&u(aL{w)jp!KolN0EIki80?AUuj=`!o;mp8Z! z@>nn^T)nl9%J{vxIartn6$v#??bal3fP5SizmaEkXityfXbSP*t`Epb^!Sgr9fn!G zrq{0BC+48@=P6KRhJ3p}-=M9ztbiYTo)Qia+?=fEgFCMhinVZd7DL;X3+oN~r(7?Y zvI+|cm7w;@B|TOG^?uFN^ytZR)oS<7o;^E*l@o|+`T6sKzrX*@`JL=vvATy29Jt4! zj^2VAYjyYTp3J1QH4NXtP=dCrV59;fBe@Obh+=T?``%M`nDRE(U9gSkJL7f+6c-mC z5D<95aTk@6vt|t#jOd+{lark0Awj{xd%(5RpcBR~q5f0q(y4?%r{SaZtE{UlLpp3p z_ELhn+0)Z=;AClC-K7X45-6O_fN3Fni-d1#HPuE*`xE#g69Ux9l*{tl0t`UegMnp; zZ$(!HpMJT=J8!?Xwl)D@Utd2WA)y<$d?`}w5n%LmsSx1N^X_els+AHXC%`k#x{V{o zrOyJET~$;9bYH&wC(y;2Ns7d}+PsO5CIK1_`Rgp0O-n3~`fpx_3 z`DyzcJ6qd_Al{CrW7+%qj1o%1g%}pMW5fMK!t&M|*?pj;l4-R(Dwr);PdFXWdimdDw;DW8mUI|s;9Yc*v^wl)> z5u8|QLf^w>A)+wL%X{BbBk;kXf}!C7 z%kwQ{o5|55T$fD!E-5N9#LW!>@>-2Ha-fu?c*=N%VzimY=o;Uu{!zOZiWhw*`zbLo zv2EM8Uw_?Wh|sv8q_jJe*bsbV;8k7SX8_&ttr!6)b$$P0^tpdaEeG5;F{!evq9TCm zPSDFfb#)wI(Ubce4f^z2re;CNz|fEp+Qx$xmCKj!p|@8)yQWorx=B+#a?3qX)Ra2g z4sL(hcR8<^C-bNhf;5dV-YGhPmu=l}w} zptO{nhKA+`NHd2vPgmO|v8}+tgpGk+?NAhyf`Y4qNW6%;aWo#aXn3>pB&q;*@1l$h| zWhyQ!J9O|M8HQ5uN^%gyfRC;j8r}mycmsZxSi5k+Tboew?L*d@dPHb0UcBhIy2MX} zOmOgHFcSwb>2KY-^+$dEvZL}1LqigNR#QvMO(NrSYHIXY67wYT-*I+;5^&~uM8v9e z%aQFncBp{J2k#P%R+pfYksN+Pz3WMx9b!s9$8pB`m4dvyl*MOYm^*jwTn3rh+TQ+C zh)U){7W#9kptUbL7x@n6!!mNCNXZ>A1yDiL8}`K?wPpEoS=-FaOukNf=cVa`sA)od zi(Nl|?!r2r*VNPu<9By=XA-q}8*Pu|k{#+JC#wF;4BeNO|I6v;4etQvT3dU|?i4grN_8*bHh8WGv~Tma)QF)-y=8-yRRo$e_Nm2^1;UbM<} zf0=b_mhG`UJh};rVKIFoGXU3 zAG5XX;{?Vs>r96!R-isBzP{<}Cu>)_zv%Y5f$csQYb^#D?MJ$t5VR)S}tLheB|X0ENR zz1a}IgN21f(CmlTQ7?c0GDPJJY%czhA=2A_R#sK5)D<7aHK*t1&Vo2m)jzMSOhXWm zz-~R2K_?U=t)$|h%b{Vs0m7Z0oxL))as0if=N4i*KpqqqJ)zw=`9lk!|LD=9Y{$6G zT2l{dXIS{6Qr&Lc;9CBwm+u~#VXTY-Bh^g&PSI*w2PoL&|()oI)5Y(YJ9>?c$TgFGQv+tB6Wgrjo800-e z3%lPhGSo8m`*$>Ezuz5MCv$Rg)^DWM%>Krhf!ip65er0Bzkk{5sqXv@kqW=WM2-(1 zJ`foiry=|ltBQVTy)dq&o9n!L@7}#s8F46B;^N{WqM~o0DFYQgj*N^frKM87c(D*= zeZy9AqDb~3Tk<=%(8luG+R6TTL2#<}A+=)|;V^;~l+9)Q`D2%*ZwVlag7gLz5eS}P zfaPiv^Z@@KKQ4Pdder+fP651UoNh`AB*6Bs<~|_)jCu<0C#Zi6KOMA7#>+O3mPiW}*mm0m5tzznaV&w zVBp)daKOXeZm$?@hN|~=g?DsxY^jQR{knGf?_V2O3WlqztGBrLBN;MrIa??f56l&` z;4CZE>4sV;o1(yl+wK4%Q87Q>_VVPZQ+viGEq;CFW@KV2hp_!L&zInCKTcuQ1%4gp z;u-*)%Ea&6ppx2H=F778VhgIwyYnJXaB(r*s%ndS`_>Bh{K}HUTQrsqP|sO_mF3lQ z0~PdLUq_oip7^Ow?LWA(m6YK)V`LxlR~l?gX!i!2$EwPozi-VEM@60g9B;^jU1_7N~54%1;j&gG<&%_9t4B-1c$J z1vzD78A1e2hGiW%-uHvy>`@5`$CC~6-6K>v)!JON-pFjNZD@Fz?KBtvO?b)&4%PDI zrKN;F5o!twK4W0&98h!4m@S|%ta>~jJUGD5!Qr7lC85$qA6WAXf(t@RUkT}n;( z^}d?agAbpa%HL2Q*+LDbX8?Woz^K%51!!x+H)>gw!7v^9bu{2YCZq=|YinzR>hqiL z<*)uICM!TLnyl~O9`}|oh@jX1fI=Rk5H^9UFb_i1C9E8kUlIyXdA2{*12cvj| zkB?76cNH6Je0;p_&6^27e_eh}PC9nvh&5(j`TbJ~W+VU?!IqCY!iC+#_+`rG8F|){ zl9CSiF+_l9gUnxHpscP9HW(ur`t@gmFci4NlBqN#fe~En!(ms}1^;WU>N?NFC6Kv%oM= ziK(b-Ma2T?S-}CVK61*<0!|>sc_3X%{VIxC*A`&lr&nHbO1dsRU$*7Lh3rF4T*ZUW zk*W}ea-Sh^)6`|ftLwN?08P3_jZz$!z4=!SUnYwLsAk%4U#*5{>0}hQNODeB&%DuI2IAy z)&yJBcDD)K%8}s@NrbkfQrq3p*_j1ImgHh9>bJ6}ADEGm(bIhblre&Y*M^MLbz{yhZM@z!)_w#QGYonMtPEM>K zei9CM10aUZI=Q&KKg{L>jV3-Ez4M^FB%sdV#}bG=f!f3nt`xuZKXdI}4F34_xl+uu zAF7A{{uy})o51W>f)vd%qdyB^3o9uZWL-kNz`PkV==bz#A(YpE;NYX$%IvS9-l8}e z!mdd$`iKd+nvK~(g=fq{R8S`5z$GMPI4rD4MsSE;lkYVChcw%B!6%ZhCiauV4hOb%AWNGdc$y^>bh(L=VZcLC5ZV0 z<#Zsi4I%w<-g=pE9#xs&b;&Be6&HoGTBr2^iNH_5^)W0@;5593f#fE@B-#V}&19l> zJVf~S!M+ePu%ZiA4n~9I;Eqwk&e8homvP-|$r!dNS5AzlkZff^)LVo4D4av2#A3S% zod}AE-;BN5V=uhAO}=)4Xy0K`|sbMfXGnx52l2)pxEQR zi=ueaFadFpx{UMhP`tIj9+Jd&vep6D$Fn9fUzy$*F-hZ#+r^;DU{FFY-2+XAquFjt! zdA)q+g}5tW{HPybxQ#5X9>;i=!w*K$IT!NNex<96>FYRVzG=|;X%GS0BWm>LcIScf3;vW$m{ZF4h!OVRK zw$bRHW7#t^pw6f7fhukHTU1a`fHPSDt_;<{xeV}tklx5nXe2YNF;Bh&&AC3as`Yy+ zsJ#3FG1h)It=To7#|T!p0&_%I-#K6ABUVSk&zwJhKF<2BD}+^JKeb`WAH2QU$$_Dv z$6MF-!jKqN=i=ma1~k(1joig`4>PEB>{o8aaGR}{?)wNT+0siHz zD2qY20rn%e?0`d8E`j_eOj#H+O-dmlCeDj7Aq8V7|3|?SWL9`5LQhZc=;#=@oCCfG zV}j!^QP(AKMgjv#moA{)5^GW?y+J7D@3UEEgE+XjRNGFUHt~G&Bo>VqC|KQr!ypo} z9Sorf+1oJ;Q=o^+7#YQUQ&^6{TuMAWrk@9cI4r^jf7XG&(PSjeJXcY`SwMBJ3oD>{ z;6I}R1dFAM5{?NKwH@N4EvMSCWA~R}gd^xl8Vtm*qn)G{SC@$6pI_H!^)RJy+I7g+-Kk+8gQ!K?ZgB?b`>rLV9EM>T|Js9@4hbtJ9ks4hSGyAb_7q)%GlQmgr2@ z69;<-+H&^XGp2*(S)N&0qG$z9{hmv&Uz8Ds2Lgm=(j7XNz;(mSj1$Ythrt_8vBVF0 zd!TMUeEE_dbgf*?2?a<5_;xC!ta`t6TN|4npKo0Hpp&8e@u5)D2ukeD&Tm2(CAl>H zK$qH$Hc}$_=();5uA7(;iVAqU-S#9KuuP_PuXi9k>+7yT4B|JfW`fOIyOE3y9al5m zY`3nS-Ys@*68sUKz=dvt79EKkeOjdb&=x7tb}AcA^p|ab#Me+ za6DFoF7WheuP?L|Y;M-JCRZKJ1nTZAD+}iFnHbFy4zs;S)txQPaap86-F(o( zj$fT}!;X3jT--qc4i-#xD+O^)nj8V#Oa3 zw$OFZ|Duj>9wz80NI)J}BQHa=|AYfmVVi}eGwsLrU}w26>?aI{=qh1G9?OG_aBgco z7b`9mAhnj1$a%^K9t)C(0LXpvDEw4|n_n%7X`-v|g{IC~qt#{2@+8XrFC~~BhPQ4M z6ciuyvV%G9LXdr+G)Z*P2r0L4VdYDgXc3wx7*CjcfB^BkWkohUHD5a$4W^u!?yruc zF%6o%iZlL$3=0*nr@SB6kcp|d(w$MMJ02wOHr$$SEDRB1a!r(77d=A2iPp^u& zHfB88gx|k#rSA-70(*I>gKvjiNn{{~<%%+I`+^zNheK9JHjJ_|?yfFb({U1#h9Kh( z(oy{FRoYIdzMSM-pC`n`#bZIo=2(9aUiP$u!jqYm1wWA<{6>S{%ld&0sw%JXR3 z08X;tWLC)U_jdyavCpvDvLVzCYu6&U4I#b741jG9j(%_Jb`j(y%nnD*lw-sQFS&OW zfQ8ffVVF^|xC9VTyOr%7F6|+;zSK_}^mSxviud>E_kj%#9-dOfwm%vnViJy+7(l|9 zciT$UdMA+(AS07+p2t#C{;tZEJt$SK`&1zow-*krla1b#orA-ZM~}8zM(jKx{0Y?YSt~0(%Lv@Iyn69Bx0O>Uc5<&8<$|F`5VSSz zO-31DIsye(avqNQi<3A5tkvs6M1Li^|LBbS_3MY@6~ovaUxP*<&PbU>=8Qaq2Ln2_ z-1JxiNLIj&0_@e+nxa1Z1))4{WwYl_6%!MaUI@C1p8#@pWirk(4_YKE zK)Zb8=cgQ2H#{(qU>AMc-Cb%*k|$V>+OzntbT&#uN4CSI9UeOxvfK3{+yuoAzARJ@lC;{nR z8!Dx$ju8Bp%E{ou%u}aM-R#bjyy_w)B?Y5+UUeu+UOzAoq5oZdm2|hibO-#z4{!C% z4MP;@86EWo;}k>a2hiOVm6Qn80%|DXaE8AJ5XAA%Z#tmMCkP;L)&_x12QMzeq9#Oe zkwBO5x|~OoSHXF@(6BIoC0cmBf%8fs-A+$-iXT3FxCdMXVP9iEbZAifhyX6TnS6Tz z0MZ*+P4H8m<37J7uK z@bTlv@NS=jR!CT?k^Wik{ZfpuC;J};PI+oYDu{LWx!6Jc67|FuD#^#jZDS?0S0aE#vea+f=s!Wo-PEV>Saw$ z2npMWcoq{N&FmGKCpUH-cy%ki1 zhV31K74E8w0fYiSD3^4>3D|`&2*Qe`WBLr{ze;r>nr+*jw}}?PZHTnFdXeW7AwHr= z5kQk5`v1<46+yoO(!e6#%gd9ZqN0*|eF;{aUK}gUwC*P-+A+lbtXbdv;=n3jP6L*z z<#7{36&T(boJ$R}#t_1E(sX-6!FgEX_D(M>n2Jdge8bI`oRs(N?*(BilQdFztb~&K zM@K6e%B)#W+8G|Jb;0V3F!f`b_$!2N#8gSiAX=2RFMPQSjp`oLT zhNr>a+f8-thdc8eZh}zf2xm7rIXQUZRY&eApav087;t3Oy6TBZO74eCm~cWULZ@%z ziX)CT3{ADXBUA-q_Y<#dC4Tq#@zcm9D2Uk0vJUHMa4E#;fPth2teS;|1*X_@FslYIX z#wj2xbk{6(0mS4f2}w!ozkhBO`n>~Y<6b;$iH5BA&F&0PK|PUO?=@(N2(7O_gP7h$ zPj9`k?goQ8Ii`#9@^V89aY(WVFJ2z>&Q34f{OWXc-Rm zhZjBp zX6DL$8rs_42hTq40T;zAn)&Ma>?8t4Gu4pH63jRm;jxsF>kbAWdpgqIf&)})FL;p) zBks0XZPgc-SU+rzh>~*S1inbi$an(57IRY7GpCgWZs6G;5bagW*a^Hr^BM1Xgwa4KQq=Zw#!*P4L4!X2{u@R#dU|@v z7|T0QE3+`r$Jty5Hwvm@2$hkuW!M>Ja?bY3jh~Hmv6n$sZw)*EP`i9c|gf?>@`uLR8xl*TiuO&Xe6J6j?|B8}s%r z0k>B^e*BmPFn(s?jH)WbyV%%68j>KE`f$ATdnfvm=`S>c4g|B~Vic^3h&Iu#9DLC3 z>ud>|s}`wA7Vx2u@~9mJW{sZ!?eVbEW*xRF8#jFrm05&>gJIKVn2MHm7-MolL{)2R zC>~wIc^}xm+KA6^n(4w}22JsuYAsmpN%#>vK#gPpqOD(g4YK8UuHL^|2{jc}pJdkt z9KV@(f?3vKhCO?1Ac75o$|%?i<-lH%1t|!>0Du0}mBhe(puQY1BV{crV3B}IC2D{C zcrMxvv+zJ|(J-KaE*^H^uLnU760!}u~1~Y(Y=;TY%idy8Iz%dCbg1t_fHc zL(Ak57uPwGe(L6r)27Mj@@_NsNIK*8QVhCDZ)<5IA|moa-(mdf0DYDPR}kmChnlu_ zWhADGxj%mb$C&a!9SGzL2N4d{WSK`)iuSAXEe4zwBfY(afpw*&j{#XD-AH#PY4H*A|YUdUvbWnJltGnrT zJ@rKKJ>W3YCzoXlSZ0lL7thBu7hvzk#z_N*4AtDYd9xgnUF9>Nr(UqsHR%4Y6fRy2 zz=7doPpBy=d*Rm;#lfPmPbdn8UA&M?fvdjR`3aceGd@i3R-=k&?nYm8E{=%B~EPsy)d#@?O0{Pttg&yq`x}+F)d2?FG(% zm#bk!rpy3yHHnX@76s!`#jTa*c@nO@6D^>6xXMp~8P`u1gM%as;(C?6q$qCl7hX+) zQ!zXm$p9LOb~;-5I*sO#`4v~*p*f851eM>P*EL039p#yS)kxUZ7ICYh2zWtMEX9?# z2w!~begDWv#g{1@!~r*a_VM;>NoAFl@~O;$xva$w`>(PGSfM#xz4#Ga>dUbAXnY2) z`>U+IliZJC!8u#_wJ_8<*1fAd)Or(8wmQ9L51XU0ugtf+tV*qgQWfPvbqo$!U~VvD91tUV}GiyZo{$vL(Z)gsQf^ z{jV`AGl`4Fo|a@$AG0+BUR<6-ht8UaN~L2rYLUz%pUp8umHTc{T9cp}oFgkh`gDL+ z+OpSC8-&une?(QhKaSYdK404^* zD>F8bG&c5B$xx~@t`(7IiN^*923jFTSB%OUX#Fu}%nZFFD+s>c52?;N9 z3Z8}PC=D1DEWo63?j7$N9xjv6Ov4BwKL`$C5HQ?n4z>_Hh@9@NTZun^Egk`H)khTb zkc}L((?i!;zyrk-e?&{INvG^=@F8vh+oRSnInjbd8h>c5D%E z+OUGcsd~$g7Sc$K(5;`I%h{^Cr!H#2E?cGg@bzm}hvC}&DmEA6t~{!361<4x19L0; zn3xhKZ3c%XCu_f$BO#w>PoU?_ef@>TMfNr64m9-$c+4#Iu+CS-LL?q4!;6`Tu`SLv z&wVX?Zg$qF)}^O_EY8-3MQ7Ln5|u3}E+a#D%G1K+;)M&x=dw_T`R%20?p^7=Kd6LH4_l}JFld5Abp9ndDI_>pK+m7TQeXZgvpFej|F{@1XKj7ub$&kx<{c#U5D+gGFmEWXUAhW)jF35v;6xf$jf>` zZQ?-Pwt7COKp_14d~ajG#Oyd=_N%Pyi7+-t80U|I-s_og>wROusZm4kkC0R`Rz3!v zje*;Q^J7s*2MaiOxT9FW&HKR_mH5Ri#t8(fHC_qSk>f-UAMhDqh^-YTEjmOnBGcls z!@e~Y6@`$JwaErVv%Hd%M7w%D53S057-BGdAhh9A814 zX1Xl$pw%B(9G+LeaRR~%&%c)c8rYOzYD8La3i5eaSjE2Ku`wTP>JFIXdv()9aM%~) zo+FMBL+B$xm_0L_pmXkADV_u41BS0+bOhos>ZA7b)YN-OpsVA6oYu&qE|LBF_u~aK zthm5g^i+nVv8#}si_xKQjC)I0>x&n=p6wH+VJYK?WF+B@4PH2C5w8i}I6~584{$7O zs!uzzz)M?!?-8gQBW6T6XS05B*AdoDWI106NNEt<=gpy2fIupl{%b(56&0Q6vHQ0x9Z6>TbNmtQdX244IgH<79 zQdFR=6%By&L?l2_H}*C_Td1r%CPk=hNK40l;`rI%;3FWwN3$JyZu`(uO#eAjAv0_i zei(D3XmerVnF4vwdf2k#GdbWChjL+p$w6FODdL_PtXKdjN$cZZ7ROC+Bxql{SW_ zFts4)OF)be)AghFV0&&?u+=$bbs%tv1bc_Q zpc?+5pDXsgsEFUJ@p!zWUq2t-w*i5ZBVx`LUXjyh&X8TbgQ%p#nJo;xCnD-F-9aAH z%(OZ!-Zk*z-We|tHcmMstQQ|F2IMVil<0}{~ zkgPaU?OphgqUsstwr!XHE(w5i9$LPJl&!~G$l`1g9^e5mFAX{)aV`0rX0H?E2Yer8 zn5niV`8`khg>TdYkK%yYTq%T{!tQQ1jBo6!3-eXg)y2@qdjHPIHfil>__)!ABU5G8DDn z*WOJy{klCiA~~8tM*zbIuYAwR!O(rqkL4-I514L439dyb0C&F4*R+g_*0zS1j-#6bu9W2||kniDv*FK$l zvoL4^XCEe6(5ni8uA}krSV9yf98@s_*&Z8G4bkT@*W%WVp-OYsqq99e z=9_(ElauReuEU>|qtP9h`Ns_vh4 zdvsJ{`2fgBf^71JWq}*IRQwCdmr_E|?fyB~W~qzAo_KlFho2p@FxwI;-w&XWLYvfx zUu!t$hs>t?@c2^GM;%5&-h{XO__EXuSoR_P;0-qFBVU9+<(d{I|#rUrmpyV80js$FD9G<#|1dEne{`y~qk(`43&CZ%B z7Z)Zw_Yq=N=eyf~+g47=g2q@YlQKA`p@WT%W&nHa>8A6w!r+J(=u-(|VTj7cQKZmG!(Lx>QS>o0B7(m0WDpSNv3Q@so7Oix&@& zJ^R7q5i}T~*GC{YU%h(va;H;ZaByEomMw8!ACw&MaqS8-qHDY(iyp0KS6)GiuB)pA zj>%GCPoQl2jp*lRXJ=Q|=1Lnzre1zYLE2n^6@%r|fXnR{JRkRg9G_m^LCAkj|H|Vu zRXsX5%|N_z!Y0G~`gKpZXXi>WVKVdT=RD7Llf!X;|69SLs7t^ZoSoP7S$A`)-c#k= z&CN!4i6~6p>~Gi4;UzzPD6Bcc!32j4?Ziv9sU;DJ=)p(jBR-%g(F@CejR+n+`gr8% zljnAJc3^ape%6K|i#5O8q`Nwf&s7Uv#PJs6Q3(T7d%USdF;TfZN`Q~=Gz$Bi*(KS} zI3vJM+Y0yI6_GlkQ0&}Uu#Xu1SR|bpU`?bNeo=xGXSd>>;AGt#jW#EB71a%cqI-Lk z4hLLF#o;_S(AB;~AXH4mk_`}xsN2Uh_hZ^J`gW#LAoO7!D9SMMt;|eJJvcecx&Ox( z(;8;HbmW4`M3BS(q3OEgv2NSGh6XKVhGdUqZ=%S|9u=kJGBQe(q=*!S%O2UXi4;*t zq;iQwcF8D|P$^VG^?uKu`+fg-KlkUkyLI_p=kGX=FMnaDkJivFEk@;NXavFpd;;-W0~8-G{ORK$zok(Q9a z0<}5Z6=SYPx0G$ufaG=`MP=3V989dOWhFcG{q3Bbh$$Xer+uXtE535atx`%53Fpng z(!TeD&-iLW$>QEfXc2r)6xL8$exo6dD9Bga%nFbD5n3|(dWi;~lLdf-X4YPmgBs52 zS8gn(w#OvRfw}nRlndq{!hTznKyNVn^g;>1dc*`UKtq#154*RN?c(T@nsOf^k_Y3O zz{3cr_u4PNS9nm}J%ej`hd1;#KQl5kl(Kt7$0TN6567R3(YfVx^-DA1P=9zMBTMkh zK=l*mH`S+|^YycOiXg?PEnX{jS^|)8^M#9r`f)?(rKNa$uD{2XNj?lwG7~chuoPk; zhBV>|7|@ilbUzEF$S3G2V(`Aihl{2%GSG zL3F&DH^CIaS@DeXJ`V1?aNeL(US5xZg!ztk|K28f=-xVL(f0d3(D*aY-!W$euB+4r!K&_xO=cmLUw10mZKB8&K1pogP{*D=V9SR-Sw6 zM&Hary(v6B9}a4_2_9529ESY^x3ky%osx-d@6gX*DK0L4tPGpe9RM6dRp=>XHriRD zdE5il*mSiu$aKPn9p8Dh9DFJU3Wk(Xh^o#l{fo&=(OIGDdu}Q1(>|56lk`fF3yIziERw*eg`H zctZCEK@Zmev`0|^t~ZPi7QXARY-4{@OIMBVHY3>P9A2g33qF2v;MvX%bK-hJFh~xB z4R`L|)xvl56~P)rO9YCuwHiSaX%V&WWb?!(RD`?DUi6@**ID3r^nyd(^jIF$j$ zC(VAGoV3R)x@PTKvtMtI($)6Gsc#xtI+WmReP7EOvUJ0~5Y#O}O?e^=_>lEK-+qS( zUSC7DfQ004Z9P3C8RKmP%16QD^h4HVZCi&C4CdiPzij4263)l8VbFMcrmntzs2&TG zRjR6w#5BXmWUX}%E;K~dX+_@yhC_bup(^xg+oh$=Cj3Z*3x+a}0Z71novZg-q611g zpe~eR^l{lEfO=ZEsXPYID~{P{8*)GvGG^=e89f6mWuXHn0N*_GtHaCSbzgrTjAgj5 z6~EOnj&m?8hv1`ynZBq`r-$2;^7-q$Ago)4#eZw6tB;|3WEhXp#tT_=V!oeHlu+&; z3$q3BLG(+q`4tt+1ZA}GE(S_@)O*~oZY?+6qyB!ID+X7dC{{^;pn*8e>;5AAkC;RE z7Yz(&aWx0d$s8;@7PbXWSf=k)n;aSP`F0qEM%DO@BjC!^lg2I@lRh`-BmNk-$h-yd%C@R>Pu_-g)dBL zi%7kNTPG>k7g-_^-M?g!_~XAY$Mk8&3r8D`TcX?#bT@*cQe7;QzwTzSZb}p}3mPc0 z9^CMV4si79&JVlIJw7I7WEl4c76<(OW8+==XZY_Q;a5hAN9+9N$v^J9>JAPSG9i5_ z<1e%29(BJ~VT?-f3Ef6>|q2E_f%Lo25Bc= z_MM_